From fce43af02e2bccb73a16c984cf37fc4311d20043 Mon Sep 17 00:00:00 2001 From: ronzheng Date: Wed, 27 Oct 2021 17:34:18 +0800 Subject: [PATCH 001/379] feat: use pointcloud as template param --- CMakeLists.txt | 5 +- demo/CMakeLists.txt | 8 +- demo/demo_online.cpp | 32 +-- demo/demo_pcap.cpp | 38 +-- demo/pcl_point_cloud_msg.h | 73 ++++++ demo/point_cloud_msg.h | 80 +++++++ src/rs_driver/api/lidar_driver.h | 11 +- .../driver/decoder/decoder_RS128.hpp | 29 +-- src/rs_driver/driver/decoder/decoder_RS16.hpp | 29 +-- src/rs_driver/driver/decoder/decoder_RS32.hpp | 29 +-- src/rs_driver/driver/decoder/decoder_RS80.hpp | 29 +-- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 29 +-- .../driver/decoder/decoder_RSHELIOS.hpp | 29 +-- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 38 +-- .../driver/decoder/decoder_RSROCK.hpp | 28 +-- src/rs_driver/driver/decoder/decoder_base.hpp | 91 ++++---- .../driver/decoder/decoder_factory.hpp | 54 ++--- src/rs_driver/driver/lidar_driver_impl.hpp | 216 +++++++----------- 18 files changed, 493 insertions(+), 355 deletions(-) create mode 100644 demo/pcl_point_cloud_msg.h create mode 100644 demo/point_cloud_msg.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 4da64aee..3afacd5e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,14 +1,17 @@ cmake_minimum_required(VERSION 3.5) + cmake_policy(SET CMP0048 NEW) + if(WIN32) cmake_policy(SET CMP0074 NEW) endif(WIN32) + project(rs_driver VERSION 1.3.0) #============================= # Compile Demos&Tools #============================= -option(COMPILE_DEMOS "Build rs_driver demos" OFF) +option(COMPILE_DEMOS "Build rs_driver demos" ON) option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) #============================= diff --git a/demo/CMakeLists.txt b/demo/CMakeLists.txt index 3e15f2b2..fa81d23a 100644 --- a/demo/CMakeLists.txt +++ b/demo/CMakeLists.txt @@ -3,6 +3,12 @@ project(rs_driver_demos) message(=============================================================) message("-- Ready to compile demos") message(=============================================================) + +find_package(PCL QUIET REQUIRED) +include_directories(${PCL_INCLUDE_DIRS}) +link_directories(${PCL_LIBRARY_DIRS}) +add_definitions(${PCL_DEFINITIONS}) + include_directories(${DRIVER_INCLUDE_DIRS}) add_executable(demo_online demo_online.cpp @@ -19,4 +25,4 @@ target_link_libraries(demo_pcap ${EXTERNAL_LIBS} ) - \ No newline at end of file + diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index e6e214fb..a9494ce8 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -31,26 +31,30 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #include "rs_driver/api/lidar_driver.h" -using namespace robosense::lidar; -struct PointXYZI ///< user defined point type -{ - float x; - float y; - float z; - uint8_t intensity; -}; +#define PCL_POINTCLOUD + +#ifdef PCL_POINTCLOUD +#include "pcl_point_cloud_msg.h" +#else +#include "point_cloud_msg.h" +#endif + +typedef PointCloudT PointCloudMsg; + +using namespace robosense::lidar; /** * @brief The point cloud callback function. This function will be registered to lidar driver. * When the point cloud message is ready, driver can send out messages through this function. * @param msg The lidar point cloud message. */ -void pointCloudCallback(const PointCloudMsg& msg) +void pointCloudCallback(const PointCloudMsg& msg) { /* Note: Please do not put time-consuming operations in the callback function! */ /* Make a copy of the message and process it in another thread is recommended*/ - RS_MSG << "msg: " << msg.seq << " point cloud size: " << msg.point_cloud_ptr->size() << RS_REND; + RS_MSG << "msg: " << msg.seq + << " point cloud size: " << msg.points.size() << RS_REND; } /** @@ -71,12 +75,14 @@ int main(int argc, char* argv[]) << RSLIDAR_VERSION_PATCH << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; - LidarDriver driver; ///< Declare the driver object + std::shared_ptr> driver_ = std::make_shared>(); + LidarDriver& driver = *driver_; RSDriverParam param; ///< Create a parameter object param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct + param.lidar_type = LidarType::RSBP; ///< Set the lidar type. Make sure this type is correct + param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet param.print(); driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver @@ -95,4 +101,4 @@ int main(int argc, char* argv[]) } return 0; -} \ No newline at end of file +} diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 35c0f03b..b676de2d 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -31,26 +31,30 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #include "rs_driver/api/lidar_driver.h" -using namespace robosense::lidar; -struct PointXYZI ///< user defined point type -{ - float x; - float y; - float z; - uint8_t intensity; -}; +#define PCL_POINTCLOUD + +#ifdef PCL_POINTCLOUD +#include "pcl_point_cloud_msg.h" +#else +#include "point_cloud_msg.h" +#endif + +typedef PointCloudT PointCloudMsg; + +using namespace robosense::lidar; /** * @brief The point cloud callback function. This function will be registered to lidar driver. * When the point cloud message is ready, driver can send out messages through this function. * @param msg The lidar point cloud message. */ -void pointCloudCallback(const PointCloudMsg& msg) +void pointCloudCallback(const PointCloudMsg& msg) { /* Note: Please do not put time-consuming operations in the callback function! */ /* Make a copy of the message and process it in another thread is recommended*/ - RS_MSG << "msg: " << msg.seq << " point cloud size: " << msg.point_cloud_ptr->size() << RS_REND; + RS_MSG << "msg: " << msg.seq + << " point cloud size: " << msg.points.size() << RS_REND; } /** @@ -71,14 +75,16 @@ int main(int argc, char* argv[]) << RSLIDAR_VERSION_PATCH << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; - LidarDriver driver; ///< Declare the driver object + LidarDriver driver; ///< Declare the driver object RSDriverParam param; ///< Create a parameter object param.input_param.read_pcap = true; ///< Set read_pcap to true - param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file directory - param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 - param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct + param.input_param.pcap_path = "/mnt/share/pcap/BP/RsBp.pcap";///< Set the pcap file directory + param.input_param.msop_port = 2370; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 8310; ///< Set the lidar difop port number, the default is 7788 + param.lidar_type = LidarType::RSBP; ///< Set the lidar type. Make sure this type is correct + param.angle_path = "/mnt/share/channel_bp/angle.csv"; + param.print(); driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver @@ -97,4 +103,4 @@ int main(int argc, char* argv[]) } return 0; -} \ No newline at end of file +} diff --git a/demo/pcl_point_cloud_msg.h b/demo/pcl_point_cloud_msg.h new file mode 100644 index 00000000..1ea6fc7c --- /dev/null +++ b/demo/pcl_point_cloud_msg.h @@ -0,0 +1,73 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include +#include + +#if 1 + +typedef pcl::PointXYZI PointT; + +#else + +struct RsPointXYZIRT +{ + PCL_ADD_POINT4D; + uint8_t intensity; + uint16_t ring = 0; + double timestamp = 0; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +} EIGEN_ALIGN16; + +POINT_CLOUD_REGISTER_POINT_STRUCT(RsPointXYZIRT, + (float, x, x)(float, y, y)(float, z, z)(uint8_t, intensity, intensity) + (uint16_t, ring, ring)(double, timestamp, timestamp)) + +typedef RsPointXYZIRT PointT; + +#endif + +template +class PointCloudT : public pcl::PointCloud +{ +public: + + typedef T_Point PointT; + typedef typename pcl::PointCloud::VectorType VectorT; + + double timestamp = 0.0; + std::string frame_id = ""; ///< Point cloud frame id + uint32_t seq = 0; ///< Sequence number of message +}; + diff --git a/demo/point_cloud_msg.h b/demo/point_cloud_msg.h new file mode 100644 index 00000000..707bcf16 --- /dev/null +++ b/demo/point_cloud_msg.h @@ -0,0 +1,80 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#if 1 + + struct PointXYZI + { + float x; + float y; + float z; + uint8_t intensity; + }; + + typedef PointXYZI PointT; + +#else + + struct PointXYZIRT + { + float x; + float y; + float z; + uint8_t intensity; + uint16_t ring; + double timestamp; + }; + + typedef PointXYZIRT PointT; + +#endif + +template +class PointCloudT +{ +public: + + typedef T_Point PointT; + typedef std::vector VectorT; + + uint32_t height = 0; ///< Height of point cloud + uint32_t width = 0; ///< Width of point cloud + bool is_dense = false; ///< If is_dense=true, the point cloud does not contain NAN points + double timestamp = 0.0; + std::string frame_id = ""; ///< Point cloud frame id + uint32_t seq = 0; ///< Sequence number of message + + VectorT points; +}; + diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index d9aa24f2..3ea0bf91 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -40,14 +40,15 @@ namespace lidar /** * @brief This is the RoboSense LiDAR driver interface class */ -template +template class LidarDriver { public: /** * @brief Constructor, instanciate the driver pointer */ - LidarDriver():driver_ptr_(std::make_shared>()) + LidarDriver() + : driver_ptr_(std::make_shared>()) { } @@ -102,7 +103,7 @@ class LidarDriver * called * @param callback The callback function */ - inline void regRecvCallback(const std::function&)>& callback) + inline void regRecvCallback(const std::function& callback) { driver_ptr_->regRecvCallback(callback); } @@ -163,7 +164,7 @@ class LidarDriver * @param point_cloud_msg The output point cloud message * @return if decode successfully, return true; else return false */ - inline bool decodeMsopScan(const ScanMsg& pkt_scan_msg, PointCloudMsg& point_msg) + inline bool decodeMsopScan(const ScanMsg& pkt_scan_msg, T_PointCloud& point_msg) { return driver_ptr_->decodeMsopScan(pkt_scan_msg, point_msg); } @@ -178,7 +179,7 @@ class LidarDriver } private: - std::shared_ptr> driver_ptr_; ///< The driver pointer + std::shared_ptr> driver_ptr_; ///< The driver pointer }; } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 0b442653..a5e3f8cd 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -77,19 +77,20 @@ typedef struct #pragma pack(pop) -template -class DecoderRS128 : public DecoderBase +template +class DecoderRS128 : public DecoderBase { public: explicit DecoderRS128(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; -template -inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) +template +inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) + : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -104,15 +105,15 @@ inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, const Li } } -template -inline double DecoderRS128::getLidarTime(const uint8_t* pkt) +template +inline double DecoderRS128::getLidarTime(const uint8_t* pkt) { return this->template calculateTimeUTC(pkt, LidarType::RS128); } -template -inline RSDecoderResult DecoderRS128::decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, - int& azimuth) +template +inline RSDecoderResult DecoderRS128::decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RS128MsopPkt* mpkt_ptr = reinterpret_cast(pkt); @@ -182,7 +183,7 @@ inline RSDecoderResult DecoderRS128::decodeMsopPkt(const uint8_t* pkt, this->lidar_const_param_.DIS_RESOLUTION; int angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; - T_Point point; + typename T_PointCloud::PointT point; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -215,8 +216,8 @@ inline RSDecoderResult DecoderRS128::decodeMsopPkt(const uint8_t* pkt, return RSDecoderResult::DECODE_OK; } -template -inline RSDecoderResult DecoderRS128::decodeDifopPkt(const uint8_t* pkt) +template +inline RSDecoderResult DecoderRS128::decodeDifopPkt(const uint8_t* pkt) { const RS128DifopPkt* dpkt_ptr = reinterpret_cast(pkt); if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 0b82ed16..38714d0e 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -78,19 +78,20 @@ typedef struct #pragma pack(pop) -template -class DecoderRS16 : public DecoderBase +template +class DecoderRS16 : public DecoderBase { public: DecoderRS16(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; -template -inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) +template +inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) + : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -105,15 +106,15 @@ inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, const Lida } } -template -inline double DecoderRS16::getLidarTime(const uint8_t* pkt) +template +inline double DecoderRS16::getLidarTime(const uint8_t* pkt) { return this->template calculateTimeYMD(pkt); } -template -inline RSDecoderResult DecoderRS16::decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, - int& azimuth) +template +inline RSDecoderResult DecoderRS16::decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RS16MsopPkt* mpkt_ptr = reinterpret_cast(pkt); @@ -168,7 +169,7 @@ inline RSDecoderResult DecoderRS16::decodeMsopPkt(const uint8_t* pkt, s this->lidar_const_param_.DIS_RESOLUTION; int angle_horiz_ori = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; int angle_vert = ((this->vert_angle_list_[channel_idx % 16]) + RS_ONE_ROUND) % RS_ONE_ROUND; - T_Point point; + typename T_PointCloud::PointT point; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -208,8 +209,8 @@ inline RSDecoderResult DecoderRS16::decodeMsopPkt(const uint8_t* pkt, s return RSDecoderResult::DECODE_OK; } -template -inline RSDecoderResult DecoderRS16::decodeDifopPkt(const uint8_t* pkt) +template +inline RSDecoderResult DecoderRS16::decodeDifopPkt(const uint8_t* pkt) { const RS16DifopPkt* dpkt_ptr = reinterpret_cast(pkt); if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index cb984a9b..1526b496 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -78,19 +78,20 @@ typedef struct #pragma pack(pop) -template -class DecoderRS32 : public DecoderBase +template +class DecoderRS32 : public DecoderBase { public: explicit DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; -template -inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) +template +inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) + : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -105,15 +106,15 @@ inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const Lida } } -template -inline double DecoderRS32::getLidarTime(const uint8_t* pkt) +template +inline double DecoderRS32::getLidarTime(const uint8_t* pkt) { return this->template calculateTimeYMD(pkt); } -template -inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, - int& azimuth) +template +inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RS32MsopPkt* mpkt_ptr = reinterpret_cast(pkt); @@ -179,7 +180,7 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* pkt, s int angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; - T_Point point; + typename T_PointCloud::PointT point; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -212,8 +213,8 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* pkt, s return RSDecoderResult::DECODE_OK; } -template -inline RSDecoderResult DecoderRS32::decodeDifopPkt(const uint8_t* pkt) +template +inline RSDecoderResult DecoderRS32::decodeDifopPkt(const uint8_t* pkt) { const RS32DifopPkt* dpkt_ptr = reinterpret_cast(pkt); if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 7ab31cbd..4c8c7ebd 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -78,19 +78,20 @@ typedef struct #pragma pack(pop) -template -class DecoderRS80 : public DecoderBase +template +class DecoderRS80 : public DecoderBase { public: explicit DecoderRS80(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; -template -inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) +template +inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) + : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -105,15 +106,15 @@ inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, const Lida } } -template -inline double DecoderRS80::getLidarTime(const uint8_t* pkt) +template +inline double DecoderRS80::getLidarTime(const uint8_t* pkt) { return this->template calculateTimeUTC(pkt, LidarType::RS80); } -template -inline RSDecoderResult DecoderRS80::decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, - int& azimuth) +template +inline RSDecoderResult DecoderRS80::decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RS80MsopPkt* mpkt_ptr = reinterpret_cast(pkt); @@ -180,7 +181,7 @@ inline RSDecoderResult DecoderRS80::decodeMsopPkt(const uint8_t* pkt, s int angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; - T_Point point; + typename T_PointCloud::PointT point; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -213,8 +214,8 @@ inline RSDecoderResult DecoderRS80::decodeMsopPkt(const uint8_t* pkt, s return RSDecoderResult::DECODE_OK; } -template -inline RSDecoderResult DecoderRS80::decodeDifopPkt(const uint8_t* pkt) +template +inline RSDecoderResult DecoderRS80::decodeDifopPkt(const uint8_t* pkt) { const RS80DifopPkt* dpkt_ptr = reinterpret_cast(pkt); if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index a2289f94..b670149a 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -78,19 +78,20 @@ typedef struct #pragma pack(pop) -template -class DecoderRSBP : public DecoderBase +template +class DecoderRSBP : public DecoderBase { public: explicit DecoderRSBP(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; -template -inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) +template +inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) + : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -105,15 +106,15 @@ inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, const Lida } } -template -inline double DecoderRSBP::getLidarTime(const uint8_t* pkt) +template +inline double DecoderRSBP::getLidarTime(const uint8_t* pkt) { return this->template calculateTimeYMD(pkt); } -template -inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, - int& azimuth) +template +inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RSBPMsopPkt* mpkt_ptr = reinterpret_cast(pkt); @@ -181,7 +182,7 @@ inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, s int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; // store to point cloud buffer - T_Point point; + typename T_PointCloud::PointT point; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -214,8 +215,8 @@ inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, s return RSDecoderResult::DECODE_OK; } -template -inline RSDecoderResult DecoderRSBP::decodeDifopPkt(const uint8_t* pkt) +template +inline RSDecoderResult DecoderRSBP::decodeDifopPkt(const uint8_t* pkt) { const RSBPDifopPkt* dpkt_ptr = reinterpret_cast(pkt); if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 24f7e264..b2c790f6 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -89,20 +89,21 @@ typedef struct #pragma pack(pop) -template -class DecoderRSHELIOS : public DecoderBase +template +class DecoderRSHELIOS : public DecoderBase { public: explicit DecoderRSHELIOS(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; -template -inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, +template +inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) + : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -117,15 +118,15 @@ inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, } } -template -inline double DecoderRSHELIOS::getLidarTime(const uint8_t* pkt) +template +inline double DecoderRSHELIOS::getLidarTime(const uint8_t* pkt) { return this->template calculateTimeUTC(pkt, LidarType::RSHELIOS); } -template -inline RSDecoderResult DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, std::vector& vec, - int& height, int& azimuth) +template +inline RSDecoderResult DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RSHELIOSMsopPkt* mpkt_ptr = reinterpret_cast(pkt); @@ -193,7 +194,7 @@ inline RSDecoderResult DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pk int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; // store to point cloud buffer - T_Point point; + typename T_PointCloud::PointT point; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -226,8 +227,8 @@ inline RSDecoderResult DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pk return RSDecoderResult::DECODE_OK; } -template -inline RSDecoderResult DecoderRSHELIOS::decodeDifopPkt(const uint8_t* pkt) +template +inline RSDecoderResult DecoderRSHELIOS::decodeDifopPkt(const uint8_t* pkt) { RSHELIOSDifopPkt* dpkt_ptr = (RSHELIOSDifopPkt*)pkt; if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 9dc97b92..221b4e39 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -134,15 +134,17 @@ typedef struct } RSM1DifopPkt; #pragma pack(pop) -template -class DecoderRSM1 : public DecoderBase +template +class DecoderRSM1 : public DecoderBase { public: DecoderRSM1(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); - RSDecoderResult processMsopPkt(const uint8_t* pkt, std::vector& pointcloud_vec, int& height); + RSDecoderResult processMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& pointcloud_vec, int& height); private: uint32_t last_pkt_cnt_; @@ -150,9 +152,9 @@ class DecoderRSM1 : public DecoderBase double last_pkt_time_; }; -template -inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param), last_pkt_cnt_(1), max_pkt_num_(SINGLE_PKT_NUM), last_pkt_time_(0) +template +inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) + : DecoderBase(param, lidar_const_param), last_pkt_cnt_(1), max_pkt_num_(SINGLE_PKT_NUM), last_pkt_time_(0) { if (this->param_.max_distance > 200.0f) { @@ -165,15 +167,15 @@ inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, const Lida this->time_duration_between_blocks_ = 5 * 1e-6; } -template -inline double DecoderRSM1::getLidarTime(const uint8_t* pkt) +template +inline double DecoderRSM1::getLidarTime(const uint8_t* pkt) { return this->template calculateTimeUTC(pkt, LidarType::RSM1); } -template -inline RSDecoderResult DecoderRSM1::processMsopPkt(const uint8_t* pkt, std::vector& pointcloud_vec, - int& height) +template +inline RSDecoderResult DecoderRSM1::processMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& pointcloud_vec, int& height) { int azimuth = 0; RSDecoderResult ret = decodeMsopPkt(pkt, pointcloud_vec, height, azimuth); @@ -198,9 +200,9 @@ inline RSDecoderResult DecoderRSM1::processMsopPkt(const uint8_t* pkt, return DECODE_OK; } -template -inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, - int& azimuth) +template +inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; RSM1MsopPkt* mpkt_ptr = (RSM1MsopPkt*)pkt; @@ -231,7 +233,7 @@ inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* pkt, s double point_time = pkt_timestamp + blk.time_offset * 1e-6; for (size_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) { - T_Point point; + typename T_PointCloud::PointT point; float distance = RS_SWAP_SHORT(blk.channel[channel_idx].distance) * this->lidar_const_param_.DIS_RESOLUTION; if (distance <= this->param_.max_distance && distance >= this->param_.min_distance) { @@ -271,8 +273,8 @@ inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* pkt, s return RSDecoderResult::DECODE_OK; } -template -inline RSDecoderResult DecoderRSM1::decodeDifopPkt(const uint8_t* pkt) +template +inline RSDecoderResult DecoderRSM1::decodeDifopPkt(const uint8_t* pkt) { RSM1DifopPkt* dpkt_ptr = (RSM1DifopPkt*)pkt; if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) diff --git a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp index 3a80e9c2..258e6e4e 100644 --- a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp @@ -85,20 +85,20 @@ typedef struct #pragma pack(pop) -template -class DecoderRSROCK : public DecoderBase +template +class DecoderRSROCK : public DecoderBase { public: explicit DecoderRSROCK(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; -template -inline DecoderRSROCK::DecoderRSROCK(const RSDecoderParam& param, +template +inline DecoderRSROCK::DecoderRSROCK(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) + : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -125,15 +125,15 @@ inline DecoderRSROCK::DecoderRSROCK(const RSDecoderParam& param, } } -template -inline double DecoderRSROCK::getLidarTime(const uint8_t* pkt) +template +inline double DecoderRSROCK::getLidarTime(const uint8_t* pkt) { return this->template calculateTimeYMD(pkt); } -template -inline RSDecoderResult DecoderRSROCK::decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, - int& azimuth) +template +inline RSDecoderResult DecoderRSROCK::decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RSROCKMsopPkt* mpkt_ptr = reinterpret_cast(pkt); @@ -171,7 +171,7 @@ inline RSDecoderResult DecoderRSROCK::decodeMsopPkt(const uint8_t* pkt, int angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; - T_Point point; + typename T_PointCloud::PointT point; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -205,8 +205,8 @@ inline RSDecoderResult DecoderRSROCK::decodeMsopPkt(const uint8_t* pkt, return RSDecoderResult::DECODE_OK; } -template -inline RSDecoderResult DecoderRSROCK::decodeDifopPkt(const uint8_t* pkt) +template +inline RSDecoderResult DecoderRSROCK::decodeDifopPkt(const uint8_t* pkt) { const RSROCKDifopPkt* dpkt_ptr = reinterpret_cast(pkt); if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 3f0fbdef..566b66cf 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -270,7 +270,7 @@ typedef struct #pragma pack(pop) //----------------- Decoder --------------------- -template +template class DecoderBase { public: @@ -278,7 +278,8 @@ class DecoderBase DecoderBase(const DecoderBase&) = delete; DecoderBase& operator=(const DecoderBase&) = delete; virtual ~DecoderBase() = default; - virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, std::vector& point_cloud_vec, int& height); + virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& point_cloud_vec, int& height); virtual RSDecoderResult processDifopPkt(const uint8_t* pkt); virtual void loadAngleFile(const std::string& angle_path); virtual void regRecvCallback(const std::function& callback); ///< Camera trigger @@ -290,7 +291,8 @@ class DecoderBase virtual float computeTemperature(const uint8_t& temp_low, const uint8_t& temp_high); virtual int azimuthCalibration(const float& azimuth, const int& channel); virtual void checkTriggerAngle(const int& angle, const double& timestamp); - virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, std::vector& vec, int& height, int& azimuth) = 0; + virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, int& azimuth) = 0; virtual RSDecoderResult decodeDifopPkt(const uint8_t* pkt) = 0; RSEchoMode getEchoMode(const LidarType& type, const uint8_t& return_mode); template @@ -343,8 +345,8 @@ class DecoderBase std::vector sin_lookup_table_; }; -template -inline DecoderBase::DecoderBase(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) +template +inline DecoderBase::DecoderBase(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) : lidar_const_param_(lidar_const_param) , param_(param) , echo_mode_(ECHO_SINGLE) @@ -383,6 +385,7 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, const Lida // even though T_Point does not have timestamp, it gives the timestamp /* Point time function*/ + // typedef typename T_PointCloud::PointT T_Point; // if (RS_HAS_MEMBER(T_Point, timestamp)) ///< return the timestamp of the first block in one packet // { if (this->param_.use_lidar_clock) @@ -431,8 +434,8 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, const Lida lidar_Rxy_ = std::sqrt(lidar_const_param_.RX * lidar_const_param_.RX + lidar_const_param_.RY * lidar_const_param_.RY); } -template -inline RSDecoderResult DecoderBase::processDifopPkt(const uint8_t* pkt) +template +inline RSDecoderResult DecoderBase::processDifopPkt(const uint8_t* pkt) { if (pkt == NULL) { @@ -441,9 +444,9 @@ inline RSDecoderResult DecoderBase::processDifopPkt(const uint8_t* pkt) return decodeDifopPkt(pkt); } -template -inline RSDecoderResult DecoderBase::processMsopPkt(const uint8_t* pkt, std::vector& point_cloud_vec, - int& height) +template +inline RSDecoderResult DecoderBase::processMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& point_cloud_vec, int& height) { if (pkt == NULL) { @@ -497,20 +500,20 @@ inline RSDecoderResult DecoderBase::processMsopPkt(const uint8_t* pkt, return DECODE_OK; } -template -inline void DecoderBase::regRecvCallback(const std::function& callback) +template +inline void DecoderBase::regRecvCallback(const std::function& callback) { camera_trigger_cb_vec_.emplace_back(callback); } -template -inline double DecoderBase::getLidarTemperature() +template +inline double DecoderBase::getLidarTemperature() { return current_temperature_; } -template -inline void DecoderBase::loadAngleFile(const std::string& angle_path) +template +inline void DecoderBase::loadAngleFile(const std::string& angle_path) { std::string line_str; std::ifstream fd_angle(angle_path.c_str(), std::ios::in); @@ -547,8 +550,8 @@ inline void DecoderBase::loadAngleFile(const std::string& angle_path) } } -template -inline void DecoderBase::checkTriggerAngle(const int& angle, const double& timestamp) +template +inline void DecoderBase::checkTriggerAngle(const int& angle, const double& timestamp) { std::map::iterator iter = param_.trigger_param.trigger_map.begin(); for (size_t i = 0; i < trigger_index_; i++) @@ -576,8 +579,8 @@ inline void DecoderBase::checkTriggerAngle(const int& angle, const doub } /* 16, 32, BP & RSHELIOS */ -template -inline float DecoderBase::computeTemperature(const uint16_t& temp_raw) +template +inline float DecoderBase::computeTemperature(const uint16_t& temp_raw) { uint8_t neg_flag = (temp_raw >> 8) & 0x80; float msb = (temp_raw >> 8) & 0x7F; @@ -596,8 +599,8 @@ inline float DecoderBase::computeTemperature(const uint16_t& temp_raw) } /* 128 & 80 */ -template -inline float DecoderBase::computeTemperature(const uint8_t& temp_low, const uint8_t& temp_high) +template +inline float DecoderBase::computeTemperature(const uint8_t& temp_low, const uint8_t& temp_high) { uint8_t neg_flag = temp_low & 0x80; float msb = temp_low & 0x7F; @@ -615,15 +618,15 @@ inline float DecoderBase::computeTemperature(const uint8_t& temp_low, c return temp; } -template -inline int DecoderBase::azimuthCalibration(const float& azimuth, const int& channel) +template +inline int DecoderBase::azimuthCalibration(const float& azimuth, const int& channel) { return (static_cast(azimuth) + this->hori_angle_list_[channel] + RS_ONE_ROUND) % RS_ONE_ROUND; } -template +template template -inline void DecoderBase::decodeDifopCommon(const uint8_t* pkt, const LidarType& type) +inline void DecoderBase::decodeDifopCommon(const uint8_t* pkt, const LidarType& type) { const T_Difop* dpkt_ptr = reinterpret_cast(pkt); this->echo_mode_ = this->getEchoMode(type, dpkt_ptr->return_mode); @@ -657,9 +660,9 @@ inline void DecoderBase::decodeDifopCommon(const uint8_t* pkt, const Li static_cast(this->pkts_per_frame_); ///< ((rpm/60)*360)/pkts_rate/blocks_per_pkt } -template +template template -inline void DecoderBase::decodeDifopCalibration(const uint8_t* pkt, const LidarType& type) +inline void DecoderBase::decodeDifopCalibration(const uint8_t* pkt, const LidarType& type) { const T_Difop* dpkt_ptr = reinterpret_cast(pkt); const uint8_t* p_ver_cali = reinterpret_cast(dpkt_ptr->ver_angle_cali); @@ -687,9 +690,9 @@ inline void DecoderBase::decodeDifopCalibration(const uint8_t* pkt, con this->difop_flag_ = true; } -template +template template -inline double DecoderBase::calculateTimeUTC(const uint8_t* pkt, const LidarType& type) +inline double DecoderBase::calculateTimeUTC(const uint8_t* pkt, const LidarType& type) { const T_Msop* mpkt_ptr = reinterpret_cast(pkt); union u_ts @@ -715,9 +718,9 @@ inline double DecoderBase::calculateTimeUTC(const uint8_t* pkt, const L return static_cast(timestamp.ts) + (static_cast(RS_SWAP_LONG(mpkt_ptr->header.timestamp.us))) / MICRO; } -template +template template -inline double DecoderBase::calculateTimeYMD(const uint8_t* pkt) +inline double DecoderBase::calculateTimeYMD(const uint8_t* pkt) { #ifdef _MSC_VER long timezone = 0; @@ -736,8 +739,8 @@ inline double DecoderBase::calculateTimeYMD(const uint8_t* pkt) static_cast(RS_SWAP_SHORT(mpkt_ptr->header.timestamp.us)) / 1000000.0 - static_cast(timezone); } -template -inline void DecoderBase::transformPoint(float& x, float& y, float& z) +template +inline void DecoderBase::transformPoint(float& x, float& y, float& z) { #ifdef ENABLE_TRANSFORM Eigen::AngleAxisd current_rotation_x(param_.transform_param.roll, Eigen::Vector3d::UnitX()); @@ -754,8 +757,8 @@ inline void DecoderBase::transformPoint(float& x, float& y, float& z) #endif } -template -inline void DecoderBase::sortBeamTable() +template +inline void DecoderBase::sortBeamTable() { std::vector sorted_idx(this->lidar_const_param_.LASER_NUM); std::iota(sorted_idx.begin(), sorted_idx.end(), 0); @@ -838,8 +841,8 @@ inline typename std::enable_if::type setTimes point.timestamp = value; } -template -inline RSEchoMode DecoderBase::getEchoMode(const LidarType& type, const uint8_t& return_mode) +template +inline RSEchoMode DecoderBase::getEchoMode(const LidarType& type, const uint8_t& return_mode) { switch (type) { @@ -881,20 +884,20 @@ inline RSEchoMode DecoderBase::getEchoMode(const LidarType& type, const return RSEchoMode::ECHO_SINGLE; } -template -inline float DecoderBase::checkCosTable(const int& angle) +template +inline float DecoderBase::checkCosTable(const int& angle) { return cos_lookup_table_[angle + RS_ONE_ROUND]; } -template -inline float DecoderBase::checkSinTable(const int& angle) +template +inline float DecoderBase::checkSinTable(const int& angle) { return sin_lookup_table_[angle + RS_ONE_ROUND]; } -template +template inline std::vector -DecoderBase::initTrigonometricLookupTable(const std::function& func) +DecoderBase::initTrigonometricLookupTable(const std::function& func) { std::vector temp_table = std::vector(2 * RS_ONE_ROUND, 0.0); for (int i = 0; i < 2 * RS_ONE_ROUND; i++) diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 1a0c9e66..5f8724d3 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -44,13 +44,13 @@ namespace robosense { namespace lidar { -template +template class DecoderFactory { public: DecoderFactory() = default; ~DecoderFactory() = default; - static std::shared_ptr> createDecoder(const RSDriverParam& param); + static std::shared_ptr> createDecoder(const RSDriverParam& param); private: static const LidarConstantParameter getRS16ConstantParam(); @@ -63,35 +63,35 @@ class DecoderFactory static const LidarConstantParameter getRSROCKConstantParam(); }; -template -inline std::shared_ptr> DecoderFactory::createDecoder(const RSDriverParam& param) +template +inline std::shared_ptr> DecoderFactory::createDecoder(const RSDriverParam& param) { - std::shared_ptr> ret_ptr; + std::shared_ptr> ret_ptr; switch (param.lidar_type) { case LidarType::RS16: - ret_ptr = std::make_shared>(param.decoder_param, getRS16ConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param, getRS16ConstantParam()); break; case LidarType::RS32: - ret_ptr = std::make_shared>(param.decoder_param, getRS32ConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param, getRS32ConstantParam()); break; case LidarType::RSBP: - ret_ptr = std::make_shared>(param.decoder_param, getRSBPConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param, getRSBPConstantParam()); break; case LidarType::RS128: - ret_ptr = std::make_shared>(param.decoder_param, getRS128ConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param, getRS128ConstantParam()); break; case LidarType::RS80: - ret_ptr = std::make_shared>(param.decoder_param, getRS80ConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param, getRS80ConstantParam()); break; case LidarType::RSM1: - ret_ptr = std::make_shared>(param.decoder_param, getRSM1ConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param, getRSM1ConstantParam()); break; case LidarType::RSHELIOS: - ret_ptr = std::make_shared>(param.decoder_param, getRSHELIOSConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param, getRSHELIOSConstantParam()); break; case LidarType::RSROCK: - ret_ptr = std::make_shared>(param.decoder_param, getRSROCKConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param, getRSROCKConstantParam()); break; default: RS_ERROR << "Wrong LiDAR Type. Please check your LiDAR Version! " << RS_REND; @@ -101,8 +101,8 @@ inline std::shared_ptr> DecoderFactory::createDeco return ret_ptr; } -template -inline const LidarConstantParameter DecoderFactory::getRS16ConstantParam() +template +inline const LidarConstantParameter DecoderFactory::getRS16ConstantParam() { LidarConstantParameter ret_param; ret_param.MSOP_ID = 0xA050A55A0A05AA55; @@ -121,8 +121,8 @@ inline const LidarConstantParameter DecoderFactory::getRS16ConstantPara return ret_param; } -template -inline const LidarConstantParameter DecoderFactory::getRS32ConstantParam() +template +inline const LidarConstantParameter DecoderFactory::getRS32ConstantParam() { LidarConstantParameter ret_param; ret_param.MSOP_ID = 0xA050A55A0A05AA55; @@ -141,8 +141,8 @@ inline const LidarConstantParameter DecoderFactory::getRS32ConstantPara return ret_param; } -template -inline const LidarConstantParameter DecoderFactory::getRSBPConstantParam() +template +inline const LidarConstantParameter DecoderFactory::getRSBPConstantParam() { LidarConstantParameter ret_param; ret_param.MSOP_ID = 0xA050A55A0A05AA55; @@ -161,8 +161,8 @@ inline const LidarConstantParameter DecoderFactory::getRSBPConstantPara return ret_param; } -template -inline const LidarConstantParameter DecoderFactory::getRS80ConstantParam() +template +inline const LidarConstantParameter DecoderFactory::getRS80ConstantParam() { LidarConstantParameter ret_param; ret_param.MSOP_ID = 0x5A05AA55; @@ -181,8 +181,8 @@ inline const LidarConstantParameter DecoderFactory::getRS80ConstantPara return ret_param; } -template -inline const LidarConstantParameter DecoderFactory::getRS128ConstantParam() +template +inline const LidarConstantParameter DecoderFactory::getRS128ConstantParam() { LidarConstantParameter ret_param; ret_param.MSOP_ID = 0x5A05AA55; @@ -201,8 +201,8 @@ inline const LidarConstantParameter DecoderFactory::getRS128ConstantPar return ret_param; } -template -inline const LidarConstantParameter DecoderFactory::getRSM1ConstantParam() +template +inline const LidarConstantParameter DecoderFactory::getRSM1ConstantParam() { LidarConstantParameter ret_param; ret_param.MSOP_ID = 0xA55AAA55; @@ -214,8 +214,8 @@ inline const LidarConstantParameter DecoderFactory::getRSM1ConstantPara return ret_param; } -template -inline const LidarConstantParameter DecoderFactory::getRSHELIOSConstantParam() +template +inline const LidarConstantParameter DecoderFactory::getRSHELIOSConstantParam() { LidarConstantParameter ret_param; ret_param.MSOP_ID = 0x5A05AA55; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 58e250b7..4a163858 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -31,7 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include +//#include #include #include #include @@ -45,7 +45,8 @@ namespace robosense { namespace lidar { -template + +template class LidarDriverImpl { public: @@ -55,39 +56,38 @@ class LidarDriverImpl void initDecoderOnly(const RSDriverParam& param); bool start(); void stop(); - void regRecvCallback(const std::function&)>& callback); + void regRecvCallback(const std::function& callback); void regRecvCallback(const std::function& callback); void regRecvCallback(const std::function& callback); void regRecvCallback(const std::function& callback); void regExceptionCallback(const std::function& callback); bool getLidarTemperature(double& input_temperature); - bool decodeMsopScan(const ScanMsg& scan_msg, PointCloudMsg& point_cloud_msg); + bool decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg); void decodeDifopPkt(const PacketMsg& msg); private: void runCallBack(const ScanMsg& msg); void runCallBack(const PacketMsg& msg); - void runCallBack(const PointCloudMsg& msg); + void runCallBack(const T_PointCloud& msg); void reportError(const Error& error); void msopCallback(const PacketMsg& msg); void difopCallback(const PacketMsg& msg); void processMsop(); void processDifop(); void localCameraTriggerCallback(const CameraTrigger& msg); - void initPointCloudTransFunc(); void setScanMsgHeader(ScanMsg& msg); - void setPointCloudMsgHeader(PointCloudMsg& msg); + void setPointCloudHeader(T_PointCloud& msg); private: Queue msop_pkt_queue_; Queue difop_pkt_queue_; std::vector> msop_pkt_cb_vec_; std::vector> difop_pkt_cb_vec_; - std::vector&)>> point_cloud_cb_vec_; + std::vector> point_cloud_cb_vec_; std::vector> camera_trigger_cb_vec_; std::vector> excb_; std::shared_ptr lidar_thread_ptr_; - std::shared_ptr> lidar_decoder_ptr_; + std::shared_ptr> lidar_decoder_ptr_; std::shared_ptr input_ptr_; std::shared_ptr scan_ptr_; std::shared_ptr thread_pool_ptr_; @@ -98,31 +98,27 @@ class LidarDriverImpl uint32_t scan_seq_; uint32_t ndifop_count_; RSDriverParam driver_param_; - std::function::PointCloudPtr(const typename PointCloudMsg::PointCloudPtr, - const size_t& height)> - point_cloud_transform_func_; - typename PointCloudMsg::PointCloudPtr point_cloud_ptr_; + T_PointCloud point_cloud_; }; -template -inline LidarDriverImpl::LidarDriverImpl() +template +inline LidarDriverImpl::LidarDriverImpl() : init_flag_(false), start_flag_(false), difop_flag_(false), point_cloud_seq_(0), scan_seq_(0), ndifop_count_(0) { thread_pool_ptr_ = std::make_shared(); - point_cloud_ptr_ = std::make_shared::PointCloud>(); scan_ptr_ = std::make_shared(); } -template -inline LidarDriverImpl::~LidarDriverImpl() +template +inline LidarDriverImpl::~LidarDriverImpl() { stop(); thread_pool_ptr_.reset(); input_ptr_.reset(); } -template -inline bool LidarDriverImpl::init(const RSDriverParam& param) +template +inline bool LidarDriverImpl::init(const RSDriverParam& param) { if (init_flag_) { @@ -130,70 +126,36 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) } driver_param_ = param; input_ptr_ = std::make_shared(driver_param_.lidar_type, driver_param_.input_param, - std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); - input_ptr_->regRecvMsopCallback(std::bind(&LidarDriverImpl::msopCallback, this, std::placeholders::_1)); - input_ptr_->regRecvDifopCallback(std::bind(&LidarDriverImpl::difopCallback, this, std::placeholders::_1)); + std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); + input_ptr_->regRecvMsopCallback(std::bind(&LidarDriverImpl::msopCallback, this, std::placeholders::_1)); + input_ptr_->regRecvDifopCallback(std::bind(&LidarDriverImpl::difopCallback, this, std::placeholders::_1)); if (!input_ptr_->init()) { return false; } - lidar_decoder_ptr_ = DecoderFactory::createDecoder(driver_param_); + lidar_decoder_ptr_ = DecoderFactory::createDecoder(driver_param_); lidar_decoder_ptr_->regRecvCallback( - std::bind(&LidarDriverImpl::localCameraTriggerCallback, this, std::placeholders::_1)); + std::bind(&LidarDriverImpl::localCameraTriggerCallback, this, std::placeholders::_1)); init_flag_ = true; - initPointCloudTransFunc(); return true; } -template -inline void LidarDriverImpl::initDecoderOnly(const RSDriverParam& param) +template +inline void LidarDriverImpl::initDecoderOnly(const RSDriverParam& param) { if (init_flag_) { return; } driver_param_ = param; - lidar_decoder_ptr_ = DecoderFactory::createDecoder(driver_param_); + lidar_decoder_ptr_ = DecoderFactory::createDecoder(driver_param_); lidar_decoder_ptr_->regRecvCallback( - std::bind(&LidarDriverImpl::localCameraTriggerCallback, this, std::placeholders::_1)); + std::bind(&LidarDriverImpl::localCameraTriggerCallback, this, std::placeholders::_1)); init_flag_ = true; - initPointCloudTransFunc(); -} - -template -inline void LidarDriverImpl::initPointCloudTransFunc() -{ - if (driver_param_.saved_by_rows) - { - point_cloud_transform_func_ = [](const typename PointCloudMsg::PointCloudPtr input_ptr, - const size_t& height) -> typename PointCloudMsg::PointCloudPtr - { - typename PointCloudMsg::PointCloudPtr row_major_ptr = - std::make_shared::PointCloud>(); - row_major_ptr->resize(input_ptr->size()); - size_t width = input_ptr->size() / height; - for (int i = 0; i < static_cast(height); i++) - { - for (int j = 0; j < static_cast(width); j++) - { - row_major_ptr->at(i * width + j) = input_ptr->at(j * height + i); - } - } - return row_major_ptr; - }; - } - else - { - point_cloud_transform_func_ = [](const typename PointCloudMsg::PointCloudPtr input_ptr, - const size_t& height) -> typename PointCloudMsg::PointCloudPtr - { - return input_ptr; - }; - } } -template -inline bool LidarDriverImpl::start() +template +inline bool LidarDriverImpl::start() { if (start_flag_ || input_ptr_ == nullptr) { @@ -203,8 +165,8 @@ inline bool LidarDriverImpl::start() return input_ptr_->start(); } -template -inline void LidarDriverImpl::stop() +template +inline void LidarDriverImpl::stop() { if (input_ptr_ != nullptr) { @@ -217,39 +179,39 @@ inline void LidarDriverImpl::stop() } } -template +template inline void -LidarDriverImpl::regRecvCallback(const std::function&)>& callback) +LidarDriverImpl::regRecvCallback(const std::function& callback) { point_cloud_cb_vec_.emplace_back(callback); } -template -inline void LidarDriverImpl::regRecvCallback(const std::function& callback) +template +inline void LidarDriverImpl::regRecvCallback(const std::function& callback) { msop_pkt_cb_vec_.emplace_back(callback); } -template -inline void LidarDriverImpl::regRecvCallback(const std::function& callback) +template +inline void LidarDriverImpl::regRecvCallback(const std::function& callback) { difop_pkt_cb_vec_.emplace_back(callback); } -template -inline void LidarDriverImpl::regRecvCallback(const std::function& callback) +template +inline void LidarDriverImpl::regRecvCallback(const std::function& callback) { camera_trigger_cb_vec_.emplace_back(callback); } -template -inline void LidarDriverImpl::regExceptionCallback(const std::function& callback) +template +inline void LidarDriverImpl::regExceptionCallback(const std::function& callback) { excb_.emplace_back(callback); } -template -inline bool LidarDriverImpl::getLidarTemperature(double& input_temperature) +template +inline bool LidarDriverImpl::getLidarTemperature(double& input_temperature) { if (lidar_decoder_ptr_ != nullptr) { @@ -259,11 +221,9 @@ inline bool LidarDriverImpl::getLidarTemperature(double& input_temperat return false; } -template -inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, PointCloudMsg& point_cloud_msg) +template +inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg) { - typename PointCloudMsg::PointCloudPtr output_point_cloud_ptr = - std::make_shared::PointCloud>(); if (!difop_flag_ && driver_param_.wait_for_difop) { ndifop_count_++; @@ -272,19 +232,19 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, Po reportError(Error(ERRCODE_NODIFOPRECV)); ndifop_count_ = 0; } - point_cloud_msg.point_cloud_ptr = output_point_cloud_ptr; std::this_thread::sleep_for(std::chrono::milliseconds(10)); return false; } - std::vector> pointcloud_one_frame; + std::vector pointcloud_one_frame; int height = 1; pointcloud_one_frame.resize(scan_msg.packets.size()); for (int i = 0; i < static_cast(scan_msg.packets.size()); i++) { - std::vector pointcloud_one_packet; - RSDecoderResult ret = - lidar_decoder_ptr_->processMsopPkt(scan_msg.packets[i].packet.data(), pointcloud_one_packet, height); + typename T_PointCloud::VectorT pointcloud_one_packet; + + RSDecoderResult ret = lidar_decoder_ptr_->processMsopPkt( + scan_msg.packets[i].packet.data(), pointcloud_one_packet, height); switch (ret) { case RSDecoderResult::DECODE_OK: @@ -303,19 +263,13 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, Po } for (auto iter : pointcloud_one_frame) { - output_point_cloud_ptr->insert(output_point_cloud_ptr->end(), iter.begin(), iter.end()); + point_cloud_msg.points.insert(point_cloud_msg.points.end(), iter.begin(), iter.end()); } - point_cloud_msg.point_cloud_ptr = point_cloud_transform_func_(output_point_cloud_ptr, height); point_cloud_msg.height = height; - point_cloud_msg.width = point_cloud_msg.point_cloud_ptr->size() / point_cloud_msg.height; - size_t iter_move = point_cloud_msg.point_cloud_ptr->size() - point_cloud_msg.height * point_cloud_msg.width; - for (size_t i = 0; i < iter_move; i++) - { - point_cloud_msg.point_cloud_ptr->erase(point_cloud_msg.point_cloud_ptr->end()); - } - setPointCloudMsgHeader(point_cloud_msg); + point_cloud_msg.width = point_cloud_msg.points.size() / point_cloud_msg.height; + setPointCloudHeader(point_cloud_msg); point_cloud_msg.timestamp = scan_msg.timestamp; - if (point_cloud_msg.point_cloud_ptr->size() == 0) + if (point_cloud_msg.points.size() == 0) { reportError(Error(ERRCODE_ZEROPOINTS)); return false; @@ -323,15 +277,15 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, Po return true; } -template -inline void LidarDriverImpl::decodeDifopPkt(const PacketMsg& msg) +template +inline void LidarDriverImpl::decodeDifopPkt(const PacketMsg& msg) { lidar_decoder_ptr_->processDifopPkt(msg.packet.data()); difop_flag_ = true; } -template -inline void LidarDriverImpl::runCallBack(const ScanMsg& msg) +template +inline void LidarDriverImpl::runCallBack(const ScanMsg& msg) { if (msg.seq != 0) { @@ -342,8 +296,8 @@ inline void LidarDriverImpl::runCallBack(const ScanMsg& msg) } } -template -inline void LidarDriverImpl::runCallBack(const PacketMsg& msg) +template +inline void LidarDriverImpl::runCallBack(const PacketMsg& msg) { for (auto& it : difop_pkt_cb_vec_) { @@ -351,8 +305,8 @@ inline void LidarDriverImpl::runCallBack(const PacketMsg& msg) } } -template -inline void LidarDriverImpl::runCallBack(const PointCloudMsg& msg) +template +inline void LidarDriverImpl::runCallBack(const T_PointCloud& msg) { if (msg.seq != 0) { @@ -363,8 +317,8 @@ inline void LidarDriverImpl::runCallBack(const PointCloudMsg& } } -template -inline void LidarDriverImpl::reportError(const Error& error) +template +inline void LidarDriverImpl::reportError(const Error& error) { for (auto& it : excb_) { @@ -372,8 +326,8 @@ inline void LidarDriverImpl::reportError(const Error& error) } } -template -inline void LidarDriverImpl::msopCallback(const PacketMsg& msg) +template +inline void LidarDriverImpl::msopCallback(const PacketMsg& msg) { if (msop_pkt_queue_.size() > MAX_PACKETS_BUFFER_SIZE) { @@ -399,8 +353,8 @@ inline void LidarDriverImpl::difopCallback(const PacketMsg& msg) } } -template -inline void LidarDriverImpl::processMsop() +template +inline void LidarDriverImpl::processMsop() { if (!difop_flag_ && driver_param_.wait_for_difop) { @@ -419,21 +373,16 @@ inline void LidarDriverImpl::processMsop() { PacketMsg pkt = msop_pkt_queue_.popFront(); int height = 1; - int ret = lidar_decoder_ptr_->processMsopPkt(pkt.packet.data(), *point_cloud_ptr_, height); + int ret = lidar_decoder_ptr_->processMsopPkt (pkt.packet.data(), point_cloud_.points, height); scan_ptr_->packets.emplace_back(pkt); if ((ret == DECODE_OK || ret == FRAME_SPLIT)) { if (ret == FRAME_SPLIT) { - PointCloudMsg msg(point_cloud_transform_func_(point_cloud_ptr_, height)); + T_PointCloud& msg = point_cloud_; msg.height = height; - msg.width = point_cloud_ptr_->size() / msg.height; - size_t iter_move = point_cloud_ptr_->size() - msg.height * msg.width; - for (size_t i = 0; i < iter_move; i++) - { - point_cloud_ptr_->erase(point_cloud_ptr_->end()); - } - setPointCloudMsgHeader(msg); + msg.width = msg.points.size() / msg.height; + setPointCloudHeader(msg); if (driver_param_.decoder_param.use_lidar_clock == true) { msg.timestamp = lidar_decoder_ptr_->getLidarTime(pkt.packet.data()); @@ -442,7 +391,8 @@ inline void LidarDriverImpl::processMsop() { msg.timestamp = getTime(); } - if (msg.point_cloud_ptr->size() == 0) + + if (msg.points.size() == 0) { reportError(Error(ERRCODE_ZEROPOINTS)); } @@ -450,16 +400,18 @@ inline void LidarDriverImpl::processMsop() { runCallBack(msg); } + setScanMsgHeader(*scan_ptr_); runCallBack(*scan_ptr_); - point_cloud_ptr_.reset(new typename PointCloudMsg::PointCloud); scan_ptr_.reset(new ScanMsg); + + point_cloud_.points.resize(0); } } else if (ret == DISCARD_PKT) { scan_ptr_->packets.clear(); - point_cloud_ptr_.reset(new typename PointCloudMsg::PointCloud); + point_cloud_.points.resize(0); } else { @@ -471,8 +423,8 @@ inline void LidarDriverImpl::processMsop() msop_pkt_queue_.is_task_finished_.store(true); } -template -inline void LidarDriverImpl::localCameraTriggerCallback(const CameraTrigger& msg) +template +inline void LidarDriverImpl::localCameraTriggerCallback(const CameraTrigger& msg) { for (auto& it : camera_trigger_cb_vec_) { @@ -480,8 +432,8 @@ inline void LidarDriverImpl::localCameraTriggerCallback(const CameraTri } } -template -inline void LidarDriverImpl::processDifop() +template +inline void LidarDriverImpl::processDifop() { while (difop_pkt_queue_.size() > 0) { @@ -492,8 +444,8 @@ inline void LidarDriverImpl::processDifop() difop_pkt_queue_.is_task_finished_.store(true); } -template -inline void LidarDriverImpl::setScanMsgHeader(ScanMsg& msg) +template +inline void LidarDriverImpl::setScanMsgHeader(ScanMsg& msg) { msg.timestamp = getTime(); if (driver_param_.decoder_param.use_lidar_clock == true) @@ -504,8 +456,8 @@ inline void LidarDriverImpl::setScanMsgHeader(ScanMsg& msg) msg.frame_id = driver_param_.frame_id; } -template -inline void LidarDriverImpl::setPointCloudMsgHeader(PointCloudMsg& msg) +template +inline void LidarDriverImpl::setPointCloudHeader(T_PointCloud& msg) { msg.seq = point_cloud_seq_++; msg.frame_id = driver_param_.frame_id; From 3668d2c55f9bcdb6c274572bb72da5c39b2ef41c Mon Sep 17 00:00:00 2001 From: ronzheng Date: Thu, 28 Oct 2021 12:25:01 +0800 Subject: [PATCH 002/379] feat: disalbe scan msg --- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 2 + src/rs_driver/driver/lidar_driver_impl.hpp | 6 ++ src/rs_driver/msg/point_cloud_msg.h | 64 ------------------- src/rs_driver/utility/thread_pool.hpp | 2 +- 4 files changed, 9 insertions(+), 65 deletions(-) delete mode 100644 src/rs_driver/msg/point_cloud_msg.h diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index b670149a..320ea277 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -194,7 +194,9 @@ inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* p this->lidar_const_param_.RX * this->checkSinTable(angle_horiz); float z = distance * this->checkSinTable(angle_vert) + this->lidar_const_param_.RZ; uint8_t intensity = mpkt_ptr->blocks[blk_idx].channels[channel_idx].intensity; +#if 0 this->transformPoint(x, y, z); +#endif setX(point, x); setY(point, y); setZ(point, z); diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 4a163858..1f7a3763 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -374,7 +374,9 @@ inline void LidarDriverImpl::processMsop() PacketMsg pkt = msop_pkt_queue_.popFront(); int height = 1; int ret = lidar_decoder_ptr_->processMsopPkt (pkt.packet.data(), point_cloud_.points, height); +#if 0 scan_ptr_->packets.emplace_back(pkt); +#endif if ((ret == DECODE_OK || ret == FRAME_SPLIT)) { if (ret == FRAME_SPLIT) @@ -401,16 +403,20 @@ inline void LidarDriverImpl::processMsop() runCallBack(msg); } +#if 0 setScanMsgHeader(*scan_ptr_); runCallBack(*scan_ptr_); scan_ptr_.reset(new ScanMsg); +#endif point_cloud_.points.resize(0); } } else if (ret == DISCARD_PKT) { +#if 0 scan_ptr_->packets.clear(); +#endif point_cloud_.points.resize(0); } else diff --git a/src/rs_driver/msg/point_cloud_msg.h b/src/rs_driver/msg/point_cloud_msg.h deleted file mode 100644 index 884b2a82..00000000 --- a/src/rs_driver/msg/point_cloud_msg.h +++ /dev/null @@ -1,64 +0,0 @@ -/********************************************************************************************************************* -Copyright (c) 2020 RoboSense -All rights reserved - -By downloading, copying, installing or using the software you agree to this license. If you do not agree to this -license, do not download, install, copy or use the software. - -License Agreement -For RoboSense LiDAR SDK Library -(3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials provided with the distribution. - -3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used -to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*********************************************************************************************************************/ - -#pragma once -#include -namespace robosense -{ -namespace lidar -{ -template -#ifdef _MSC_VER -struct __declspec(align(16)) PointCloudMsg -#elif __GNUC__ -struct __attribute__((aligned(16))) PointCloudMsg -#endif -{ - typedef std::vector PointCloud; - typedef std::shared_ptr PointCloudPtr; - typedef std::shared_ptr PointCloudConstPtr; - double timestamp = 0.0; - std::string frame_id = ""; ///< Point cloud frame id - uint32_t seq = 0; ///< Sequence number of message - uint32_t height = 0; ///< Height of point cloud - uint32_t width = 0; ///< Width of point cloud - bool is_dense = false; ///< If is_dense=true, the point cloud does not contain NAN points - PointCloudPtr point_cloud_ptr; ///< Point cloud pointer - PointCloudMsg() = default; - explicit PointCloudMsg(const PointCloudPtr& ptr) : point_cloud_ptr(ptr) - { - } - typedef std::shared_ptr Ptr; - typedef std::shared_ptr ConstPtr; -}; -} // namespace lidar -} // namespace robosense diff --git a/src/rs_driver/utility/thread_pool.hpp b/src/rs_driver/utility/thread_pool.hpp index a581cd1e..00264a9d 100644 --- a/src/rs_driver/utility/thread_pool.hpp +++ b/src/rs_driver/utility/thread_pool.hpp @@ -36,7 +36,7 @@ namespace robosense { namespace lidar { -constexpr uint16_t MAX_THREAD_NUM = 4; +constexpr uint16_t MAX_THREAD_NUM = 2; struct Thread { Thread() : start_(false) From 20566a0f5a1034a44111e980408dd33d37bc0490 Mon Sep 17 00:00:00 2001 From: ronzheng Date: Sat, 30 Oct 2021 10:25:43 +0800 Subject: [PATCH 003/379] feat: change Input classes --- CMakeLists.txt | 5 + demo/demo_online.cpp | 7 +- src/rs_driver/driver/decoder/decoder_base.hpp | 13 +- .../driver/decoder/decoder_factory.hpp | 21 +- src/rs_driver/driver/input.hpp | 521 ------------------ src/rs_driver/driver/input/input.hpp | 139 +++++ src/rs_driver/driver/input/input_factory.hpp | 113 ++++ src/rs_driver/driver/input/pcap_input.hpp | 179 ++++++ src/rs_driver/driver/input/sock_input.hpp | 252 +++++++++ src/rs_driver/driver/lidar_driver_impl.hpp | 253 +++++---- src/rs_driver/msg/packet_msg.h | 37 +- src/rs_driver/utility/dbg.h | 55 ++ src/rs_driver/utility/lock_queue.h | 56 +- 13 files changed, 981 insertions(+), 670 deletions(-) delete mode 100644 src/rs_driver/driver/input.hpp create mode 100644 src/rs_driver/driver/input/input.hpp create mode 100644 src/rs_driver/driver/input/input_factory.hpp create mode 100644 src/rs_driver/driver/input/pcap_input.hpp create mode 100644 src/rs_driver/driver/input/sock_input.hpp create mode 100644 src/rs_driver/utility/dbg.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 3afacd5e..65f6aa5e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -17,6 +17,7 @@ option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) #============================= # Compile Demos&Tools #============================= +option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) option(ENABLE_TRANSFORM "Enable transform functions" OFF) #======================== @@ -119,6 +120,10 @@ if(${ENABLE_TRANSFORM}) message(=============================================================) endif(${ENABLE_TRANSFORM}) +if(${ENABLE_HIGH_PRIORITY_THREAD}) + add_definitions("-DENABLE_HIGH_PRIORITY_THREAD") +endif(${ENABLE_HIGH_PRIORITY_THREAD}) + #======================== # Build Demos #======================== diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index a9494ce8..60cfc7da 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -75,18 +75,17 @@ int main(int argc, char* argv[]) << RSLIDAR_VERSION_PATCH << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; - std::shared_ptr> driver_ = std::make_shared>(); - LidarDriver& driver = *driver_; - RSDriverParam param; ///< Create a parameter object param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 param.lidar_type = LidarType::RSBP; ///< Set the lidar type. Make sure this type is correct + param.angle_path = "/mnt/share/channel_bp/angle.csv"; param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet param.print(); - driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver + LidarDriver driver; driver.regRecvCallback(pointCloudCallback); ///< Register the point cloud callback function into the driver + driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver if (!driver.init(param)) ///< Call the init function and pass the parameter { RS_ERROR << "Driver Initialize Error..." << RS_REND; diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 566b66cf..48db234d 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -309,7 +309,7 @@ class DecoderBase void sortBeamTable(); private: - std::vector initTrigonometricLookupTable(const std::function& func); + std::vector initTrigonometricLookupTable(const std::function& func); protected: const LidarConstantParameter lidar_const_param_; @@ -341,8 +341,8 @@ class DecoderBase float lidar_Rxy_; // sqrt(Rx*Rx + Ry*Ry) private: - std::vector cos_lookup_table_; - std::vector sin_lookup_table_; + std::vector cos_lookup_table_; + std::vector sin_lookup_table_; }; template @@ -896,14 +896,15 @@ inline float DecoderBase::checkSinTable(const int& angle) } template -inline std::vector +inline std::vector DecoderBase::initTrigonometricLookupTable(const std::function& func) { - std::vector temp_table = std::vector(2 * RS_ONE_ROUND, 0.0); + std::vector temp_table = std::vector(2 * RS_ONE_ROUND, 0.0); + for (int i = 0; i < 2 * RS_ONE_ROUND; i++) { const double rad = RS_TO_RADS(static_cast(i - RS_ONE_ROUND) * RS_ANGLE_RESOLUTION); - temp_table[i] = func(rad); + temp_table[i] = (float)func(rad); } return temp_table; } diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 5f8724d3..958059a6 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -38,7 +38,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include +#include #include namespace robosense { @@ -255,5 +255,24 @@ inline const LidarConstantParameter DecoderFactory::getRSROCKConstantPa return ret_param; } +void getLidarPktLength(uint8_t type, uint32_t* msop_pkt_len, uint32_t* difop_pkt_len) +{ + switch (type) + { + case LidarType::RSM1: + *msop_pkt_len = MEMS_MSOP_LEN; + *difop_pkt_len = MEMS_DIFOP_LEN; + break; + case LidarType::RSROCK: + *msop_pkt_len = 1236; // TODO + *difop_pkt_len = MECH_PKT_LEN; + break; + default: + *msop_pkt_len = MECH_PKT_LEN; + *difop_pkt_len = MECH_PKT_LEN; + break; + } +} + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/input.hpp b/src/rs_driver/driver/input.hpp deleted file mode 100644 index 27b638d6..00000000 --- a/src/rs_driver/driver/input.hpp +++ /dev/null @@ -1,521 +0,0 @@ -/********************************************************************************************************************* -Copyright (c) 2020 RoboSense -All rights reserved - -By downloading, copying, installing or using the software you agree to this license. If you do not agree to this -license, do not download, install, copy or use the software. - -License Agreement -For RoboSense LiDAR SDK Library -(3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials provided with the distribution. - -3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used -to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*********************************************************************************************************************/ - -#pragma once -#include -#include -#include -#include -#include -///< 1.0 second / 10 Hz / (360 degree / horiz angle resolution / column per msop packet) * (s to us) -constexpr double RS16_PCAP_SLEEP_DURATION = 1200; ///< us -constexpr double RS32_PCAP_SLEEP_DURATION = 530; ///< us -constexpr double RSBP_PCAP_SLEEP_DURATION = 530; ///< us -constexpr double RS128_PCAP_SLEEP_DURATION = 100; ///< us -constexpr double RS80_PCAP_SLEEP_DURATION = 135; ///< us -constexpr double RSM1_PCAP_SLEEP_DURATION = 90; ///< us -constexpr double RSHELIOS_PCAP_SLEEP_DURATION = 530; ///< us -constexpr double RSROCK_PCAP_SLEEP_DURATION = 530; ///< us TODO -using boost::asio::deadline_timer; -using boost::asio::ip::address; -using boost::asio::ip::udp; - -namespace robosense -{ -namespace lidar -{ -class Input -{ -public: - Input(const LidarType& type, const RSInputParam& input_param, const std::function& excb); - ~Input(); - bool init(); - bool start(); - void stop(); - void regRecvMsopCallback(const std::function& callback); - void regRecvDifopCallback(const std::function& callback); - -private: - inline bool setSocket(const std::string& pkt_type); - inline void getMsopPacket(); - inline void getDifopPacket(); - inline void getPcapPacket(); - inline void checkDifopDeadline(); - inline void checkMsopDeadline(); - static void handleReceive(const boost::system::error_code& ec, std::size_t length, boost::system::error_code* out_ec, - std::size_t* out_length); - -private: - LidarType lidar_type_; - RSInputParam input_param_; - std::function excb_; - bool init_flag_; - uint32_t msop_pkt_length_; - uint32_t difop_pkt_length_; - /* pcap file parse */ - pcap_t* pcap_; - bpf_program pcap_msop_filter_; - bpf_program pcap_difop_filter_; - std::chrono::time_point last_packet_time_; - /* live socket */ - std::unique_ptr msop_sock_ptr_; - std::unique_ptr difop_sock_ptr_; - std::unique_ptr msop_deadline_; - std::unique_ptr difop_deadline_; - Thread msop_thread_; - Thread difop_thread_; - Thread pcap_thread_; - int vlan_offset_; - int someip_offset_; - int pcap_offset_; - boost::asio::io_service msop_io_service_; - boost::asio::io_service difop_io_service_; - std::vector> difop_cb_; - std::vector> msop_cb_; -}; - -inline Input::Input(const LidarType& type, const RSInputParam& input_param, - const std::function& excb) - : lidar_type_(type) - , input_param_(input_param) - , excb_(excb) - , init_flag_(false) - , pcap_(nullptr) - , vlan_offset_(0) - , someip_offset_(0) - , pcap_offset_(42) -{ - last_packet_time_ = std::chrono::system_clock::now(); - input_param_.pcap_rate = input_param_.pcap_rate < 0.1 ? 0.1 : input_param_.pcap_rate; - switch (type) - { - case LidarType::RSM1: - msop_pkt_length_ = MEMS_MSOP_LEN; - difop_pkt_length_ = MEMS_DIFOP_LEN; - break; - case LidarType::RSROCK: - msop_pkt_length_ = 1236; // TODO - difop_pkt_length_ = MECH_PKT_LEN; - break; - default: - msop_pkt_length_ = MECH_PKT_LEN; - difop_pkt_length_ = MECH_PKT_LEN; - break; - } - if (input_param_.use_vlan) - { - vlan_offset_ = 4; - } - if (input_param_.use_someip) - { - someip_offset_ = 16; - } -} - -inline Input::~Input() -{ - stop(); - if (pcap_ != NULL) - { - pcap_close(pcap_); - } - msop_sock_ptr_.reset(); - difop_sock_ptr_.reset(); - msop_deadline_.reset(); - difop_deadline_.reset(); -} - -inline bool Input::init() -{ - if (input_param_.read_pcap) - { - char errbuf[PCAP_ERRBUF_SIZE]; - if ((pcap_ = pcap_open_offline(input_param_.pcap_path.c_str(), errbuf)) == NULL) - { - excb_(Error(ERRCODE_PCAPWRONGPATH)); - return false; - } - else - { - std::stringstream msop_filter; - std::stringstream difop_filter; - /*ip address filter*/ - // msop_filter << "src host " << input_param_.device_ip << " && "; - // difop_filter << "src host " << input_param_.device_ip << " && "; - if (input_param_.use_vlan) - { - msop_filter << "vlan && "; - difop_filter << "vlan && "; - } - msop_filter << "udp dst port " << input_param_.msop_port; - difop_filter << "udp dst port " << input_param_.difop_port; - pcap_compile(pcap_, &pcap_msop_filter_, msop_filter.str().c_str(), 1, 0xFFFFFFFF); - pcap_compile(pcap_, &pcap_difop_filter_, difop_filter.str().c_str(), 1, 0xFFFFFFFF); - pcap_offset_ += vlan_offset_ + someip_offset_; - } - } - else - { - if (!setSocket("msop") || !setSocket("difop")) - { - return false; - } - } - init_flag_ = true; - return true; -} - -inline bool Input::start() -{ - if (!init_flag_) - { - excb_(Error(ERRCODE_STARTBEFOREINIT)); - return false; - } - if (!input_param_.read_pcap) - { - msop_thread_.start_.store(true); - difop_thread_.start_.store(true); - msop_thread_.thread_.reset(new std::thread([this]() { getMsopPacket(); })); - difop_thread_.thread_.reset(new std::thread([this]() { getDifopPacket(); })); - } - else - { - pcap_thread_.start_.store(true); - pcap_thread_.thread_.reset(new std::thread([this]() { getPcapPacket(); })); - } - return true; -} - -inline void Input::stop() -{ - if (!input_param_.read_pcap) - { - msop_thread_.start_.store(false); - difop_thread_.start_.store(false); - if (msop_thread_.thread_ != nullptr && msop_thread_.thread_->joinable()) - { - msop_thread_.thread_->join(); - } - if (difop_thread_.thread_ != nullptr && difop_thread_.thread_->joinable()) - { - difop_thread_.thread_->join(); - } - } - else - { - pcap_thread_.start_.store(false); - if (pcap_thread_.thread_ != nullptr && pcap_thread_.thread_->joinable()) - { - pcap_thread_.thread_->join(); - } - } -} - -inline void Input::regRecvMsopCallback(const std::function& callback) -{ - msop_cb_.emplace_back(callback); -} - -inline void Input::regRecvDifopCallback(const std::function& callback) -{ - difop_cb_.emplace_back(callback); -} - -inline bool Input::setSocket(const std::string& pkt_type) -{ - if (pkt_type == "msop") - { - try - { - msop_sock_ptr_.reset(new udp::socket(msop_io_service_, udp::endpoint(udp::v4(), input_param_.msop_port))); - msop_deadline_.reset(new deadline_timer(msop_io_service_)); - } - catch (...) - { - excb_(Error(ERRCODE_MSOPPORTBUZY)); - return false; - } - if (input_param_.multi_cast_address != "0.0.0.0") - { - msop_sock_ptr_->set_option( - boost::asio::ip::multicast::join_group(address::from_string(input_param_.multi_cast_address).to_v4(), - udp::endpoint(udp::v4(), input_param_.msop_port).address().to_v4())); - } - msop_deadline_->expires_at(boost::posix_time::pos_infin); - checkMsopDeadline(); - } - else if (pkt_type == "difop") - { - try - { - difop_sock_ptr_.reset(new udp::socket(difop_io_service_, udp::endpoint(udp::v4(), input_param_.difop_port))); - difop_deadline_.reset(new deadline_timer(difop_io_service_)); - } - catch (...) - { - excb_(Error(ERRCODE_DIFOPPORTBUZY)); - return false; - } - if (input_param_.multi_cast_address != "0.0.0.0") - { - difop_sock_ptr_->set_option( - boost::asio::ip::multicast::join_group(address::from_string(input_param_.multi_cast_address).to_v4(), - udp::endpoint(udp::v4(), input_param_.difop_port).address().to_v4())); - } - difop_deadline_->expires_at(boost::posix_time::pos_infin); - checkDifopDeadline(); - } - return true; -} - -inline void Input::getMsopPacket() -{ - char* precv_buffer = (char*)malloc(msop_pkt_length_ + someip_offset_); - while (msop_thread_.start_.load()) - { - msop_deadline_->expires_from_now(boost::posix_time::seconds(1)); - boost::system::error_code ec = boost::asio::error::would_block; - std::size_t ret = 0; - - msop_sock_ptr_->async_receive(boost::asio::buffer(precv_buffer, msop_pkt_length_ + someip_offset_), - boost::bind(&Input::handleReceive, _1, _2, &ec, &ret)); - do - { - msop_io_service_.run_one(); - } while (ec == boost::asio::error::would_block); - if (ec) - { - excb_(Error(ERRCODE_MSOPTIMEOUT)); - continue; - } - - // use_someip, the msop and difop port are the same. - if (input_param_.use_someip && ret == difop_pkt_length_ + someip_offset_) - { - PacketMsg msg(difop_pkt_length_); - memcpy(msg.packet.data(), precv_buffer + someip_offset_, difop_pkt_length_); - for (auto& iter : difop_cb_) - { - iter(msg); - } - continue; - } - - if (ret < msop_pkt_length_ + someip_offset_) - { - excb_(Error(ERRCODE_MSOPINCOMPLETE)); - continue; - } - - PacketMsg msg(msop_pkt_length_); - memcpy(msg.packet.data(), precv_buffer + someip_offset_, msop_pkt_length_); - for (auto& iter : msop_cb_) - { - iter(msg); - } - } - free(precv_buffer); -} - -inline void Input::getDifopPacket() -{ - if (!input_param_.use_someip) - { - char* precv_buffer = (char*)malloc(difop_pkt_length_); - while (difop_thread_.start_.load()) - { - difop_deadline_->expires_from_now(boost::posix_time::seconds(2)); - boost::system::error_code ec = boost::asio::error::would_block; - std::size_t ret = 0; - - difop_sock_ptr_->async_receive(boost::asio::buffer(precv_buffer, difop_pkt_length_), - boost::bind(&Input::handleReceive, _1, _2, &ec, &ret)); - do - { - difop_io_service_.run_one(); - } while (ec == boost::asio::error::would_block); - if (ec) - { - excb_(Error(ERRCODE_DIFOPTIMEOUT)); - continue; - } - if (ret < difop_pkt_length_) - { - excb_(Error(ERRCODE_DIFOPINCOMPLETE)); - continue; - } - PacketMsg msg(difop_pkt_length_); - memcpy(msg.packet.data(), precv_buffer, difop_pkt_length_); - for (auto& iter : difop_cb_) - { - iter(msg); - } - } - free(precv_buffer); - } -} - -inline void Input::getPcapPacket() -{ - while (pcap_thread_.start_.load()) - { - struct pcap_pkthdr* header; - const u_char* pkt_data; - if (pcap_next_ex(pcap_, &header, &pkt_data) >= 0) - { - if (pcap_offline_filter(&pcap_msop_filter_, header, pkt_data) != 0) - { - if (header->len == msop_pkt_length_ + pcap_offset_) - { - PacketMsg msg(msop_pkt_length_); - memcpy(msg.packet.data(), pkt_data + pcap_offset_, msop_pkt_length_); - for (auto& iter : msop_cb_) - { - iter(msg); - } - } - else if (input_param_.use_someip && header->len == difop_pkt_length_ + pcap_offset_) // the someip case - { - PacketMsg msg(difop_pkt_length_); - memcpy(msg.packet.data(), pkt_data + pcap_offset_, difop_pkt_length_); - for (auto& iter : difop_cb_) - { - iter(msg); - } - } - else - { - continue; - } - } - else if (pcap_offline_filter(&pcap_difop_filter_, header, pkt_data) != 0) - { - PacketMsg msg(difop_pkt_length_); - memcpy(msg.packet.data(), pkt_data + pcap_offset_, difop_pkt_length_); - for (auto& iter : difop_cb_) - { - iter(msg); - } - } - else - { - continue; - } - } - else - { - if (input_param_.pcap_repeat) - { - excb_(Error(ERRCODE_PCAPREPEAT)); - char errbuf[PCAP_ERRBUF_SIZE]; - pcap_ = pcap_open_offline(input_param_.pcap_path.c_str(), errbuf); - } - else - { - excb_(Error(ERRCODE_PCAPEXIT)); - break; - } - } - - if (!pcap_thread_.start_.load()) - { - break; - } - - auto time2go = last_packet_time_; - switch (lidar_type_) - { - case LidarType::RS16: - time2go += std::chrono::microseconds(static_cast(RS16_PCAP_SLEEP_DURATION / input_param_.pcap_rate)); - break; - case LidarType::RS32: - time2go += std::chrono::microseconds(static_cast(RS32_PCAP_SLEEP_DURATION / input_param_.pcap_rate)); - break; - case LidarType::RSBP: - time2go += std::chrono::microseconds(static_cast(RSBP_PCAP_SLEEP_DURATION / input_param_.pcap_rate)); - break; - case LidarType::RS128: - time2go += - std::chrono::microseconds(static_cast(RS128_PCAP_SLEEP_DURATION / input_param_.pcap_rate)); - break; - case LidarType::RS80: - time2go += std::chrono::microseconds(static_cast(RS80_PCAP_SLEEP_DURATION / input_param_.pcap_rate)); - break; - case LidarType::RSM1: - time2go += std::chrono::microseconds(static_cast(RSM1_PCAP_SLEEP_DURATION / input_param_.pcap_rate)); - break; - case LidarType::RSHELIOS: - time2go += - std::chrono::microseconds(static_cast(RSHELIOS_PCAP_SLEEP_DURATION / input_param_.pcap_rate)); - case LidarType::RSROCK: - time2go += - std::chrono::microseconds(static_cast(RSROCK_PCAP_SLEEP_DURATION / input_param_.pcap_rate)); - break; - - default: - break; - } - std::this_thread::sleep_until(time2go); - last_packet_time_ = std::chrono::system_clock::now(); - } -} // namespace lidar - -inline void Input::checkDifopDeadline() -{ - if (difop_deadline_->expires_at() <= deadline_timer::traits_type::now()) - { - difop_sock_ptr_->cancel(); - difop_deadline_->expires_at(boost::posix_time::pos_infin); - } - difop_deadline_->async_wait(boost::bind(&Input::checkDifopDeadline, this)); -} - -inline void Input::checkMsopDeadline() -{ - if (msop_deadline_->expires_at() <= deadline_timer::traits_type::now()) - { - msop_sock_ptr_->cancel(); - msop_deadline_->expires_at(boost::posix_time::pos_infin); - } - msop_deadline_->async_wait(boost::bind(&Input::checkMsopDeadline, this)); -} - -inline void Input::handleReceive(const boost::system::error_code& ec, std::size_t length, - boost::system::error_code* out_ec, std::size_t* out_length) -{ - *out_ec = ec; - *out_length = length; -} - -} // namespace lidar -} // namespace robosense diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp new file mode 100644 index 00000000..b8b23be2 --- /dev/null +++ b/src/rs_driver/driver/input/input.hpp @@ -0,0 +1,139 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#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 + +#define MAX_ETH_LEN 1500 +#define ETH_HDR_LEN 42 +#define VLAN_LEN 16 +#define SOME_IP_LEN 16 + +namespace robosense +{ +namespace lidar +{ + +class Input +{ +public: + + Input(const RSInputParam& input_param, const std::function& excb); + + void regRecvCallback(const std::function(size_t)>& cb_get, + const std::function)>& cb_put_msop, + const std::function)>& cb_put_difop); + + virtual bool init() = 0; + virtual bool start() = 0; + virtual void stop(); + virtual ~Input() {} + +protected: + + inline void pushPacket (std::shared_ptr pkt); + + RSInputParam input_param_; + std::function(size_t size)> cb_get_; + std::function)> cb_put_msop_; + std::function)> cb_put_difop_; + std::function excb_; + std::thread recv_thread_; + bool to_exit_recv_; + bool init_flag_; +}; + +inline Input::Input(const RSInputParam& input_param, + const std::function& excb) + : input_param_(input_param), excb_(excb), to_exit_recv_(false), init_flag_(false) +{ +} + +void Input::regRecvCallback(const std::function(size_t)>& cb_get, + const std::function)>& cb_put_msop, + const std::function)>& cb_put_difop) +{ + cb_get_ = cb_get; + cb_put_msop_ = cb_put_msop; + cb_put_difop_ = cb_put_difop; +} + +inline void Input::stop() +{ + to_exit_recv_ = true; + recv_thread_.join(); +} + +inline void Input::pushPacket (std::shared_ptr pkt) +{ + uint8_t* id = pkt->data(); + if (*id == 0x55) + { + cb_put_msop_(pkt); + } + else if (*id == 0xA5) + { + cb_put_difop_(pkt); + } +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp new file mode 100644 index 00000000..38e93468 --- /dev/null +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -0,0 +1,113 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#include +#include +#include + +namespace robosense +{ +namespace lidar +{ + +long long msecToDelay(LidarType type, double replay_rate) +{ + constexpr double RS16_PCAP_SLEEP_DURATION = 1200; ///< us + constexpr double RS32_PCAP_SLEEP_DURATION = 530; ///< us + constexpr double RSBP_PCAP_SLEEP_DURATION = 530; ///< us + constexpr double RS128_PCAP_SLEEP_DURATION = 100; ///< us + constexpr double RS80_PCAP_SLEEP_DURATION = 135; ///< us + constexpr double RSM1_PCAP_SLEEP_DURATION = 90; ///< us + constexpr double RSHELIOS_PCAP_SLEEP_DURATION = 530; ///< us + constexpr double RSROCK_PCAP_SLEEP_DURATION = 530; ///< us TODO + + double duration; + switch (type) + { + case LidarType::RS16: + duration = RS16_PCAP_SLEEP_DURATION; + break; + case LidarType::RS32: + duration = RS32_PCAP_SLEEP_DURATION; + break; + case LidarType::RSBP: + duration = RSBP_PCAP_SLEEP_DURATION; + break; + case LidarType::RS128: + duration = RS128_PCAP_SLEEP_DURATION; + break; + case LidarType::RS80: + duration = RS80_PCAP_SLEEP_DURATION; + break; + case LidarType::RSM1: + duration = RSM1_PCAP_SLEEP_DURATION; + break; + case LidarType::RSHELIOS: + duration = RSHELIOS_PCAP_SLEEP_DURATION; + break; + case LidarType::RSROCK: + default: + duration = RSROCK_PCAP_SLEEP_DURATION; + break; + } + + return static_cast(duration / replay_rate); +} + +class InputFactory +{ +public: + static std::shared_ptr createInput( + const RSDriverParam& driver_param, const std::function& excb); +}; + +inline std::shared_ptr InputFactory::createInput( + const RSDriverParam& driver_param, const std::function& excb) +{ + const RSInputParam& input_param = driver_param.input_param; + std::shared_ptr input; + + if (input_param.read_pcap) + { + long long msec = msecToDelay(driver_param.lidar_type, input_param.pcap_rate); + input = std::make_shared(input_param, excb, msec); + } + else + { + input = std::make_shared(input_param, excb); + } + + return input; +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/input/pcap_input.hpp b/src/rs_driver/driver/input/pcap_input.hpp new file mode 100644 index 00000000..70220384 --- /dev/null +++ b/src/rs_driver/driver/input/pcap_input.hpp @@ -0,0 +1,179 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include "input.hpp" + +namespace robosense +{ +namespace lidar +{ + +class PcapInput : public Input +{ +public: + + PcapInput(const RSInputParam& input_param, + const std::function& excb, long long msec_to_delay) + : Input (input_param, excb), + pcap_offset_(ETH_HDR_LEN), difop_filter_valid_(false), msec_to_delay_(msec_to_delay) + { + if (input_param.use_vlan) + pcap_offset_ += VLAN_LEN; + if (input_param.use_someip) + pcap_offset_ += SOME_IP_LEN; + + std::stringstream msop_stream, difop_stream; + if (input_param_.use_vlan) + { + msop_stream << "vlan && "; + difop_stream << "vlan && "; + } + + msop_stream << "udp dst port " << input_param_.msop_port; + difop_stream << "udp dst port " << input_param_.difop_port; + + msop_filter_str_ = msop_stream.str(); + difop_filter_str_ = difop_stream.str(); + } + + virtual bool init(); + virtual bool start(); + virtual ~PcapInput(); + +private: + void recvPacket(); + +private: + pcap_t* pcap_; + size_t pcap_offset_; + std::string msop_filter_str_; + std::string difop_filter_str_; + bpf_program msop_filter_; + bpf_program difop_filter_; + bool difop_filter_valid_; + long long msec_to_delay_; +}; + +inline bool PcapInput::init() +{ + char errbuf[PCAP_ERRBUF_SIZE]; + pcap_ = pcap_open_offline(input_param_.pcap_path.c_str(), errbuf); + if (pcap_ == NULL) + { + excb_(Error(ERRCODE_PCAPWRONGPATH)); + return false; + } + + pcap_compile(pcap_, &msop_filter_, msop_filter_str_.c_str(), 1, 0xFFFFFFFF); + + if ((input_param_.difop_port != 0) && (input_param_.difop_port != input_param_.msop_port)) + { + pcap_compile(pcap_, &difop_filter_, difop_filter_str_.c_str(), 1, 0xFFFFFFFF); + difop_filter_valid_ = true; + } + + init_flag_ = true; + return true; +} + +inline bool PcapInput::start() +{ + if (!init_flag_) + { + excb_(Error(ERRCODE_STARTBEFOREINIT)); + return false; + } + + recv_thread_ = std::thread (std::bind(&PcapInput::recvPacket, this)); + + return true; +} + +inline PcapInput::~PcapInput() +{ + stop(); + + if (pcap_ != NULL) + pcap_close(pcap_); +} + +inline void PcapInput::recvPacket() +{ + while (!to_exit_recv_) + { + struct pcap_pkthdr* header; + const u_char* pkt_data; + int ret = pcap_next_ex(pcap_, &header, &pkt_data); + if (ret < 0) // reach file end. + { + if (input_param_.pcap_repeat) + { + excb_(Error(ERRCODE_PCAPREPEAT)); + + char errbuf[PCAP_ERRBUF_SIZE]; + pcap_ = pcap_open_offline(input_param_.pcap_path.c_str(), errbuf); + continue; + } + else + { + excb_(Error(ERRCODE_PCAPEXIT)); + break; + } + } + + if (pcap_offline_filter(&msop_filter_, header, pkt_data) != 0) + { + std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); + memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_); + pkt->setData(0, header->len - pcap_offset_); + pushPacket (pkt); + } + else if (difop_filter_valid_ && + (pcap_offline_filter(&difop_filter_, header, pkt_data) != 0)) + { + std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); + memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_); + pkt->setData(0, header->len - pcap_offset_); + pushPacket (pkt); + } + else + { + continue; + } + + std::this_thread::sleep_for(std::chrono::microseconds(msec_to_delay_)); + } +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp new file mode 100644 index 00000000..0373c067 --- /dev/null +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -0,0 +1,252 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include "input.hpp" + +namespace robosense +{ +namespace lidar +{ + +class SockInput : public Input +{ +public: + + SockInput(const RSInputParam& input_param, const std::function& excb) + : Input (input_param, excb), sock_offset_(0) + { + if (input_param.use_someip) + sock_offset_ += SOME_IP_LEN; + } + + virtual bool init(); + virtual bool start(); + virtual ~SockInput(); + +private: + + inline void recvPacket(); + inline void higherThreadPrioty(std::thread::native_handle_type handle); + inline int createSocket(uint16_t port, const std::string& ip); + +private: + int fds_[2]; + size_t sock_offset_; +}; + +inline void SockInput::higherThreadPrioty(std::thread::native_handle_type handle) +{ +#ifdef ENABLE_HIGH_PRIORITY_THREAD + int policy; + sched_param sch; + pthread_getschedparam (handle, &policy, &sch); + + sch.sched_priority = 63; + if (pthread_setschedparam (handle, SCHED_RR, &sch)) + { + std::cout << "setschedparam failed: " << std::strerror(errno) << '\n'; + } +#endif +} + +inline bool SockInput::init() +{ + if (init_flag_) + return true; + + int msop_fd = -1, difop_fd = -1; + + msop_fd = createSocket (input_param_.msop_port, input_param_.multi_cast_address); + if (msop_fd < 0) + goto failMsop; + + if ((input_param_.difop_port != 0) && (input_param_.difop_port != input_param_.msop_port)) + { + difop_fd = createSocket (input_param_.difop_port, input_param_.multi_cast_address); + if (difop_fd < 0) + goto failDifop; + } + + fds_[0] = msop_fd; + fds_[1] = difop_fd; + + init_flag_ = true; + return true; + +failDifop: + close(msop_fd); +failMsop: + return false; +} + +inline bool SockInput::start() +{ + if (!init_flag_) + { + excb_(Error(ERRCODE_STARTBEFOREINIT)); + return false; + } + + recv_thread_ = std::thread (std::bind(&SockInput::recvPacket, this)); + + higherThreadPrioty (recv_thread_.native_handle()); + + return true; +} + +inline SockInput::~SockInput() +{ + stop(); + + close(fds_[0]); + if (fds_[1] >= 0) + close(fds_[1]); +} + +inline int SockInput::createSocket(uint16_t port, const std::string& ip) +{ + int fd; + int flags; + int ret; + + fd = socket(PF_INET, SOCK_DGRAM, 0); + if (fd < 0) + { + std::cerr << "socket: " << std::strerror(errno) << std::endl; + goto failSocket; + } + + struct sockaddr_in my_addr; + memset((char*)&my_addr, 0, sizeof(my_addr)); + my_addr.sin_family = AF_INET; + my_addr.sin_port = htons(port); + my_addr.sin_addr.s_addr = INADDR_ANY; + + ret = bind(fd, (struct sockaddr*)&my_addr, sizeof(my_addr)); + if (ret < 0) + { + std::cerr << "bind: " << std::strerror(errno) << std::endl; + goto failBind; + } + + if (ip != "0.0.0.0") + { + struct ip_mreq group; + inet_pton(AF_INET, ip.c_str(), &group.imr_multiaddr.s_addr); + group.imr_interface.s_addr = INADDR_ANY; + + ret = setsockopt(fd, IPPROTO_IP, IP_ADD_MEMBERSHIP, &group, sizeof(group)); + if (ret < 0) + { + std::cerr << "setsockopt: " << std::strerror(errno) << std::endl; + goto failGroup; + } + } + + flags = fcntl (fd, F_GETFL, 0); + ret = fcntl (fd, F_SETFL, flags|O_NONBLOCK); + if (ret < 0) + { + std::cerr << "setsockopt: " << std::strerror(errno) << std::endl; + goto failNonBlock; + } + + return fd; + +failNonBlock: +failGroup: +failBind: + close(fd); +failSocket: + return -1; +} + +inline void SockInput::recvPacket() +{ + fd_set rfds; + + while (!to_exit_recv_) + { + FD_ZERO(&rfds); + FD_SET(fds_[0], &rfds); + if (fds_[1] >= 0) FD_SET(fds_[1], &rfds); + int max_fd = std::max(fds_[0], fds_[1]); + + struct timeval tv; + tv.tv_sec = 0; + tv.tv_usec = 500000; + int retval = select(max_fd + 1, &rfds, NULL, NULL, &tv); + if (retval == 0) + { + continue; + } + else if (retval == -1) + { + if (errno == EINTR) + continue; + + std::cerr << "select: " << std::strerror(errno) << std::endl; + break; + } + + if (FD_ISSET(fds_[0], &rfds)) + { + std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); + pkt->resetData(); + ssize_t ret = recvfrom(fds_[0], pkt->data(), MAX_ETH_LEN, 0, NULL, NULL); + if (ret <= 0) + { + std::cout << "recv failed" << std::endl; + break; + } + + pkt->setData (sock_offset_, ret - sock_offset_); + pushPacket (pkt); + } + else if (FD_ISSET(fds_[1], &rfds)) + { + std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); + pkt->resetData(); + ssize_t ret = recvfrom(fds_[1], pkt->data(), MAX_ETH_LEN, 0, NULL, NULL); + if (ret <= 0) + break; + + pkt->setData (sock_offset_, ret - sock_offset_); + pushPacket(pkt); + } + } +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 1f7a3763..59f55f2a 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -31,15 +31,15 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -//#include #include #include -#include -#include #include #include -#include +#include +#include #include + + constexpr size_t MAX_PACKETS_BUFFER_SIZE = 100000; namespace robosense { @@ -69,9 +69,11 @@ class LidarDriverImpl void runCallBack(const ScanMsg& msg); void runCallBack(const PacketMsg& msg); void runCallBack(const T_PointCloud& msg); + std::shared_ptr packetGet(size_t size); + void packetPut(std::shared_ptr pkt); + void msopCallback(std::shared_ptr msg); + void difopCallback(std::shared_ptr msg); void reportError(const Error& error); - void msopCallback(const PacketMsg& msg); - void difopCallback(const PacketMsg& msg); void processMsop(); void processDifop(); void localCameraTriggerCallback(const CameraTrigger& msg); @@ -79,18 +81,21 @@ class LidarDriverImpl void setPointCloudHeader(T_PointCloud& msg); private: - Queue msop_pkt_queue_; - Queue difop_pkt_queue_; + Queue> free_pkt_queue_; + Queue> msop_pkt_queue_; + Queue> difop_pkt_queue_; + std::vector> point_cloud_cb_vec_; + std::vector> excb_; std::vector> msop_pkt_cb_vec_; std::vector> difop_pkt_cb_vec_; - std::vector> point_cloud_cb_vec_; std::vector> camera_trigger_cb_vec_; - std::vector> excb_; - std::shared_ptr lidar_thread_ptr_; - std::shared_ptr> lidar_decoder_ptr_; std::shared_ptr input_ptr_; + std::shared_ptr> lidar_decoder_ptr_; std::shared_ptr scan_ptr_; - std::shared_ptr thread_pool_ptr_; + std::thread msop_handle_thread_; + std::thread difop_handle_thread_; + bool to_exit_msop_handle_; + bool to_exit_difop_handle_; bool init_flag_; bool start_flag_; bool difop_flag_; @@ -99,13 +104,14 @@ class LidarDriverImpl uint32_t ndifop_count_; RSDriverParam driver_param_; T_PointCloud point_cloud_; + int x_count; }; template inline LidarDriverImpl::LidarDriverImpl() - : init_flag_(false), start_flag_(false), difop_flag_(false), point_cloud_seq_(0), scan_seq_(0), ndifop_count_(0) + : init_flag_(false), start_flag_(false), difop_flag_(false), + point_cloud_seq_(0), scan_seq_(0), ndifop_count_(0), x_count(0) { - thread_pool_ptr_ = std::make_shared(); scan_ptr_ = std::make_shared(); } @@ -113,8 +119,14 @@ template inline LidarDriverImpl::~LidarDriverImpl() { stop(); - thread_pool_ptr_.reset(); + input_ptr_.reset(); + + to_exit_msop_handle_ = true; + msop_handle_thread_.join(); + + to_exit_difop_handle_ = true; + difop_handle_thread_.join(); } template @@ -122,22 +134,34 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) { if (init_flag_) { - return false; + return true; } + driver_param_ = param; - input_ptr_ = std::make_shared(driver_param_.lidar_type, driver_param_.input_param, - std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); - input_ptr_->regRecvMsopCallback(std::bind(&LidarDriverImpl::msopCallback, this, std::placeholders::_1)); - input_ptr_->regRecvDifopCallback(std::bind(&LidarDriverImpl::difopCallback, this, std::placeholders::_1)); + + lidar_decoder_ptr_ = DecoderFactory::createDecoder(driver_param_); + lidar_decoder_ptr_->regRecvCallback( + std::bind(&LidarDriverImpl::localCameraTriggerCallback, this, std::placeholders::_1)); + + input_ptr_ = InputFactory::createInput(driver_param_, + std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); + input_ptr_->regRecvCallback( + std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), + std::bind(&LidarDriverImpl::msopCallback, this, std::placeholders::_1), + std::bind(&LidarDriverImpl::difopCallback, this, std::placeholders::_1)); + if (!input_ptr_->init()) { - return false; + goto failInputInit; } - lidar_decoder_ptr_ = DecoderFactory::createDecoder(driver_param_); - lidar_decoder_ptr_->regRecvCallback( - std::bind(&LidarDriverImpl::localCameraTriggerCallback, this, std::placeholders::_1)); + init_flag_ = true; return true; + +failInputInit: + input_ptr_.reset(); + lidar_decoder_ptr_.reset(); + return false; } template @@ -147,6 +171,7 @@ inline void LidarDriverImpl::initDecoderOnly(const RSDriverParam& { return; } + driver_param_ = param; lidar_decoder_ptr_ = DecoderFactory::createDecoder(driver_param_); lidar_decoder_ptr_->regRecvCallback( @@ -157,26 +182,35 @@ inline void LidarDriverImpl::initDecoderOnly(const RSDriverParam& template inline bool LidarDriverImpl::start() { - if (start_flag_ || input_ptr_ == nullptr) - { + if (!init_flag_) return false; - } + + if (start_flag_) + return true; + + msop_handle_thread_ = std::thread ( + std::bind(&LidarDriverImpl::processMsop, this)); + difop_handle_thread_ = std::thread ( + std::bind(&LidarDriverImpl::processDifop, this)); + + input_ptr_->start(); + start_flag_ = true; - return input_ptr_->start(); + return true; } template inline void LidarDriverImpl::stop() { if (input_ptr_ != nullptr) - { input_ptr_->stop(); - } + + to_exit_msop_handle_ = true; + to_exit_difop_handle_ = true; + msop_handle_thread_.join(); + difop_handle_thread_.join(); + start_flag_ = false; - if (!msop_pkt_cb_vec_.empty() || !difop_pkt_cb_vec_.empty()) - { - std::this_thread::sleep_for(std::chrono::microseconds(10)); - } } template @@ -222,7 +256,8 @@ inline bool LidarDriverImpl::getLidarTemperature(double& input_tem } template -inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg) +inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, + T_PointCloud& point_cloud_msg) { if (!difop_flag_ && driver_param_.wait_for_difop) { @@ -237,14 +272,15 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_ms } std::vector pointcloud_one_frame; - int height = 1; pointcloud_one_frame.resize(scan_msg.packets.size()); + + int height = 1; for (int i = 0; i < static_cast(scan_msg.packets.size()); i++) { typename T_PointCloud::VectorT pointcloud_one_packet; RSDecoderResult ret = lidar_decoder_ptr_->processMsopPkt( - scan_msg.packets[i].packet.data(), pointcloud_one_packet, height); + scan_msg.packets[i].data(), pointcloud_one_packet, height); switch (ret) { case RSDecoderResult::DECODE_OK: @@ -278,9 +314,9 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_ms } template -inline void LidarDriverImpl::decodeDifopPkt(const PacketMsg& msg) +inline void LidarDriverImpl::decodeDifopPkt(const PacketMsg& pkt) { - lidar_decoder_ptr_->processDifopPkt(msg.packet.data()); + lidar_decoder_ptr_->processDifopPkt(pkt.data()); difop_flag_ = true; } @@ -325,37 +361,40 @@ inline void LidarDriverImpl::reportError(const Error& error) it(error); } } - template -inline void LidarDriverImpl::msopCallback(const PacketMsg& msg) +inline std::shared_ptr LidarDriverImpl::packetGet(size_t size) { - if (msop_pkt_queue_.size() > MAX_PACKETS_BUFFER_SIZE) + std::shared_ptr pkt = free_pkt_queue_.pop(); + if (pkt.get() != NULL) { - reportError(Error(ERRCODE_PKTBUFOVERFLOW)); - msop_pkt_queue_.clear(); - } - msop_pkt_queue_.push(msg); - if (msop_pkt_queue_.is_task_finished_.load()) - { - msop_pkt_queue_.is_task_finished_.store(false); - thread_pool_ptr_->commit([this]() { processMsop(); }); + return pkt; } + + return std::make_shared(size); } -template -inline void LidarDriverImpl::difopCallback(const PacketMsg& msg) +template +inline void LidarDriverImpl::packetPut(std::shared_ptr pkt) { - difop_pkt_queue_.push(msg); - if (difop_pkt_queue_.is_task_finished_.load()) - { - difop_pkt_queue_.is_task_finished_.store(false); - thread_pool_ptr_->commit([this]() { processDifop(); }); - } + free_pkt_queue_.push(pkt); +} + +template +inline void LidarDriverImpl::msopCallback(std::shared_ptr pkt) +{ + msop_pkt_queue_.push(pkt); +} + +template +inline void LidarDriverImpl::difopCallback(std::shared_ptr pkt) +{ + difop_pkt_queue_.push(pkt); } template inline void LidarDriverImpl::processMsop() { +#if 0 if (!difop_flag_ && driver_param_.wait_for_difop) { ndifop_count_++; @@ -369,64 +408,64 @@ inline void LidarDriverImpl::processMsop() msop_pkt_queue_.is_task_finished_.store(true); return; } - while (msop_pkt_queue_.size() > 0) +#endif + + while (!to_exit_msop_handle_) { - PacketMsg pkt = msop_pkt_queue_.popFront(); + std::shared_ptr pkt = msop_pkt_queue_.popWait(1000); + if (pkt.get() == NULL) + continue; + int height = 1; - int ret = lidar_decoder_ptr_->processMsopPkt (pkt.packet.data(), point_cloud_.points, height); + int ret = lidar_decoder_ptr_->processMsopPkt (pkt->data(), point_cloud_.points, height); + #if 0 scan_ptr_->packets.emplace_back(pkt); #endif - if ((ret == DECODE_OK || ret == FRAME_SPLIT)) + + if (ret == FRAME_SPLIT) { - if (ret == FRAME_SPLIT) + T_PointCloud& msg = point_cloud_; + msg.height = height; + msg.width = msg.points.size() / msg.height; + setPointCloudHeader(msg); + + if (driver_param_.decoder_param.use_lidar_clock == true) + { + msg.timestamp = lidar_decoder_ptr_->getLidarTime(pkt->data()); + } + else { - T_PointCloud& msg = point_cloud_; - msg.height = height; - msg.width = msg.points.size() / msg.height; - setPointCloudHeader(msg); - if (driver_param_.decoder_param.use_lidar_clock == true) - { - msg.timestamp = lidar_decoder_ptr_->getLidarTime(pkt.packet.data()); - } - else - { - msg.timestamp = getTime(); - } - - if (msg.points.size() == 0) - { - reportError(Error(ERRCODE_ZEROPOINTS)); - } - else - { - runCallBack(msg); - } + msg.timestamp = getTime(); + } + + if (msg.points.size() == 0) + { + reportError(Error(ERRCODE_ZEROPOINTS)); + } + else + { + runCallBack(msg); + } #if 0 - setScanMsgHeader(*scan_ptr_); - runCallBack(*scan_ptr_); - scan_ptr_.reset(new ScanMsg); + setScanMsgHeader(*scan_ptr_); + runCallBack(*scan_ptr_); + scan_ptr_.reset(new ScanMsg); #endif - point_cloud_.points.resize(0); - } + point_cloud_.points.resize(0); } - else if (ret == DISCARD_PKT) + else if (ret < 0) { + reportError(Error(ERRCODE_WRONGPKTHEADER)); #if 0 scan_ptr_->packets.clear(); #endif - point_cloud_.points.resize(0); - } - else - { - reportError(Error(ERRCODE_WRONGPKTHEADER)); - // msop_pkt_queue_.clear(); - // std::this_thread::sleep_for(std::chrono::milliseconds(100)); } + + packetPut(pkt); } - msop_pkt_queue_.is_task_finished_.store(true); } template @@ -441,13 +480,17 @@ inline void LidarDriverImpl::localCameraTriggerCallback(const Came template inline void LidarDriverImpl::processDifop() { - while (difop_pkt_queue_.size() > 0) + while (!to_exit_difop_handle_) { - PacketMsg pkt = difop_pkt_queue_.popFront(); - decodeDifopPkt(pkt); - runCallBack(pkt); + std::shared_ptr pkt = difop_pkt_queue_.popWait(500000); + if (pkt.get() == NULL) + continue; + + decodeDifopPkt (*pkt); + //runCallBack(*pkt); + + packetPut(pkt); } - difop_pkt_queue_.is_task_finished_.store(true); } template @@ -456,7 +499,7 @@ inline void LidarDriverImpl::setScanMsgHeader(ScanMsg& msg) msg.timestamp = getTime(); if (driver_param_.decoder_param.use_lidar_clock == true) { - msg.timestamp = lidar_decoder_ptr_->getLidarTime(msg.packets.back().packet.data()); + msg.timestamp = lidar_decoder_ptr_->getLidarTime(msg.packets.back().data()); } msg.seq = scan_seq_++; msg.frame_id = driver_param_.frame_id; diff --git a/src/rs_driver/msg/packet_msg.h b/src/rs_driver/msg/packet_msg.h index a9ed4a22..1f5e13fa 100644 --- a/src/rs_driver/msg/packet_msg.h +++ b/src/rs_driver/msg/packet_msg.h @@ -37,29 +37,54 @@ namespace robosense { namespace lidar { +#if 0 enum PktType { MSOP = 0, DIFOP }; +#endif #ifdef _MSC_VER struct __declspec(align(16)) PacketMsg #elif __GNUC__ struct __attribute__((aligned(16))) PacketMsg ///< LiDAR single packet message #endif { - std::vector packet; - PacketMsg() + PacketMsg(size_t cap) : off_(0), len_(0) { + buf_ = (uint8_t*) malloc(cap); } - PacketMsg(const PacketMsg& msg) + + void setData (size_t off, size_t len) { - this->packet.assign(msg.packet.begin(), msg.packet.end()); + off_ = off; + len_ = len; } - PacketMsg(const size_t& pkt_length) + + void resetData() { - packet.resize(pkt_length); + setData(0, 0); } + + const uint8_t* data() const + { + return buf_ + off_; + } + + uint8_t* data() + { + return buf_ + off_; + } + + size_t len() const + { + return len_; + } + + private: + uint8_t* buf_; + size_t off_; + size_t len_; }; } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/utility/dbg.h b/src/rs_driver/utility/dbg.h new file mode 100644 index 00000000..cc28f500 --- /dev/null +++ b/src/rs_driver/utility/dbg.h @@ -0,0 +1,55 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include + +namespace robosense +{ +namespace lidar +{ + +inline void hexdump (const unsigned char* data, size_t size, const char* desc = NULL) +{ + printf ("\n---------------%s------------------", (desc ? desc : "")); + + for (size_t i = 0; i < size; i++) + { + if (i % 16 == 0) printf ("\n"); + printf ("%02x ", data[i]); + } + + printf ("\n---------------------------------\n"); +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/utility/lock_queue.h b/src/rs_driver/utility/lock_queue.h index 7f33e118..93a3bb77 100644 --- a/src/rs_driver/utility/lock_queue.h +++ b/src/rs_driver/utility/lock_queue.h @@ -40,62 +40,64 @@ template class Queue { public: - inline Queue():is_task_finished_(true) - { - } - inline T front() + inline Queue() { - std::lock_guard lock(mutex_); - return queue_.front(); } inline void push(const T& value) { - std::lock_guard lock(mutex_); + std::lock_guard lg(mtx_); + + bool empty = queue_.empty(); + queue_.push(value); + + if (empty) + cv_.notify_one(); } - inline void pop() + inline T pop() { - std::lock_guard lock(mutex_); + T value; + + std::lock_guard lg(mtx_); if (!queue_.empty()) { + value = queue_.front(); queue_.pop(); } + + return value; } - inline T popFront() + inline T popWait (unsigned int usec) { T value; - std::lock_guard lock(mutex_); + + std::unique_lock lck(mtx_); + + cv_.wait_for (lck, std::chrono::microseconds(usec), + [this]{return (!queue_.empty());}); + if (!queue_.empty()) { - value = std::move(queue_.front()); + value = queue_.front(); queue_.pop(); } - return value; - } - inline void clear() - { - std::queue empty; - std::lock_guard lock(mutex_); - swap(empty, queue_); + return value; } - inline size_t size() + int count() { - std::lock_guard lock(mutex_); return queue_.size(); } -public: - std::queue queue_; - std::atomic is_task_finished_; - private: - mutable std::mutex mutex_; + std::queue queue_; + std::mutex mtx_; + std::condition_variable cv_; }; } // namespace lidar -} // namespace robosense \ No newline at end of file +} // namespace robosense From c1975cf6d46489d41f00b1fa4b6176b541cbd193 Mon Sep 17 00:00:00 2001 From: ronzheng Date: Sat, 30 Oct 2021 12:02:39 +0800 Subject: [PATCH 004/379] feat: add conditional macros --- CMakeLists.txt | 12 +++ src/rs_driver/driver/decoder/decoder_RSBP.hpp | 2 - src/rs_driver/driver/decoder/decoder_base.hpp | 7 +- .../driver/decoder/decoder_factory.hpp | 5 +- src/rs_driver/driver/input/input.hpp | 24 ++--- src/rs_driver/driver/input/input_factory.hpp | 2 +- src/rs_driver/driver/input/pcap_input.hpp | 4 +- src/rs_driver/driver/input/sock_input.hpp | 4 +- src/rs_driver/driver/lidar_driver_impl.hpp | 85 +++++++++-------- src/rs_driver/msg/packet.h | 80 ++++++++++++++++ src/rs_driver/msg/packet_msg.h | 37 ++------ src/rs_driver/utility/lock_queue.h | 56 ++++++----- src/rs_driver/utility/sync_queue.h | 94 +++++++++++++++++++ 13 files changed, 289 insertions(+), 123 deletions(-) create mode 100644 src/rs_driver/msg/packet.h create mode 100644 src/rs_driver/utility/sync_queue.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 65f6aa5e..88cf412d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -18,6 +18,8 @@ option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) # Compile Demos&Tools #============================= option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) +option(ENABLE_PUBLISH_RAW_MSG "Publish raw messages" OFF) +option(ENABLE_PUBLISH_CAM_MSG "Publish camera trigger messages" OFF) option(ENABLE_TRANSFORM "Enable transform functions" OFF) #======================== @@ -124,6 +126,16 @@ if(${ENABLE_HIGH_PRIORITY_THREAD}) add_definitions("-DENABLE_HIGH_PRIORITY_THREAD") endif(${ENABLE_HIGH_PRIORITY_THREAD}) +if(${ENABLE_PUBLISH_RAW_MSG}) + add_definitions("-DENABLE_PUBLISH_RAW_MSG") +endif(${ENABLE_PUBLISH_RAW_MSG}) + +option(ENABLE_PUBLISH_CAM_MSG "Publish camera trigger messages" OFF) +if(${ENABLE_PUBLISH_CAM_MSG}) + add_definitions("-DENABLE_PUBLISH_CAM_MSG") +endif(${ENABLE_PUBLISH_CAM_MSG}) + + #======================== # Build Demos #======================== diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 320ea277..b670149a 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -194,9 +194,7 @@ inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* p this->lidar_const_param_.RX * this->checkSinTable(angle_horiz); float z = distance * this->checkSinTable(angle_vert) + this->lidar_const_param_.RZ; uint8_t intensity = mpkt_ptr->blocks[blk_idx].channels[channel_idx].intensity; -#if 0 this->transformPoint(x, y, z); -#endif setX(point, x); setY(point, y); setZ(point, z); diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 48db234d..fb4277d4 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -404,8 +404,10 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, const // { // get_point_time_func_ = [this](const uint8_t* pkt) { return 0; }; // } - /*Camera trigger function*/ - if (param.trigger_param.trigger_map.size() != 0) + + // Camera trigger function +#ifdef ENABLE_PUBLISH_CAM_MSG + if (param.trigger_param.trigger_map.size() > 0) { if (this->param_.use_lidar_clock) { @@ -421,6 +423,7 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, const } } else +#endif { check_camera_trigger_func_ = [this](const int& azimuth, const uint8_t* pkt) { return; }; } diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 958059a6..299f9431 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -39,7 +39,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include +//#include +#include namespace robosense { namespace lidar @@ -255,7 +256,7 @@ inline const LidarConstantParameter DecoderFactory::getRSROCKConstantPa return ret_param; } -void getLidarPktLength(uint8_t type, uint32_t* msop_pkt_len, uint32_t* difop_pkt_len) +inline void getLidarPktLength(uint8_t type, uint32_t* msop_pkt_len, uint32_t* difop_pkt_len) { switch (type) { diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index b8b23be2..bf112177 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -35,7 +35,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include +#include #include #include @@ -78,9 +78,9 @@ class Input Input(const RSInputParam& input_param, const std::function& excb); - void regRecvCallback(const std::function(size_t)>& cb_get, - const std::function)>& cb_put_msop, - const std::function)>& cb_put_difop); + inline void regRecvCallback(const std::function(size_t)>& cb_get, + const std::function)>& cb_put_msop, + const std::function)>& cb_put_difop); virtual bool init() = 0; virtual bool start() = 0; @@ -89,12 +89,12 @@ class Input protected: - inline void pushPacket (std::shared_ptr pkt); + inline void pushPacket (std::shared_ptr pkt); RSInputParam input_param_; - std::function(size_t size)> cb_get_; - std::function)> cb_put_msop_; - std::function)> cb_put_difop_; + std::function(size_t size)> cb_get_; + std::function)> cb_put_msop_; + std::function)> cb_put_difop_; std::function excb_; std::thread recv_thread_; bool to_exit_recv_; @@ -107,9 +107,9 @@ inline Input::Input(const RSInputParam& input_param, { } -void Input::regRecvCallback(const std::function(size_t)>& cb_get, - const std::function)>& cb_put_msop, - const std::function)>& cb_put_difop) +inline void Input::regRecvCallback(const std::function(size_t)>& cb_get, + const std::function)>& cb_put_msop, + const std::function)>& cb_put_difop) { cb_get_ = cb_get; cb_put_msop_ = cb_put_msop; @@ -122,7 +122,7 @@ inline void Input::stop() recv_thread_.join(); } -inline void Input::pushPacket (std::shared_ptr pkt) +inline void Input::pushPacket (std::shared_ptr pkt) { uint8_t* id = pkt->data(); if (*id == 0x55) diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 38e93468..cad85698 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -39,7 +39,7 @@ namespace robosense namespace lidar { -long long msecToDelay(LidarType type, double replay_rate) +inline long long msecToDelay(LidarType type, double replay_rate) { constexpr double RS16_PCAP_SLEEP_DURATION = 1200; ///< us constexpr double RS32_PCAP_SLEEP_DURATION = 530; ///< us diff --git a/src/rs_driver/driver/input/pcap_input.hpp b/src/rs_driver/driver/input/pcap_input.hpp index 70220384..d261cb8d 100644 --- a/src/rs_driver/driver/input/pcap_input.hpp +++ b/src/rs_driver/driver/input/pcap_input.hpp @@ -153,7 +153,7 @@ inline void PcapInput::recvPacket() if (pcap_offline_filter(&msop_filter_, header, pkt_data) != 0) { - std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); + std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_); pkt->setData(0, header->len - pcap_offset_); pushPacket (pkt); @@ -161,7 +161,7 @@ inline void PcapInput::recvPacket() else if (difop_filter_valid_ && (pcap_offline_filter(&difop_filter_, header, pkt_data) != 0)) { - std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); + std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_); pkt->setData(0, header->len - pcap_offset_); pushPacket (pkt); diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index 0373c067..27fb1424 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -222,7 +222,7 @@ inline void SockInput::recvPacket() if (FD_ISSET(fds_[0], &rfds)) { - std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); + std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); pkt->resetData(); ssize_t ret = recvfrom(fds_[0], pkt->data(), MAX_ETH_LEN, 0, NULL, NULL); if (ret <= 0) @@ -236,7 +236,7 @@ inline void SockInput::recvPacket() } else if (FD_ISSET(fds_[1], &rfds)) { - std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); + std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); pkt->resetData(); ssize_t ret = recvfrom(fds_[1], pkt->data(), MAX_ETH_LEN, 0, NULL, NULL); if (ret <= 0) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 59f55f2a..a3702961 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -31,11 +31,12 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once +#include #include #include #include #include -#include +#include #include #include @@ -61,37 +62,41 @@ class LidarDriverImpl void regRecvCallback(const std::function& callback); void regRecvCallback(const std::function& callback); void regExceptionCallback(const std::function& callback); + bool getLidarTemperature(double& input_temperature); bool decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg); void decodeDifopPkt(const PacketMsg& msg); private: + void runCallBack(const T_PointCloud& msg); + void runCallBack(const ScanMsg& msg); void runCallBack(const PacketMsg& msg); - void runCallBack(const T_PointCloud& msg); - std::shared_ptr packetGet(size_t size); - void packetPut(std::shared_ptr pkt); - void msopCallback(std::shared_ptr msg); - void difopCallback(std::shared_ptr msg); + void setScanMsgHeader(ScanMsg& msg); + void localCameraTriggerCallback(const CameraTrigger& msg); + std::shared_ptr packetGet(size_t size); + void packetPut(std::shared_ptr pkt); + void msopCallback(std::shared_ptr msg); + void difopCallback(std::shared_ptr msg); void reportError(const Error& error); void processMsop(); void processDifop(); - void localCameraTriggerCallback(const CameraTrigger& msg); - void setScanMsgHeader(ScanMsg& msg); void setPointCloudHeader(T_PointCloud& msg); private: - Queue> free_pkt_queue_; - Queue> msop_pkt_queue_; - Queue> difop_pkt_queue_; + RSDriverParam driver_param_; std::vector> point_cloud_cb_vec_; std::vector> excb_; std::vector> msop_pkt_cb_vec_; std::vector> difop_pkt_cb_vec_; - std::vector> camera_trigger_cb_vec_; std::shared_ptr input_ptr_; std::shared_ptr> lidar_decoder_ptr_; - std::shared_ptr scan_ptr_; + ScanMsg scan_ptr_; + std::vector> camera_trigger_cb_vec_; + T_PointCloud point_cloud_; + SyncQueue> free_pkt_queue_; + SyncQueue> msop_pkt_queue_; + SyncQueue> difop_pkt_queue_; std::thread msop_handle_thread_; std::thread difop_handle_thread_; bool to_exit_msop_handle_; @@ -102,17 +107,13 @@ class LidarDriverImpl uint32_t point_cloud_seq_; uint32_t scan_seq_; uint32_t ndifop_count_; - RSDriverParam driver_param_; - T_PointCloud point_cloud_; - int x_count; }; template inline LidarDriverImpl::LidarDriverImpl() : init_flag_(false), start_flag_(false), difop_flag_(false), - point_cloud_seq_(0), scan_seq_(0), ndifop_count_(0), x_count(0) + point_cloud_seq_(0), scan_seq_(0), ndifop_count_(0) { - scan_ptr_ = std::make_shared(); } template @@ -259,6 +260,7 @@ template inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg) { +#if 0 if (!difop_flag_ && driver_param_.wait_for_difop) { ndifop_count_++; @@ -270,6 +272,7 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_ms std::this_thread::sleep_for(std::chrono::milliseconds(10)); return false; } +#endif std::vector pointcloud_one_frame; pointcloud_one_frame.resize(scan_msg.packets.size()); @@ -280,7 +283,7 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_ms typename T_PointCloud::VectorT pointcloud_one_packet; RSDecoderResult ret = lidar_decoder_ptr_->processMsopPkt( - scan_msg.packets[i].data(), pointcloud_one_packet, height); + scan_msg.packets[i].packet.data(), pointcloud_one_packet, height); switch (ret) { case RSDecoderResult::DECODE_OK: @@ -316,7 +319,7 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_ms template inline void LidarDriverImpl::decodeDifopPkt(const PacketMsg& pkt) { - lidar_decoder_ptr_->processDifopPkt(pkt.data()); + lidar_decoder_ptr_->processDifopPkt(pkt.packet.data()); difop_flag_ = true; } @@ -362,31 +365,31 @@ inline void LidarDriverImpl::reportError(const Error& error) } } template -inline std::shared_ptr LidarDriverImpl::packetGet(size_t size) +inline std::shared_ptr LidarDriverImpl::packetGet(size_t size) { - std::shared_ptr pkt = free_pkt_queue_.pop(); + std::shared_ptr pkt = free_pkt_queue_.pop(); if (pkt.get() != NULL) { return pkt; } - return std::make_shared(size); + return std::make_shared(size); } template -inline void LidarDriverImpl::packetPut(std::shared_ptr pkt) +inline void LidarDriverImpl::packetPut(std::shared_ptr pkt) { free_pkt_queue_.push(pkt); } template -inline void LidarDriverImpl::msopCallback(std::shared_ptr pkt) +inline void LidarDriverImpl::msopCallback(std::shared_ptr pkt) { msop_pkt_queue_.push(pkt); } template -inline void LidarDriverImpl::difopCallback(std::shared_ptr pkt) +inline void LidarDriverImpl::difopCallback(std::shared_ptr pkt) { difop_pkt_queue_.push(pkt); } @@ -412,15 +415,16 @@ inline void LidarDriverImpl::processMsop() while (!to_exit_msop_handle_) { - std::shared_ptr pkt = msop_pkt_queue_.popWait(1000); + std::shared_ptr pkt = msop_pkt_queue_.popWait(1000); if (pkt.get() == NULL) continue; int height = 1; int ret = lidar_decoder_ptr_->processMsopPkt (pkt->data(), point_cloud_.points, height); -#if 0 - scan_ptr_->packets.emplace_back(pkt); +#ifdef ENABLE_PUBLISH_RAW_MSG + PacketMsg msg; + scan_ptr_.packets.emplace_back(msg); #endif if (ret == FRAME_SPLIT) @@ -448,10 +452,10 @@ inline void LidarDriverImpl::processMsop() runCallBack(msg); } -#if 0 - setScanMsgHeader(*scan_ptr_); - runCallBack(*scan_ptr_); - scan_ptr_.reset(new ScanMsg); +#ifdef ENABLE_PUBLISH_RAW_MSG + setScanMsgHeader(scan_ptr_); + runCallBack(scan_ptr_); + scan_ptr_.packets.reset(0); #endif point_cloud_.points.resize(0); @@ -459,9 +463,6 @@ inline void LidarDriverImpl::processMsop() else if (ret < 0) { reportError(Error(ERRCODE_WRONGPKTHEADER)); -#if 0 - scan_ptr_->packets.clear(); -#endif } packetPut(pkt); @@ -482,12 +483,16 @@ inline void LidarDriverImpl::processDifop() { while (!to_exit_difop_handle_) { - std::shared_ptr pkt = difop_pkt_queue_.popWait(500000); + std::shared_ptr pkt = difop_pkt_queue_.popWait(500000); if (pkt.get() == NULL) continue; - decodeDifopPkt (*pkt); - //runCallBack(*pkt); + lidar_decoder_ptr_->processDifopPkt(pkt->data()); + difop_flag_ = true; + +#ifdef ENABLE_PUBLISH_RAW_MSG + runCallBack(*pkt); +#endif packetPut(pkt); } @@ -499,7 +504,7 @@ inline void LidarDriverImpl::setScanMsgHeader(ScanMsg& msg) msg.timestamp = getTime(); if (driver_param_.decoder_param.use_lidar_clock == true) { - msg.timestamp = lidar_decoder_ptr_->getLidarTime(msg.packets.back().data()); + msg.timestamp = lidar_decoder_ptr_->getLidarTime(msg.packets.back().packet.data()); } msg.seq = scan_seq_++; msg.frame_id = driver_param_.frame_id; diff --git a/src/rs_driver/msg/packet.h b/src/rs_driver/msg/packet.h new file mode 100644 index 00000000..12d30d7e --- /dev/null +++ b/src/rs_driver/msg/packet.h @@ -0,0 +1,80 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include + +namespace robosense +{ +namespace lidar +{ +class Packet +{ +public: + Packet(size_t cap) : off_(0), len_(0) + { + buf_ = (uint8_t*) malloc(cap); + } + + void setData (size_t off, size_t len) + { + off_ = off; + len_ = len; + } + + void resetData() + { + setData(0, 0); + } + + const uint8_t* data() const + { + return buf_ + off_; + } + + uint8_t* data() + { + return buf_ + off_; + } + + size_t len() const + { + return len_; + } + +private: + uint8_t* buf_; + size_t off_; + size_t len_; +}; +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/msg/packet_msg.h b/src/rs_driver/msg/packet_msg.h index 1f5e13fa..a9ed4a22 100644 --- a/src/rs_driver/msg/packet_msg.h +++ b/src/rs_driver/msg/packet_msg.h @@ -37,54 +37,29 @@ namespace robosense { namespace lidar { -#if 0 enum PktType { MSOP = 0, DIFOP }; -#endif #ifdef _MSC_VER struct __declspec(align(16)) PacketMsg #elif __GNUC__ struct __attribute__((aligned(16))) PacketMsg ///< LiDAR single packet message #endif { - PacketMsg(size_t cap) : off_(0), len_(0) + std::vector packet; + PacketMsg() { - buf_ = (uint8_t*) malloc(cap); } - - void setData (size_t off, size_t len) + PacketMsg(const PacketMsg& msg) { - off_ = off; - len_ = len; + this->packet.assign(msg.packet.begin(), msg.packet.end()); } - - void resetData() + PacketMsg(const size_t& pkt_length) { - setData(0, 0); + packet.resize(pkt_length); } - - const uint8_t* data() const - { - return buf_ + off_; - } - - uint8_t* data() - { - return buf_ + off_; - } - - size_t len() const - { - return len_; - } - - private: - uint8_t* buf_; - size_t off_; - size_t len_; }; } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/utility/lock_queue.h b/src/rs_driver/utility/lock_queue.h index 93a3bb77..56e19d12 100644 --- a/src/rs_driver/utility/lock_queue.h +++ b/src/rs_driver/utility/lock_queue.h @@ -40,64 +40,62 @@ template class Queue { public: + inline Queue() : is_task_finished_(true) + { + } - inline Queue() + inline T front() { + std::lock_guard lock(mutex_); + return queue_.front(); } inline void push(const T& value) { - std::lock_guard lg(mtx_); - - bool empty = queue_.empty(); - + std::lock_guard lock(mutex_); queue_.push(value); - - if (empty) - cv_.notify_one(); } - inline T pop() + inline void pop() { - T value; - - std::lock_guard lg(mtx_); + std::lock_guard lock(mutex_); if (!queue_.empty()) { - value = queue_.front(); queue_.pop(); } - - return value; } - inline T popWait (unsigned int usec) + inline T popFront() { T value; - - std::unique_lock lck(mtx_); - - cv_.wait_for (lck, std::chrono::microseconds(usec), - [this]{return (!queue_.empty());}); - + std::lock_guard lock(mutex_); if (!queue_.empty()) { - value = queue_.front(); + value = std::move(queue_.front()); queue_.pop(); } - return value; } - int count() + inline void clear() + { + std::queue empty; + std::lock_guard lock(mutex_); + swap(empty, queue_); + } + + inline size_t size() { + std::lock_guard lock(mutex_); return queue_.size(); } -private: +public: std::queue queue_; - std::mutex mtx_; - std::condition_variable cv_; + std::atomic is_task_finished_; + +private: + mutable std::mutex mutex_; }; } // namespace lidar -} // namespace robosense +} // namespace robosense \ No newline at end of file diff --git a/src/rs_driver/utility/sync_queue.h b/src/rs_driver/utility/sync_queue.h new file mode 100644 index 00000000..d8ca52e6 --- /dev/null +++ b/src/rs_driver/utility/sync_queue.h @@ -0,0 +1,94 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include +namespace robosense +{ +namespace lidar +{ +template +class SyncQueue +{ +public: + + inline void push(const T& value) + { + std::lock_guard lg(mtx_); + + bool empty = queue_.empty(); + + queue_.push(value); + + if (empty) + cv_.notify_one(); + } + + inline T pop() + { + T value; + + std::lock_guard lg(mtx_); + if (!queue_.empty()) + { + value = queue_.front(); + queue_.pop(); + } + + return value; + } + + inline T popWait (unsigned int usec) + { + T value; + + std::unique_lock lck(mtx_); + + cv_.wait_for (lck, std::chrono::microseconds(usec), + [this]{return (!queue_.empty());}); + + if (!queue_.empty()) + { + value = queue_.front(); + queue_.pop(); + } + + return value; + } + +private: + std::queue queue_; + std::mutex mtx_; + std::condition_variable cv_; +}; +} // namespace lidar +} // namespace robosense From be0ac745d9624572259d87db9cb9a84fe2802c8f Mon Sep 17 00:00:00 2001 From: ronzheng Date: Mon, 1 Nov 2021 10:11:12 +0800 Subject: [PATCH 005/379] fix: fix vlan len --- src/rs_driver/driver/input/input.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index bf112177..85cd8e2a 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -64,7 +64,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #define MAX_ETH_LEN 1500 #define ETH_HDR_LEN 42 -#define VLAN_LEN 16 +#define VLAN_LEN 4 #define SOME_IP_LEN 16 namespace robosense From b6eebcaf101069407e3c4852d7481f45c530c245 Mon Sep 17 00:00:00 2001 From: ronzheng Date: Mon, 1 Nov 2021 10:45:53 +0800 Subject: [PATCH 006/379] fix: fix wait_for_difop --- src/rs_driver/driver/lidar_driver_impl.hpp | 10 ++-------- src/rs_driver/utility/sync_queue.h | 7 +++++++ 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index a3702961..b7f651ec 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -260,8 +260,7 @@ template inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg) { -#if 0 - if (!difop_flag_ && driver_param_.wait_for_difop) + if (driver_param_.wait_for_difop && !difop_flag_) { ndifop_count_++; if (ndifop_count_ > 20) @@ -272,7 +271,6 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_ms std::this_thread::sleep_for(std::chrono::milliseconds(10)); return false; } -#endif std::vector pointcloud_one_frame; pointcloud_one_frame.resize(scan_msg.packets.size()); @@ -397,8 +395,7 @@ inline void LidarDriverImpl::difopCallback(std::shared_ptr template inline void LidarDriverImpl::processMsop() { -#if 0 - if (!difop_flag_ && driver_param_.wait_for_difop) + while (!to_exit_msop_handle_ && driver_param_.wait_for_difop && !difop_flag_) { ndifop_count_++; if (ndifop_count_ > 120) @@ -408,10 +405,7 @@ inline void LidarDriverImpl::processMsop() } std::this_thread::sleep_for(std::chrono::milliseconds(10)); msop_pkt_queue_.clear(); - msop_pkt_queue_.is_task_finished_.store(true); - return; } -#endif while (!to_exit_msop_handle_) { diff --git a/src/rs_driver/utility/sync_queue.h b/src/rs_driver/utility/sync_queue.h index d8ca52e6..66181f8c 100644 --- a/src/rs_driver/utility/sync_queue.h +++ b/src/rs_driver/utility/sync_queue.h @@ -85,6 +85,13 @@ class SyncQueue return value; } + inline void clear() + { + std::queue empty; + std::lock_guard lg(mtx_); + swap(empty, queue_); + } + private: std::queue queue_; std::mutex mtx_; From c8c70f55215595e2f962b0e551e3141b0512e79a Mon Sep 17 00:00:00 2001 From: ronzheng Date: Mon, 1 Nov 2021 11:05:28 +0800 Subject: [PATCH 007/379] style: do clang-format --- demo/demo_online.cpp | 10 ++-- demo/demo_pcap.cpp | 14 +++-- demo/pcl_point_cloud_msg.h | 11 ++-- demo/point_cloud_msg.h | 46 ++++++++-------- src/rs_driver/api/lidar_driver.h | 3 +- .../driver/decoder/decoder_RS128.hpp | 11 ++-- src/rs_driver/driver/decoder/decoder_RS16.hpp | 10 ++-- src/rs_driver/driver/decoder/decoder_RS32.hpp | 10 ++-- src/rs_driver/driver/decoder/decoder_RS80.hpp | 10 ++-- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 18 ++++--- .../driver/decoder/decoder_RSHELIOS.hpp | 10 ++-- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 23 ++++---- .../driver/decoder/decoder_RSROCK.hpp | 7 +-- src/rs_driver/driver/decoder/decoder_base.hpp | 28 +++++----- .../driver/decoder/decoder_factory.hpp | 3 +- src/rs_driver/driver/input/input.hpp | 28 +++++----- src/rs_driver/driver/input/input_factory.hpp | 9 ++-- src/rs_driver/driver/input/pcap_input.hpp | 27 ++++------ src/rs_driver/driver/input/sock_input.hpp | 52 +++++++++---------- src/rs_driver/driver/lidar_driver_impl.hpp | 38 ++++++-------- src/rs_driver/msg/packet.h | 4 +- src/rs_driver/utility/dbg.h | 12 ++--- src/rs_driver/utility/sync_queue.h | 6 +-- 23 files changed, 185 insertions(+), 205 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 60cfc7da..a388c05c 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -40,7 +40,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include "point_cloud_msg.h" #endif -typedef PointCloudT PointCloudMsg; +typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; @@ -53,8 +53,7 @@ void pointCloudCallback(const PointCloudMsg& msg) { /* Note: Please do not put time-consuming operations in the callback function! */ /* Make a copy of the message and process it in another thread is recommended*/ - RS_MSG << "msg: " << msg.seq - << " point cloud size: " << msg.points.size() << RS_REND; + RS_MSG << "msg: " << msg.seq << " point cloud size: " << msg.points.size() << RS_REND; } /** @@ -78,9 +77,8 @@ int main(int argc, char* argv[]) RSDriverParam param; ///< Create a parameter object param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RSBP; ///< Set the lidar type. Make sure this type is correct - param.angle_path = "/mnt/share/channel_bp/angle.csv"; - param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct + param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet param.print(); LidarDriver driver; diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index b676de2d..6ff6d552 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -40,7 +40,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include "point_cloud_msg.h" #endif -typedef PointCloudT PointCloudMsg; +typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; @@ -53,8 +53,7 @@ void pointCloudCallback(const PointCloudMsg& msg) { /* Note: Please do not put time-consuming operations in the callback function! */ /* Make a copy of the message and process it in another thread is recommended*/ - RS_MSG << "msg: " << msg.seq - << " point cloud size: " << msg.points.size() << RS_REND; + RS_MSG << "msg: " << msg.seq << " point cloud size: " << msg.points.size() << RS_REND; } /** @@ -79,11 +78,10 @@ int main(int argc, char* argv[]) RSDriverParam param; ///< Create a parameter object param.input_param.read_pcap = true; ///< Set read_pcap to true - param.input_param.pcap_path = "/mnt/share/pcap/BP/RsBp.pcap";///< Set the pcap file directory - param.input_param.msop_port = 2370; ///< Set the lidar msop port number, the default is 6699 - param.input_param.difop_port = 8310; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RSBP; ///< Set the lidar type. Make sure this type is correct - param.angle_path = "/mnt/share/channel_bp/angle.csv"; + param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file directory + param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 + param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct param.print(); diff --git a/demo/pcl_point_cloud_msg.h b/demo/pcl_point_cloud_msg.h index 1ea6fc7c..cef350a8 100644 --- a/demo/pcl_point_cloud_msg.h +++ b/demo/pcl_point_cloud_msg.h @@ -50,9 +50,8 @@ struct RsPointXYZIRT EIGEN_MAKE_ALIGNED_OPERATOR_NEW } EIGEN_ALIGN16; -POINT_CLOUD_REGISTER_POINT_STRUCT(RsPointXYZIRT, - (float, x, x)(float, y, y)(float, z, z)(uint8_t, intensity, intensity) - (uint16_t, ring, ring)(double, timestamp, timestamp)) +POINT_CLOUD_REGISTER_POINT_STRUCT(RsPointXYZIRT, (float, x, x)(float, y, y)(float, z, z)(uint8_t, intensity, intensity)( + uint16_t, ring, ring)(double, timestamp, timestamp)) typedef RsPointXYZIRT PointT; @@ -62,12 +61,10 @@ template class PointCloudT : public pcl::PointCloud { public: - typedef T_Point PointT; typedef typename pcl::PointCloud::VectorType VectorT; double timestamp = 0.0; - std::string frame_id = ""; ///< Point cloud frame id - uint32_t seq = 0; ///< Sequence number of message + std::string frame_id = ""; ///< Point cloud frame id + uint32_t seq = 0; ///< Sequence number of message }; - diff --git a/demo/point_cloud_msg.h b/demo/point_cloud_msg.h index 707bcf16..e340df35 100644 --- a/demo/point_cloud_msg.h +++ b/demo/point_cloud_msg.h @@ -34,29 +34,29 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #if 1 - struct PointXYZI - { - float x; - float y; - float z; - uint8_t intensity; - }; +struct PointXYZI +{ + float x; + float y; + float z; + uint8_t intensity; +}; - typedef PointXYZI PointT; +typedef PointXYZI PointT; #else - struct PointXYZIRT - { - float x; - float y; - float z; - uint8_t intensity; - uint16_t ring; - double timestamp; - }; +struct PointXYZIRT +{ + float x; + float y; + float z; + uint8_t intensity; + uint16_t ring; + double timestamp; +}; - typedef PointXYZIRT PointT; +typedef PointXYZIRT PointT; #endif @@ -64,17 +64,15 @@ template class PointCloudT { public: - typedef T_Point PointT; typedef std::vector VectorT; - uint32_t height = 0; ///< Height of point cloud - uint32_t width = 0; ///< Width of point cloud + uint32_t height = 0; ///< Height of point cloud + uint32_t width = 0; ///< Width of point cloud bool is_dense = false; ///< If is_dense=true, the point cloud does not contain NAN points double timestamp = 0.0; - std::string frame_id = ""; ///< Point cloud frame id - uint32_t seq = 0; ///< Sequence number of message + std::string frame_id = ""; ///< Point cloud frame id + uint32_t seq = 0; ///< Sequence number of message VectorT points; }; - diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index 3ea0bf91..4fbccf92 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -47,8 +47,7 @@ class LidarDriver /** * @brief Constructor, instanciate the driver pointer */ - LidarDriver() - : driver_ptr_(std::make_shared>()) + LidarDriver() : driver_ptr_(std::make_shared>()) { } diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index a5e3f8cd..2e993352 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -83,13 +83,13 @@ class DecoderRS128 : public DecoderBase public: explicit DecoderRS128(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; template -inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) +inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, + const LidarConstantParameter& lidar_const_param) : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -112,8 +112,9 @@ inline double DecoderRS128::getLidarTime(const uint8_t* pkt) } template -inline RSDecoderResult DecoderRS128::decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth) +inline RSDecoderResult DecoderRS128::decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, + int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RS128MsopPkt* mpkt_ptr = reinterpret_cast(pkt); diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 38714d0e..dfe5f33d 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -84,13 +84,13 @@ class DecoderRS16 : public DecoderBase public: DecoderRS16(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; template -inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) +inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, + const LidarConstantParameter& lidar_const_param) : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -113,8 +113,8 @@ inline double DecoderRS16::getLidarTime(const uint8_t* pkt) } template -inline RSDecoderResult DecoderRS16::decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth) +inline RSDecoderResult DecoderRS16::decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, + int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RS16MsopPkt* mpkt_ptr = reinterpret_cast(pkt); diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 1526b496..7a6aed21 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -84,13 +84,13 @@ class DecoderRS32 : public DecoderBase public: explicit DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; template -inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) +inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, + const LidarConstantParameter& lidar_const_param) : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -113,8 +113,8 @@ inline double DecoderRS32::getLidarTime(const uint8_t* pkt) } template -inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth) +inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, + int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RS32MsopPkt* mpkt_ptr = reinterpret_cast(pkt); diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 4c8c7ebd..25b16b65 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -84,13 +84,13 @@ class DecoderRS80 : public DecoderBase public: explicit DecoderRS80(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; template -inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) +inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, + const LidarConstantParameter& lidar_const_param) : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -113,8 +113,8 @@ inline double DecoderRS80::getLidarTime(const uint8_t* pkt) } template -inline RSDecoderResult DecoderRS80::decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth) +inline RSDecoderResult DecoderRS80::decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, + int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RS80MsopPkt* mpkt_ptr = reinterpret_cast(pkt); diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index b670149a..4add5499 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -84,13 +84,13 @@ class DecoderRSBP : public DecoderBase public: explicit DecoderRSBP(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; template -inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) +inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, + const LidarConstantParameter& lidar_const_param) : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -113,8 +113,8 @@ inline double DecoderRSBP::getLidarTime(const uint8_t* pkt) } template -inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth) +inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, + int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RSBPMsopPkt* mpkt_ptr = reinterpret_cast(pkt); @@ -171,9 +171,11 @@ inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* p for (int channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) { // charge + reserved = 5.2f - float azi_channel_ori = cur_azi + - azi_diff * this->lidar_const_param_.FIRING_FREQUENCY * - (this->lidar_const_param_.DSR_TOFFSET * static_cast(2 * (channel_idx % 16) + (channel_idx / 16)) + 5.2f * static_cast(channel_idx / 8 % 2)); + float azi_channel_ori = + cur_azi + + azi_diff * this->lidar_const_param_.FIRING_FREQUENCY * + (this->lidar_const_param_.DSR_TOFFSET * static_cast(2 * (channel_idx % 16) + (channel_idx / 16)) + + 5.2f * static_cast(channel_idx / 8 % 2)); int azi_channel_final = this->azimuthCalibration(azi_channel_ori, channel_idx); float distance = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].channels[channel_idx].distance) * diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index b2c790f6..621c01a4 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -95,14 +95,13 @@ class DecoderRSHELIOS : public DecoderBase public: explicit DecoderRSHELIOS(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); }; template inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param) + const LidarConstantParameter& lidar_const_param) : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -125,8 +124,9 @@ inline double DecoderRSHELIOS::getLidarTime(const uint8_t* pkt) } template -inline RSDecoderResult DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth) +inline RSDecoderResult DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, + int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RSHELIOSMsopPkt* mpkt_ptr = reinterpret_cast(pkt); diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 221b4e39..095ba977 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -140,11 +140,9 @@ class DecoderRSM1 : public DecoderBase public: DecoderRSM1(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); - RSDecoderResult processMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& pointcloud_vec, int& height); + RSDecoderResult processMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& pointcloud_vec, int& height); private: uint32_t last_pkt_cnt_; @@ -153,8 +151,12 @@ class DecoderRSM1 : public DecoderBase }; template -inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param), last_pkt_cnt_(1), max_pkt_num_(SINGLE_PKT_NUM), last_pkt_time_(0) +inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, + const LidarConstantParameter& lidar_const_param) + : DecoderBase(param, lidar_const_param) + , last_pkt_cnt_(1) + , max_pkt_num_(SINGLE_PKT_NUM) + , last_pkt_time_(0) { if (this->param_.max_distance > 200.0f) { @@ -174,8 +176,9 @@ inline double DecoderRSM1::getLidarTime(const uint8_t* pkt) } template -inline RSDecoderResult DecoderRSM1::processMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& pointcloud_vec, int& height) +inline RSDecoderResult DecoderRSM1::processMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& pointcloud_vec, + int& height) { int azimuth = 0; RSDecoderResult ret = decodeMsopPkt(pkt, pointcloud_vec, height, azimuth); @@ -201,8 +204,8 @@ inline RSDecoderResult DecoderRSM1::processMsopPkt(const uint8_t* } template -inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth) +inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, + int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; RSM1MsopPkt* mpkt_ptr = (RSM1MsopPkt*)pkt; diff --git a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp index 258e6e4e..c9afabb3 100644 --- a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp @@ -97,7 +97,7 @@ class DecoderRSROCK : public DecoderBase template inline DecoderRSROCK::DecoderRSROCK(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param) + const LidarConstantParameter& lidar_const_param) : DecoderBase(param, lidar_const_param) { this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -132,8 +132,9 @@ inline double DecoderRSROCK::getLidarTime(const uint8_t* pkt) } template -inline RSDecoderResult DecoderRSROCK::decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth) +inline RSDecoderResult DecoderRSROCK::decodeMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& vec, int& height, + int& azimuth) { height = this->lidar_const_param_.LASER_NUM; const RSROCKMsopPkt* mpkt_ptr = reinterpret_cast(pkt); diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index fb4277d4..44d930be 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -278,8 +278,8 @@ class DecoderBase DecoderBase(const DecoderBase&) = delete; DecoderBase& operator=(const DecoderBase&) = delete; virtual ~DecoderBase() = default; - virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& point_cloud_vec, int& height); + virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& point_cloud_vec, + int& height); virtual RSDecoderResult processDifopPkt(const uint8_t* pkt); virtual void loadAngleFile(const std::string& angle_path); virtual void regRecvCallback(const std::function& callback); ///< Camera trigger @@ -291,8 +291,8 @@ class DecoderBase virtual float computeTemperature(const uint8_t& temp_low, const uint8_t& temp_high); virtual int azimuthCalibration(const float& azimuth, const int& channel); virtual void checkTriggerAngle(const int& angle, const double& timestamp); - virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, int& azimuth) = 0; + virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, + int& azimuth) = 0; virtual RSDecoderResult decodeDifopPkt(const uint8_t* pkt) = 0; RSEchoMode getEchoMode(const LidarType& type, const uint8_t& return_mode); template @@ -346,7 +346,8 @@ class DecoderBase }; template -inline DecoderBase::DecoderBase(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) +inline DecoderBase::DecoderBase(const RSDecoderParam& param, + const LidarConstantParameter& lidar_const_param) : lidar_const_param_(lidar_const_param) , param_(param) , echo_mode_(ECHO_SINGLE) @@ -399,13 +400,13 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, const return ret_time; }; } - // } - // else - // { - // get_point_time_func_ = [this](const uint8_t* pkt) { return 0; }; - // } +// } +// else +// { +// get_point_time_func_ = [this](const uint8_t* pkt) { return 0; }; +// } - // Camera trigger function +// Camera trigger function #ifdef ENABLE_PUBLISH_CAM_MSG if (param.trigger_param.trigger_map.size() > 0) { @@ -448,8 +449,9 @@ inline RSDecoderResult DecoderBase::processDifopPkt(const uint8_t* } template -inline RSDecoderResult DecoderBase::processMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& point_cloud_vec, int& height) +inline RSDecoderResult DecoderBase::processMsopPkt(const uint8_t* pkt, + typename T_PointCloud::VectorT& point_cloud_vec, + int& height) { if (pkt == NULL) { diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 299f9431..286295b3 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -65,7 +65,8 @@ class DecoderFactory }; template -inline std::shared_ptr> DecoderFactory::createDecoder(const RSDriverParam& param) +inline std::shared_ptr> +DecoderFactory::createDecoder(const RSDriverParam& param) { std::shared_ptr> ret_ptr; switch (param.lidar_type) diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index 85cd8e2a..746de5b6 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -62,7 +62,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include -#define MAX_ETH_LEN 1500 +#define MAX_PKT_LEN 1500 #define ETH_HDR_LEN 42 #define VLAN_LEN 4 #define SOME_IP_LEN 16 @@ -71,25 +71,24 @@ namespace robosense { namespace lidar { - class Input { public: - Input(const RSInputParam& input_param, const std::function& excb); inline void regRecvCallback(const std::function(size_t)>& cb_get, - const std::function)>& cb_put_msop, - const std::function)>& cb_put_difop); + const std::function)>& cb_put_msop, + const std::function)>& cb_put_difop); virtual bool init() = 0; virtual bool start() = 0; virtual void stop(); - virtual ~Input() {} + virtual ~Input() + { + } protected: - - inline void pushPacket (std::shared_ptr pkt); + inline void pushPacket(std::shared_ptr pkt); RSInputParam input_param_; std::function(size_t size)> cb_get_; @@ -101,15 +100,14 @@ class Input bool init_flag_; }; -inline Input::Input(const RSInputParam& input_param, - const std::function& excb) +inline Input::Input(const RSInputParam& input_param, const std::function& excb) : input_param_(input_param), excb_(excb), to_exit_recv_(false), init_flag_(false) { } inline void Input::regRecvCallback(const std::function(size_t)>& cb_get, - const std::function)>& cb_put_msop, - const std::function)>& cb_put_difop) + const std::function)>& cb_put_msop, + const std::function)>& cb_put_difop) { cb_get_ = cb_get; cb_put_msop_ = cb_put_msop; @@ -122,14 +120,14 @@ inline void Input::stop() recv_thread_.join(); } -inline void Input::pushPacket (std::shared_ptr pkt) +inline void Input::pushPacket(std::shared_ptr pkt) { uint8_t* id = pkt->data(); - if (*id == 0x55) + if (*id == 0x55) { cb_put_msop_(pkt); } - else if (*id == 0xA5) + else if (*id == 0xA5) { cb_put_difop_(pkt); } diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index cad85698..39217fe7 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -38,7 +38,6 @@ namespace robosense { namespace lidar { - inline long long msecToDelay(LidarType type, double replay_rate) { constexpr double RS16_PCAP_SLEEP_DURATION = 1200; ///< us @@ -86,12 +85,12 @@ inline long long msecToDelay(LidarType type, double replay_rate) class InputFactory { public: - static std::shared_ptr createInput( - const RSDriverParam& driver_param, const std::function& excb); + static std::shared_ptr createInput(const RSDriverParam& driver_param, + const std::function& excb); }; -inline std::shared_ptr InputFactory::createInput( - const RSDriverParam& driver_param, const std::function& excb) +inline std::shared_ptr InputFactory::createInput(const RSDriverParam& driver_param, + const std::function& excb) { const RSInputParam& input_param = driver_param.input_param; std::shared_ptr input; diff --git a/src/rs_driver/driver/input/pcap_input.hpp b/src/rs_driver/driver/input/pcap_input.hpp index d261cb8d..68992c2a 100644 --- a/src/rs_driver/driver/input/pcap_input.hpp +++ b/src/rs_driver/driver/input/pcap_input.hpp @@ -37,20 +37,16 @@ namespace robosense { namespace lidar { - class PcapInput : public Input { public: - - PcapInput(const RSInputParam& input_param, - const std::function& excb, long long msec_to_delay) - : Input (input_param, excb), - pcap_offset_(ETH_HDR_LEN), difop_filter_valid_(false), msec_to_delay_(msec_to_delay) + PcapInput(const RSInputParam& input_param, const std::function& excb, long long msec_to_delay) + : Input(input_param, excb), pcap_offset_(ETH_HDR_LEN), difop_filter_valid_(false), msec_to_delay_(msec_to_delay) { if (input_param.use_vlan) - pcap_offset_ += VLAN_LEN; + pcap_offset_ += VLAN_LEN; if (input_param.use_someip) - pcap_offset_ += SOME_IP_LEN; + pcap_offset_ += SOME_IP_LEN; std::stringstream msop_stream, difop_stream; if (input_param_.use_vlan) @@ -114,7 +110,7 @@ inline bool PcapInput::start() return false; } - recv_thread_ = std::thread (std::bind(&PcapInput::recvPacket, this)); + recv_thread_ = std::thread(std::bind(&PcapInput::recvPacket, this)); return true; } @@ -134,7 +130,7 @@ inline void PcapInput::recvPacket() struct pcap_pkthdr* header; const u_char* pkt_data; int ret = pcap_next_ex(pcap_, &header, &pkt_data); - if (ret < 0) // reach file end. + if (ret < 0) // reach file end. { if (input_param_.pcap_repeat) { @@ -153,18 +149,17 @@ inline void PcapInput::recvPacket() if (pcap_offline_filter(&msop_filter_, header, pkt_data) != 0) { - std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); + std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_); pkt->setData(0, header->len - pcap_offset_); - pushPacket (pkt); + pushPacket(pkt); } - else if (difop_filter_valid_ && - (pcap_offline_filter(&difop_filter_, header, pkt_data) != 0)) + else if (difop_filter_valid_ && (pcap_offline_filter(&difop_filter_, header, pkt_data) != 0)) { - std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); + std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_); pkt->setData(0, header->len - pcap_offset_); - pushPacket (pkt); + pushPacket(pkt); } else { diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index 27fb1424..5c067e54 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -38,16 +38,14 @@ namespace robosense { namespace lidar { - class SockInput : public Input { public: - - SockInput(const RSInputParam& input_param, const std::function& excb) - : Input (input_param, excb), sock_offset_(0) + SockInput(const RSInputParam& input_param, const std::function& excb) + : Input(input_param, excb), sock_offset_(0) { if (input_param.use_someip) - sock_offset_ += SOME_IP_LEN; + sock_offset_ += SOME_IP_LEN; } virtual bool init(); @@ -55,7 +53,6 @@ class SockInput : public Input virtual ~SockInput(); private: - inline void recvPacket(); inline void higherThreadPrioty(std::thread::native_handle_type handle); inline int createSocket(uint16_t port, const std::string& ip); @@ -67,15 +64,15 @@ class SockInput : public Input inline void SockInput::higherThreadPrioty(std::thread::native_handle_type handle) { -#ifdef ENABLE_HIGH_PRIORITY_THREAD +#ifdef ENABLE_HIGH_PRIORITY_THREAD int policy; sched_param sch; - pthread_getschedparam (handle, &policy, &sch); + pthread_getschedparam(handle, &policy, &sch); sch.sched_priority = 63; - if (pthread_setschedparam (handle, SCHED_RR, &sch)) + if (pthread_setschedparam(handle, SCHED_RR, &sch)) { - std::cout << "setschedparam failed: " << std::strerror(errno) << '\n'; + std::cout << "setschedparam failed: " << std::strerror(errno) << '\n'; } #endif } @@ -87,20 +84,20 @@ inline bool SockInput::init() int msop_fd = -1, difop_fd = -1; - msop_fd = createSocket (input_param_.msop_port, input_param_.multi_cast_address); + msop_fd = createSocket(input_param_.msop_port, input_param_.multi_cast_address); if (msop_fd < 0) goto failMsop; - + if ((input_param_.difop_port != 0) && (input_param_.difop_port != input_param_.msop_port)) { - difop_fd = createSocket (input_param_.difop_port, input_param_.multi_cast_address); + difop_fd = createSocket(input_param_.difop_port, input_param_.multi_cast_address); if (difop_fd < 0) goto failDifop; } fds_[0] = msop_fd; fds_[1] = difop_fd; - + init_flag_ = true; return true; @@ -118,9 +115,9 @@ inline bool SockInput::start() return false; } - recv_thread_ = std::thread (std::bind(&SockInput::recvPacket, this)); + recv_thread_ = std::thread(std::bind(&SockInput::recvPacket, this)); - higherThreadPrioty (recv_thread_.native_handle()); + higherThreadPrioty(recv_thread_.native_handle()); return true; } @@ -130,7 +127,7 @@ inline SockInput::~SockInput() stop(); close(fds_[0]); - if (fds_[1] >= 0) + if (fds_[1] >= 0) close(fds_[1]); } @@ -174,8 +171,8 @@ inline int SockInput::createSocket(uint16_t port, const std::string& ip) } } - flags = fcntl (fd, F_GETFL, 0); - ret = fcntl (fd, F_SETFL, flags|O_NONBLOCK); + flags = fcntl(fd, F_GETFL, 0); + ret = fcntl(fd, F_SETFL, flags | O_NONBLOCK); if (ret < 0) { std::cerr << "setsockopt: " << std::strerror(errno) << std::endl; @@ -200,7 +197,8 @@ inline void SockInput::recvPacket() { FD_ZERO(&rfds); FD_SET(fds_[0], &rfds); - if (fds_[1] >= 0) FD_SET(fds_[1], &rfds); + if (fds_[1] >= 0) + FD_SET(fds_[1], &rfds); int max_fd = std::max(fds_[0], fds_[1]); struct timeval tv; @@ -222,27 +220,27 @@ inline void SockInput::recvPacket() if (FD_ISSET(fds_[0], &rfds)) { - std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); + std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); pkt->resetData(); - ssize_t ret = recvfrom(fds_[0], pkt->data(), MAX_ETH_LEN, 0, NULL, NULL); + ssize_t ret = recvfrom(fds_[0], pkt->data(), MAX_PKT_LEN, 0, NULL, NULL); if (ret <= 0) { std::cout << "recv failed" << std::endl; break; } - pkt->setData (sock_offset_, ret - sock_offset_); - pushPacket (pkt); + pkt->setData(sock_offset_, ret - sock_offset_); + pushPacket(pkt); } else if (FD_ISSET(fds_[1], &rfds)) { - std::shared_ptr pkt = cb_get_(MAX_ETH_LEN); + std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); pkt->resetData(); - ssize_t ret = recvfrom(fds_[1], pkt->data(), MAX_ETH_LEN, 0, NULL, NULL); + ssize_t ret = recvfrom(fds_[1], pkt->data(), MAX_PKT_LEN, 0, NULL, NULL); if (ret <= 0) break; - pkt->setData (sock_offset_, ret - sock_offset_); + pkt->setData(sock_offset_, ret - sock_offset_); pushPacket(pkt); } } diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index b7f651ec..839661fe 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -40,13 +40,11 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include - constexpr size_t MAX_PACKETS_BUFFER_SIZE = 100000; namespace robosense { namespace lidar { - template class LidarDriverImpl { @@ -111,8 +109,7 @@ class LidarDriverImpl template inline LidarDriverImpl::LidarDriverImpl() - : init_flag_(false), start_flag_(false), difop_flag_(false), - point_cloud_seq_(0), scan_seq_(0), ndifop_count_(0) + : init_flag_(false), start_flag_(false), difop_flag_(false), point_cloud_seq_(0), scan_seq_(0), ndifop_count_(0) { } @@ -141,15 +138,14 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) driver_param_ = param; lidar_decoder_ptr_ = DecoderFactory::createDecoder(driver_param_); - lidar_decoder_ptr_->regRecvCallback( + lidar_decoder_ptr_->regRecvCallback( std::bind(&LidarDriverImpl::localCameraTriggerCallback, this, std::placeholders::_1)); - input_ptr_ = InputFactory::createInput(driver_param_, - std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); - input_ptr_->regRecvCallback( - std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), - std::bind(&LidarDriverImpl::msopCallback, this, std::placeholders::_1), - std::bind(&LidarDriverImpl::difopCallback, this, std::placeholders::_1)); + input_ptr_ = InputFactory::createInput( + driver_param_, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); + input_ptr_->regRecvCallback(std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), + std::bind(&LidarDriverImpl::msopCallback, this, std::placeholders::_1), + std::bind(&LidarDriverImpl::difopCallback, this, std::placeholders::_1)); if (!input_ptr_->init()) { @@ -189,10 +185,8 @@ inline bool LidarDriverImpl::start() if (start_flag_) return true; - msop_handle_thread_ = std::thread ( - std::bind(&LidarDriverImpl::processMsop, this)); - difop_handle_thread_ = std::thread ( - std::bind(&LidarDriverImpl::processDifop, this)); + msop_handle_thread_ = std::thread(std::bind(&LidarDriverImpl::processMsop, this)); + difop_handle_thread_ = std::thread(std::bind(&LidarDriverImpl::processDifop, this)); input_ptr_->start(); @@ -215,8 +209,7 @@ inline void LidarDriverImpl::stop() } template -inline void -LidarDriverImpl::regRecvCallback(const std::function& callback) +inline void LidarDriverImpl::regRecvCallback(const std::function& callback) { point_cloud_cb_vec_.emplace_back(callback); } @@ -257,8 +250,7 @@ inline bool LidarDriverImpl::getLidarTemperature(double& input_tem } template -inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, - T_PointCloud& point_cloud_msg) +inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg) { if (driver_param_.wait_for_difop && !difop_flag_) { @@ -280,8 +272,8 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_ms { typename T_PointCloud::VectorT pointcloud_one_packet; - RSDecoderResult ret = lidar_decoder_ptr_->processMsopPkt( - scan_msg.packets[i].packet.data(), pointcloud_one_packet, height); + RSDecoderResult ret = + lidar_decoder_ptr_->processMsopPkt(scan_msg.packets[i].packet.data(), pointcloud_one_packet, height); switch (ret) { case RSDecoderResult::DECODE_OK: @@ -414,7 +406,7 @@ inline void LidarDriverImpl::processMsop() continue; int height = 1; - int ret = lidar_decoder_ptr_->processMsopPkt (pkt->data(), point_cloud_.points, height); + int ret = lidar_decoder_ptr_->processMsopPkt(pkt->data(), point_cloud_.points, height); #ifdef ENABLE_PUBLISH_RAW_MSG PacketMsg msg; @@ -438,7 +430,7 @@ inline void LidarDriverImpl::processMsop() } if (msg.points.size() == 0) - { + { reportError(Error(ERRCODE_ZEROPOINTS)); } else diff --git a/src/rs_driver/msg/packet.h b/src/rs_driver/msg/packet.h index 12d30d7e..01e92d49 100644 --- a/src/rs_driver/msg/packet.h +++ b/src/rs_driver/msg/packet.h @@ -42,10 +42,10 @@ class Packet public: Packet(size_t cap) : off_(0), len_(0) { - buf_ = (uint8_t*) malloc(cap); + buf_ = (uint8_t*)malloc(cap); } - void setData (size_t off, size_t len) + void setData(size_t off, size_t len) { off_ = off; len_ = len; diff --git a/src/rs_driver/utility/dbg.h b/src/rs_driver/utility/dbg.h index cc28f500..d8bb9b83 100644 --- a/src/rs_driver/utility/dbg.h +++ b/src/rs_driver/utility/dbg.h @@ -37,18 +37,18 @@ namespace robosense { namespace lidar { - -inline void hexdump (const unsigned char* data, size_t size, const char* desc = NULL) +inline void hexdump(const unsigned char* data, size_t size, const char* desc = NULL) { - printf ("\n---------------%s------------------", (desc ? desc : "")); + printf("\n---------------%s------------------", (desc ? desc : "")); for (size_t i = 0; i < size; i++) { - if (i % 16 == 0) printf ("\n"); - printf ("%02x ", data[i]); + if (i % 16 == 0) + printf("\n"); + printf("%02x ", data[i]); } - printf ("\n---------------------------------\n"); + printf("\n---------------------------------\n"); } } // namespace lidar diff --git a/src/rs_driver/utility/sync_queue.h b/src/rs_driver/utility/sync_queue.h index 66181f8c..ee84a38a 100644 --- a/src/rs_driver/utility/sync_queue.h +++ b/src/rs_driver/utility/sync_queue.h @@ -40,7 +40,6 @@ template class SyncQueue { public: - inline void push(const T& value) { std::lock_guard lg(mtx_); @@ -67,14 +66,13 @@ class SyncQueue return value; } - inline T popWait (unsigned int usec) + inline T popWait(unsigned int usec) { T value; std::unique_lock lck(mtx_); - cv_.wait_for (lck, std::chrono::microseconds(usec), - [this]{return (!queue_.empty());}); + cv_.wait_for(lck, std::chrono::microseconds(usec), [this] { return (!queue_.empty()); }); if (!queue_.empty()) { From 8f1d9450e173efd7b446e085d9c0db1472c24926 Mon Sep 17 00:00:00 2001 From: ronzheng Date: Mon, 1 Nov 2021 12:16:53 +0800 Subject: [PATCH 008/379] fix: check msop/difop pkt len --- src/rs_driver/common/error_code.h | 7 +++-- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 13 ++++++-- .../driver/decoder/decoder_RSROCK.hpp | 2 ++ src/rs_driver/driver/decoder/decoder_base.hpp | 31 ++++++++++++++----- .../driver/decoder/decoder_factory.hpp | 20 ------------ src/rs_driver/driver/lidar_driver_impl.hpp | 14 ++++++--- 6 files changed, 51 insertions(+), 36 deletions(-) diff --git a/src/rs_driver/common/error_code.h b/src/rs_driver/common/error_code.h index cb21ff55..79f95479 100644 --- a/src/rs_driver/common/error_code.h +++ b/src/rs_driver/common/error_code.h @@ -65,8 +65,9 @@ enum ErrCode ERRCODE_MSOPPORTBUZY = 0x49, ///< Input msop port is already used ERRCODE_DIFOPPORTBUZY = 0x50, ///< Input difop port is already used ERRCODE_WRONGPKTHEADER = 0x51, ///< Packet header is wrong - ERRCODE_PKTNULL = 0x52, ///< Input packet is null - ERRCODE_PKTBUFOVERFLOW = 0x53 ///< Packet buffer is over flow + ERRCODE_WRONGPKTLENGTH = 0x52, ///< Packet length is wrong + ERRCODE_PKTNULL = 0x53, ///< Input packet is null + ERRCODE_PKTBUFOVERFLOW = 0x54 ///< Packet buffer is over flow }; struct Error @@ -118,6 +119,8 @@ struct Error return "ERRCODE_STARTBEFOREINIT"; case ERRCODE_WRONGPKTHEADER: return "ERRCODE_WRONGPKTHEADER"; + case ERRCODE_WRONGPKTLENGTH: + return "ERRCODE_WRONGPKTLENGTH"; case ERRCODE_PKTNULL: return "ERRCODE_PKTNULL"; case ERRCODE_PKTBUFOVERFLOW: diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 095ba977..bd3d9a57 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -142,7 +142,8 @@ class DecoderRSM1 : public DecoderBase RSDecoderResult decodeDifopPkt(const uint8_t* pkt); RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); double getLidarTime(const uint8_t* pkt); - RSDecoderResult processMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& pointcloud_vec, int& height); + RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size, typename T_PointCloud::VectorT& pointcloud_vec, + int& height); private: uint32_t last_pkt_cnt_; @@ -158,6 +159,9 @@ inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, , max_pkt_num_(SINGLE_PKT_NUM) , last_pkt_time_(0) { + this->msop_pkt_len_ = MEMS_MSOP_LEN; + this->difop_pkt_len_ = MEMS_DIFOP_LEN; + if (this->param_.max_distance > 200.0f) { this->param_.max_distance = 200.0f; @@ -176,10 +180,15 @@ inline double DecoderRSM1::getLidarTime(const uint8_t* pkt) } template -inline RSDecoderResult DecoderRSM1::processMsopPkt(const uint8_t* pkt, +inline RSDecoderResult DecoderRSM1::processMsopPkt(const uint8_t* pkt, size_t size, typename T_PointCloud::VectorT& pointcloud_vec, int& height) { + if (size != this->msop_pkt_len_) + { + return WRONG_PKT_LENGTH; + } + int azimuth = 0; RSDecoderResult ret = decodeMsopPkt(pkt, pointcloud_vec, height, azimuth); this->pkt_count_++; diff --git a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp index c9afabb3..fce2cf10 100644 --- a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp @@ -100,6 +100,8 @@ inline DecoderRSROCK::DecoderRSROCK(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) : DecoderBase(param, lidar_const_param) { + this->msop_pkt_len_ = 1236; // TODO + this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->beam_ring_table_.resize(this->lidar_const_param_.LASER_NUM); diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 44d930be..98eb49c7 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -77,8 +77,9 @@ enum RSDecoderResult DECODE_OK = 0, FRAME_SPLIT = 1, WRONG_PKT_HEADER = -1, - PKT_NULL = -2, - DISCARD_PKT = -3 + WRONG_PKT_LENGTH = -2, + PKT_NULL = -3, + DISCARD_PKT = -4 }; #pragma pack(push, 1) @@ -278,9 +279,9 @@ class DecoderBase DecoderBase(const DecoderBase&) = delete; DecoderBase& operator=(const DecoderBase&) = delete; virtual ~DecoderBase() = default; - virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& point_cloud_vec, - int& height); - virtual RSDecoderResult processDifopPkt(const uint8_t* pkt); + virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size, + typename T_PointCloud::VectorT& point_cloud_vec, int& height); + virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size); virtual void loadAngleFile(const std::string& angle_path); virtual void regRecvCallback(const std::function& callback); ///< Camera trigger virtual double getLidarTemperature(); @@ -314,6 +315,8 @@ class DecoderBase protected: const LidarConstantParameter lidar_const_param_; RSDecoderParam param_; + uint32_t msop_pkt_len_; + uint32_t difop_pkt_len_; RSEchoMode echo_mode_; unsigned int pkts_per_frame_; unsigned int pkt_count_; @@ -350,6 +353,8 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) : lidar_const_param_(lidar_const_param) , param_(param) + , msop_pkt_len_(MECH_PKT_LEN) + , difop_pkt_len_(MECH_PKT_LEN) , echo_mode_(ECHO_SINGLE) , pkts_per_frame_(lidar_const_param.PKT_RATE / 10) , pkt_count_(0) @@ -439,17 +444,23 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, } template -inline RSDecoderResult DecoderBase::processDifopPkt(const uint8_t* pkt) +inline RSDecoderResult DecoderBase::processDifopPkt(const uint8_t* pkt, size_t size) { if (pkt == NULL) { return PKT_NULL; } + + if (size != this->difop_pkt_len_) + { + return WRONG_PKT_LENGTH; + } + return decodeDifopPkt(pkt); } template -inline RSDecoderResult DecoderBase::processMsopPkt(const uint8_t* pkt, +inline RSDecoderResult DecoderBase::processMsopPkt(const uint8_t* pkt, size_t size, typename T_PointCloud::VectorT& point_cloud_vec, int& height) { @@ -457,6 +468,12 @@ inline RSDecoderResult DecoderBase::processMsopPkt(const uint8_t* { return PKT_NULL; } + + if (size != this->msop_pkt_len_) + { + return WRONG_PKT_LENGTH; + } + int azimuth = 0; RSDecoderResult ret = decodeMsopPkt(pkt, point_cloud_vec, height, azimuth); if (ret != RSDecoderResult::DECODE_OK) diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 286295b3..3007dd7d 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -39,7 +39,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -//#include #include namespace robosense { @@ -257,24 +256,5 @@ inline const LidarConstantParameter DecoderFactory::getRSROCKConstantPa return ret_param; } -inline void getLidarPktLength(uint8_t type, uint32_t* msop_pkt_len, uint32_t* difop_pkt_len) -{ - switch (type) - { - case LidarType::RSM1: - *msop_pkt_len = MEMS_MSOP_LEN; - *difop_pkt_len = MEMS_DIFOP_LEN; - break; - case LidarType::RSROCK: - *msop_pkt_len = 1236; // TODO - *difop_pkt_len = MECH_PKT_LEN; - break; - default: - *msop_pkt_len = MECH_PKT_LEN; - *difop_pkt_len = MECH_PKT_LEN; - break; - } -} - } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 839661fe..5ba1dd74 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -272,8 +272,9 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_ms { typename T_PointCloud::VectorT pointcloud_one_packet; + const PacketMsg& pkt = scan_msg.packets[i]; RSDecoderResult ret = - lidar_decoder_ptr_->processMsopPkt(scan_msg.packets[i].packet.data(), pointcloud_one_packet, height); + lidar_decoder_ptr_->processMsopPkt(pkt.packet.data(), pkt.packet.size(), pointcloud_one_packet, height); switch (ret) { case RSDecoderResult::DECODE_OK: @@ -309,7 +310,7 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_ms template inline void LidarDriverImpl::decodeDifopPkt(const PacketMsg& pkt) { - lidar_decoder_ptr_->processDifopPkt(pkt.packet.data()); + lidar_decoder_ptr_->processDifopPkt(pkt.packet.data(), pkt.packet.size()); difop_flag_ = true; } @@ -406,7 +407,7 @@ inline void LidarDriverImpl::processMsop() continue; int height = 1; - int ret = lidar_decoder_ptr_->processMsopPkt(pkt->data(), point_cloud_.points, height); + int ret = lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->len(), point_cloud_.points, height); #ifdef ENABLE_PUBLISH_RAW_MSG PacketMsg msg; @@ -448,7 +449,10 @@ inline void LidarDriverImpl::processMsop() } else if (ret < 0) { - reportError(Error(ERRCODE_WRONGPKTHEADER)); + if (ret == WRONG_PKT_LENGTH) + reportError(Error(ERRCODE_WRONGPKTLENGTH)); + else + reportError(Error(ERRCODE_WRONGPKTHEADER)); } packetPut(pkt); @@ -473,7 +477,7 @@ inline void LidarDriverImpl::processDifop() if (pkt.get() == NULL) continue; - lidar_decoder_ptr_->processDifopPkt(pkt->data()); + lidar_decoder_ptr_->processDifopPkt(pkt->data(), pkt->len()); difop_flag_ = true; #ifdef ENABLE_PUBLISH_RAW_MSG From a405d94af9a21c5c21fab7e3b6990998b2ee6699 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 1 Nov 2021 15:11:00 +0800 Subject: [PATCH 009/379] feat: update CHANGELOG --- CHANGELOG.md | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index bb190a4a..9accaadf 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,6 +1,16 @@ # Changelog -## Unreleased +## v1.4.0 - 2021-11-01 + +### Changed + +Optimazation to decrease CPU uage, includes: +- replace point with point cloud as template parameter +- instead of alloc/free packet, use packet pool +- instead of alloc/free point cloud, always keep point cloud memory +- by default, use conditional macro to disable scan_msg/camera_trigger related code + +## V1.3.1 ### Added - Add vlan support - Add somip support @@ -15,9 +25,6 @@ ### Removed - Remove redundance condition code in vec.emplace_back(std::move(point)) in mech lidars - - - ## v1.3.0 - 2020-11-10 ### Added From 8aae53401b73689e79148078fb0215b8a1dc6b3d Mon Sep 17 00:00:00 2001 From: ronzheng Date: Wed, 3 Nov 2021 16:42:18 +0800 Subject: [PATCH 010/379] fix: fix compiling error --- src/rs_driver/driver/lidar_driver_impl.hpp | 9 ++++--- tool/rs_driver_viewer.cpp | 28 +++++++++++++++++++--- 2 files changed, 31 insertions(+), 6 deletions(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 5ba1dd74..390747ec 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -410,7 +410,8 @@ inline void LidarDriverImpl::processMsop() int ret = lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->len(), point_cloud_.points, height); #ifdef ENABLE_PUBLISH_RAW_MSG - PacketMsg msg; + PacketMsg msg(pkt->len()); + memcpy (msg.packet.data(), pkt->data(), pkt->len()); scan_ptr_.packets.emplace_back(msg); #endif @@ -442,7 +443,7 @@ inline void LidarDriverImpl::processMsop() #ifdef ENABLE_PUBLISH_RAW_MSG setScanMsgHeader(scan_ptr_); runCallBack(scan_ptr_); - scan_ptr_.packets.reset(0); + scan_ptr_.packets.resize(0); #endif point_cloud_.points.resize(0); @@ -481,7 +482,9 @@ inline void LidarDriverImpl::processDifop() difop_flag_ = true; #ifdef ENABLE_PUBLISH_RAW_MSG - runCallBack(*pkt); + PacketMsg msg(pkt->len()); + memcpy (msg.packet.data(), pkt->data(), pkt->len()); + runCallBack(msg); #endif packetPut(pkt); diff --git a/tool/rs_driver_viewer.cpp b/tool/rs_driver_viewer.cpp index aa7278d0..91f1565b 100644 --- a/tool/rs_driver_viewer.cpp +++ b/tool/rs_driver_viewer.cpp @@ -33,6 +33,23 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include "rs_driver/api/lidar_driver.h" + +typedef pcl::PointXYZI PointT; + +template +class PointCloudT : public pcl::PointCloud +{ +public: + typedef T_Point PointT; + typedef typename pcl::PointCloud::VectorType VectorT; + + double timestamp = 0.0; + std::string frame_id = ""; ///< Point cloud frame id + uint32_t seq = 0; ///< Sequence number of message +}; + +typedef PointCloudT PointCloudMsg; + using namespace robosense::lidar; using namespace pcl::visualization; std::shared_ptr pcl_viewer; @@ -173,16 +190,20 @@ void printParam(const RSDriverParam& param) * When the point cloud message is ready, driver can send out messages through this function. * @param msg The lidar point cloud message. */ -void pointCloudCallback(const PointCloudMsg& msg) +void pointCloudCallback(const PointCloudMsg& msg) { + std::cout << "ponits:" << msg.points.size() << std::endl; + /* Note: Please do not put time-consuming operations in the callback function! */ /* Make a copy of the message and process it in another thread is recommended*/ pcl::PointCloud::Ptr pcl_pointcloud(new pcl::PointCloud); - pcl_pointcloud->points.assign(msg.point_cloud_ptr->begin(), msg.point_cloud_ptr->end()); + pcl_pointcloud->points.assign(msg.points.begin(), msg.points.end()); pcl_pointcloud->height = msg.height; pcl_pointcloud->width = msg.width; pcl_pointcloud->is_dense = false; + PointCloudColorHandlerGenericField point_color_handle(pcl_pointcloud, "intensity"); + { const std::lock_guard lock(mex_viewer); pcl_viewer->updatePointCloud(pcl_pointcloud, point_color_handle, "rslidar"); @@ -224,10 +245,11 @@ int main(int argc, char* argv[]) pcl_viewer->addPointCloud(pcl_pointcloud, "rslidar"); pcl_viewer->setPointCloudRenderingProperties(PCL_VISUALIZER_POINT_SIZE, 2, "rslidar"); - LidarDriver driver; ///< Declare the driver object RSDriverParam param; ///< Create a parameter object parseParam(argc, argv, param); printParam(param); + + LidarDriver driver; ///< Declare the driver object driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver driver.regRecvCallback(pointCloudCallback); ///< Register the point cloud callback function into the driver if (!driver.init(param)) ///< Call the init function and pass the parameter From 319ce161008c971353ed054bb750c330df7f62e5 Mon Sep 17 00:00:00 2001 From: ronzheng Date: Fri, 5 Nov 2021 18:06:45 +0800 Subject: [PATCH 011/379] feat: support dense attribute --- .../driver/decoder/decoder_RS128.hpp | 16 +++-- src/rs_driver/driver/decoder/decoder_RS16.hpp | 26 +++++--- src/rs_driver/driver/decoder/decoder_RS32.hpp | 15 +++-- src/rs_driver/driver/decoder/decoder_RS80.hpp | 15 +++-- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 15 +++-- .../driver/decoder/decoder_RSHELIOS.hpp | 15 +++-- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 15 +++-- .../driver/decoder/decoder_RSROCK.hpp | 15 +++-- src/rs_driver/driver/decoder/decoder_base.hpp | 8 +++ src/rs_driver/driver/driver_param.h | 1 + src/rs_driver/driver/lidar_driver_impl.hpp | 59 +++++++++++-------- 11 files changed, 138 insertions(+), 62 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 2e993352..def2ca12 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -184,7 +184,9 @@ inline RSDecoderResult DecoderRS128::decodeMsopPkt(const uint8_t* this->lidar_const_param_.DIS_RESOLUTION; int angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; + typename T_PointCloud::PointT point; + bool pointValid = false; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -201,17 +203,23 @@ inline RSDecoderResult DecoderRS128::decodeMsopPkt(const uint8_t* setY(point, y); setZ(point, z); setIntensity(point, intensity); + pointValid = true; } - else + else if (!this->param_.is_dense) { setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); + pointValid = true; + } + + if (pointValid) + { + setRing(point, this->beam_ring_table_[channel_idx]); + setTimestamp(point, block_timestamp); + vec.emplace_back(std::move(point)); } - setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, block_timestamp); - vec.emplace_back(std::move(point)); } } return RSDecoderResult::DECODE_OK; diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index dfe5f33d..7362e420 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -169,7 +169,9 @@ inline RSDecoderResult DecoderRS16::decodeMsopPkt(const uint8_t* p this->lidar_const_param_.DIS_RESOLUTION; int angle_horiz_ori = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; int angle_vert = ((this->vert_angle_list_[channel_idx % 16]) + RS_ONE_ROUND) % RS_ONE_ROUND; + typename T_PointCloud::PointT point; + bool pointValid = false; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -186,24 +188,30 @@ inline RSDecoderResult DecoderRS16::decodeMsopPkt(const uint8_t* p setY(point, y); setZ(point, z); setIntensity(point, intensity); + pointValid = true; } - else + else if (!this->param_.is_dense) { setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); + pointValid = true; } - setRing(point, this->beam_ring_table_[channel_idx % 16]); - if (this->echo_mode_ != ECHO_DUAL && channel_idx > 15) - { - setTimestamp(point, block_timestamp + this->time_duration_between_blocks_ / 2); - } - else + + if (pointValid) { - setTimestamp(point, block_timestamp); + setRing(point, this->beam_ring_table_[channel_idx % 16]); + if (this->echo_mode_ != ECHO_DUAL && channel_idx > 15) + { + setTimestamp(point, block_timestamp + this->time_duration_between_blocks_ / 2); + } + else + { + setTimestamp(point, block_timestamp); + } + vec.emplace_back(std::move(point)); } - vec.emplace_back(std::move(point)); } } return RSDecoderResult::DECODE_OK; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 7a6aed21..4388cede 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -181,6 +181,7 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; typename T_PointCloud::PointT point; + bool pointValid = false; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -197,17 +198,23 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p setY(point, y); setZ(point, z); setIntensity(point, intensity); + pointValid = true; } - else + else if (!this->param_.is_dense) { setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); + pointValid = true; + } + + if (pointValid) + { + setRing(point, this->beam_ring_table_[channel_idx]); + setTimestamp(point, block_timestamp); + vec.emplace_back(std::move(point)); } - setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, block_timestamp); - vec.emplace_back(std::move(point)); } } return RSDecoderResult::DECODE_OK; diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 25b16b65..fea5cfd2 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -182,6 +182,7 @@ inline RSDecoderResult DecoderRS80::decodeMsopPkt(const uint8_t* p int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; typename T_PointCloud::PointT point; + bool pointValid = false; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -198,17 +199,23 @@ inline RSDecoderResult DecoderRS80::decodeMsopPkt(const uint8_t* p setY(point, y); setZ(point, z); setIntensity(point, intensity); + pointValid = true; } - else + else if (!this->param_.is_dense) { setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); + pointValid = true; + } + + if (pointValid) + { + setRing(point, this->beam_ring_table_[channel_idx]); + setTimestamp(point, block_timestamp); + vec.emplace_back(std::move(point)); } - setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, block_timestamp); - vec.emplace_back(std::move(point)); } } return RSDecoderResult::DECODE_OK; diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 4add5499..e545acb5 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -185,6 +185,7 @@ inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* p // store to point cloud buffer typename T_PointCloud::PointT point; + bool pointValid = false; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -201,17 +202,23 @@ inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* p setY(point, y); setZ(point, z); setIntensity(point, intensity); + pointValid = true; } - else + else if (!this->param_.is_dense) { setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); + pointValid = true; + } + + if (pointValid) + { + setRing(point, this->beam_ring_table_[channel_idx]); + setTimestamp(point, block_timestamp); + vec.emplace_back(std::move(point)); } - setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, block_timestamp); - vec.emplace_back(std::move(point)); } } return RSDecoderResult::DECODE_OK; diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 621c01a4..c6559ad4 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -195,6 +195,7 @@ inline RSDecoderResult DecoderRSHELIOS::decodeMsopPkt(const uint8_ // store to point cloud buffer typename T_PointCloud::PointT point; + bool pointValid = false; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -211,17 +212,23 @@ inline RSDecoderResult DecoderRSHELIOS::decodeMsopPkt(const uint8_ setY(point, y); setZ(point, z); setIntensity(point, intensity); + pointValid = true; } - else + else if (!this->param_.is_dense) { setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); + pointValid = true; + } + + if (pointValid) + { + setRing(point, this->beam_ring_table_[channel_idx]); + setTimestamp(point, block_timestamp); + vec.emplace_back(std::move(point)); } - setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, block_timestamp); - vec.emplace_back(std::move(point)); } } return RSDecoderResult::DECODE_OK; diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index bd3d9a57..6797fa2b 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -246,6 +246,7 @@ inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* p for (size_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) { typename T_PointCloud::PointT point; + bool pointValid = false; float distance = RS_SWAP_SHORT(blk.channel[channel_idx].distance) * this->lidar_const_param_.DIS_RESOLUTION; if (distance <= this->param_.max_distance && distance >= this->param_.min_distance) { @@ -260,17 +261,23 @@ inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* p setY(point, y); setZ(point, z); setIntensity(point, intensity); + pointValid = true; } - else + else if (!this->param_.is_dense) { setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); + pointValid = true; + } + + if (pointValid) + { + setTimestamp(point, point_time); + setRing(point, channel_idx + 1); + vec.emplace_back(std::move(point)); } - setTimestamp(point, point_time); - setRing(point, channel_idx + 1); - vec.emplace_back(std::move(point)); } } unsigned int pkt_cnt = RS_SWAP_SHORT(mpkt_ptr->header.pkt_cnt); diff --git a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp index fce2cf10..c49f4988 100644 --- a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp @@ -175,6 +175,7 @@ inline RSDecoderResult DecoderRSROCK::decodeMsopPkt(const uint8_t* int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; typename T_PointCloud::PointT point; + bool pointValid = false; if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && @@ -191,17 +192,23 @@ inline RSDecoderResult DecoderRSROCK::decodeMsopPkt(const uint8_t* setY(point, y); setZ(point, z); setIntensity(point, intensity); + pointValid = true; } - else + else if (!this->param_.is_dense) { setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); + pointValid = true; + } + + if (pointValid) + { + setRing(point, this->beam_ring_table_[channel_idx]); + setTimestamp(point, block_timestamp); + vec.emplace_back(std::move(point)); } - setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, block_timestamp); - vec.emplace_back(std::move(point)); } } } diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 98eb49c7..51624082 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -287,6 +287,8 @@ class DecoderBase virtual double getLidarTemperature(); virtual double getLidarTime(const uint8_t* pkt) = 0; + unsigned int blocksPerPacket(); + protected: virtual float computeTemperature(const uint16_t& temp_raw); virtual float computeTemperature(const uint8_t& temp_low, const uint8_t& temp_high); @@ -528,6 +530,12 @@ inline void DecoderBase::regRecvCallback(const std::function +unsigned int DecoderBase::blocksPerPacket() +{ + return this->lidar_const_param_.BLOCKS_PER_PKT; +} + template inline double DecoderBase::getLidarTemperature() { diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index c56668f1..ac144ca5 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -105,6 +105,7 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter uint32_t num_pkts_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 float cut_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp + bool is_dense = false; /// Whether to reserve NAN points RSTransformParam transform_param; ///< Used to transform points RSCameraTriggerParam trigger_param; ///< Used to trigger camera void print() const diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 390747ec..fee9cde6 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -388,6 +388,8 @@ inline void LidarDriverImpl::difopCallback(std::shared_ptr template inline void LidarDriverImpl::processMsop() { + unsigned int width = 0; + while (!to_exit_msop_handle_ && driver_param_.wait_for_difop && !difop_flag_) { ndifop_count_++; @@ -415,38 +417,45 @@ inline void LidarDriverImpl::processMsop() scan_ptr_.packets.emplace_back(msg); #endif - if (ret == FRAME_SPLIT) + if (ret >= 0) { - T_PointCloud& msg = point_cloud_; - msg.height = height; - msg.width = msg.points.size() / msg.height; - setPointCloudHeader(msg); - - if (driver_param_.decoder_param.use_lidar_clock == true) - { - msg.timestamp = lidar_decoder_ptr_->getLidarTime(pkt->data()); - } - else - { - msg.timestamp = getTime(); - } + width += lidar_decoder_ptr_->blocksPerPacket(); - if (msg.points.size() == 0) - { - reportError(Error(ERRCODE_ZEROPOINTS)); - } - else + if (ret == FRAME_SPLIT) { - runCallBack(msg); - } + T_PointCloud& msg = point_cloud_; + msg.height = height; + msg.width = width; + + setPointCloudHeader(msg); + + if (driver_param_.decoder_param.use_lidar_clock == true) + { + msg.timestamp = lidar_decoder_ptr_->getLidarTime(pkt->data()); + } + else + { + msg.timestamp = getTime(); + } + + if (msg.points.size() == 0) + { + reportError(Error(ERRCODE_ZEROPOINTS)); + } + else + { + runCallBack(msg); + } #ifdef ENABLE_PUBLISH_RAW_MSG - setScanMsgHeader(scan_ptr_); - runCallBack(scan_ptr_); - scan_ptr_.packets.resize(0); + setScanMsgHeader(scan_ptr_); + runCallBack(scan_ptr_); + scan_ptr_.packets.resize(0); #endif - point_cloud_.points.resize(0); + point_cloud_.points.resize(0); + width = 0; + } } else if (ret < 0) { From 18d2e3bb6187b893f5a03723c9d5051733066a8d Mon Sep 17 00:00:00 2001 From: ronzheng Date: Thu, 4 Nov 2021 15:20:29 +0800 Subject: [PATCH 012/379] feat: support to bind to host ip --- src/rs_driver/driver/driver_param.h | 1 + src/rs_driver/driver/input/sock_input.hpp | 17 +++++++++++------ 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index ac144ca5..ed6efa8c 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -130,6 +130,7 @@ typedef struct RSInputParam ///< The LiDAR input parameter { std::string device_ip = "192.168.1.200"; ///< Ip of LiDAR std::string multi_cast_address = "0.0.0.0"; ///< Address of multicast + std::string host_address = "0.0.0.0"; ///< Address of host uint16_t msop_port = 6699; ///< Msop packet port number uint16_t difop_port = 7788; ///< Difop packet port number bool read_pcap = false; ///< true: The driver will process the pcap through pcap_path. false: The driver will diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index 5c067e54..e37f62eb 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -55,7 +55,7 @@ class SockInput : public Input private: inline void recvPacket(); inline void higherThreadPrioty(std::thread::native_handle_type handle); - inline int createSocket(uint16_t port, const std::string& ip); + inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); private: int fds_[2]; @@ -84,13 +84,13 @@ inline bool SockInput::init() int msop_fd = -1, difop_fd = -1; - msop_fd = createSocket(input_param_.msop_port, input_param_.multi_cast_address); + msop_fd = createSocket(input_param_.msop_port, input_param_.host_address, input_param_.multi_cast_address); if (msop_fd < 0) goto failMsop; if ((input_param_.difop_port != 0) && (input_param_.difop_port != input_param_.msop_port)) { - difop_fd = createSocket(input_param_.difop_port, input_param_.multi_cast_address); + difop_fd = createSocket(input_param_.difop_port, input_param_.host_address, input_param_.multi_cast_address); if (difop_fd < 0) goto failDifop; } @@ -131,7 +131,7 @@ inline SockInput::~SockInput() close(fds_[1]); } -inline int SockInput::createSocket(uint16_t port, const std::string& ip) +inline int SockInput::createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp) { int fd; int flags; @@ -150,6 +150,11 @@ inline int SockInput::createSocket(uint16_t port, const std::string& ip) my_addr.sin_port = htons(port); my_addr.sin_addr.s_addr = INADDR_ANY; + if (hostIp != "0.0.0.0") + { + inet_aton(hostIp.c_str(), &(my_addr.sin_addr)); + } + ret = bind(fd, (struct sockaddr*)&my_addr, sizeof(my_addr)); if (ret < 0) { @@ -157,10 +162,10 @@ inline int SockInput::createSocket(uint16_t port, const std::string& ip) goto failBind; } - if (ip != "0.0.0.0") + if (grpIp != "0.0.0.0") { struct ip_mreq group; - inet_pton(AF_INET, ip.c_str(), &group.imr_multiaddr.s_addr); + inet_pton(AF_INET, grpIp.c_str(), &group.imr_multiaddr.s_addr); group.imr_interface.s_addr = INADDR_ANY; ret = setsockopt(fd, IPPROTO_IP, IP_ADD_MEMBERSHIP, &group, sizeof(group)); From 890b61daa5f645d80744429b6a7f454b924d7a4b Mon Sep 17 00:00:00 2001 From: ronzheng Date: Mon, 8 Nov 2021 09:55:01 +0800 Subject: [PATCH 013/379] feat: support dense attribute --- src/rs_driver/driver/decoder/decoder_base.hpp | 8 ----- src/rs_driver/driver/driver_param.h | 2 +- src/rs_driver/driver/lidar_driver_impl.hpp | 31 +++++++++---------- 3 files changed, 16 insertions(+), 25 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 51624082..98eb49c7 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -287,8 +287,6 @@ class DecoderBase virtual double getLidarTemperature(); virtual double getLidarTime(const uint8_t* pkt) = 0; - unsigned int blocksPerPacket(); - protected: virtual float computeTemperature(const uint16_t& temp_raw); virtual float computeTemperature(const uint8_t& temp_low, const uint8_t& temp_high); @@ -530,12 +528,6 @@ inline void DecoderBase::regRecvCallback(const std::function -unsigned int DecoderBase::blocksPerPacket() -{ - return this->lidar_const_param_.BLOCKS_PER_PKT; -} - template inline double DecoderBase::getLidarTemperature() { diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index ed6efa8c..b2bcc92a 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -105,7 +105,7 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter uint32_t num_pkts_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 float cut_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp - bool is_dense = false; /// Whether to reserve NAN points + bool is_dense = false; ///< true: discard NAN points; false: reserve NAN points RSTransformParam transform_param; ///< Used to transform points RSCameraTriggerParam trigger_param; ///< Used to trigger camera void print() const diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index fee9cde6..9030d205 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -79,7 +79,7 @@ class LidarDriverImpl void reportError(const Error& error); void processMsop(); void processDifop(); - void setPointCloudHeader(T_PointCloud& msg); + void setPointCloudHeader(T_PointCloud& msg, int height); private: RSDriverParam driver_param_; @@ -295,9 +295,7 @@ inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_ms { point_cloud_msg.points.insert(point_cloud_msg.points.end(), iter.begin(), iter.end()); } - point_cloud_msg.height = height; - point_cloud_msg.width = point_cloud_msg.points.size() / point_cloud_msg.height; - setPointCloudHeader(point_cloud_msg); + setPointCloudHeader(point_cloud_msg, height); point_cloud_msg.timestamp = scan_msg.timestamp; if (point_cloud_msg.points.size() == 0) { @@ -388,8 +386,6 @@ inline void LidarDriverImpl::difopCallback(std::shared_ptr template inline void LidarDriverImpl::processMsop() { - unsigned int width = 0; - while (!to_exit_msop_handle_ && driver_param_.wait_for_difop && !difop_flag_) { ndifop_count_++; @@ -419,16 +415,10 @@ inline void LidarDriverImpl::processMsop() if (ret >= 0) { - width += lidar_decoder_ptr_->blocksPerPacket(); - if (ret == FRAME_SPLIT) { T_PointCloud& msg = point_cloud_; - msg.height = height; - msg.width = width; - - setPointCloudHeader(msg); - + setPointCloudHeader(msg, height); if (driver_param_.decoder_param.use_lidar_clock == true) { msg.timestamp = lidar_decoder_ptr_->getLidarTime(pkt->data()); @@ -454,7 +444,6 @@ inline void LidarDriverImpl::processMsop() #endif point_cloud_.points.resize(0); - width = 0; } } else if (ret < 0) @@ -513,11 +502,21 @@ inline void LidarDriverImpl::setScanMsgHeader(ScanMsg& msg) } template -inline void LidarDriverImpl::setPointCloudHeader(T_PointCloud& msg) +inline void LidarDriverImpl::setPointCloudHeader(T_PointCloud& msg, int height) { msg.seq = point_cloud_seq_++; msg.frame_id = driver_param_.frame_id; - msg.is_dense = false; + msg.is_dense = driver_param_.decoder_param.is_dense; + if (msg.is_dense) + { + msg.height = 1; + msg.width = msg.points.size(); + } + else + { + msg.height = height; + msg.width = msg.points.size() / msg.height; + } } } // namespace lidar From 7eded35755ef0a115fd36584e2bcbf28ba7aa75a Mon Sep 17 00:00:00 2001 From: ronzheng Date: Tue, 9 Nov 2021 16:17:26 +0800 Subject: [PATCH 014/379] feat: usleep in case of wrong packet len --- src/rs_driver/driver/lidar_driver_impl.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 9030d205..bab3f052 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -452,6 +452,8 @@ inline void LidarDriverImpl::processMsop() reportError(Error(ERRCODE_WRONGPKTLENGTH)); else reportError(Error(ERRCODE_WRONGPKTHEADER)); + + std::this_thread::sleep_for(std::chrono::milliseconds(300)); } packetPut(pkt); From 302c34f306c968edb96b216c655c81579ddf1f12 Mon Sep 17 00:00:00 2001 From: ronzheng Date: Tue, 9 Nov 2021 17:07:52 +0800 Subject: [PATCH 015/379] feat: add callback_get_point_cloud --- demo/demo_online.cpp | 15 +++++++-- demo/demo_pcap.cpp | 16 +++++++--- src/rs_driver/api/lidar_driver.h | 5 +-- src/rs_driver/driver/lidar_driver_impl.hpp | 37 ++++++++++++++-------- tool/rs_driver_viewer.cpp | 24 +++++++++----- 5 files changed, 67 insertions(+), 30 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index a388c05c..7814e0e5 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -44,16 +44,23 @@ typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; +std::shared_ptr g_pointcloud; + +std::shared_ptr pointCloudGetCallback(void) +{ + return g_pointcloud; +} + /** * @brief The point cloud callback function. This function will be registered to lidar driver. * When the point cloud message is ready, driver can send out messages through this function. * @param msg The lidar point cloud message. */ -void pointCloudCallback(const PointCloudMsg& msg) +void pointCloudPutCallback(std::shared_ptr msg) { /* Note: Please do not put time-consuming operations in the callback function! */ /* Make a copy of the message and process it in another thread is recommended*/ - RS_MSG << "msg: " << msg.seq << " point cloud size: " << msg.points.size() << RS_REND; + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; } /** @@ -74,6 +81,8 @@ int main(int argc, char* argv[]) << RSLIDAR_VERSION_PATCH << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; + g_pointcloud = std::make_shared(); + RSDriverParam param; ///< Create a parameter object param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 @@ -82,7 +91,7 @@ int main(int argc, char* argv[]) param.print(); LidarDriver driver; - driver.regRecvCallback(pointCloudCallback); ///< Register the point cloud callback function into the driver + driver.regRecvCallback(pointCloudPutCallback, pointCloudGetCallback); ///< Register the point cloud callback function into the driver driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver if (!driver.init(param)) ///< Call the init function and pass the parameter { diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 6ff6d552..be02ea42 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -44,16 +44,23 @@ typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; +std::shared_ptr g_pointcloud; + +std::shared_ptr pointCloudGetCallback(void) +{ + return g_pointcloud; +} + /** * @brief The point cloud callback function. This function will be registered to lidar driver. * When the point cloud message is ready, driver can send out messages through this function. * @param msg The lidar point cloud message. */ -void pointCloudCallback(const PointCloudMsg& msg) +void pointCloudPutCallback(std::shared_ptr msg) { /* Note: Please do not put time-consuming operations in the callback function! */ /* Make a copy of the message and process it in another thread is recommended*/ - RS_MSG << "msg: " << msg.seq << " point cloud size: " << msg.points.size() << RS_REND; + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; } /** @@ -74,7 +81,7 @@ int main(int argc, char* argv[]) << RSLIDAR_VERSION_PATCH << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; - LidarDriver driver; ///< Declare the driver object + g_pointcloud = std::make_shared(); RSDriverParam param; ///< Create a parameter object param.input_param.read_pcap = true; ///< Set read_pcap to true @@ -85,8 +92,9 @@ int main(int argc, char* argv[]) param.print(); + LidarDriver driver; ///< Declare the driver object + driver.regRecvCallback(pointCloudPutCallback, pointCloudGetCallback); ///< Register the point cloud callback function into the driver driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver - driver.regRecvCallback(pointCloudCallback); ///< Register the point cloud callback function into the driver if (!driver.init(param)) ///< Call the init function and pass the parameter { RS_ERROR << "Driver Initialize Error..." << RS_REND; diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index 4fbccf92..e48ee512 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -102,9 +102,10 @@ class LidarDriver * called * @param callback The callback function */ - inline void regRecvCallback(const std::function& callback) + inline void regRecvCallback(const std::function)>& cb_put, + const std::function(void)>& cb_get = nullptr) { - driver_ptr_->regRecvCallback(callback); + driver_ptr_->regRecvCallback(cb_put, cb_get); } /** diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index bab3f052..eaf0cf5d 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -55,7 +55,8 @@ class LidarDriverImpl void initDecoderOnly(const RSDriverParam& param); bool start(); void stop(); - void regRecvCallback(const std::function& callback); + void regRecvCallback(const std::function)>& cb_put, + const std::function(void)>& cb_get); void regRecvCallback(const std::function& callback); void regRecvCallback(const std::function& callback); void regRecvCallback(const std::function& callback); @@ -66,7 +67,7 @@ class LidarDriverImpl void decodeDifopPkt(const PacketMsg& msg); private: - void runCallBack(const T_PointCloud& msg); + void runCallBack(std::shared_ptr msg); void runCallBack(const ScanMsg& msg); void runCallBack(const PacketMsg& msg); @@ -83,7 +84,8 @@ class LidarDriverImpl private: RSDriverParam driver_param_; - std::vector> point_cloud_cb_vec_; + std::function(void)> point_cloud_cb_get_; + std::vector)>> point_cloud_cb_put_vec_; std::vector> excb_; std::vector> msop_pkt_cb_vec_; std::vector> difop_pkt_cb_vec_; @@ -91,7 +93,7 @@ class LidarDriverImpl std::shared_ptr> lidar_decoder_ptr_; ScanMsg scan_ptr_; std::vector> camera_trigger_cb_vec_; - T_PointCloud point_cloud_; + std::shared_ptr point_cloud_; SyncQueue> free_pkt_queue_; SyncQueue> msop_pkt_queue_; SyncQueue> difop_pkt_queue_; @@ -209,9 +211,14 @@ inline void LidarDriverImpl::stop() } template -inline void LidarDriverImpl::regRecvCallback(const std::function& callback) +inline void LidarDriverImpl::regRecvCallback(const std::function)>& cb_put, + const std::function(void)>& cb_get) { - point_cloud_cb_vec_.emplace_back(callback); + point_cloud_cb_put_vec_.emplace_back(cb_put); + if (cb_get != nullptr) + { + point_cloud_cb_get_ = cb_get; + } } template @@ -334,11 +341,11 @@ inline void LidarDriverImpl::runCallBack(const PacketMsg& msg) } template -inline void LidarDriverImpl::runCallBack(const T_PointCloud& msg) +inline void LidarDriverImpl::runCallBack(std::shared_ptr msg) { - if (msg.seq != 0) + if (msg->seq != 0) { - for (auto& it : point_cloud_cb_vec_) + for (auto& it : point_cloud_cb_put_vec_) { it(msg); } @@ -398,6 +405,9 @@ inline void LidarDriverImpl::processMsop() msop_pkt_queue_.clear(); } + point_cloud_ = point_cloud_cb_get_(); + point_cloud_->points.resize(0); + while (!to_exit_msop_handle_) { std::shared_ptr pkt = msop_pkt_queue_.popWait(1000); @@ -405,7 +415,7 @@ inline void LidarDriverImpl::processMsop() continue; int height = 1; - int ret = lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->len(), point_cloud_.points, height); + int ret = lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->len(), point_cloud_->points, height); #ifdef ENABLE_PUBLISH_RAW_MSG PacketMsg msg(pkt->len()); @@ -417,7 +427,7 @@ inline void LidarDriverImpl::processMsop() { if (ret == FRAME_SPLIT) { - T_PointCloud& msg = point_cloud_; + T_PointCloud& msg = *point_cloud_; setPointCloudHeader(msg, height); if (driver_param_.decoder_param.use_lidar_clock == true) { @@ -434,7 +444,7 @@ inline void LidarDriverImpl::processMsop() } else { - runCallBack(msg); + runCallBack(point_cloud_); } #ifdef ENABLE_PUBLISH_RAW_MSG @@ -443,7 +453,8 @@ inline void LidarDriverImpl::processMsop() scan_ptr_.packets.resize(0); #endif - point_cloud_.points.resize(0); + point_cloud_ = point_cloud_cb_get_(); + point_cloud_->points.resize(0); } } else if (ret < 0) diff --git a/tool/rs_driver_viewer.cpp b/tool/rs_driver_viewer.cpp index 91f1565b..3052d457 100644 --- a/tool/rs_driver_viewer.cpp +++ b/tool/rs_driver_viewer.cpp @@ -49,6 +49,7 @@ class PointCloudT : public pcl::PointCloud }; typedef PointCloudT PointCloudMsg; +std::shared_ptr g_pointcloud; using namespace robosense::lidar; using namespace pcl::visualization; @@ -185,22 +186,26 @@ void printParam(const RSDriverParam& param) RS_INFOL << "yaw: "; RS_INFO << std::fixed << param.decoder_param.transform_param.yaw << RS_REND; } + +std::shared_ptr pointCloudGetCallback(void) +{ + return g_pointcloud; +} + /** * @brief The point cloud callback function. This function will be registered to lidar driver. * When the point cloud message is ready, driver can send out messages through this function. * @param msg The lidar point cloud message. */ -void pointCloudCallback(const PointCloudMsg& msg) +void pointCloudPutCallback(std::shared_ptr msg) { - std::cout << "ponits:" << msg.points.size() << std::endl; - /* Note: Please do not put time-consuming operations in the callback function! */ /* Make a copy of the message and process it in another thread is recommended*/ pcl::PointCloud::Ptr pcl_pointcloud(new pcl::PointCloud); - pcl_pointcloud->points.assign(msg.points.begin(), msg.points.end()); - pcl_pointcloud->height = msg.height; - pcl_pointcloud->width = msg.width; - pcl_pointcloud->is_dense = false; + pcl_pointcloud->points.assign(msg->points.begin(), msg->points.end()); + pcl_pointcloud->height = msg->height; + pcl_pointcloud->width = msg->width; + pcl_pointcloud->is_dense = msg->is_dense; PointCloudColorHandlerGenericField point_color_handle(pcl_pointcloud, "intensity"); @@ -237,6 +242,9 @@ int main(int argc, char* argv[]) printHelpMenu(); return 0; } + + g_pointcloud = std::make_shared(); + pcl_viewer = std::make_shared("RSPointCloudViewer"); pcl_viewer->setBackgroundColor(0.0, 0.0, 0.0); @@ -251,7 +259,7 @@ int main(int argc, char* argv[]) LidarDriver driver; ///< Declare the driver object driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver - driver.regRecvCallback(pointCloudCallback); ///< Register the point cloud callback function into the driver + driver.regRecvCallback(pointCloudPutCallback, pointCloudGetCallback); ///< Register the point cloud callback function into the driver if (!driver.init(param)) ///< Call the init function and pass the parameter { RS_ERROR << "Driver Initialize Error..." << RS_REND; From 2151aaabf6c417031ab5b35875f914d0421adee3 Mon Sep 17 00:00:00 2001 From: ronzheng Date: Tue, 9 Nov 2021 18:18:06 +0800 Subject: [PATCH 016/379] fix: fix system_error exception when app exit --- src/rs_driver/api/lidar_driver.h | 1 - src/rs_driver/driver/input/input.hpp | 12 +++++++++--- src/rs_driver/driver/input/pcap_input.hpp | 7 +++++++ src/rs_driver/driver/input/sock_input.hpp | 4 ++++ src/rs_driver/driver/lidar_driver_impl.hpp | 21 ++++++++------------- 5 files changed, 28 insertions(+), 17 deletions(-) diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index e48ee512..0f409fdf 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -56,7 +56,6 @@ class LidarDriver */ ~LidarDriver() { - stop(); } /** diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index 746de5b6..13aa3da3 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -98,10 +98,11 @@ class Input std::thread recv_thread_; bool to_exit_recv_; bool init_flag_; + bool start_flag_; }; inline Input::Input(const RSInputParam& input_param, const std::function& excb) - : input_param_(input_param), excb_(excb), to_exit_recv_(false), init_flag_(false) + : input_param_(input_param), excb_(excb), to_exit_recv_(false), init_flag_(false), start_flag_(false) { } @@ -116,8 +117,13 @@ inline void Input::regRecvCallback(const std::function(s inline void Input::stop() { - to_exit_recv_ = true; - recv_thread_.join(); + if (start_flag_) + { + to_exit_recv_ = true; + recv_thread_.join(); + + start_flag_ = false; + } } inline void Input::pushPacket(std::shared_ptr pkt) diff --git a/src/rs_driver/driver/input/pcap_input.hpp b/src/rs_driver/driver/input/pcap_input.hpp index 68992c2a..6003fa52 100644 --- a/src/rs_driver/driver/input/pcap_input.hpp +++ b/src/rs_driver/driver/input/pcap_input.hpp @@ -82,6 +82,9 @@ class PcapInput : public Input inline bool PcapInput::init() { + if (init_flag_) + return true; + char errbuf[PCAP_ERRBUF_SIZE]; pcap_ = pcap_open_offline(input_param_.pcap_path.c_str(), errbuf); if (pcap_ == NULL) @@ -104,6 +107,9 @@ inline bool PcapInput::init() inline bool PcapInput::start() { + if (start_flag_) + return true; + if (!init_flag_) { excb_(Error(ERRCODE_STARTBEFOREINIT)); @@ -112,6 +118,7 @@ inline bool PcapInput::start() recv_thread_ = std::thread(std::bind(&PcapInput::recvPacket, this)); + start_flag_ = true; return true; } diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index e37f62eb..a98b747f 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -109,6 +109,9 @@ inline bool SockInput::init() inline bool SockInput::start() { + if (start_flag_) + return true; + if (!init_flag_) { excb_(Error(ERRCODE_STARTBEFOREINIT)); @@ -119,6 +122,7 @@ inline bool SockInput::start() higherThreadPrioty(recv_thread_.native_handle()); + start_flag_ = true; return true; } diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index eaf0cf5d..fe982f0e 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -119,14 +119,6 @@ template inline LidarDriverImpl::~LidarDriverImpl() { stop(); - - input_ptr_.reset(); - - to_exit_msop_handle_ = true; - msop_handle_thread_.join(); - - to_exit_difop_handle_ = true; - difop_handle_thread_.join(); } template @@ -202,12 +194,15 @@ inline void LidarDriverImpl::stop() if (input_ptr_ != nullptr) input_ptr_->stop(); - to_exit_msop_handle_ = true; - to_exit_difop_handle_ = true; - msop_handle_thread_.join(); - difop_handle_thread_.join(); + if (start_flag_) + { + to_exit_msop_handle_ = true; + to_exit_difop_handle_ = true; + msop_handle_thread_.join(); + difop_handle_thread_.join(); - start_flag_ = false; + start_flag_ = false; + } } template From a6fed52e59144dd42a682a63b7ab9f88b73fde3a Mon Sep 17 00:00:00 2001 From: ronzheng Date: Tue, 9 Nov 2021 18:19:42 +0800 Subject: [PATCH 017/379] feat: increase version --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 88cf412d..a7022490 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) endif(WIN32) -project(rs_driver VERSION 1.3.0) +project(rs_driver VERSION 1.4.0) #============================= # Compile Demos&Tools From ee558e6f3a84afa40330df7432729c069e943b76 Mon Sep 17 00:00:00 2001 From: ronzheng Date: Tue, 9 Nov 2021 20:20:02 +0800 Subject: [PATCH 018/379] fix: fix incorrect exit of handle thread --- src/rs_driver/driver/input/pcap_input.hpp | 1 + src/rs_driver/driver/lidar_driver_impl.hpp | 8 +++++--- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/src/rs_driver/driver/input/pcap_input.hpp b/src/rs_driver/driver/input/pcap_input.hpp index 6003fa52..98f3ba9d 100644 --- a/src/rs_driver/driver/input/pcap_input.hpp +++ b/src/rs_driver/driver/input/pcap_input.hpp @@ -116,6 +116,7 @@ inline bool PcapInput::start() return false; } + to_exit_recv_ = false; recv_thread_ = std::thread(std::bind(&PcapInput::recvPacket, this)); start_flag_ = true; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index fe982f0e..3f426eb2 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -173,13 +173,15 @@ inline void LidarDriverImpl::initDecoderOnly(const RSDriverParam& template inline bool LidarDriverImpl::start() { - if (!init_flag_) - return false; - if (start_flag_) return true; + if (!init_flag_) + return false; + + to_exit_msop_handle_ = false; msop_handle_thread_ = std::thread(std::bind(&LidarDriverImpl::processMsop, this)); + to_exit_difop_handle_ = false; difop_handle_thread_ = std::thread(std::bind(&LidarDriverImpl::processDifop, this)); input_ptr_->start(); From 1db544996abe76182ac658d747a254d0450d5f4d Mon Sep 17 00:00:00 2001 From: ronzheng Date: Tue, 9 Nov 2021 20:55:49 +0800 Subject: [PATCH 019/379] feat: add error code for null point cloud --- src/rs_driver/common/error_code.h | 5 +++- src/rs_driver/driver/lidar_driver_impl.hpp | 29 ++++++++++++++++++---- 2 files changed, 28 insertions(+), 6 deletions(-) diff --git a/src/rs_driver/common/error_code.h b/src/rs_driver/common/error_code.h index 79f95479..9553d516 100644 --- a/src/rs_driver/common/error_code.h +++ b/src/rs_driver/common/error_code.h @@ -67,7 +67,8 @@ enum ErrCode ERRCODE_WRONGPKTHEADER = 0x51, ///< Packet header is wrong ERRCODE_WRONGPKTLENGTH = 0x52, ///< Packet length is wrong ERRCODE_PKTNULL = 0x53, ///< Input packet is null - ERRCODE_PKTBUFOVERFLOW = 0x54 ///< Packet buffer is over flow + ERRCODE_PKTBUFOVERFLOW = 0x54, ///< Packet buffer is over flow + ERRCODE_POINTCLOUDNULL = 0x55 ///< PointCloud buffer is invalid }; struct Error @@ -125,6 +126,8 @@ struct Error return "ERRCODE_PKTNULL"; case ERRCODE_PKTBUFOVERFLOW: return "ERRCODE_PKTBUFOVERFLOW"; + case ERRCODE_POINTCLOUDNULL: + return "ERRCODE_POINTCLOUDNULL"; default: return "ERRCODE_SUCCESS"; } diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 3f426eb2..a2f8f52d 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -68,7 +68,6 @@ class LidarDriverImpl private: void runCallBack(std::shared_ptr msg); - void runCallBack(const ScanMsg& msg); void runCallBack(const PacketMsg& msg); void setScanMsgHeader(ScanMsg& msg); @@ -78,6 +77,7 @@ class LidarDriverImpl void msopCallback(std::shared_ptr msg); void difopCallback(std::shared_ptr msg); void reportError(const Error& error); + std::shared_ptr getPointCloud(); void processMsop(); void processDifop(); void setPointCloudHeader(T_PointCloud& msg, int height); @@ -387,6 +387,27 @@ inline void LidarDriverImpl::difopCallback(std::shared_ptr difop_pkt_queue_.push(pkt); } +template +inline std::shared_ptr LidarDriverImpl::getPointCloud() +{ + std::shared_ptr pc; + + while (1) + { + if (point_cloud_cb_get_ != nullptr) + pc = point_cloud_cb_get_(); + + if (pc) + { + pc->points.resize(0); + return pc; + } + + reportError(Error(ERRCODE_POINTCLOUDNULL)); + std::this_thread::sleep_for(std::chrono::milliseconds(300)); + }; +} + template inline void LidarDriverImpl::processMsop() { @@ -402,8 +423,7 @@ inline void LidarDriverImpl::processMsop() msop_pkt_queue_.clear(); } - point_cloud_ = point_cloud_cb_get_(); - point_cloud_->points.resize(0); + point_cloud_ = getPointCloud(); while (!to_exit_msop_handle_) { @@ -450,8 +470,7 @@ inline void LidarDriverImpl::processMsop() scan_ptr_.packets.resize(0); #endif - point_cloud_ = point_cloud_cb_get_(); - point_cloud_->points.resize(0); + point_cloud_ = getPointCloud(); } } else if (ret < 0) From 65d2b719815d363bff54204c84491fc4f7411535 Mon Sep 17 00:00:00 2001 From: ronzheng Date: Wed, 10 Nov 2021 11:45:08 +0800 Subject: [PATCH 020/379] feat: use code to join multicast group instead of shell script --- src/rs_driver/driver/driver_param.h | 1 + src/rs_driver/driver/input/sock_input.hpp | 31 ++++++++++------------- 2 files changed, 15 insertions(+), 17 deletions(-) diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index b2bcc92a..c2806b11 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -145,6 +145,7 @@ typedef struct RSInputParam ///< The LiDAR input parameter RS_INFO << "------------------------------------------------------" << RS_REND; RS_INFO << " RoboSense Input Parameters " << RS_REND; RS_INFOL << "multi_cast_address: " << multi_cast_address << RS_REND; + RS_INFOL << "host_address: " << host_address << RS_REND; RS_INFOL << "msop_port: " << msop_port << RS_REND; RS_INFOL << "difop_port: " << difop_port << RS_REND; RS_INFOL << "read_pcap: " << read_pcap << RS_REND; diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index a98b747f..211e13e6 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -148,18 +148,15 @@ inline int SockInput::createSocket(uint16_t port, const std::string& hostIp, con goto failSocket; } - struct sockaddr_in my_addr; - memset((char*)&my_addr, 0, sizeof(my_addr)); - my_addr.sin_family = AF_INET; - my_addr.sin_port = htons(port); - my_addr.sin_addr.s_addr = INADDR_ANY; - - if (hostIp != "0.0.0.0") - { - inet_aton(hostIp.c_str(), &(my_addr.sin_addr)); - } - - ret = bind(fd, (struct sockaddr*)&my_addr, sizeof(my_addr)); + struct sockaddr_in host_addr; + memset(&host_addr, 0, sizeof(host_addr)); + host_addr.sin_family = AF_INET; + host_addr.sin_port = htons(port); + host_addr.sin_addr.s_addr = INADDR_ANY; + if (hostIp != "0.0.0.0" && grpIp == "0.0.0.0") + inet_pton(AF_INET, hostIp.c_str(), &(host_addr.sin_addr)); + + ret = bind(fd, (struct sockaddr*)&host_addr, sizeof(host_addr)); if (ret < 0) { std::cerr << "bind: " << std::strerror(errno) << std::endl; @@ -168,11 +165,11 @@ inline int SockInput::createSocket(uint16_t port, const std::string& hostIp, con if (grpIp != "0.0.0.0") { - struct ip_mreq group; - inet_pton(AF_INET, grpIp.c_str(), &group.imr_multiaddr.s_addr); - group.imr_interface.s_addr = INADDR_ANY; - - ret = setsockopt(fd, IPPROTO_IP, IP_ADD_MEMBERSHIP, &group, sizeof(group)); + struct ip_mreqn ipm; + memset(&ipm, 0, sizeof(ipm)); + inet_pton(AF_INET, grpIp.c_str(), &(ipm.imr_multiaddr)); + inet_pton(AF_INET, hostIp.c_str(), &(ipm.imr_address)); + ret = setsockopt(fd, IPPROTO_IP, IP_ADD_MEMBERSHIP, &ipm, sizeof(ipm)); if (ret < 0) { std::cerr << "setsockopt: " << std::strerror(errno) << std::endl; From 58d39c8bdbb39c1b0df6d13f9b055dc0565581fe Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 10 Nov 2021 15:59:49 +0800 Subject: [PATCH 021/379] feat: disable boost link --- CMakeLists.txt | 53 +++++++++-------------- src/rs_driver/common/common_header.h | 3 -- src/rs_driver/driver/driver_param.h | 1 + src/rs_driver/driver/input/sock_input.hpp | 2 + 4 files changed, 23 insertions(+), 36 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a7022490..e1fc82ed 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,9 +1,9 @@ cmake_minimum_required(VERSION 3.5) -cmake_policy(SET CMP0048 NEW) +cmake_policy(SET CMP0048 NEW) # CMake 3.6 required if(WIN32) - cmake_policy(SET CMP0074 NEW) + cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) project(rs_driver VERSION 1.4.0) @@ -11,11 +11,11 @@ project(rs_driver VERSION 1.4.0) #============================= # Compile Demos&Tools #============================= -option(COMPILE_DEMOS "Build rs_driver demos" ON) +option(COMPILE_DEMOS "Build rs_driver demos" OFF) option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) #============================= -# Compile Demos&Tools +# Compile Features #============================= option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) option(ENABLE_PUBLISH_RAW_MSG "Publish raw messages" OFF) @@ -48,20 +48,22 @@ if(MSVC) add_compile_definitions(_DISABLE_EXTENDED_ALIGNED_STORAGE) # to disable a msvc error set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} /STACK:100000000") elseif(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") - if(MINGW) - set(COMPILER "MINGW Compiler") - elseif(UNIX) + + if(UNIX) set(COMPILER "UNIX GNU Compiler") + elseif(MINGW) + set(COMPILER "MINGW Compiler") else() message(FATAL_ERROR "Unsupported compiler.") endif() - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++14") + + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++11") set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -g") set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3") endif() message(=============================================================) -message("-- Cmake run for ${COMPILER}") +message("-- CMake run for ${COMPILER}") message(=============================================================) #======================== @@ -73,24 +75,6 @@ set(INSTALL_CMAKE_DIR ${CMAKE_INSTALL_PREFIX}/lib/cmake) set(DRIVER_INCLUDE_DIRS ${CMAKE_CURRENT_LIST_DIR}/src) set(DRIVER_CMAKE_ROOT ${CMAKE_CURRENT_LIST_DIR}/cmake) -#======================== -# Boost -#======================== -if(WIN32) - if(CMAKE_SIZEOF_VOID_P EQUAL 8) # 64-bit - set(Boost_ARCHITECTURE "-x64") - elseif(CMAKE_SIZEOF_VOID_P EQUAL 4) # 32-bit - set(Boost_ARCHITECTURE "-x32") - endif() - set(Boost_USE_STATIC_LIBS ON) - set(Boost_USE_MULTITHREADED ON) - set(Boost_USE_STATIC_RUNTIME OFF) -endif(WIN32) - -find_package(Boost COMPONENTS system date_time regex REQUIRED) -include_directories(${Boost_INCLUDE_DIRS}) -list(APPEND EXTERNAL_LIBS ${Boost_LIBRARIES}) - # fix pthread missing on ubuntu18.04 or ubuntu20.04 if(WIN32) else() @@ -109,7 +93,6 @@ else() list(APPEND EXTERNAL_LIBS pcap) endif(WIN32) - #======================== # Eigen #======================== @@ -122,6 +105,9 @@ if(${ENABLE_TRANSFORM}) message(=============================================================) endif(${ENABLE_TRANSFORM}) +#======================== +# Build Features +#======================== if(${ENABLE_HIGH_PRIORITY_THREAD}) add_definitions("-DENABLE_HIGH_PRIORITY_THREAD") endif(${ENABLE_HIGH_PRIORITY_THREAD}) @@ -130,12 +116,10 @@ if(${ENABLE_PUBLISH_RAW_MSG}) add_definitions("-DENABLE_PUBLISH_RAW_MSG") endif(${ENABLE_PUBLISH_RAW_MSG}) -option(ENABLE_PUBLISH_CAM_MSG "Publish camera trigger messages" OFF) if(${ENABLE_PUBLISH_CAM_MSG}) add_definitions("-DENABLE_PUBLISH_CAM_MSG") endif(${ENABLE_PUBLISH_CAM_MSG}) - #======================== # Build Demos #======================== @@ -152,17 +136,20 @@ endif(${COMPILE_TOOLS}) #======================== configure_file( ${DRIVER_CMAKE_ROOT}/rs_driverConfig.cmake.in - ${DRIVER_CMAKE_ROOT}/rs_driverConfig.cmake @ONLY + ${DRIVER_CMAKE_ROOT}/rs_driverConfig.cmake + @ONLY ) configure_file( ${DRIVER_CMAKE_ROOT}/rs_driverConfigVersion.cmake.in - ${DRIVER_CMAKE_ROOT}/rs_driverConfigVersion.cmake @ONLY + ${DRIVER_CMAKE_ROOT}/rs_driverConfigVersion.cmake + @ONLY ) configure_file ( ${CMAKE_CURRENT_LIST_DIR}/src/rs_driver/macro/version.h.in - ${CMAKE_CURRENT_LIST_DIR}/src/rs_driver/macro/version.h @ONLY + ${CMAKE_CURRENT_LIST_DIR}/src/rs_driver/macro/version.h + @ONLY ) if(NOT ${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/rs_driver/common/common_header.h b/src/rs_driver/common/common_header.h index 4a91c5c7..ca85d81e 100644 --- a/src/rs_driver/common/common_header.h +++ b/src/rs_driver/common/common_header.h @@ -58,9 +58,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include -#include -#include #include /*Linux*/ #ifdef __linux__ diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index c2806b11..85e42004 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -31,6 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once +#include #include #include namespace robosense diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index 211e13e6..b7c19ebd 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -33,6 +33,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include "input.hpp" +#include +#include namespace robosense { From 5036b8f8cdbf4930c465f3b6059733b7e52c9366 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 16 Nov 2021 09:14:59 +0800 Subject: [PATCH 022/379] feat: change version to v1.4.1 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e1fc82ed..072ebbd5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.4.0) +project(rs_driver VERSION 1.4.1) #============================= # Compile Demos&Tools From 4fab234cd5b5e8bb6f2f8b5d3727dac1200e421b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 22 Nov 2021 14:09:25 +0800 Subject: [PATCH 023/379] fix: limit max size of packet queue --- src/rs_driver/driver/lidar_driver_impl.hpp | 8 +++++++- src/rs_driver/utility/sync_queue.h | 4 +++- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index a2f8f52d..08c6bf80 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -378,7 +378,13 @@ inline void LidarDriverImpl::packetPut(std::shared_ptr pkt template inline void LidarDriverImpl::msopCallback(std::shared_ptr pkt) { - msop_pkt_queue_.push(pkt); + static const int PACKET_POOL_MAX = 1024; + size_t sz = msop_pkt_queue_.push(pkt); + if (sz > PACKET_POOL_MAX) + { + reportError(Error(ERRCODE_PKTBUFOVERFLOW)); + msop_pkt_queue_.clear(); + } } template diff --git a/src/rs_driver/utility/sync_queue.h b/src/rs_driver/utility/sync_queue.h index ee84a38a..e8095766 100644 --- a/src/rs_driver/utility/sync_queue.h +++ b/src/rs_driver/utility/sync_queue.h @@ -40,7 +40,7 @@ template class SyncQueue { public: - inline void push(const T& value) + inline size_t push(const T& value) { std::lock_guard lg(mtx_); @@ -50,6 +50,8 @@ class SyncQueue if (empty) cv_.notify_one(); + + return queue_.size(); } inline T pop() From 573f085542d9b91a1fe9a4741586fe8cda277c01 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 22 Nov 2021 14:36:22 +0800 Subject: [PATCH 024/379] format: format driver_impl.h --- src/rs_driver/api/lidar_driver.h | 20 ++++---- src/rs_driver/driver/lidar_driver_impl.hpp | 54 +++++++++++----------- 2 files changed, 37 insertions(+), 37 deletions(-) diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index 0f409fdf..c6ca2f83 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -146,16 +146,6 @@ class LidarDriver driver_ptr_->regExceptionCallback(callback); } - /** - * @brief Get the current lidar temperature - * @param input_temperature The variable to store lidar temperature - * @return if get temperature successfully, return true; else return false - */ - inline bool getLidarTemperature(double& input_temperature) - { - return driver_ptr_->getLidarTemperature(input_temperature); - } - /** * @brief Decode lidar scan messages to point cloud * @note This function will only work after decodeDifopPkt is called unless wait_for_difop is set to false @@ -177,6 +167,16 @@ class LidarDriver driver_ptr_->decodeDifopPkt(pkt_msg); } + /** + * @brief Get the current lidar temperature + * @param input_temperature The variable to store lidar temperature + * @return if get temperature successfully, return true; else return false + */ + inline bool getLidarTemperature(double& input_temperature) + { + return driver_ptr_->getLidarTemperature(input_temperature); + } + private: std::shared_ptr> driver_ptr_; ///< The driver pointer }; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 08c6bf80..6867f5bc 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -61,26 +61,25 @@ class LidarDriverImpl void regRecvCallback(const std::function& callback); void regRecvCallback(const std::function& callback); void regExceptionCallback(const std::function& callback); - - bool getLidarTemperature(double& input_temperature); bool decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg); void decodeDifopPkt(const PacketMsg& msg); + bool getLidarTemperature(double& input_temperature); private: void runCallBack(std::shared_ptr msg); void runCallBack(const ScanMsg& msg); void runCallBack(const PacketMsg& msg); - void setScanMsgHeader(ScanMsg& msg); + void reportError(const Error& error); void localCameraTriggerCallback(const CameraTrigger& msg); - std::shared_ptr packetGet(size_t size); - void packetPut(std::shared_ptr pkt); void msopCallback(std::shared_ptr msg); void difopCallback(std::shared_ptr msg); - void reportError(const Error& error); + std::shared_ptr packetGet(size_t size); + void packetPut(std::shared_ptr pkt); std::shared_ptr getPointCloud(); void processMsop(); void processDifop(); void setPointCloudHeader(T_PointCloud& msg, int height); + void setScanMsgHeader(ScanMsg& msg); private: RSDriverParam driver_param_; @@ -91,9 +90,9 @@ class LidarDriverImpl std::vector> difop_pkt_cb_vec_; std::shared_ptr input_ptr_; std::shared_ptr> lidar_decoder_ptr_; + std::shared_ptr point_cloud_; ScanMsg scan_ptr_; std::vector> camera_trigger_cb_vec_; - std::shared_ptr point_cloud_; SyncQueue> free_pkt_queue_; SyncQueue> msop_pkt_queue_; SyncQueue> difop_pkt_queue_; @@ -242,17 +241,6 @@ inline void LidarDriverImpl::regExceptionCallback(const std::funct excb_.emplace_back(callback); } -template -inline bool LidarDriverImpl::getLidarTemperature(double& input_temperature) -{ - if (lidar_decoder_ptr_ != nullptr) - { - input_temperature = lidar_decoder_ptr_->getLidarTemperature(); - return true; - } - return false; -} - template inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg) { @@ -316,6 +304,17 @@ inline void LidarDriverImpl::decodeDifopPkt(const PacketMsg& pkt) difop_flag_ = true; } +template +inline bool LidarDriverImpl::getLidarTemperature(double& input_temperature) +{ + if (lidar_decoder_ptr_ != nullptr) + { + input_temperature = lidar_decoder_ptr_->getLidarTemperature(); + return true; + } + return false; +} + template inline void LidarDriverImpl::runCallBack(const ScanMsg& msg) { @@ -357,6 +356,16 @@ inline void LidarDriverImpl::reportError(const Error& error) it(error); } } + +template +inline void LidarDriverImpl::localCameraTriggerCallback(const CameraTrigger& msg) +{ + for (auto& it : camera_trigger_cb_vec_) + { + it(msg); + } +} + template inline std::shared_ptr LidarDriverImpl::packetGet(size_t size) { @@ -493,15 +502,6 @@ inline void LidarDriverImpl::processMsop() } } -template -inline void LidarDriverImpl::localCameraTriggerCallback(const CameraTrigger& msg) -{ - for (auto& it : camera_trigger_cb_vec_) - { - it(msg); - } -} - template inline void LidarDriverImpl::processDifop() { From a64cd27dca4801a1ec0ef9fbf98b6a11a12b66d1 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 22 Nov 2021 15:05:56 +0800 Subject: [PATCH 025/379] fix: fix time of NODIFOPRECV error --- src/rs_driver/driver/lidar_driver_impl.hpp | 25 +++++++++++----------- 1 file changed, 13 insertions(+), 12 deletions(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 6867f5bc..0dc09473 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -426,18 +426,6 @@ inline std::shared_ptr LidarDriverImpl::getPointClou template inline void LidarDriverImpl::processMsop() { - while (!to_exit_msop_handle_ && driver_param_.wait_for_difop && !difop_flag_) - { - ndifop_count_++; - if (ndifop_count_ > 120) - { - reportError(Error(ERRCODE_NODIFOPRECV)); - ndifop_count_ = 0; - } - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - msop_pkt_queue_.clear(); - } - point_cloud_ = getPointCloud(); while (!to_exit_msop_handle_) @@ -446,6 +434,19 @@ inline void LidarDriverImpl::processMsop() if (pkt.get() == NULL) continue; + if (!difop_flag_ && driver_param_.wait_for_difop) + { + ndifop_count_++; + if (ndifop_count_ > 240) + { + reportError(Error(ERRCODE_NODIFOPRECV)); + ndifop_count_ = 0; + } + + packetPut(pkt); + continue; + } + int height = 1; int ret = lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->len(), point_cloud_->points, height); From a8c365b4328a3640ca9ac36a1b4abbd513aabd77 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 23 Nov 2021 12:16:32 +0800 Subject: [PATCH 026/379] feat: refactory decoder --- CMakeLists.txt | 7 +- src/rs_driver/api/lidar_driver.h | 38 +- src/rs_driver/common/common_header.h | 51 +- src/rs_driver/common/error_code.h | 1 - .../driver/decoder/decoder_RS128.hpp | 18 +- src/rs_driver/driver/decoder/decoder_RS16.hpp | 7 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 58 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 1 - src/rs_driver/driver/decoder/decoder_RSBP.hpp | 1 - .../driver/decoder/decoder_RSHELIOS.hpp | 1 - .../driver/decoder/decoder_RSROCK.hpp | 3 +- src/rs_driver/driver/decoder/decoder_base.hpp | 624 +++++------------ .../driver/decoder/decoder_base_opt.hpp | 633 ++++++++++++++++++ .../driver/decoder/decoder_factory.hpp | 19 +- src/rs_driver/driver/decoder/set_member.hpp | 125 ++++ src/rs_driver/driver/driver_param.h | 4 +- src/rs_driver/driver/input/input.hpp | 27 +- src/rs_driver/driver/input/pcap_input.hpp | 7 +- src/rs_driver/driver/input/sock_input.hpp | 18 +- src/rs_driver/driver/lidar_driver_impl.hpp | 132 +--- src/rs_driver/msg/packet.h | 4 +- src/rs_driver/msg/packet_msg.h | 2 +- src/rs_driver/msg/scan_msg.h | 3 +- src/rs_driver/utility/dbg.h | 2 +- src/rs_driver/utility/sync_queue.h | 6 +- src/rs_driver/utility/time.h | 2 +- test/CMakeLists.txt | 16 + test/res/angle.csv | 4 + test/rs_driver_test.cpp | 204 ++++++ 29 files changed, 1320 insertions(+), 698 deletions(-) create mode 100644 src/rs_driver/driver/decoder/decoder_base_opt.hpp create mode 100644 src/rs_driver/driver/decoder/set_member.hpp create mode 100644 test/CMakeLists.txt create mode 100644 test/res/angle.csv create mode 100644 test/rs_driver_test.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 072ebbd5..7f836b2d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -11,8 +11,9 @@ project(rs_driver VERSION 1.4.1) #============================= # Compile Demos&Tools #============================= -option(COMPILE_DEMOS "Build rs_driver demos" OFF) +option(COMPILE_DEMOS "Build rs_driver demos" ON) option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) +option(COMPILE_TESTS "Build rs_driver unit tests" ON) #============================= # Compile Features @@ -131,6 +132,10 @@ if(${COMPILE_TOOLS}) add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/tool) endif(${COMPILE_TOOLS}) +if(${COMPILE_TESTS}) + add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/test) +endif(${COMPILE_TESTS}) + #======================== # Cmake #======================== diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index c6ca2f83..1c7a29e9 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -44,6 +44,12 @@ template class LidarDriver { public: + + static std::string getVersion() + { + return LidarDriverImpl::getVersion(); + } + /** * @brief Constructor, instanciate the driver pointer */ @@ -69,16 +75,6 @@ class LidarDriver return driver_ptr_->init(param); } - /** - * @brief The initialization function which only initialize decoder(not include input module). If lidar packets are - * from ROS or other ways excluding online lidar and pcap, call this function to initialize instead of calling init() - * @param param The custom struct RSDriverParam - */ - inline void initDecoderOnly(const RSDriverParam& param) - { - driver_ptr_->initDecoderOnly(param); - } - /** * @brief Start the thread to receive and decode packets * @return If successful, return true; else return false @@ -127,16 +123,6 @@ class LidarDriver driver_ptr_->regRecvCallback(callback); } - /** - * @brief Register the camera trigger message callback function to driver. When trigger message is ready, this - * function will be called - * @param callback The callback function - */ - inline void regRecvCallback(const std::function& callback) - { - driver_ptr_->regRecvCallback(callback); - } - /** * @brief Register the exception message callback function to driver. When error occurs, this function will be called * @param callback The callback function @@ -146,18 +132,6 @@ class LidarDriver driver_ptr_->regExceptionCallback(callback); } - /** - * @brief Decode lidar scan messages to point cloud - * @note This function will only work after decodeDifopPkt is called unless wait_for_difop is set to false - * @param pkt_scan_msg The lidar scan message - * @param point_cloud_msg The output point cloud message - * @return if decode successfully, return true; else return false - */ - inline bool decodeMsopScan(const ScanMsg& pkt_scan_msg, T_PointCloud& point_msg) - { - return driver_ptr_->decodeMsopScan(pkt_scan_msg, point_msg); - } - /** * @brief Decode lidar difop messages * @param pkt_msg The lidar difop packet diff --git a/src/rs_driver/common/common_header.h b/src/rs_driver/common/common_header.h index ca85d81e..c384d385 100644 --- a/src/rs_driver/common/common_header.h +++ b/src/rs_driver/common/common_header.h @@ -31,50 +31,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#ifndef _USE_MATH_DEFINES -#define _USE_MATH_DEFINES -#endif -/*Common*/ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -/*Linux*/ -#ifdef __linux__ -#include -#include -#include -#include -#include -#elif _WIN32 -#include -#include -#endif -/*Eigen*/ -#ifdef ENABLE_TRANSFORM -#include -#endif +#include #if defined(_WIN32) #include @@ -86,16 +44,9 @@ inline void setConsoleColor(WORD c) } #endif -/*Pcap*/ -#include - /*Camera*/ typedef std::pair CameraTrigger; -/*Packet Length*/ -const size_t MECH_PKT_LEN = 1248; -const size_t MEMS_MSOP_LEN = 1210; -const size_t MEMS_DIFOP_LEN = 256; /*Output style*/ #ifndef RS_INFOL #if defined(_WIN32) diff --git a/src/rs_driver/common/error_code.h b/src/rs_driver/common/error_code.h index 9553d516..9f6d74e4 100644 --- a/src/rs_driver/common/error_code.h +++ b/src/rs_driver/common/error_code.h @@ -31,7 +31,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include namespace robosense { namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index def2ca12..c6cb24ea 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -125,16 +125,20 @@ inline RSDecoderResult DecoderRS128::decodeMsopPkt(const uint8_t* this->protocol_ver_ = RS_SWAP_SHORT(mpkt_ptr->header.protocol_version); azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth); this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_low, mpkt_ptr->header.temp_high); + double block_timestamp = this->get_point_time_func_(pkt); - this->check_camera_trigger_func_(azimuth, pkt); float azi_diff = 0; + for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) { if (mpkt_ptr->blocks[blk_idx].id != this->lidar_const_param_.BLOCK_ID) { break; } + int cur_azi = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].azimuth); + +#if 0 if (this->echo_mode_ == ECHO_DUAL) { azi_diff = static_cast( @@ -158,28 +162,32 @@ inline RSDecoderResult DecoderRS128::decodeMsopPkt(const uint8_t* } } else +#endif { if (blk_idx == 0) { - azi_diff = static_cast((RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx + 1].azimuth) - cur_azi) % - RS_ONE_ROUND); + azi_diff = static_cast((RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx + 1].azimuth) - cur_azi) % RS_ONE_ROUND); } else { - azi_diff = static_cast((RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx - 1].azimuth)) % - RS_ONE_ROUND); + azi_diff = static_cast((RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx - 1].azimuth)) % RS_ONE_ROUND); + block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : (block_timestamp + this->time_duration_between_blocks_); } } + azi_diff = (azi_diff > 100) ? this->azi_diff_between_block_theoretical_ : azi_diff; + for (size_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) { int dsr_temp = (channel_idx / 4) % 16; float azi_channel_ori = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].azimuth) + (azi_diff * static_cast(dsr_temp) * this->lidar_const_param_.DSR_TOFFSET * this->lidar_const_param_.FIRING_FREQUENCY); + int azi_channel_final = this->azimuthCalibration(azi_channel_ori, channel_idx); + float distance = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].channels[channel_idx].distance) * this->lidar_const_param_.DIS_RESOLUTION; int angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 7362e420..0cf5da3b 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -83,9 +83,9 @@ class DecoderRS16 : public DecoderBase { public: DecoderRS16(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); - double getLidarTime(const uint8_t* pkt); + virtual RSDecoderResult decodeDifopPkt(const uint8_t* pkt); + virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); + virtual double getLidarTime(const uint8_t* pkt); }; template @@ -125,7 +125,6 @@ inline RSDecoderResult DecoderRS16::decodeMsopPkt(const uint8_t* p azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth); this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_raw); double block_timestamp = this->get_point_time_func_(pkt); - this->check_camera_trigger_func_(azimuth, pkt); float azi_diff = 0; for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) { diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 4388cede..42287cf6 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -35,6 +35,7 @@ namespace robosense { namespace lidar { + #pragma pack(push, 1) typedef struct { @@ -82,10 +83,16 @@ template class DecoderRS32 : public DecoderBase { public: + + virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size); + virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRS32() = default; + +#if 0 + virtual double getLidarTime(const uint8_t* pkt); +#endif + explicit DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); - double getLidarTime(const uint8_t* pkt); }; template @@ -93,9 +100,11 @@ inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) : DecoderBase(param, lidar_const_param) { +#if 0 this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->beam_ring_table_.resize(this->lidar_const_param_.LASER_NUM); +#endif if (this->param_.max_distance > 200.0f) { this->param_.max_distance = 200.0f; @@ -106,26 +115,38 @@ inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, } } +#if 0 template inline double DecoderRS32::getLidarTime(const uint8_t* pkt) { return this->template calculateTimeYMD(pkt); } +#endif template -inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, - int& height, int& azimuth) +inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* pkt, size_t size) { - height = this->lidar_const_param_.LASER_NUM; + uint8_t id[] = {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0}; + const RS32MsopPkt* mpkt_ptr = reinterpret_cast(pkt); - if (mpkt_ptr->header.id != this->lidar_const_param_.MSOP_ID) + + if (memcpy((uint8_t*)mpkt_ptr->header.id, id, sizeof(id)) != 0) { return RSDecoderResult::WRONG_PKT_HEADER; } - azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth); + + this->current_temperature_ = calcTemp(&(mpkt_ptr->header.temp)); + +#if 0 this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_raw); +#endif + +#if 0 double block_timestamp = this->get_point_time_func_(pkt); - this->check_camera_trigger_func_(azimuth, pkt); +#else + double block_timestamp = 0; +#endif + float azi_diff = 0; for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) { @@ -174,26 +195,37 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p azi_diff * this->lidar_const_param_.FIRING_FREQUENCY * this->lidar_const_param_.DSR_TOFFSET * static_cast(2 * (channel_idx % 16) + (channel_idx / 16)); + +#if 0 int azi_channel_final = this->azimuthCalibration(azi_channel_ori, channel_idx); +#else + int azi_channel_final = azi_channel_ori; +#endif + float distance = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].channels[channel_idx].distance) * this->lidar_const_param_.DIS_RESOLUTION; + int angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; typename T_PointCloud::PointT point; bool pointValid = false; + if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && ((azi_channel_final >= this->start_angle_) || (azi_channel_final <= this->end_angle_))))) { + float x = distance * this->checkCosTable(angle_vert) * this->checkCosTable(azi_channel_final) + this->lidar_const_param_.RX * this->checkCosTable(angle_horiz); float y = -distance * this->checkCosTable(angle_vert) * this->checkSinTable(azi_channel_final) - this->lidar_const_param_.RX * this->checkSinTable(angle_horiz); float z = distance * this->checkSinTable(angle_vert) + this->lidar_const_param_.RZ; uint8_t intensity = mpkt_ptr->blocks[blk_idx].channels[channel_idx].intensity; +#if 0 this->transformPoint(x, y, z); +#endif setX(point, x); setY(point, y); setZ(point, z); @@ -213,7 +245,7 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p { setRing(point, this->beam_ring_table_[channel_idx]); setTimestamp(point, block_timestamp); - vec.emplace_back(std::move(point)); + //vec.emplace_back(std::move(point)); } } } @@ -221,18 +253,22 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p } template -inline RSDecoderResult DecoderRS32::decodeDifopPkt(const uint8_t* pkt) +inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* pkt, size_t size) { const RS32DifopPkt* dpkt_ptr = reinterpret_cast(pkt); + if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) { return RSDecoderResult::WRONG_PKT_HEADER; } + +#if 0 this->template decodeDifopCommon(pkt, LidarType::RS32); if (!this->difop_flag_) { this->template decodeDifopCalibration(pkt, LidarType::RS32); } +#endif return RSDecoderResult::DECODE_OK; } diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index fea5cfd2..2f61858e 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -126,7 +126,6 @@ inline RSDecoderResult DecoderRS80::decodeMsopPkt(const uint8_t* p azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth); this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_low, mpkt_ptr->header.temp_high); double block_timestamp = this->get_point_time_func_(pkt); - this->check_camera_trigger_func_(azimuth, pkt); float azi_diff = 0; for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) { diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index e545acb5..f710f1fc 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -125,7 +125,6 @@ inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* p azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth); this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_raw); double block_timestamp = this->get_point_time_func_(pkt); - this->check_camera_trigger_func_(azimuth, pkt); float azi_diff = 0; for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) { diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index c6559ad4..baa4c77c 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -138,7 +138,6 @@ inline RSDecoderResult DecoderRSHELIOS::decodeMsopPkt(const uint8_ azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth); this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_raw); double block_timestamp = this->get_point_time_func_(pkt); - this->check_camera_trigger_func_(azimuth, pkt); float azi_diff = 0; for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) { diff --git a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp index c49f4988..662a667e 100644 --- a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp @@ -100,7 +100,7 @@ inline DecoderRSROCK::DecoderRSROCK(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) : DecoderBase(param, lidar_const_param) { - this->msop_pkt_len_ = 1236; // TODO + this->msop_pkt_len_ = ROCK_MSOP_LEN; this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); @@ -148,7 +148,6 @@ inline RSDecoderResult DecoderRSROCK::decodeMsopPkt(const uint8_t* azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].channels[0].azimuth); this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_raw); double block_timestamp = this->get_point_time_func_(pkt); - this->check_camera_trigger_func_(azimuth, pkt); float azi_diff = 0; for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) { diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 98eb49c7..37cfb938 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -31,39 +31,52 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include -#include + +#include +#include #include +#include + +#include +#include +#include +#include +#include +#include +#include + +#ifndef _USE_MATH_DEFINES +#define _USE_MATH_DEFINES // for VC++, required to use const M_IP in +#endif + +/*Eigen*/ +#ifdef ENABLE_TRANSFORM +#include +#endif + namespace robosense { namespace lidar { -#define DEFINE_MEMBER_CHECKER(member) \ - template \ - struct has_##member : std::false_type \ - { \ - }; \ - template \ - struct has_##member< \ - T, typename std::enable_if().member), void>::value, bool>::type> \ - : std::true_type \ - { \ - }; -#define RS_HAS_MEMBER(C, member) has_##member::value -DEFINE_MEMBER_CHECKER(x) -DEFINE_MEMBER_CHECKER(y) -DEFINE_MEMBER_CHECKER(z) -DEFINE_MEMBER_CHECKER(intensity) -DEFINE_MEMBER_CHECKER(ring) -DEFINE_MEMBER_CHECKER(timestamp) + #define RS_SWAP_SHORT(x) ((((x)&0xFF) << 8) | (((x)&0xFF00) >> 8)) #define RS_SWAP_LONG(x) ((((x)&0xFF) << 24) | (((x)&0xFF00) << 8) | (((x)&0xFF0000) >> 8) | (((x)&0xFF000000) >> 24)) #define RS_TO_RADS(x) ((x) * (M_PI) / 180) + +/*Packet Length*/ +const size_t MECH_PKT_LEN = 1248; + +const size_t MEMS_MSOP_LEN = 1210; +const size_t MEMS_DIFOP_LEN = 256; + +const size_t ROCK_MSOP_LEN = 1236; + constexpr float RS_ANGLE_RESOLUTION = 0.01; constexpr float MICRO = 1000000.0; constexpr float NANO = 1000000000.0; constexpr int RS_ONE_ROUND = 36000; constexpr uint16_t PROTOCOL_VER_0 = 0x00; + /* Echo mode definition */ enum RSEchoMode { @@ -82,264 +95,148 @@ enum RSDecoderResult DISCARD_PKT = -4 }; -#pragma pack(push, 1) -typedef struct -{ - uint64_t MSOP_ID; - uint64_t DIFOP_ID; - uint64_t BLOCK_ID; - uint32_t PKT_RATE; - uint16_t BLOCKS_PER_PKT; - uint16_t CHANNELS_PER_BLOCK; - uint16_t LASER_NUM; - float DSR_TOFFSET; - float FIRING_FREQUENCY; - float DIS_RESOLUTION; - float RX; - float RY; - float RZ; -} LidarConstantParameter; - -typedef struct -{ - uint8_t year; - uint8_t month; - uint8_t day; - uint8_t hour; - uint8_t minute; - uint8_t second; - uint16_t ms; - uint16_t us; -} RSTimestampYMD; - -typedef struct +template +class DecoderBase { - uint8_t sec[6]; - uint32_t us; -} RSTimestampUTC; +public: -typedef struct -{ - uint8_t sync_mode; - uint8_t sync_sts; - RSTimestampUTC timestamp; -} RSTimeInfo; + virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size) = 0; + virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size) = 0; -typedef struct -{ - uint64_t id; - uint8_t reserved_1[12]; - RSTimestampYMD timestamp; - uint8_t lidar_type; - uint8_t reserved_2[7]; - uint16_t temp_raw; - uint8_t reserved_3[2]; -} RSMsopHeader; - -typedef struct -{ - uint32_t id; - uint16_t protocol_version; - uint8_t reserved_1; - uint8_t wave_mode; - uint8_t temp_low; - uint8_t temp_high; - RSTimestampUTC timestamp; - uint8_t reserved_2[10]; - uint8_t lidar_type; - uint8_t reserved_3[49]; -} RSMsopHeaderNew; - -typedef struct -{ - uint8_t lidar_ip[4]; - uint8_t host_ip[4]; - uint8_t mac_addr[6]; - uint16_t local_port; - uint16_t dest_port; - uint16_t port3; - uint16_t port4; -} RSEthNet; - -typedef struct -{ - uint8_t lidar_ip[4]; - uint8_t dest_ip[4]; - uint8_t mac_addr[6]; - uint16_t msop_port; - uint16_t reserve_1; - uint16_t difop_port; - uint16_t reserve_2; -} RSEthNetNew; - -typedef struct -{ - uint16_t start_angle; - uint16_t end_angle; -} RSFOV; +#if 0 + virtual double getLidarTime(const uint8_t* pkt) = 0; +#endif -typedef struct -{ - uint8_t sign; - uint16_t value; -} RSCalibrationAngle; + virtual ~DecoderBase() = default; -typedef struct -{ - uint16_t distance; - uint8_t intensity; -} RSChannel; + uint16_t height() + { + return height_; + } -typedef struct -{ - uint8_t top_ver[5]; - uint8_t bottom_ver[5]; -} RSVersion; + void regRecvCallback(const std::function)>& cb_put, + const std::function(void)>& cb_get) + { + point_cloud_cb_put_vec_.emplace_back(cb_put); + if (cb_get != nullptr) + { + point_cloud_cb_get_ = cb_get; + } + } -typedef struct -{ - uint8_t top_firmware_ver[5]; - uint8_t bot_firmware_ver[5]; - uint8_t bot_soft_ver[5]; - uint8_t motor_firmware_ver[5]; - uint8_t hw_ver[3]; -} RSVersionNew; - -typedef struct -{ - uint8_t num[6]; -} RSSn; + std::shared_ptr getPointCloud() + { + std::shared_ptr pc; + + while (1) + { + if (point_cloud_cb_get_ != nullptr) + pc = point_cloud_cb_get_(); + + if (pc) + { + pc->points.resize(0); + return pc; + } + +#if 0 + reportError(Error(ERRCODE_POINTCLOUDNULL)); + std::this_thread::sleep_for(std::chrono::milliseconds(300)); +#endif + }; + } + + double getLidarTemperature() + { + return current_temperature_; + } -typedef struct -{ - uint8_t device_current[3]; - uint8_t main_current[3]; - uint16_t vol_12v; - uint16_t vol_sim_1v8; - uint16_t vol_dig_3v3; - uint16_t vol_sim_3v3; - uint16_t vol_dig_5v4; - uint16_t vol_sim_5v; - uint16_t vol_ejc_5v; - uint16_t vol_recv_5v; - uint16_t vol_apd; -} RSStatus; - -typedef struct -{ - uint16_t device_current; - uint16_t vol_fpga; - uint16_t vol_12v; - uint16_t vol_dig_5v4; - uint16_t vol_sim_5v; - uint16_t vol_apd; - uint8_t reserved[12]; -} RSStatusNew; - -typedef struct -{ - uint8_t reserved_1[9]; - uint16_t checksum; - uint16_t manc_err1; - uint16_t manc_err2; - uint8_t gps_status; - uint16_t temperature1; - uint16_t temperature2; - uint16_t temperature3; - uint16_t temperature4; - uint16_t temperature5; - uint8_t reserved_2[5]; - uint16_t cur_rpm; - uint8_t reserved_3[7]; -} RSDiagno; - -typedef struct -{ - uint16_t bot_fpga_temperature; - uint16_t recv_A_temperature; - uint16_t recv_B_temperature; - uint16_t main_fpga_temperature; - uint16_t main_fpga_core_temperature; - uint16_t real_rpm; - uint8_t lane_up; - uint16_t lane_up_cnt; - uint16_t main_status; - uint8_t gps_status; - uint8_t reserved[22]; -} RSDiagnoNew; - -#pragma pack(pop) - -//----------------- Decoder --------------------- -template -class DecoderBase -{ -public: explicit DecoderBase(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - DecoderBase(const DecoderBase&) = delete; - DecoderBase& operator=(const DecoderBase&) = delete; - virtual ~DecoderBase() = default; - virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size, - typename T_PointCloud::VectorT& point_cloud_vec, int& height); - virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size); - virtual void loadAngleFile(const std::string& angle_path); - virtual void regRecvCallback(const std::function& callback); ///< Camera trigger - virtual double getLidarTemperature(); - virtual double getLidarTime(const uint8_t* pkt) = 0; + + void loadAngleFile(const std::string& angle_path); protected: - virtual float computeTemperature(const uint16_t& temp_raw); - virtual float computeTemperature(const uint8_t& temp_low, const uint8_t& temp_high); - virtual int azimuthCalibration(const float& azimuth, const int& channel); - virtual void checkTriggerAngle(const int& angle, const double& timestamp); - virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, - int& azimuth) = 0; - virtual RSDecoderResult decodeDifopPkt(const uint8_t* pkt) = 0; + +#if 0 + int azimuthCalibration(const float& azimuth, const int& channel); +#endif + +#if 0 RSEchoMode getEchoMode(const LidarType& type, const uint8_t& return_mode); +#endif + +#if 0 template double calculateTimeUTC(const uint8_t* pkt, const LidarType& type); template double calculateTimeYMD(const uint8_t* pkt); +#endif + template void decodeDifopCommon(const uint8_t* pkt, const LidarType& type); + +#if 0 template void decodeDifopCalibration(const uint8_t* pkt, const LidarType& type); + void sortBeamTable(); +#endif + +#if 0 void transformPoint(float& x, float& y, float& z); +#endif + float checkCosTable(const int& angle); float checkSinTable(const int& angle); - void sortBeamTable(); -private: +#if 0 std::vector initTrigonometricLookupTable(const std::function& func); +#endif + +private: + DecoderBase(const DecoderBase&) = delete; + DecoderBase& operator=(const DecoderBase&) = delete; protected: + + std::function(void)> point_cloud_cb_get_; + std::vector)>> point_cloud_cb_put_vec_; + std::shared_ptr point_cloud_; + const LidarConstantParameter lidar_const_param_; RSDecoderParam param_; + double current_temperature_; + uint16_t height_; + uint32_t msop_pkt_len_; uint32_t difop_pkt_len_; + RSEchoMode echo_mode_; + unsigned int pkts_per_frame_; unsigned int pkt_count_; unsigned int trigger_index_; unsigned int prev_angle_diff_; unsigned int rpm_; unsigned int protocol_ver_; + int start_angle_; int end_angle_; + bool angle_flag_; + int cut_angle_; int last_azimuth_; - bool angle_flag_; bool difop_flag_; float fov_time_jump_diff_; float time_duration_between_blocks_; - float current_temperature_; float azi_diff_between_block_theoretical_; + std::vector vert_angle_list_; std::vector hori_angle_list_; std::vector beam_ring_table_; - std::vector> camera_trigger_cb_vec_; + +#if 0 std::function get_point_time_func_; - std::function check_camera_trigger_func_; +#endif int lidar_alph0_; // atan2(Ry, Rx) * 180 / M_PI * 100 float lidar_Rxy_; // sqrt(Rx*Rx + Ry*Ry) @@ -353,6 +250,8 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) : lidar_const_param_(lidar_const_param) , param_(param) + , current_temperature_(0) + , height_(0) , msop_pkt_len_(MECH_PKT_LEN) , difop_pkt_len_(MECH_PKT_LEN) , echo_mode_(ECHO_SINGLE) @@ -364,31 +263,33 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, , protocol_ver_(0) , start_angle_(param.start_angle * 100) , end_angle_(param.end_angle * 100) + , angle_flag_(true) , cut_angle_(param.cut_angle * 100) , last_azimuth_(-36001) - , angle_flag_(true) , difop_flag_(false) , fov_time_jump_diff_(0) , time_duration_between_blocks_(0) - , current_temperature_(0) , azi_diff_between_block_theoretical_(20) { if (cut_angle_ > RS_ONE_ROUND) { cut_angle_ = 0; } - if (this->start_angle_ > RS_ONE_ROUND || this->start_angle_ < 0 || this->end_angle_ > RS_ONE_ROUND || - this->end_angle_ < 0) + + if (this->start_angle_ > RS_ONE_ROUND || this->start_angle_ < 0 || + this->end_angle_ > RS_ONE_ROUND || this->end_angle_ < 0) { RS_WARNING << "start_angle & end_angle should be in range 0~360° " << RS_REND; this->start_angle_ = 0; this->end_angle_ = RS_ONE_ROUND; } + if (this->start_angle_ > this->end_angle_) { this->angle_flag_ = false; } +#if 0 // even though T_Point does not have timestamp, it gives the timestamp /* Point time function*/ // typedef typename T_PointCloud::PointT T_Point; @@ -411,38 +312,18 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, // get_point_time_func_ = [this](const uint8_t* pkt) { return 0; }; // } -// Camera trigger function -#ifdef ENABLE_PUBLISH_CAM_MSG - if (param.trigger_param.trigger_map.size() > 0) - { - if (this->param_.use_lidar_clock) - { - check_camera_trigger_func_ = [this](const int& azimuth, const uint8_t* pkt) { - checkTriggerAngle(azimuth, getLidarTime(pkt)); - }; - } - else - { - check_camera_trigger_func_ = [this](const int& azimuth, const uint8_t* pkt) { - checkTriggerAngle(azimuth, getTime()); - }; - } - } - else -#endif - { - check_camera_trigger_func_ = [this](const int& azimuth, const uint8_t* pkt) { return; }; - } - /* Cos & Sin look-up table*/ cos_lookup_table_ = initTrigonometricLookupTable([](const double rad) -> double { return std::cos(rad); }); sin_lookup_table_ = initTrigonometricLookupTable([](const double rad) -> double { return std::sin(rad); }); +#endif + /* Calulate the lidar_alph0 and lidar_Rxy */ lidar_alph0_ = std::atan2(lidar_const_param_.RY, lidar_const_param_.RX) * 180 / M_PI * 100; lidar_Rxy_ = std::sqrt(lidar_const_param_.RX * lidar_const_param_.RX + lidar_const_param_.RY * lidar_const_param_.RY); } +#if 0 template inline RSDecoderResult DecoderBase::processDifopPkt(const uint8_t* pkt, size_t size) { @@ -460,15 +341,9 @@ inline RSDecoderResult DecoderBase::processDifopPkt(const uint8_t* } template -inline RSDecoderResult DecoderBase::processMsopPkt(const uint8_t* pkt, size_t size, - typename T_PointCloud::VectorT& point_cloud_vec, - int& height) +inline RSDecoderResult DecoderBase::processMsopPkt( + const uint8_t* pkt, size_t size) { - if (pkt == NULL) - { - return PKT_NULL; - } - if (size != this->msop_pkt_len_) { return WRONG_PKT_LENGTH; @@ -521,154 +396,51 @@ inline RSDecoderResult DecoderBase::processMsopPkt(const uint8_t* } return DECODE_OK; } - -template -inline void DecoderBase::regRecvCallback(const std::function& callback) -{ - camera_trigger_cb_vec_.emplace_back(callback); -} - -template -inline double DecoderBase::getLidarTemperature() -{ - return current_temperature_; -} +#endif template inline void DecoderBase::loadAngleFile(const std::string& angle_path) { - std::string line_str; - std::ifstream fd_angle(angle_path.c_str(), std::ios::in); - if (fd_angle.is_open()) - { - unsigned int row_index = 0; - while (std::getline(fd_angle, line_str)) - { - std::stringstream ss(line_str); - std::string str; - std::vector vect_str; - while (std::getline(ss, str, ',')) - { - vect_str.emplace_back(str); - } - try - { - this->vert_angle_list_[row_index] = std::stof(vect_str.at(0)) * 100; // degree - this->hori_angle_list_[row_index] = std::stof(vect_str.at(1)) * 100; // degree - } - catch (...) - { - RS_WARNING << "Wrong calibration file format! Please check your angle.csv file!" << RS_REND; - break; - } - row_index++; - if (row_index >= this->lidar_const_param_.LASER_NUM) - { - this->sortBeamTable(); - break; - } - } - fd_angle.close(); - } -} - -template -inline void DecoderBase::checkTriggerAngle(const int& angle, const double& timestamp) -{ - std::map::iterator iter = param_.trigger_param.trigger_map.begin(); - for (size_t i = 0; i < trigger_index_; i++) - { - iter++; - } - if (iter != param_.trigger_param.trigger_map.end()) - { - unsigned int angle_diff = std::abs(iter->first * 100 - angle); - if (angle_diff < prev_angle_diff_) - { - prev_angle_diff_ = angle_diff; - return; - } - else - { - trigger_index_++; - prev_angle_diff_ = RS_ONE_ROUND; - for (auto cb : camera_trigger_cb_vec_) - { - cb(std::make_pair(iter->second, timestamp)); - } - } - } -} - -/* 16, 32, BP & RSHELIOS */ -template -inline float DecoderBase::computeTemperature(const uint16_t& temp_raw) -{ - uint8_t neg_flag = (temp_raw >> 8) & 0x80; - float msb = (temp_raw >> 8) & 0x7F; - float lsb = (temp_raw & 0x00FF) >> 3; - float temp; - if (neg_flag == 0x80) - { - temp = -1 * (msb * 32 + lsb) * 0.0625f; - } - else - { - temp = (msb * 32 + lsb) * 0.0625f; - } - - return temp; -} - -/* 128 & 80 */ -template -inline float DecoderBase::computeTemperature(const uint8_t& temp_low, const uint8_t& temp_high) -{ - uint8_t neg_flag = temp_low & 0x80; - float msb = temp_low & 0x7F; - float lsb = temp_high >> 4; - float temp; - if (neg_flag == 0x80) - { - temp = -1 * (msb * 16 + lsb) * 0.0625f; - } - else - { - temp = (msb * 16 + lsb) * 0.0625f; - } - - return temp; } +#if 0 template inline int DecoderBase::azimuthCalibration(const float& azimuth, const int& channel) { return (static_cast(azimuth) + this->hori_angle_list_[channel] + RS_ONE_ROUND) % RS_ONE_ROUND; } +#endif template template inline void DecoderBase::decodeDifopCommon(const uint8_t* pkt, const LidarType& type) { const T_Difop* dpkt_ptr = reinterpret_cast(pkt); + +#if 0 this->echo_mode_ = this->getEchoMode(type, dpkt_ptr->return_mode); +#endif + this->rpm_ = RS_SWAP_SHORT(dpkt_ptr->rpm); if (this->rpm_ == 0) { RS_WARNING << "LiDAR RPM is 0" << RS_REND; this->rpm_ = 600; } - this->time_duration_between_blocks_ = - (60 / static_cast(this->rpm_)) / - ((this->lidar_const_param_.PKT_RATE * 60 / this->rpm_) * this->lidar_const_param_.BLOCKS_PER_PKT); + + this->time_duration_between_blocks_ = + (60 / static_cast(this->rpm_)) / ((this->lidar_const_param_.PKT_RATE * 60 / this->rpm_) * this->lidar_const_param_.BLOCKS_PER_PKT); + int fov_start_angle = RS_SWAP_SHORT(dpkt_ptr->fov.start_angle); int fov_end_angle = RS_SWAP_SHORT(dpkt_ptr->fov.end_angle); int fov_range = (fov_start_angle < fov_end_angle) ? (fov_end_angle - fov_start_angle) : (RS_ONE_ROUND - fov_start_angle + fov_end_angle); int blocks_per_round = (this->lidar_const_param_.PKT_RATE / (this->rpm_ / 60)) * this->lidar_const_param_.BLOCKS_PER_PKT; + this->fov_time_jump_diff_ = this->time_duration_between_blocks_ * (fov_range / (RS_ONE_ROUND / static_cast(blocks_per_round))); + if (this->echo_mode_ == RSEchoMode::ECHO_DUAL) { this->pkts_per_frame_ = ceil(2 * this->lidar_const_param_.PKT_RATE * 60 / this->rpm_); @@ -677,41 +449,54 @@ inline void DecoderBase::decodeDifopCommon(const uint8_t* pkt, con { this->pkts_per_frame_ = ceil(this->lidar_const_param_.PKT_RATE * 60 / this->rpm_); } + this->azi_diff_between_block_theoretical_ = (RS_ONE_ROUND / this->lidar_const_param_.BLOCKS_PER_PKT) / static_cast(this->pkts_per_frame_); ///< ((rpm/60)*360)/pkts_rate/blocks_per_pkt } +#if 0 template template inline void DecoderBase::decodeDifopCalibration(const uint8_t* pkt, const LidarType& type) { const T_Difop* dpkt_ptr = reinterpret_cast(pkt); + const uint8_t* p_ver_cali = reinterpret_cast(dpkt_ptr->ver_angle_cali); - if ((p_ver_cali[0] == 0x00 || p_ver_cali[0] == 0xFF) && (p_ver_cali[1] == 0x00 || p_ver_cali[1] == 0xFF) && - (p_ver_cali[2] == 0x00 || p_ver_cali[2] == 0xFF) && (p_ver_cali[3] == 0x00 || p_ver_cali[3] == 0xFF)) + + if ((p_ver_cali[0] == 0x00 || p_ver_cali[0] == 0xFF) && + (p_ver_cali[1] == 0x00 || p_ver_cali[1] == 0xFF) && + (p_ver_cali[2] == 0x00 || p_ver_cali[2] == 0xFF) && + (p_ver_cali[3] == 0x00 || p_ver_cali[3] == 0xFF)) { return; } + int neg = 1; for (size_t i = 0; i < this->lidar_const_param_.LASER_NUM; i++) { /* vert angle calibration data */ neg = static_cast(dpkt_ptr->ver_angle_cali[i].sign) == 0 ? 1 : -1; this->vert_angle_list_[i] = static_cast(RS_SWAP_SHORT(dpkt_ptr->ver_angle_cali[i].value)) * neg; + /* horizon angle calibration data */ neg = static_cast(dpkt_ptr->hori_angle_cali[i].sign) == 0 ? 1 : -1; this->hori_angle_list_[i] = static_cast(RS_SWAP_SHORT(dpkt_ptr->hori_angle_cali[i].value)) * neg; + if (type == LidarType::RS32) { this->vert_angle_list_[i] *= 0.1f; this->hori_angle_list_[i] *= 0.1f; } } + this->sortBeamTable(); + this->difop_flag_ = true; } +#endif +#if 0 template template inline double DecoderBase::calculateTimeUTC(const uint8_t* pkt, const LidarType& type) @@ -778,7 +563,9 @@ inline void DecoderBase::transformPoint(float& x, float& y, float& z = target_rotate(2); #endif } +#endif +#if 0 template inline void DecoderBase::sortBeamTable() { @@ -792,77 +579,9 @@ inline void DecoderBase::sortBeamTable() this->beam_ring_table_[sorted_idx[i]] = i; } } +#endif -template -inline typename std::enable_if::type setX(T_Point& point, const float& value) -{ -} - -template -inline typename std::enable_if::type setX(T_Point& point, const float& value) -{ - point.x = value; -} - -template -inline typename std::enable_if::type setY(T_Point& point, const float& value) -{ -} - -template -inline typename std::enable_if::type setY(T_Point& point, const float& value) -{ - point.y = value; -} - -template -inline typename std::enable_if::type setZ(T_Point& point, const float& value) -{ -} - -template -inline typename std::enable_if::type setZ(T_Point& point, const float& value) -{ - point.z = value; -} - -template -inline typename std::enable_if::type setIntensity(T_Point& point, - const uint8_t& value) -{ -} - -template -inline typename std::enable_if::type setIntensity(T_Point& point, - const uint8_t& value) -{ - point.intensity = value; -} - -template -inline typename std::enable_if::type setRing(T_Point& point, const uint16_t& value) -{ -} - -template -inline typename std::enable_if::type setRing(T_Point& point, const uint16_t& value) -{ - point.ring = value; -} - -template -inline typename std::enable_if::type setTimestamp(T_Point& point, - const double& value) -{ -} - -template -inline typename std::enable_if::type setTimestamp(T_Point& point, - const double& value) -{ - point.timestamp = value; -} - +#if 0 template inline RSEchoMode DecoderBase::getEchoMode(const LidarType& type, const uint8_t& return_mode) { @@ -905,6 +624,7 @@ inline RSEchoMode DecoderBase::getEchoMode(const LidarType& type, } return RSEchoMode::ECHO_SINGLE; } +#endif template inline float DecoderBase::checkCosTable(const int& angle) @@ -917,6 +637,7 @@ inline float DecoderBase::checkSinTable(const int& angle) return sin_lookup_table_[angle + RS_ONE_ROUND]; } +#if 0 template inline std::vector DecoderBase::initTrigonometricLookupTable(const std::function& func) @@ -930,6 +651,7 @@ DecoderBase::initTrigonometricLookupTable(const std::function +#include +#include + +#include +#include +#include +#include +#include +#include + +namespace robosense +{ +namespace lidar +{ + +#pragma pack(push, 1) +typedef struct +{ + uint64_t MSOP_ID; + uint64_t DIFOP_ID; + uint64_t BLOCK_ID; + uint32_t PKT_RATE; + uint16_t BLOCKS_PER_PKT; + uint16_t CHANNELS_PER_BLOCK; + uint16_t LASER_NUM; + float DSR_TOFFSET; + float FIRING_FREQUENCY; + float DIS_RESOLUTION; + float RX; + float RY; + float RZ; +} LidarConstantParameter; + +typedef struct +{ + uint8_t year; + uint8_t month; + uint8_t day; + uint8_t hour; + uint8_t minute; + uint8_t second; + uint16_t ms; + uint16_t us; +} RSTimestampYMD; + +typedef struct +{ + uint8_t sec[6]; + uint8_t ss[4]; +} RSTimestampUTC2; + +typedef struct +{ + uint8_t sec[6]; + uint32_t us; +} RSTimestampUTC; + +typedef struct +{ + uint8_t sync_mode; + uint8_t sync_sts; + RSTimestampUTC timestamp; +} RSTimeInfo; + +typedef struct +{ + uint8_t tt[2]; +} RsTemp; + +typedef struct +{ + uint8_t id[8]; +// uint64_t id; + uint8_t reserved_1[12]; + RSTimestampYMD timestamp; + uint8_t lidar_type; + uint8_t reserved_2[7]; + RsTemp temp; + //uint16_t temp_raw; + uint8_t reserved_3[2]; +} RSMsopHeader; + +typedef struct +{ + uint8_t id[4]; +// uint32_t id; + uint16_t protocol_version; + uint8_t reserved_1; + uint8_t wave_mode; + RsTemp temp; +#if 0 + uint8_t temp_low; + uint8_t temp_high; +#endif + RSTimestampUTC timestamp; + uint8_t reserved_2[10]; + uint8_t lidar_type; + uint8_t reserved_3[49]; +} RSMsopHeaderNew; + +typedef struct +{ + uint8_t lidar_ip[4]; + uint8_t host_ip[4]; + uint8_t mac_addr[6]; + uint16_t local_port; + uint16_t dest_port; + uint16_t port3; + uint16_t port4; +} RSEthNet; + +typedef struct +{ + uint8_t lidar_ip[4]; + uint8_t dest_ip[4]; + uint8_t mac_addr[6]; + uint16_t msop_port; + uint16_t reserve_1; + uint16_t difop_port; + uint16_t reserve_2; +} RSEthNetNew; + +typedef struct +{ + uint16_t start_angle; + uint16_t end_angle; +} RSFOV; + +typedef struct +{ + uint8_t sign; + uint16_t value; +} RSCalibrationAngle; + +typedef struct +{ + uint16_t distance; + uint8_t intensity; +} RSChannel; + +typedef struct +{ + uint8_t top_ver[5]; + uint8_t bottom_ver[5]; +} RSVersion; + +typedef struct +{ + uint8_t top_firmware_ver[5]; + uint8_t bot_firmware_ver[5]; + uint8_t bot_soft_ver[5]; + uint8_t motor_firmware_ver[5]; + uint8_t hw_ver[3]; +} RSVersionNew; + +typedef struct +{ + uint8_t num[6]; +} RSSn; + +typedef struct +{ + uint8_t device_current[3]; + uint8_t main_current[3]; + uint16_t vol_12v; + uint16_t vol_sim_1v8; + uint16_t vol_dig_3v3; + uint16_t vol_sim_3v3; + uint16_t vol_dig_5v4; + uint16_t vol_sim_5v; + uint16_t vol_ejc_5v; + uint16_t vol_recv_5v; + uint16_t vol_apd; +} RSStatus; + +typedef struct +{ + uint16_t device_current; + uint16_t vol_fpga; + uint16_t vol_12v; + uint16_t vol_dig_5v4; + uint16_t vol_sim_5v; + uint16_t vol_apd; + uint8_t reserved[12]; +} RSStatusNew; + +typedef struct +{ + uint8_t reserved_1[9]; + uint16_t checksum; + uint16_t manc_err1; + uint16_t manc_err2; + uint8_t gps_status; + uint16_t temperature1; + uint16_t temperature2; + uint16_t temperature3; + uint16_t temperature4; + uint16_t temperature5; + uint8_t reserved_2[5]; + uint16_t cur_rpm; + uint8_t reserved_3[7]; +} RSDiagno; + +typedef struct +{ + uint16_t bot_fpga_temperature; + uint16_t recv_A_temperature; + uint16_t recv_B_temperature; + uint16_t main_fpga_temperature; + uint16_t main_fpga_core_temperature; + uint16_t real_rpm; + uint8_t lane_up; + uint16_t lane_up_cnt; + uint16_t main_status; + uint8_t gps_status; + uint8_t reserved[22]; +} RSDiagnoNew; + +#pragma pack(pop) + +inline uint64_t calcTimeUTCWithNs(const RSTimestampUTC2* tsUtc) +{ + // sec + uint64_t sec = 0; + for (int i = 0; i < 6; i++) + { + sec <<= 8; + sec += tsUtc->sec[i]; + } + + uint64_t ns = 0; + for (int i = 0; i < 4; i++) + { + ns <<= 8; + ns += tsUtc->ss[i]; + } + + return (sec * 1000000 + ns/1000); +} + +inline uint64_t calcTimeUTCWithUs(const RSTimestampUTC2* tsUtc) +{ + // sec + uint64_t sec = 0; + for (int i = 0; i < 6; i++) + { + sec <<= 8; + sec += tsUtc->sec[i]; + } + + uint64_t us = 0; + for (int i = 0; i < 4; i++) + { + us <<= 8; + us += tsUtc->ss[i]; + } + + return (sec * 1000000 + us); +} + +inline uint64_t calcTimeUTCWithMs(const RSTimestampUTC2* tsUtc) +{ + // sec + uint64_t sec = 0; + for (int i = 0; i < 6; i++) + { + sec <<= 8; + sec += tsUtc->sec[i]; + } + + // ms + uint64_t ms = tsUtc->ss[0]; + ms <<= 8; + ms += tsUtc->ss[1]; + + // us + uint64_t us = tsUtc->ss[2]; + us <<= 8; + us += tsUtc->ss[3]; + + return (sec * 1000000 + ms * 1000 + us); +} + +inline uint64_t calcTimeYMD(const RSTimestampYMD* tsYmd) +{ + std::tm stm; + memset(&stm, 0, sizeof(stm)); + + // since 2000 in robosense YMD, and since 1900 in struct tm + stm.tm_year = tsYmd->year + 2000 - 1900; + // since 1 in robosense YMD, and since 0 in struct tm + stm.tm_mon = tsYmd->month - 1; + // since 1 in both robosense YMD and struct tm + stm.tm_mday = tsYmd->day; + stm.tm_hour = tsYmd->hour; + stm.tm_min = tsYmd->minute; + stm.tm_sec = tsYmd->second; + time_t sec = std::mktime(&stm); + + uint64_t ms = ntohs(tsYmd->ms); + uint64_t us = ntohs(tsYmd->us); + +#if 0 + std::cout << "tm_year:" << stm.tm_year + << ", tm_mon:" << stm.tm_mon + << ", ms:" << ms + << ", us:" << us + << std::endl; +#endif + + return (sec * 1000000 + ms * 1000 + us); +} + +inline uint64_t calcTimeHost(void) +{ + std::chrono::system_clock::time_point t = std::chrono::system_clock::now(); + std::chrono::system_clock::duration t_s = t.time_since_epoch(); + + std::chrono::duration> t_us = + std::chrono::duration_cast>>(t_s); + return t_us.count(); +} + +#define RS_TEMP_RESOLUTION 0.0625f + +inline int16_t calcTemp(const RsTemp* tmp) +{ + // | lsb | padding | neg | msb | + // | 5 | 3 | 1 | 7 | (in bits) + uint8_t lsb = tmp->tt[0] >> 3; + uint8_t msb = tmp->tt[1] & 0x7F; + uint8_t neg = tmp->tt[1] & 0x80; + + int16_t t = ((uint16_t)msb << 5) + lsb; + if (neg) t = -t; + + return t; +} + +class ScanBlock +{ +public: + ScanBlock(uint16_t start, uint16_t end) + { + start_ = start % 36000; + end_ = (end <= 36000) ? end : (end % 36000); + cross_zero_ = (start_ > end_); + } + + bool in(uint16_t angle) + { + if (cross_zero_) + return (angle >= start_) || (angle < end_); + else + return (angle >= start_) && (angle < end_); + } + + uint16_t start() + { + return start_; + } + + uint16_t end() + { + return end_; + } + +private: + uint16_t start_; + uint16_t end_; + bool cross_zero_; +}; + +class DistanceBlock +{ +public: + DistanceBlock (float min, float max, float usr_min, float usr_max) + : min_((usr_min > min) ? usr_min : min), max_((usr_max < max) ? usr_max : max) + { + } + + bool in(float distance) + { + return ((min_ <= distance) && (distance <= max_)); + } + + float min() + { + return min_; + } + + float max() + { + return max_; + } + +private: + + float min_; + float max_; +}; + + +class ChanAngles +{ +public: + + int loadFromFile(const std::string& angle_path) + { + int ret = loadFromFile (angle_path, vert_angles_, horiz_angles_); + if (ret < 0) + return ret; + + genUserChan(vert_angles_, user_chans_); + + return 0; + } + + int loadFromDifop(const RSCalibrationAngle vert_angle_arr[], + const RSCalibrationAngle horiz_angle_arr[], size_t size) + { + int ret = + loadFromDifop (vert_angle_arr, horiz_angle_arr, size, vert_angles_, horiz_angles_); + if (ret < 0) + return ret; + + genUserChan(vert_angles_, user_chans_); + return 0; + } + + size_t chanSize() + { + return vert_angles_.size(); + } + + uint16_t toUserChan(uint16_t chan) + { + return user_chans_[chan]; + } + + void horizAdjust(uint16_t chan, int32_t& horiz) + { + horiz += horiz_angles_[chan]; + } + + void vertAdjust(uint16_t chan, int32_t& vert) + { + vert += vert_angles_[chan]; + } + + void narrow () + { + } + + static + void genUserChan(const std::vector& vert_angles, std::vector& user_chans) + { + user_chans.resize(vert_angles.size()); + + for (size_t i = 0; i < vert_angles.size(); i++) + { + int32_t angle = vert_angles[i]; + uint16_t chan = 0; + + for (size_t j = 0; j < vert_angles.size(); j++) + { + if (vert_angles[j] < angle) + { + chan++; + } + } + + user_chans[i] = chan; + } + } + + static int loadFromFile(const std::string& angle_path, + std::vector& vert_angles, std::vector& horiz_angles) + { + vert_angles.clear(); + horiz_angles.clear(); + + std::ifstream fd(angle_path.c_str(), std::ios::in); + if (!fd.is_open()) + { + std::cout << "fail to open angle file:" << angle_path << std::endl; + return -1; + } + + std::string line; + while (std::getline(fd, line)) + { + size_t pos_comma = 0; + float vert = std::stof(line, &pos_comma); + float horiz = std::stof(line.substr(pos_comma+1)); + + vert_angles.emplace_back(static_cast(vert * 100)); + horiz_angles.emplace_back(static_cast(horiz * 100)); + } + + fd.close(); + return 0; + } + + static int loadFromDifop(const RSCalibrationAngle* vert_angle_arr, + const RSCalibrationAngle* horiz_angle_arr, size_t size, + std::vector& vert_angles, std::vector& horiz_angles) + { + vert_angles.clear(); + horiz_angles.clear(); + + for (size_t i = 0; i < size; i++) + { + const RSCalibrationAngle& vert = vert_angle_arr[i]; + const RSCalibrationAngle& horiz = horiz_angle_arr[i]; + int32_t v; + + if (vert.sign == 0xFF) + break; + + v = ntohs(vert.value); + if (vert.sign != 0) v = -v; + vert_angles.emplace_back(v); + + v = ntohs(horiz.value); + if (horiz.sign != 0) v = -v; + horiz_angles.emplace_back(v); + +#if 0 + if (type == LidarType::RS32) + { + this->vert_angle_list_[i] *= 0.1f; + this->hori_angle_list_[i] *= 0.1f; + } +#endif + } + + return ((vert_angles.size() > 0) ? 0 : -1); + } + +private: + std::vector vert_angles_; + std::vector horiz_angles_; + std::vector user_chans_; +}; + +class Trigon +{ +public: + + Trigon() + { + static bool init_ = false; + + if (!init_) + { + init_ = true; + + uint16_t RS_ONE_ROUND = 36000; + float RS_ANGLE_RESOLUTION = 0.01; + + for (size_t i = 0; i < RS_ONE_ROUND; i++) + { + double rads = static_cast(i) * RS_ANGLE_RESOLUTION; + rads = rads * M_PI / 180; + + sins_.emplace_back((float)std::sin(rads)); + coss_.emplace_back((float)std::cos(rads)); + } + } + } + + void print() + { + uint16_t RS_ONE_ROUND = 36000; + for (size_t i = 0; i < RS_ONE_ROUND; i++) + { + std::cout << i << "\t" << sins_[i] << "\t" << coss_[i] << std::endl; + } + } + + float cos(uint16_t angle) + { + return coss_[angle]; + } + + float sin(uint16_t angle) + { + return sins_[angle]; + } + +private: + std::vector sins_; + std::vector coss_; +}; + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 3007dd7d..f4628b88 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -30,16 +30,17 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include #include +#if 0 +#include #include #include #include #include #include #include -#include -#include +#endif + namespace robosense { namespace lidar @@ -53,14 +54,16 @@ class DecoderFactory static std::shared_ptr> createDecoder(const RSDriverParam& param); private: - static const LidarConstantParameter getRS16ConstantParam(); static const LidarConstantParameter getRS32ConstantParam(); +#if 0 + static const LidarConstantParameter getRS16ConstantParam(); static const LidarConstantParameter getRSBPConstantParam(); static const LidarConstantParameter getRS80ConstantParam(); static const LidarConstantParameter getRS128ConstantParam(); static const LidarConstantParameter getRSM1ConstantParam(); static const LidarConstantParameter getRSHELIOSConstantParam(); static const LidarConstantParameter getRSROCKConstantParam(); +#endif }; template @@ -70,12 +73,15 @@ DecoderFactory::createDecoder(const RSDriverParam& param) std::shared_ptr> ret_ptr; switch (param.lidar_type) { +#if 0 case LidarType::RS16: ret_ptr = std::make_shared>(param.decoder_param, getRS16ConstantParam()); break; +#endif case LidarType::RS32: ret_ptr = std::make_shared>(param.decoder_param, getRS32ConstantParam()); break; +#if 0 case LidarType::RSBP: ret_ptr = std::make_shared>(param.decoder_param, getRSBPConstantParam()); break; @@ -94,6 +100,7 @@ DecoderFactory::createDecoder(const RSDriverParam& param) case LidarType::RSROCK: ret_ptr = std::make_shared>(param.decoder_param, getRSROCKConstantParam()); break; +#endif default: RS_ERROR << "Wrong LiDAR Type. Please check your LiDAR Version! " << RS_REND; exit(-1); @@ -102,6 +109,7 @@ DecoderFactory::createDecoder(const RSDriverParam& param) return ret_ptr; } +#if 0 template inline const LidarConstantParameter DecoderFactory::getRS16ConstantParam() { @@ -121,6 +129,7 @@ inline const LidarConstantParameter DecoderFactory::getRS16Constan ret_param.RZ = 0; return ret_param; } +#endif template inline const LidarConstantParameter DecoderFactory::getRS32ConstantParam() @@ -142,6 +151,7 @@ inline const LidarConstantParameter DecoderFactory::getRS32Constan return ret_param; } +#if 0 template inline const LidarConstantParameter DecoderFactory::getRSBPConstantParam() { @@ -255,6 +265,7 @@ inline const LidarConstantParameter DecoderFactory::getRSROCKConstantPa ret_param.RZ = 0.0; return ret_param; } +#endif } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/set_member.hpp b/src/rs_driver/driver/decoder/set_member.hpp new file mode 100644 index 00000000..cd5595ed --- /dev/null +++ b/src/rs_driver/driver/decoder/set_member.hpp @@ -0,0 +1,125 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#define DEFINE_MEMBER_CHECKER(member) \ + template \ + struct has_##member : std::false_type \ + { \ + }; \ + template \ + struct has_##member< \ + T, typename std::enable_if().member), void>::value, bool>::type> \ + : std::true_type \ + { \ + }; + +DEFINE_MEMBER_CHECKER(x) +DEFINE_MEMBER_CHECKER(y) +DEFINE_MEMBER_CHECKER(z) +DEFINE_MEMBER_CHECKER(intensity) +DEFINE_MEMBER_CHECKER(ring) +DEFINE_MEMBER_CHECKER(timestamp) + +#define RS_HAS_MEMBER(C, member) has_##member::value + +template +inline typename std::enable_if::type setX(T_Point& point, const float& value) +{ +} + +template +inline typename std::enable_if::type setX(T_Point& point, const float& value) +{ + point.x = value; +} + +template +inline typename std::enable_if::type setY(T_Point& point, const float& value) +{ +} + +template +inline typename std::enable_if::type setY(T_Point& point, const float& value) +{ + point.y = value; +} + +template +inline typename std::enable_if::type setZ(T_Point& point, const float& value) +{ +} + +template +inline typename std::enable_if::type setZ(T_Point& point, const float& value) +{ + point.z = value; +} + +template +inline typename std::enable_if::type setIntensity(T_Point& point, + const uint8_t& value) +{ +} + +template +inline typename std::enable_if::type setIntensity(T_Point& point, + const uint8_t& value) +{ + point.intensity = value; +} + +template +inline typename std::enable_if::type setRing(T_Point& point, const uint16_t& value) +{ +} + +template +inline typename std::enable_if::type setRing(T_Point& point, const uint16_t& value) +{ + point.ring = value; +} + +template +inline typename std::enable_if::type setTimestamp(T_Point& point, + const double& value) +{ +} + +template +inline typename std::enable_if::type setTimestamp(T_Point& point, + const double& value) +{ + point.timestamp = value; +} + diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index 85e42004..e6a69f54 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -31,9 +31,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include -#include #include +#include +#include namespace robosense { namespace lidar diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index 13aa3da3..ee800f4c 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -32,35 +32,10 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#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 #define MAX_PKT_LEN 1500 #define ETH_HDR_LEN 42 diff --git a/src/rs_driver/driver/input/pcap_input.hpp b/src/rs_driver/driver/input/pcap_input.hpp index 98f3ba9d..f2575b8c 100644 --- a/src/rs_driver/driver/input/pcap_input.hpp +++ b/src/rs_driver/driver/input/pcap_input.hpp @@ -31,7 +31,12 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include "input.hpp" + +#include + +#include + +#include namespace robosense { diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index b7c19ebd..37abd63f 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -32,7 +32,23 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#include "input.hpp" +#include + +#ifdef __linux__ + +#include +#include +#include +#include +#include + +#elif _WIN32 + +#include +#include + +#endif + #include #include diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 0dc09473..25a7a512 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -31,6 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once +#include #include #include #include @@ -40,42 +41,45 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include -constexpr size_t MAX_PACKETS_BUFFER_SIZE = 100000; +#include + namespace robosense { namespace lidar { + template class LidarDriverImpl { public: + + static std::string getVersion(); + LidarDriverImpl(); ~LidarDriverImpl(); + bool init(const RSDriverParam& param); - void initDecoderOnly(const RSDriverParam& param); bool start(); void stop(); void regRecvCallback(const std::function)>& cb_put, const std::function(void)>& cb_get); void regRecvCallback(const std::function& callback); void regRecvCallback(const std::function& callback); - void regRecvCallback(const std::function& callback); void regExceptionCallback(const std::function& callback); bool decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg); void decodeDifopPkt(const PacketMsg& msg); bool getLidarTemperature(double& input_temperature); private: + void runCallBack(std::shared_ptr msg); void runCallBack(const ScanMsg& msg); void runCallBack(const PacketMsg& msg); void reportError(const Error& error); - void localCameraTriggerCallback(const CameraTrigger& msg); void msopCallback(std::shared_ptr msg); void difopCallback(std::shared_ptr msg); std::shared_ptr packetGet(size_t size); void packetPut(std::shared_ptr pkt); - std::shared_ptr getPointCloud(); void processMsop(); void processDifop(); void setPointCloudHeader(T_PointCloud& msg, int height); @@ -83,8 +87,10 @@ class LidarDriverImpl private: RSDriverParam driver_param_; +#if 0 std::function(void)> point_cloud_cb_get_; std::vector)>> point_cloud_cb_put_vec_; +#endif std::vector> excb_; std::vector> msop_pkt_cb_vec_; std::vector> difop_pkt_cb_vec_; @@ -92,7 +98,6 @@ class LidarDriverImpl std::shared_ptr> lidar_decoder_ptr_; std::shared_ptr point_cloud_; ScanMsg scan_ptr_; - std::vector> camera_trigger_cb_vec_; SyncQueue> free_pkt_queue_; SyncQueue> msop_pkt_queue_; SyncQueue> difop_pkt_queue_; @@ -108,6 +113,17 @@ class LidarDriverImpl uint32_t ndifop_count_; }; +template +inline std::string LidarDriverImpl::getVersion() +{ + std::stringstream stream; + stream << RSLIDAR_VERSION_MAJOR << "." + << RSLIDAR_VERSION_MINOR << "." + << RSLIDAR_VERSION_PATCH; + + return stream.str(); +} + template inline LidarDriverImpl::LidarDriverImpl() : init_flag_(false), start_flag_(false), difop_flag_(false), point_cloud_seq_(0), scan_seq_(0), ndifop_count_(0) @@ -131,8 +147,6 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) driver_param_ = param; lidar_decoder_ptr_ = DecoderFactory::createDecoder(driver_param_); - lidar_decoder_ptr_->regRecvCallback( - std::bind(&LidarDriverImpl::localCameraTriggerCallback, this, std::placeholders::_1)); input_ptr_ = InputFactory::createInput( driver_param_, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); @@ -154,21 +168,6 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) return false; } -template -inline void LidarDriverImpl::initDecoderOnly(const RSDriverParam& param) -{ - if (init_flag_) - { - return; - } - - driver_param_ = param; - lidar_decoder_ptr_ = DecoderFactory::createDecoder(driver_param_); - lidar_decoder_ptr_->regRecvCallback( - std::bind(&LidarDriverImpl::localCameraTriggerCallback, this, std::placeholders::_1)); - init_flag_ = true; -} - template inline bool LidarDriverImpl::start() { @@ -210,11 +209,13 @@ template inline void LidarDriverImpl::regRecvCallback(const std::function)>& cb_put, const std::function(void)>& cb_get) { +#if 0 point_cloud_cb_put_vec_.emplace_back(cb_put); if (cb_get != nullptr) { point_cloud_cb_get_ = cb_get; } +#endif } template @@ -229,79 +230,17 @@ inline void LidarDriverImpl::regRecvCallback(const std::function -inline void LidarDriverImpl::regRecvCallback(const std::function& callback) -{ - camera_trigger_cb_vec_.emplace_back(callback); -} - template inline void LidarDriverImpl::regExceptionCallback(const std::function& callback) { excb_.emplace_back(callback); } -template -inline bool LidarDriverImpl::decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg) -{ - if (driver_param_.wait_for_difop && !difop_flag_) - { - ndifop_count_++; - if (ndifop_count_ > 20) - { - reportError(Error(ERRCODE_NODIFOPRECV)); - ndifop_count_ = 0; - } - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - return false; - } - - std::vector pointcloud_one_frame; - pointcloud_one_frame.resize(scan_msg.packets.size()); - - int height = 1; - for (int i = 0; i < static_cast(scan_msg.packets.size()); i++) - { - typename T_PointCloud::VectorT pointcloud_one_packet; - - const PacketMsg& pkt = scan_msg.packets[i]; - RSDecoderResult ret = - lidar_decoder_ptr_->processMsopPkt(pkt.packet.data(), pkt.packet.size(), pointcloud_one_packet, height); - switch (ret) - { - case RSDecoderResult::DECODE_OK: - case RSDecoderResult::FRAME_SPLIT: - pointcloud_one_frame[i] = std::move(pointcloud_one_packet); - break; - case RSDecoderResult::WRONG_PKT_HEADER: - reportError(Error(ERRCODE_WRONGPKTHEADER)); - break; - case RSDecoderResult::PKT_NULL: - reportError(Error(ERRCODE_PKTNULL)); - break; - default: - break; - } - } - for (auto iter : pointcloud_one_frame) - { - point_cloud_msg.points.insert(point_cloud_msg.points.end(), iter.begin(), iter.end()); - } - setPointCloudHeader(point_cloud_msg, height); - point_cloud_msg.timestamp = scan_msg.timestamp; - if (point_cloud_msg.points.size() == 0) - { - reportError(Error(ERRCODE_ZEROPOINTS)); - return false; - } - return true; -} - template inline void LidarDriverImpl::decodeDifopPkt(const PacketMsg& pkt) { - lidar_decoder_ptr_->processDifopPkt(pkt.packet.data(), pkt.packet.size()); - difop_flag_ = true; +// lidar_decoder_ptr_->processDifopPkt(pkt.packet.data(), pkt.packet.size()); +// difop_flag_ = true; } template @@ -339,6 +278,7 @@ inline void LidarDriverImpl::runCallBack(const PacketMsg& msg) template inline void LidarDriverImpl::runCallBack(std::shared_ptr msg) { +#if 0 if (msg->seq != 0) { for (auto& it : point_cloud_cb_put_vec_) @@ -346,6 +286,7 @@ inline void LidarDriverImpl::runCallBack(std::shared_ptr @@ -357,15 +298,6 @@ inline void LidarDriverImpl::reportError(const Error& error) } } -template -inline void LidarDriverImpl::localCameraTriggerCallback(const CameraTrigger& msg) -{ - for (auto& it : camera_trigger_cb_vec_) - { - it(msg); - } -} - template inline std::shared_ptr LidarDriverImpl::packetGet(size_t size) { @@ -402,6 +334,7 @@ inline void LidarDriverImpl::difopCallback(std::shared_ptr difop_pkt_queue_.push(pkt); } +#if 0 template inline std::shared_ptr LidarDriverImpl::getPointCloud() { @@ -422,11 +355,13 @@ inline std::shared_ptr LidarDriverImpl::getPointClou std::this_thread::sleep_for(std::chrono::milliseconds(300)); }; } +#endif template inline void LidarDriverImpl::processMsop() { - point_cloud_ = getPointCloud(); +#if 0 + //point_cloud_ = getPointCloud(); while (!to_exit_msop_handle_) { @@ -486,7 +421,7 @@ inline void LidarDriverImpl::processMsop() scan_ptr_.packets.resize(0); #endif - point_cloud_ = getPointCloud(); + //point_cloud_ = getPointCloud(); } } else if (ret < 0) @@ -501,6 +436,7 @@ inline void LidarDriverImpl::processMsop() packetPut(pkt); } +#endif } template diff --git a/src/rs_driver/msg/packet.h b/src/rs_driver/msg/packet.h index 01e92d49..270497a2 100644 --- a/src/rs_driver/msg/packet.h +++ b/src/rs_driver/msg/packet.h @@ -31,7 +31,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include + +#include +#include namespace robosense { diff --git a/src/rs_driver/msg/packet_msg.h b/src/rs_driver/msg/packet_msg.h index a9ed4a22..0a1a674d 100644 --- a/src/rs_driver/msg/packet_msg.h +++ b/src/rs_driver/msg/packet_msg.h @@ -31,7 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include +#include namespace robosense { diff --git a/src/rs_driver/msg/scan_msg.h b/src/rs_driver/msg/scan_msg.h index fd48b521..15a1487b 100644 --- a/src/rs_driver/msg/scan_msg.h +++ b/src/rs_driver/msg/scan_msg.h @@ -31,8 +31,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include #include +#include + namespace robosense { namespace lidar diff --git a/src/rs_driver/utility/dbg.h b/src/rs_driver/utility/dbg.h index d8bb9b83..b480f530 100644 --- a/src/rs_driver/utility/dbg.h +++ b/src/rs_driver/utility/dbg.h @@ -31,7 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include +#include namespace robosense { diff --git a/src/rs_driver/utility/sync_queue.h b/src/rs_driver/utility/sync_queue.h index e8095766..d7647cb4 100644 --- a/src/rs_driver/utility/sync_queue.h +++ b/src/rs_driver/utility/sync_queue.h @@ -31,7 +31,11 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include + +#include +#include +#include + namespace robosense { namespace lidar diff --git a/src/rs_driver/utility/time.h b/src/rs_driver/utility/time.h index ffbb8778..116c00bc 100644 --- a/src/rs_driver/utility/time.h +++ b/src/rs_driver/utility/time.h @@ -31,7 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include +#include namespace robosense { namespace lidar diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt new file mode 100644 index 00000000..7c538ae6 --- /dev/null +++ b/test/CMakeLists.txt @@ -0,0 +1,16 @@ + +cmake_minimum_required(VERSION 3.5) + +project(rs_driver_test) + +find_package(GTest REQUIRED) +include_directories(${GTEST_INCLUDE_DIRS}) +include_directories(${DRIVER_INCLUDE_DIRS}) + +add_executable(rs_driver_test + rs_driver_test.cpp) + +target_link_libraries(rs_driver_test + ${GTEST_LIBRARIES} + ${EXTERNAL_LIBS}) + diff --git a/test/res/angle.csv b/test/res/angle.csv new file mode 100644 index 00000000..0c02c837 --- /dev/null +++ b/test/res/angle.csv @@ -0,0 +1,4 @@ +5,0.1 +2.5,-0.2 +0,0 +-2.5,-1 diff --git a/test/rs_driver_test.cpp b/test/rs_driver_test.cpp new file mode 100644 index 00000000..6493710e --- /dev/null +++ b/test/rs_driver_test.cpp @@ -0,0 +1,204 @@ + +#include + +#include + +using namespace robosense::lidar; + +TEST(TestParseTime, calcTimeUTC) +{ + RSTimestampUTC2 ts = + {{0x01, 0x02, 0x03, 0x04, 0x05, 0x06}, {0x11, 0x22, 0x33, 0x44}}; + + ASSERT_EQ(calcTimeUTCWithNs(&ts), 0x010203040506 * 1000000 + 0x11223344/1000); + ASSERT_EQ(calcTimeUTCWithUs(&ts), 0x010203040506 * 1000000 + 0x11223344); + ASSERT_EQ(calcTimeUTCWithMs(&ts), 0x010203040506 * 1000000 + 0x1122 * 1000 + 0x3344); +} + +TEST(TestParseTime, calcTimeYMD) +{ + uint8_t ts[] = {0x15, 0x0a, 0x01, 0x01, 0x02, 0x03, 0x11, 0x22, 0x33, 0x44}; + + ASSERT_EQ(calcTimeYMD((RSTimestampYMD*)&ts), 1633021327399124); +} + +TEST(TestParseTime, calcTimeHost) +{ + calcTimeHost(); +} + +TEST(TestParseTemp, calcTemp) +{ + { + uint8_t temp[] = {0x18, 0x01}; + ASSERT_EQ(calcTemp((RsTemp*)&temp), 35); + } + + { + uint8_t temp[] = {0x18, 0x81}; + ASSERT_EQ(calcTemp((RsTemp*)&temp), -35); + } +} + +TEST(TestScanBlock, ctor) +{ + ScanBlock blk(10, 20); + ASSERT_EQ(blk.start(), 10); + ASSERT_EQ(blk.end(), 20); + + ASSERT_FALSE(blk.in(5)); + ASSERT_TRUE(blk.in(10)); + ASSERT_TRUE(blk.in(15)); + ASSERT_FALSE(blk.in(20)); + ASSERT_FALSE(blk.in(25)); +} + +TEST(TestScanBlock, ctorCrossZero) +{ + ScanBlock blk(35000, 10); + ASSERT_EQ(blk.start(), 35000); + ASSERT_EQ(blk.end(), 10); + + ASSERT_FALSE(blk.in(34999)); + ASSERT_TRUE(blk.in(35000)); + ASSERT_TRUE(blk.in(0)); + ASSERT_FALSE(blk.in(10)); + ASSERT_FALSE(blk.in(15)); +} + +TEST(TestScanBlock, ctorBeyondRound) +{ + ScanBlock blk(36100, 36200); + ASSERT_EQ(blk.start(), 100); + ASSERT_EQ(blk.end(), 200); +} + +TEST(TestDistanceBlock, ctor) +{ + DistanceBlock blk(0.5, 200, 0.75, 150); + ASSERT_EQ(blk.min(), 0.75); + ASSERT_EQ(blk.max(), 150); + + ASSERT_FALSE(blk.in(0.45)); + ASSERT_TRUE(blk.in(0.75)); + ASSERT_TRUE(blk.in(0.8)); + ASSERT_TRUE(blk.in(150)); + ASSERT_FALSE(blk.in(150.5)); +} + +TEST(TestDistanceBlock, ctorNoUseBlock) +{ + DistanceBlock blk(0.5, 200, 0.0, 200.5); + ASSERT_EQ(blk.min(), 0.5); + ASSERT_EQ(blk.max(), 200); +} + +TEST(TestChanAngles, genUserChan) +{ + std::vector vert_angles; + std::vector user_chans; + + vert_angles.push_back(100); + vert_angles.push_back(0); + vert_angles.push_back(-100); + vert_angles.push_back(200); + + ChanAngles::genUserChan (vert_angles, user_chans); + ASSERT_EQ(user_chans.size(), 4); + ASSERT_EQ(user_chans[0], 2); + ASSERT_EQ(user_chans[1], 1); + ASSERT_EQ(user_chans[2], 0); + ASSERT_EQ(user_chans[3], 3); +} + +TEST(TestChanAngles, loadFromFile) +{ + std::vector vert_angles, horiz_angles; + + ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); + ASSERT_EQ(vert_angles[0], 500); + ASSERT_EQ(vert_angles[1], 250); + ASSERT_EQ(vert_angles[2], 0); + ASSERT_EQ(vert_angles[3], -250); + + ASSERT_EQ(horiz_angles[0], 10); + ASSERT_EQ(horiz_angles[1], -20); + ASSERT_EQ(horiz_angles[2], 0); + ASSERT_EQ(horiz_angles[3], -100); + + ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); +} + +TEST(TestChanAngles, memberLoadFromFile) +{ + ChanAngles angles; + + ASSERT_EQ(angles.loadFromFile ("../rs_driver/test/res/angle.csv"), 0); + ASSERT_EQ(angles.chanSize(), 4); + ASSERT_EQ(angles.toUserChan(0), 3); + ASSERT_EQ(angles.toUserChan(1), 2); + ASSERT_EQ(angles.toUserChan(2), 1); + ASSERT_EQ(angles.toUserChan(3), 0); +} + +TEST(TestChanAngles, loadFromDifop) +{ + uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, + 0x01, 0x03, 0x04, + 0x01, 0x05, 0x06, + 0x00, 0x07, 0x08}; + uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, + 0x01, 0x33, 0x44, + 0x00, 0x55, 0x66, + 0x01, 0x77, 0x88}; + + std::vector vert_angles, horiz_angles; + + ASSERT_EQ(ChanAngles::loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4, + vert_angles, + horiz_angles), 0); + + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); + ASSERT_EQ(vert_angles[0], 258); + ASSERT_EQ(vert_angles[1], -772); + ASSERT_EQ(vert_angles[2], -1286); + ASSERT_EQ(vert_angles[3], 1800); + + ASSERT_EQ(horiz_angles[0], 4386); + ASSERT_EQ(horiz_angles[1], -13124); + ASSERT_EQ(horiz_angles[2], 21862); + ASSERT_EQ(horiz_angles[3], -30600); + + ASSERT_EQ(ChanAngles::loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4, + vert_angles, + horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); +} + +TEST(TestTrigon, ctor) +{ + Trigon trigon; + ASSERT_EQ(trigon.cos(6000), 0.5); + ASSERT_EQ(trigon.sin(3000), 0.5); +#if 0 + trigon.print(); +#endif +} + +int main(int argc, char** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} From fbdb7852ed9ad0d5efb10a545cb14de1508a0595 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 25 Nov 2021 20:15:52 +0800 Subject: [PATCH 027/379] refac: refactory decoder_rs32 --- demo/demo_online.cpp | 2 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 108 +++++++++++++----- src/rs_driver/driver/decoder/decoder_base.hpp | 36 ++++-- .../driver/decoder/decoder_base_opt.hpp | 8 +- .../driver/decoder/decoder_factory.hpp | 4 + 5 files changed, 113 insertions(+), 45 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 7814e0e5..0cba51a8 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -91,7 +91,7 @@ int main(int argc, char* argv[]) param.print(); LidarDriver driver; - driver.regRecvCallback(pointCloudPutCallback, pointCloudGetCallback); ///< Register the point cloud callback function into the driver + driver.regRecvCallback(pointCloudPutCallback, nullptr/*pointCloudGetCallback*/); ///< Register the point cloud callback function into the driver driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver if (!driver.init(param)) ///< Call the init function and pass the parameter { diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 42287cf6..4f83fcd9 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -31,6 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #include + namespace robosense { namespace lidar @@ -93,18 +94,28 @@ class DecoderRS32 : public DecoderBase #endif explicit DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); + + ChanAngles chan_angles_; + DistanceBlock distance_block_; + ScanBlock scan_block_; + Trigon trigon_; }; template inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) + : DecoderBase(param, lidar_const_param), + distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance), + scan_block_(param.start_angle * 100, param.end_angle) + { #if 0 this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); this->beam_ring_table_.resize(this->lidar_const_param_.LASER_NUM); #endif + +#if 0 if (this->param_.max_distance > 200.0f) { this->param_.max_distance = 200.0f; @@ -113,6 +124,7 @@ inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, { this->param_.min_distance = 0.4f; } +#endif } #if 0 @@ -124,18 +136,20 @@ inline double DecoderRS32::getLidarTime(const uint8_t* pkt) #endif template -inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* pkt, size_t size) +inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* packet, size_t size) { uint8_t id[] = {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0}; + uint8_t block_id[] = {0xFF, 0xEE}; + static const size_t BLOCKS_PER_PKT = 12; - const RS32MsopPkt* mpkt_ptr = reinterpret_cast(pkt); + const RS32MsopPkt& pkt = *(const RS32MsopPkt*)(packet); - if (memcpy((uint8_t*)mpkt_ptr->header.id, id, sizeof(id)) != 0) + if (memcpy((uint8_t*)&(pkt.header.id), id, sizeof(id)) != 0) { return RSDecoderResult::WRONG_PKT_HEADER; } - this->current_temperature_ = calcTemp(&(mpkt_ptr->header.temp)); + this->current_temperature_ = calcTemp(&(pkt.header.temp)); #if 0 this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_raw); @@ -148,13 +162,25 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* #endif float azi_diff = 0; - for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) + for (size_t blk_idx = 0; blk_idx < BLOCKS_PER_PKT; blk_idx++) { - if (mpkt_ptr->blocks[blk_idx].id != this->lidar_const_param_.BLOCK_ID) + const RS32MsopBlock& block = pkt.blocks[blk_idx]; + + if (memcmp(&(block.id), block_id, sizeof(block_id))) + { + break; + } +#if 0 + if (pkt.blocks[blk_idx].id != this->lidar_const_param_.BLOCK_ID) { break; } - int cur_azi = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].azimuth); + int cur_azi = RS_SWAP_SHORT(pkt.blocks[blk_idx].azimuth); +#endif + + uint16_t cur_azi = ntohs(block.azimuth); + +#if 0 if (this->echo_mode_ == ECHO_DUAL) { if (blk_idx % 2 == 0) @@ -162,67 +188,87 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* if (blk_idx == 0) { azi_diff = static_cast( - (RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx + 2].azimuth) - cur_azi) % RS_ONE_ROUND); + (RS_ONE_ROUND + RS_SWAP_SHORT(pkt.blocks[blk_idx + 2].azimuth) - cur_azi) % RS_ONE_ROUND); } else { azi_diff = static_cast( - (RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx - 2].azimuth)) % RS_ONE_ROUND); + (RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(pkt.blocks[blk_idx - 2].azimuth)) % RS_ONE_ROUND); block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : (block_timestamp + this->time_duration_between_blocks_); } } } else +#endif { - if (blk_idx == 0) // 12 + if (blk_idx < (BLOCKS_PER_PKT - 1)) { - azi_diff = static_cast((RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx + 1].azimuth) - cur_azi) % + azi_diff = static_cast((RS_ONE_ROUND + ntohs(pkt.blocks[blk_idx + 1].azimuth) - cur_azi) % RS_ONE_ROUND); } else { - azi_diff = static_cast((RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx - 1].azimuth)) % + azi_diff = static_cast((RS_ONE_ROUND + cur_azi - ntohs(pkt.blocks[blk_idx - 1].azimuth)) % RS_ONE_ROUND); + } + + if (blk_idx > 0) + { block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : (block_timestamp + this->time_duration_between_blocks_); } } - azi_diff = (azi_diff > 100) ? this->azi_diff_between_block_theoretical_ : azi_diff; - for (int channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) + + azi_diff = (azi_diff > 100) ? this->azi_diff_between_block_theoretical_ : azi_diff; + + for (uint16_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) { - float azi_channel_ori = cur_azi + - azi_diff * this->lidar_const_param_.FIRING_FREQUENCY * - this->lidar_const_param_.DSR_TOFFSET * - static_cast(2 * (channel_idx % 16) + (channel_idx / 16)); + const RSChannel& channel = pkt.blocks[blk_idx].channels[channel_idx]; + + float distance = ntohs(channel.distance) * this->lidar_const_param_.DIS_RESOLUTION; + + float azi_channel_ori = cur_azi + + azi_diff * this->lidar_const_param_.FIRING_FREQUENCY * this->lidar_const_param_.DSR_TOFFSET * + static_cast(2 * (channel_idx % 16) + (channel_idx / 16)); #if 0 + int azi_channel_final = this->azimuthCalibration(azi_channel_ori, channel_idx); #else - int azi_channel_final = azi_channel_ori; + uint16_t azi_channel_final = + chan_angles_.horizAdjust(channel_idx, (int32_t)azi_channel_ori); #endif - float distance = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].channels[channel_idx].distance) * - this->lidar_const_param_.DIS_RESOLUTION; - - int angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; - int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; + uint16_t angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; + uint16_t angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; typename T_PointCloud::PointT point; bool pointValid = false; +#if 0 if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || (!this->angle_flag_ && ((azi_channel_final >= this->start_angle_) || (azi_channel_final <= this->end_angle_))))) +#endif + +#define SIN(angle) trigon_.sin(angle) +#define COS(angle) trigon_.cos(angle) + + if (distance_block_.in(distance) && scan_block_.in(azi_channel_final)) { + float x = distance * COS(angle_vert) * COS(azi_channel_final) + this->lidar_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(azi_channel_final) - this->lidar_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->lidar_const_param_.RZ; + +#if 0 + float x = distance * this->checkCosTable(angle_vert) * this->checkCosTable(azi_channel_final) + this->lidar_const_param_.RX * this->checkCosTable(angle_horiz); + float y = -distance * this->checkCosTable(angle_vert) * this->checkSinTable(azi_channel_final) - this->lidar_const_param_.RX * this->checkSinTable(angle_horiz); + float z = distance * this->checkSinTable(angle_vert) + this->lidar_const_param_.RZ; +#endif - float x = distance * this->checkCosTable(angle_vert) * this->checkCosTable(azi_channel_final) + - this->lidar_const_param_.RX * this->checkCosTable(angle_horiz); - float y = -distance * this->checkCosTable(angle_vert) * this->checkSinTable(azi_channel_final) - - this->lidar_const_param_.RX * this->checkSinTable(angle_horiz); - float z = distance * this->checkSinTable(angle_vert) + this->lidar_const_param_.RZ; - uint8_t intensity = mpkt_ptr->blocks[blk_idx].channels[channel_idx].intensity; + uint8_t intensity = channel.intensity; #if 0 this->transformPoint(x, y, z); #endif diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 37cfb938..adc962c4 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -59,8 +59,11 @@ namespace robosense namespace lidar { +#if 0 #define RS_SWAP_SHORT(x) ((((x)&0xFF) << 8) | (((x)&0xFF00) >> 8)) #define RS_SWAP_LONG(x) ((((x)&0xFF) << 24) | (((x)&0xFF00) << 8) | (((x)&0xFF0000) >> 8) | (((x)&0xFF000000) >> 24)) +#endif + #define RS_TO_RADS(x) ((x) * (M_PI) / 180) /*Packet Length*/ @@ -212,7 +215,7 @@ class DecoderBase RSEchoMode echo_mode_; - unsigned int pkts_per_frame_; + //unsigned int pkts_per_frame_; unsigned int pkt_count_; unsigned int trigger_index_; unsigned int prev_angle_diff_; @@ -228,7 +231,8 @@ class DecoderBase bool difop_flag_; float fov_time_jump_diff_; float time_duration_between_blocks_; - float azi_diff_between_block_theoretical_; + //float azi_diff_between_block_theoretical_; + uint16_t azi_diff_between_block_theoretical_; std::vector vert_angle_list_; std::vector hori_angle_list_; @@ -255,7 +259,7 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, , msop_pkt_len_(MECH_PKT_LEN) , difop_pkt_len_(MECH_PKT_LEN) , echo_mode_(ECHO_SINGLE) - , pkts_per_frame_(lidar_const_param.PKT_RATE / 10) + //, pkts_per_frame_(lidar_const_param.PKT_RATE / 10) , pkt_count_(0) , trigger_index_(0) , prev_angle_diff_(RS_ONE_ROUND) @@ -415,6 +419,9 @@ template template inline void DecoderBase::decodeDifopCommon(const uint8_t* pkt, const LidarType& type) { + static const uint16_t BLOCKS_PER_FRAME = 1800; + static const uint16_t BLOCKS_PER_PKT = 12; + const T_Difop* dpkt_ptr = reinterpret_cast(pkt); #if 0 @@ -428,19 +435,26 @@ inline void DecoderBase::decodeDifopCommon(const uint8_t* pkt, con this->rpm_ = 600; } - this->time_duration_between_blocks_ = - (60 / static_cast(this->rpm_)) / ((this->lidar_const_param_.PKT_RATE * 60 / this->rpm_) * this->lidar_const_param_.BLOCKS_PER_PKT); +#if 0 + this->time_duration_between_blocks_ = (60 / static_cast(this->rpm_)) / ((this->lidar_const_param_.PKT_RATE * 60 / this->rpm_) * this->lidar_const_param_.BLOCKS_PER_PKT); + this->time_duration_between_blocks_ = 1 / (this->lidar_const_param_.PKT_RATE * this->lidar_const_param_.BLOCKS_PER_PKT); +#endif + this->time_duration_between_blocks_ = 60 / (this->rpm * BLOCKS_PER_FRAME); int fov_start_angle = RS_SWAP_SHORT(dpkt_ptr->fov.start_angle); int fov_end_angle = RS_SWAP_SHORT(dpkt_ptr->fov.end_angle); + int fov_range = (fov_start_angle < fov_end_angle) ? (fov_end_angle - fov_start_angle) : (RS_ONE_ROUND - fov_start_angle + fov_end_angle); +#if 0 int blocks_per_round = (this->lidar_const_param_.PKT_RATE / (this->rpm_ / 60)) * this->lidar_const_param_.BLOCKS_PER_PKT; +#endif + + this->fov_time_jump_diff_ = this->time_duration_between_blocks_ * (fov_range / (RS_ONE_ROUND / BLOCKS_PER_FRAME)); - this->fov_time_jump_diff_ = - this->time_duration_between_blocks_ * (fov_range / (RS_ONE_ROUND / static_cast(blocks_per_round))); +#if 0 if (this->echo_mode_ == RSEchoMode::ECHO_DUAL) { this->pkts_per_frame_ = ceil(2 * this->lidar_const_param_.PKT_RATE * 60 / this->rpm_); @@ -449,10 +463,14 @@ inline void DecoderBase::decodeDifopCommon(const uint8_t* pkt, con { this->pkts_per_frame_ = ceil(this->lidar_const_param_.PKT_RATE * 60 / this->rpm_); } +#endif + this->azi_diff_between_block_theoretical_ = RS_ONE_ROUND / BLOCKS_PER_FRAME; + +#if 0 this->azi_diff_between_block_theoretical_ = - (RS_ONE_ROUND / this->lidar_const_param_.BLOCKS_PER_PKT) / - static_cast(this->pkts_per_frame_); ///< ((rpm/60)*360)/pkts_rate/blocks_per_pkt + (RS_ONE_ROUND / this->lidar_const_param_.BLOCKS_PER_PKT) / static_cast(this->pkts_per_frame_); ///< ((rpm/60)*360)/pkts_rate/blocks_per_pkt +#endif } #if 0 diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index cacc0c59..d31f143f 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -473,14 +473,14 @@ class ChanAngles return user_chans_[chan]; } - void horizAdjust(uint16_t chan, int32_t& horiz) + int32_t horizAdjust(uint16_t chan, int32_t horiz) { - horiz += horiz_angles_[chan]; + return (horiz + horiz_angles_[chan]); } - void vertAdjust(uint16_t chan, int32_t& vert) + int32_t vertAdjust(uint16_t chan, int32_t vert) { - vert += vert_angles_[chan]; + return (vert + vert_angles_[chan]); } void narrow () diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index f4628b88..28117705 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -140,14 +140,18 @@ inline const LidarConstantParameter DecoderFactory::getRS32Constan ret_param.BLOCK_ID = 0xEEFF; ret_param.PKT_RATE = 1500; ret_param.BLOCKS_PER_PKT = 12; + ret_param.CHANNELS_PER_BLOCK = 32; ret_param.LASER_NUM = 32; + ret_param.DSR_TOFFSET = 1.44; ret_param.FIRING_FREQUENCY = 0.018; ret_param.DIS_RESOLUTION = 0.005; + ret_param.RX = 0.03997; ret_param.RY = -0.01087; ret_param.RZ = 0; + return ret_param; } From 99b22e75023374a82d1692c4cf2af1468fd2561f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 26 Nov 2021 12:05:29 +0800 Subject: [PATCH 028/379] refac: refac decoder --- src/rs_driver/driver/decoder/decoder_RS32.hpp | 128 +++----- src/rs_driver/driver/decoder/decoder_base.hpp | 284 ++---------------- .../driver/decoder/decoder_base_opt.hpp | 20 +- .../driver/decoder/decoder_factory.hpp | 1 + 4 files changed, 84 insertions(+), 349 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 4f83fcd9..69fe06da 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -89,52 +89,17 @@ class DecoderRS32 : public DecoderBase virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRS32() = default; -#if 0 - virtual double getLidarTime(const uint8_t* pkt); -#endif - explicit DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - ChanAngles chan_angles_; - DistanceBlock distance_block_; - ScanBlock scan_block_; - Trigon trigon_; }; template inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param), - distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance), - scan_block_(param.start_angle * 100, param.end_angle) - + : DecoderBase(param, lidar_const_param) { -#if 0 - this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->beam_ring_table_.resize(this->lidar_const_param_.LASER_NUM); -#endif - -#if 0 - if (this->param_.max_distance > 200.0f) - { - this->param_.max_distance = 200.0f; - } - if (this->param_.min_distance < 0.4f || this->param_.min_distance > this->param_.max_distance) - { - this->param_.min_distance = 0.4f; - } -#endif } -#if 0 -template -inline double DecoderRS32::getLidarTime(const uint8_t* pkt) -{ - return this->template calculateTimeYMD(pkt); -} -#endif - template inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* packet, size_t size) { @@ -151,15 +116,16 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* this->current_temperature_ = calcTemp(&(pkt.header.temp)); -#if 0 - this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_raw); -#endif - -#if 0 - double block_timestamp = this->get_point_time_func_(pkt); -#else double block_timestamp = 0; -#endif + //uint64_t ts = 0; + if (this->param_.use_lidar_clock) + { + block_timestamp = calcTimeYMD(&pkt.header.timestamp); + } + else + { + block_timestamp = calcTimeHost(); + } float azi_diff = 0; for (size_t blk_idx = 0; blk_idx < BLOCKS_PER_PKT; blk_idx++) @@ -170,13 +136,6 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* { break; } -#if 0 - if (pkt.blocks[blk_idx].id != this->lidar_const_param_.BLOCK_ID) - { - break; - } - int cur_azi = RS_SWAP_SHORT(pkt.blocks[blk_idx].azimuth); -#endif uint16_t cur_azi = ntohs(block.azimuth); @@ -224,54 +183,37 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* for (uint16_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) { - const RSChannel& channel = pkt.blocks[blk_idx].channels[channel_idx]; + static const float delta_ts[] = { 0.00, 2.88, 5.76, 8.64, 11.52, 14.40, 17.28, 20.16, + 23.04, 25.92, 28.80, 31.68, 34.56, 37.44, 40.32, 44.64, + 1.44, 4.32, 7.20, 10.08, 12.96, 15.84, 18.72, 21.60, + 24.48, 27.36, 30.24, 33.12, 36.00, 38.88, 41.76, 46.08}; + static const float delta_block = 55.52; - float distance = ntohs(channel.distance) * this->lidar_const_param_.DIS_RESOLUTION; + const RSChannel& channel = pkt.blocks[blk_idx].channels[channel_idx]; - float azi_channel_ori = cur_azi + - azi_diff * this->lidar_const_param_.FIRING_FREQUENCY * this->lidar_const_param_.DSR_TOFFSET * - static_cast(2 * (channel_idx % 16) + (channel_idx / 16)); + double chan_ts = block_timestamp + delta_ts[channel_idx]; + float azi_channel_ori = cur_azi + azi_diff * delta_ts[channel_idx] / delta_block; -#if 0 + float distance = ntohs(channel.distance) * this->lidar_const_param_.DIS_RESOLUTION; - int azi_channel_final = this->azimuthCalibration(azi_channel_ori, channel_idx); -#else - uint16_t azi_channel_final = - chan_angles_.horizAdjust(channel_idx, (int32_t)azi_channel_ori); -#endif + uint16_t azi_channel_final = this->chan_angles_.horizAdjust(channel_idx, (int32_t)azi_channel_ori); - uint16_t angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; - uint16_t angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; + uint16_t angle_horiz = azi_channel_ori; + uint16_t angle_vert = this->chan_angles_.vertAdjust(channel_idx); typename T_PointCloud::PointT point; bool pointValid = false; -#if 0 - if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && - ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || - (!this->angle_flag_ && - ((azi_channel_final >= this->start_angle_) || (azi_channel_final <= this->end_angle_))))) -#endif - -#define SIN(angle) trigon_.sin(angle) -#define COS(angle) trigon_.cos(angle) +#define SIN(angle) this->trigon_.sin(angle) +#define COS(angle) this->trigon_.cos(angle) - if (distance_block_.in(distance) && scan_block_.in(azi_channel_final)) + if (this->distance_block_.in(distance) && this->scan_block_.in(azi_channel_final)) { float x = distance * COS(angle_vert) * COS(azi_channel_final) + this->lidar_const_param_.RX * COS(angle_horiz); float y = -distance * COS(angle_vert) * SIN(azi_channel_final) - this->lidar_const_param_.RX * SIN(angle_horiz); float z = distance * SIN(angle_vert) + this->lidar_const_param_.RZ; - -#if 0 - float x = distance * this->checkCosTable(angle_vert) * this->checkCosTable(azi_channel_final) + this->lidar_const_param_.RX * this->checkCosTable(angle_horiz); - float y = -distance * this->checkCosTable(angle_vert) * this->checkSinTable(azi_channel_final) - this->lidar_const_param_.RX * this->checkSinTable(angle_horiz); - float z = distance * this->checkSinTable(angle_vert) + this->lidar_const_param_.RZ; -#endif - uint8_t intensity = channel.intensity; -#if 0 - this->transformPoint(x, y, z); -#endif + setX(point, x); setY(point, y); setZ(point, z); @@ -290,7 +232,7 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* if (pointValid) { setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, block_timestamp); + setTimestamp(point, chan_ts); //vec.emplace_back(std::move(point)); } } @@ -299,22 +241,24 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* } template -inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* pkt, size_t size) +inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* packet, size_t size) { - const RS32DifopPkt* dpkt_ptr = reinterpret_cast(pkt); + uint8_t id[] = {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55}; + + const RS32DifopPkt& pkt = *(const RS32DifopPkt*)(packet); - if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) + if (memcmp(id, &(pkt.id), sizeof(id)) != 0) { return RSDecoderResult::WRONG_PKT_HEADER; } -#if 0 - this->template decodeDifopCommon(pkt, LidarType::RS32); + this->template decodeDifopCommon(pkt); + if (!this->difop_flag_) { - this->template decodeDifopCalibration(pkt, LidarType::RS32); + this->chan_angles_.loadFromDifop(pkt.ver_angle_cali, pkt.hori_angle_cali, 32); } -#endif + return RSDecoderResult::DECODE_OK; } diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index adc962c4..51b80e47 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -59,11 +59,6 @@ namespace robosense namespace lidar { -#if 0 -#define RS_SWAP_SHORT(x) ((((x)&0xFF) << 8) | (((x)&0xFF00) >> 8)) -#define RS_SWAP_LONG(x) ((((x)&0xFF) << 24) | (((x)&0xFF00) << 8) | (((x)&0xFF0000) >> 8) | (((x)&0xFF000000) >> 24)) -#endif - #define RS_TO_RADS(x) ((x) * (M_PI) / 180) /*Packet Length*/ @@ -105,11 +100,6 @@ class DecoderBase virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size) = 0; - -#if 0 - virtual double getLidarTime(const uint8_t* pkt) = 0; -#endif - virtual ~DecoderBase() = default; uint16_t height() @@ -160,29 +150,12 @@ class DecoderBase protected: -#if 0 - int azimuthCalibration(const float& azimuth, const int& channel); -#endif - #if 0 RSEchoMode getEchoMode(const LidarType& type, const uint8_t& return_mode); #endif -#if 0 - template - double calculateTimeUTC(const uint8_t* pkt, const LidarType& type); - template - double calculateTimeYMD(const uint8_t* pkt); -#endif - template - void decodeDifopCommon(const uint8_t* pkt, const LidarType& type); - -#if 0 - template - void decodeDifopCalibration(const uint8_t* pkt, const LidarType& type); - void sortBeamTable(); -#endif + void decodeDifopCommon(const T_Difop& pkt); #if 0 void transformPoint(float& x, float& y, float& z); @@ -191,10 +164,6 @@ class DecoderBase float checkCosTable(const int& angle); float checkSinTable(const int& angle); -#if 0 - std::vector initTrigonometricLookupTable(const std::function& func); -#endif - private: DecoderBase(const DecoderBase&) = delete; DecoderBase& operator=(const DecoderBase&) = delete; @@ -238,12 +207,14 @@ class DecoderBase std::vector hori_angle_list_; std::vector beam_ring_table_; -#if 0 - std::function get_point_time_func_; -#endif int lidar_alph0_; // atan2(Ry, Rx) * 180 / M_PI * 100 float lidar_Rxy_; // sqrt(Rx*Rx + Ry*Ry) + ChanAngles chan_angles_; + DistanceBlock distance_block_; + ScanBlock scan_block_; + Trigon trigon_; + private: std::vector cos_lookup_table_; std::vector sin_lookup_table_; @@ -274,6 +245,8 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, , fov_time_jump_diff_(0) , time_duration_between_blocks_(0) , azi_diff_between_block_theoretical_(20) + , distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance) + , scan_block_(param.start_angle * 100, param.end_angle) { if (cut_angle_ > RS_ONE_ROUND) { @@ -293,57 +266,12 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, this->angle_flag_ = false; } -#if 0 - // even though T_Point does not have timestamp, it gives the timestamp - /* Point time function*/ - // typedef typename T_PointCloud::PointT T_Point; - // if (RS_HAS_MEMBER(T_Point, timestamp)) ///< return the timestamp of the first block in one packet - // { - if (this->param_.use_lidar_clock) - { - get_point_time_func_ = [this](const uint8_t* pkt) { return getLidarTime(pkt); }; - } - else - { - get_point_time_func_ = [this](const uint8_t* pkt) { - double ret_time = getTime() - (this->lidar_const_param_.BLOCKS_PER_PKT - 1) * this->time_duration_between_blocks_; - return ret_time; - }; - } -// } -// else -// { -// get_point_time_func_ = [this](const uint8_t* pkt) { return 0; }; -// } - - /* Cos & Sin look-up table*/ - cos_lookup_table_ = initTrigonometricLookupTable([](const double rad) -> double { return std::cos(rad); }); - sin_lookup_table_ = initTrigonometricLookupTable([](const double rad) -> double { return std::sin(rad); }); -#endif - - /* Calulate the lidar_alph0 and lidar_Rxy */ lidar_alph0_ = std::atan2(lidar_const_param_.RY, lidar_const_param_.RX) * 180 / M_PI * 100; lidar_Rxy_ = std::sqrt(lidar_const_param_.RX * lidar_const_param_.RX + lidar_const_param_.RY * lidar_const_param_.RY); } #if 0 -template -inline RSDecoderResult DecoderBase::processDifopPkt(const uint8_t* pkt, size_t size) -{ - if (pkt == NULL) - { - return PKT_NULL; - } - - if (size != this->difop_pkt_len_) - { - return WRONG_PKT_LENGTH; - } - - return decodeDifopPkt(pkt); -} - template inline RSDecoderResult DecoderBase::processMsopPkt( const uint8_t* pkt, size_t size) @@ -407,163 +335,47 @@ inline void DecoderBase::loadAngleFile(const std::string& angle_pa { } -#if 0 -template -inline int DecoderBase::azimuthCalibration(const float& azimuth, const int& channel) -{ - return (static_cast(azimuth) + this->hori_angle_list_[channel] + RS_ONE_ROUND) % RS_ONE_ROUND; -} -#endif - template template -inline void DecoderBase::decodeDifopCommon(const uint8_t* pkt, const LidarType& type) +inline void DecoderBase::decodeDifopCommon(const T_Difop& pkt) { - static const uint16_t BLOCKS_PER_FRAME = 1800; - static const uint16_t BLOCKS_PER_PKT = 12; - - const T_Difop* dpkt_ptr = reinterpret_cast(pkt); - -#if 0 - this->echo_mode_ = this->getEchoMode(type, dpkt_ptr->return_mode); -#endif + // return mode + switch (pkt.return_mode) + { + case 0x00: + this->echo_mode_ = RSEchoMode::ECHO_DUAL; + default: + this->echo_mode_ = RSEchoMode::ECHO_SINGLE; + } - this->rpm_ = RS_SWAP_SHORT(dpkt_ptr->rpm); + // rpm + this->rpm_ = ntohs(pkt.rpm); if (this->rpm_ == 0) { RS_WARNING << "LiDAR RPM is 0" << RS_REND; this->rpm_ = 600; } -#if 0 - this->time_duration_between_blocks_ = (60 / static_cast(this->rpm_)) / ((this->lidar_const_param_.PKT_RATE * 60 / this->rpm_) * this->lidar_const_param_.BLOCKS_PER_PKT); - this->time_duration_between_blocks_ = 1 / (this->lidar_const_param_.PKT_RATE * this->lidar_const_param_.BLOCKS_PER_PKT); -#endif - this->time_duration_between_blocks_ = 60 / (this->rpm * BLOCKS_PER_FRAME); - - int fov_start_angle = RS_SWAP_SHORT(dpkt_ptr->fov.start_angle); - int fov_end_angle = RS_SWAP_SHORT(dpkt_ptr->fov.end_angle); + // block duration - azimuth + this->azi_diff_between_block_theoretical_ = + RS_ONE_ROUND / this->lidar_const_param_.BLOCKS_PER_FRAME; - int fov_range = (fov_start_angle < fov_end_angle) ? (fov_end_angle - fov_start_angle) : - (RS_ONE_ROUND - fov_start_angle + fov_end_angle); -#if 0 - int blocks_per_round = - (this->lidar_const_param_.PKT_RATE / (this->rpm_ / 60)) * this->lidar_const_param_.BLOCKS_PER_PKT; -#endif + // block duration - timestamp + this->time_duration_between_blocks_ = + 60 / (this->rpm_ * this->lidar_const_param_.BLOCKS_PER_FRAME); - this->fov_time_jump_diff_ = this->time_duration_between_blocks_ * (fov_range / (RS_ONE_ROUND / BLOCKS_PER_FRAME)); + // blind block duration + int fov_start_angle = ntohs(pkt.fov.start_angle); + int fov_end_angle = ntohs(pkt.fov.end_angle); + int fov_range = (fov_start_angle < fov_end_angle) ? (fov_end_angle - fov_start_angle) : + (RS_ONE_ROUND - fov_start_angle + fov_end_angle); -#if 0 - if (this->echo_mode_ == RSEchoMode::ECHO_DUAL) - { - this->pkts_per_frame_ = ceil(2 * this->lidar_const_param_.PKT_RATE * 60 / this->rpm_); - } - else - { - this->pkts_per_frame_ = ceil(this->lidar_const_param_.PKT_RATE * 60 / this->rpm_); - } -#endif - - this->azi_diff_between_block_theoretical_ = RS_ONE_ROUND / BLOCKS_PER_FRAME; - -#if 0 - this->azi_diff_between_block_theoretical_ = - (RS_ONE_ROUND / this->lidar_const_param_.BLOCKS_PER_PKT) / static_cast(this->pkts_per_frame_); ///< ((rpm/60)*360)/pkts_rate/blocks_per_pkt -#endif -} - -#if 0 -template -template -inline void DecoderBase::decodeDifopCalibration(const uint8_t* pkt, const LidarType& type) -{ - const T_Difop* dpkt_ptr = reinterpret_cast(pkt); - - const uint8_t* p_ver_cali = reinterpret_cast(dpkt_ptr->ver_angle_cali); - - if ((p_ver_cali[0] == 0x00 || p_ver_cali[0] == 0xFF) && - (p_ver_cali[1] == 0x00 || p_ver_cali[1] == 0xFF) && - (p_ver_cali[2] == 0x00 || p_ver_cali[2] == 0xFF) && - (p_ver_cali[3] == 0x00 || p_ver_cali[3] == 0xFF)) - { - return; - } - - int neg = 1; - for (size_t i = 0; i < this->lidar_const_param_.LASER_NUM; i++) - { - /* vert angle calibration data */ - neg = static_cast(dpkt_ptr->ver_angle_cali[i].sign) == 0 ? 1 : -1; - this->vert_angle_list_[i] = static_cast(RS_SWAP_SHORT(dpkt_ptr->ver_angle_cali[i].value)) * neg; - - /* horizon angle calibration data */ - neg = static_cast(dpkt_ptr->hori_angle_cali[i].sign) == 0 ? 1 : -1; - this->hori_angle_list_[i] = static_cast(RS_SWAP_SHORT(dpkt_ptr->hori_angle_cali[i].value)) * neg; - - if (type == LidarType::RS32) - { - this->vert_angle_list_[i] *= 0.1f; - this->hori_angle_list_[i] *= 0.1f; - } - } - - this->sortBeamTable(); - - this->difop_flag_ = true; + this->fov_time_jump_diff_ = this->time_duration_between_blocks_ * + (fov_range / (RS_ONE_ROUND / this->lidar_const_param_.BLOCKS_PER_FRAME)); } -#endif #if 0 -template -template -inline double DecoderBase::calculateTimeUTC(const uint8_t* pkt, const LidarType& type) -{ - const T_Msop* mpkt_ptr = reinterpret_cast(pkt); - union u_ts - { - uint8_t data[8]; - uint64_t ts; - } timestamp; - timestamp.data[7] = 0; - timestamp.data[6] = 0; - timestamp.data[5] = mpkt_ptr->header.timestamp.sec[0]; - timestamp.data[4] = mpkt_ptr->header.timestamp.sec[1]; - timestamp.data[3] = mpkt_ptr->header.timestamp.sec[2]; - timestamp.data[2] = mpkt_ptr->header.timestamp.sec[3]; - timestamp.data[1] = mpkt_ptr->header.timestamp.sec[4]; - timestamp.data[0] = mpkt_ptr->header.timestamp.sec[5]; - - if ((type == LidarType::RS80 || type == LidarType::RS128) && this->protocol_ver_ == PROTOCOL_VER_0) - { - return static_cast(timestamp.ts) + - (static_cast(RS_SWAP_LONG(mpkt_ptr->header.timestamp.us))) / NANO; - } - - return static_cast(timestamp.ts) + (static_cast(RS_SWAP_LONG(mpkt_ptr->header.timestamp.us))) / MICRO; -} - -template -template -inline double DecoderBase::calculateTimeYMD(const uint8_t* pkt) -{ -#ifdef _MSC_VER - long timezone = 0; - _get_timezone(&timezone); -#endif - const T_Msop* mpkt_ptr = reinterpret_cast(pkt); - std::tm stm; - memset(&stm, 0, sizeof(stm)); - stm.tm_year = mpkt_ptr->header.timestamp.year + 100; - stm.tm_mon = mpkt_ptr->header.timestamp.month - 1; - stm.tm_mday = mpkt_ptr->header.timestamp.day; - stm.tm_hour = mpkt_ptr->header.timestamp.hour; - stm.tm_min = mpkt_ptr->header.timestamp.minute; - stm.tm_sec = mpkt_ptr->header.timestamp.second; - return std::mktime(&stm) + static_cast(RS_SWAP_SHORT(mpkt_ptr->header.timestamp.ms)) / 1000.0 + - static_cast(RS_SWAP_SHORT(mpkt_ptr->header.timestamp.us)) / 1000000.0 - static_cast(timezone); -} - template inline void DecoderBase::transformPoint(float& x, float& y, float& z) { @@ -583,22 +395,6 @@ inline void DecoderBase::transformPoint(float& x, float& y, float& } #endif -#if 0 -template -inline void DecoderBase::sortBeamTable() -{ - std::vector sorted_idx(this->lidar_const_param_.LASER_NUM); - std::iota(sorted_idx.begin(), sorted_idx.end(), 0); - std::sort(sorted_idx.begin(), sorted_idx.end(), [this](std::size_t i1, std::size_t i2) -> bool { - return this->vert_angle_list_[i1] < this->vert_angle_list_[i2]; - }); - for (size_t i = 0; i < this->lidar_const_param_.LASER_NUM; i++) - { - this->beam_ring_table_[sorted_idx[i]] = i; - } -} -#endif - #if 0 template inline RSEchoMode DecoderBase::getEchoMode(const LidarType& type, const uint8_t& return_mode) @@ -655,21 +451,5 @@ inline float DecoderBase::checkSinTable(const int& angle) return sin_lookup_table_[angle + RS_ONE_ROUND]; } -#if 0 -template -inline std::vector -DecoderBase::initTrigonometricLookupTable(const std::function& func) -{ - std::vector temp_table = std::vector(2 * RS_ONE_ROUND, 0.0); - - for (int i = 0; i < 2 * RS_ONE_ROUND; i++) - { - const double rad = RS_TO_RADS(static_cast(i - RS_ONE_ROUND) * RS_ANGLE_RESOLUTION); - temp_table[i] = (float)func(rad); - } - return temp_table; -} -#endif - } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index d31f143f..58516d47 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -51,16 +51,26 @@ namespace lidar #pragma pack(push, 1) typedef struct { + // identity uint64_t MSOP_ID; uint64_t DIFOP_ID; uint64_t BLOCK_ID; - uint32_t PKT_RATE; + + // duration + uint32_t PKT_RATE; // to be deleted uint16_t BLOCKS_PER_PKT; + uint16_t BLOCKS_PER_FRAME; uint16_t CHANNELS_PER_BLOCK; uint16_t LASER_NUM; - float DSR_TOFFSET; - float FIRING_FREQUENCY; + + // firing + float DSR_TOFFSET; // to be deleted + float FIRING_FREQUENCY; // to be deleted + + // distance float DIS_RESOLUTION; + + // lens center float RX; float RY; float RZ; @@ -478,9 +488,9 @@ class ChanAngles return (horiz + horiz_angles_[chan]); } - int32_t vertAdjust(uint16_t chan, int32_t vert) + int32_t vertAdjust(uint16_t chan) { - return (vert + vert_angles_[chan]); + return vert_angles_[chan]; } void narrow () diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 28117705..10bf4593 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -238,6 +238,7 @@ inline const LidarConstantParameter DecoderFactory::getRSHELIOSCon ret_param.BLOCK_ID = 0xEEFF; ret_param.PKT_RATE = 1500; ret_param.BLOCKS_PER_PKT = 12; + ret_param.BLOCKS_PER_FRAME = 1800; ret_param.CHANNELS_PER_BLOCK = 32; ret_param.LASER_NUM = 32; ret_param.DSR_TOFFSET = 1.0; From f8673b4a3737ad4037bb1b8944b68933fda1709c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 26 Nov 2021 17:16:03 +0800 Subject: [PATCH 029/379] refac: refac decoder --- src/rs_driver/driver/decoder/decoder_RS32.hpp | 57 ++-- src/rs_driver/driver/decoder/decoder_base.hpp | 287 +++++++----------- .../driver/decoder/decoder_base_opt.hpp | 2 + src/rs_driver/driver/driver_param.h | 5 +- src/rs_driver/driver/lidar_driver_impl.hpp | 13 +- src/rs_driver/msg/scan_msg.h | 2 +- 6 files changed, 155 insertions(+), 211 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 69fe06da..c1dd2b9b 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -85,8 +85,8 @@ class DecoderRS32 : public DecoderBase { public: - virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size); virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size); + virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRS32() = default; explicit DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); @@ -100,6 +100,28 @@ inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, { } +template +inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* packet, size_t size) +{ + uint8_t id[] = {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55}; + + const RS32DifopPkt& pkt = *(const RS32DifopPkt*)(packet); + + if (memcmp(id, &(pkt.id), sizeof(id)) != 0) + { + return RSDecoderResult::WRONG_PKT_HEADER; + } + + this->template decodeDifopCommon(pkt); + + if (!this->difop_flag_) + { + this->chan_angles_.loadFromDifop(pkt.ver_angle_cali, pkt.hori_angle_cali, 32); + } + + return RSDecoderResult::DECODE_OK; +} + template inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* packet, size_t size) { @@ -154,7 +176,7 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* azi_diff = static_cast( (RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(pkt.blocks[blk_idx - 2].azimuth)) % RS_ONE_ROUND); block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->time_duration_between_blocks_); + (block_timestamp + this->block_duration_); } } } @@ -175,7 +197,7 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* if (blk_idx > 0) { block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->time_duration_between_blocks_); + (block_timestamp + this->block_duration_); } } @@ -191,7 +213,7 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* const RSChannel& channel = pkt.blocks[blk_idx].channels[channel_idx]; - double chan_ts = block_timestamp + delta_ts[channel_idx]; + this->chan_ts_ = block_timestamp + delta_ts[channel_idx]; float azi_channel_ori = cur_azi + azi_diff * delta_ts[channel_idx] / delta_block; float distance = ntohs(channel.distance) * this->lidar_const_param_.DIS_RESOLUTION; @@ -231,32 +253,13 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* if (pointValid) { - setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, chan_ts); - //vec.emplace_back(std::move(point)); + setRing(point, this->chan_angles_.toUserChan(channel_idx)); + setTimestamp(point, this->chan_ts_); + this->point_cloud_->points.emplace_back(point); } } - } - return RSDecoderResult::DECODE_OK; -} - -template -inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* packet, size_t size) -{ - uint8_t id[] = {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55}; - - const RS32DifopPkt& pkt = *(const RS32DifopPkt*)(packet); - - if (memcmp(id, &(pkt.id), sizeof(id)) != 0) - { - return RSDecoderResult::WRONG_PKT_HEADER; - } - this->template decodeDifopCommon(pkt); - - if (!this->difop_flag_) - { - this->chan_angles_.loadFromDifop(pkt.ver_angle_cali, pkt.hori_angle_cali, 32); + this->toSplit(); } return RSDecoderResult::DECODE_OK; diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 51b80e47..49f48d0a 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -59,14 +59,10 @@ namespace robosense namespace lidar { -#define RS_TO_RADS(x) ((x) * (M_PI) / 180) - /*Packet Length*/ const size_t MECH_PKT_LEN = 1248; - const size_t MEMS_MSOP_LEN = 1210; const size_t MEMS_DIFOP_LEN = 256; - const size_t ROCK_MSOP_LEN = 1236; constexpr float RS_ANGLE_RESOLUTION = 0.01; @@ -98,19 +94,19 @@ class DecoderBase { public: - virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size) = 0; + virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual ~DecoderBase() = default; - uint16_t height() - { - return height_; - } + explicit DecoderBase(const RSDecoderParam& param, + const LidarConstantParameter& lidar_const_param); + + void toSplit(); void regRecvCallback(const std::function)>& cb_put, const std::function(void)>& cb_get) { - point_cloud_cb_put_vec_.emplace_back(cb_put); + point_cloud_cb_put_ = cb_put; if (cb_get != nullptr) { point_cloud_cb_get_ = cb_get; @@ -139,14 +135,19 @@ class DecoderBase }; } + uint16_t height() + { + return height_; + } + double getLidarTemperature() { return current_temperature_; } - explicit DecoderBase(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - - void loadAngleFile(const std::string& angle_path); + void loadAngleFile(const std::string& angle_path) + { + } protected: @@ -157,67 +158,41 @@ class DecoderBase template void decodeDifopCommon(const T_Difop& pkt); -#if 0 - void transformPoint(float& x, float& y, float& z); -#endif - - float checkCosTable(const int& angle); - float checkSinTable(const int& angle); - -private: - DecoderBase(const DecoderBase&) = delete; - DecoderBase& operator=(const DecoderBase&) = delete; - protected: - std::function(void)> point_cloud_cb_get_; - std::vector)>> point_cloud_cb_put_vec_; - std::shared_ptr point_cloud_; - const LidarConstantParameter lidar_const_param_; RSDecoderParam param_; - double current_temperature_; uint16_t height_; - uint32_t msop_pkt_len_; uint32_t difop_pkt_len_; - RSEchoMode echo_mode_; + Trigon trigon_; + DistanceBlock distance_block_; + ChanAngles chan_angles_; + ScanBlock scan_block_; + int split_angle_; + float block_duration_; + uint16_t azi_diff_between_block_theoretical_; + float fov_time_jump_diff_; + uint32_t pkts_per_frame_; - //unsigned int pkts_per_frame_; - unsigned int pkt_count_; - unsigned int trigger_index_; - unsigned int prev_angle_diff_; - unsigned int rpm_; unsigned int protocol_ver_; + unsigned int rpm_; + RSEchoMode echo_mode_; + double current_temperature_; - int start_angle_; - int end_angle_; - bool angle_flag_; - - int cut_angle_; - int last_azimuth_; bool difop_flag_; - float fov_time_jump_diff_; - float time_duration_between_blocks_; - //float azi_diff_between_block_theoretical_; - uint16_t azi_diff_between_block_theoretical_; - - std::vector vert_angle_list_; - std::vector hori_angle_list_; - std::vector beam_ring_table_; + int last_azimuth_; + unsigned int pkt_count_; + double chan_ts_; int lidar_alph0_; // atan2(Ry, Rx) * 180 / M_PI * 100 float lidar_Rxy_; // sqrt(Rx*Rx + Ry*Ry) - ChanAngles chan_angles_; - DistanceBlock distance_block_; - ScanBlock scan_block_; - Trigon trigon_; - -private: - std::vector cos_lookup_table_; - std::vector sin_lookup_table_; + std::function(void)> point_cloud_cb_get_; + std::function)> point_cloud_cb_put_; + std::shared_ptr point_cloud_; + uint32_t point_cloud_seq_; }; template @@ -225,45 +200,28 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) : lidar_const_param_(lidar_const_param) , param_(param) - , current_temperature_(0) , height_(0) , msop_pkt_len_(MECH_PKT_LEN) , difop_pkt_len_(MECH_PKT_LEN) - , echo_mode_(ECHO_SINGLE) - //, pkts_per_frame_(lidar_const_param.PKT_RATE / 10) - , pkt_count_(0) - , trigger_index_(0) - , prev_angle_diff_(RS_ONE_ROUND) - , rpm_(600) + , distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance) + , scan_block_(param.start_angle * 100, param.end_angle * 100) + , split_angle_(param.cut_angle * 100) + , block_duration_(0) + , azi_diff_between_block_theoretical_(20) + , fov_time_jump_diff_(0) + , pkts_per_frame_(0) , protocol_ver_(0) - , start_angle_(param.start_angle * 100) - , end_angle_(param.end_angle * 100) - , angle_flag_(true) - , cut_angle_(param.cut_angle * 100) - , last_azimuth_(-36001) + , rpm_(600) + , echo_mode_(ECHO_SINGLE) + , current_temperature_(0) , difop_flag_(false) - , fov_time_jump_diff_(0) - , time_duration_between_blocks_(0) - , azi_diff_between_block_theoretical_(20) - , distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance) - , scan_block_(param.start_angle * 100, param.end_angle) + , last_azimuth_(-36001) + , pkt_count_(0) + , point_cloud_seq_(0) { - if (cut_angle_ > RS_ONE_ROUND) - { - cut_angle_ = 0; - } - - if (this->start_angle_ > RS_ONE_ROUND || this->start_angle_ < 0 || - this->end_angle_ > RS_ONE_ROUND || this->end_angle_ < 0) + if (split_angle_ > RS_ONE_ROUND) { - RS_WARNING << "start_angle & end_angle should be in range 0~360° " << RS_REND; - this->start_angle_ = 0; - this->end_angle_ = RS_ONE_ROUND; - } - - if (this->start_angle_ > this->end_angle_) - { - this->angle_flag_ = false; + split_angle_ = 0; } /* Calulate the lidar_alph0 and lidar_Rxy */ @@ -271,68 +229,73 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, lidar_Rxy_ = std::sqrt(lidar_const_param_.RX * lidar_const_param_.RX + lidar_const_param_.RY * lidar_const_param_.RY); } -#if 0 template -inline RSDecoderResult DecoderBase::processMsopPkt( - const uint8_t* pkt, size_t size) +inline void DecoderBase::toSplit() { - if (size != this->msop_pkt_len_) + bool split = false; + +#if 1 +#if 0 + if (azimuth < this->last_azimuth_) + { + this->last_azimuth_ -= RS_ONE_ROUND; + } + + if ((this->last_azimuth_ != -36001) && + (this->last_azimuth_ < this->cut_angle_) && (azimuth >= this->cut_angle_)) { - return WRONG_PKT_LENGTH; + this->last_azimuth_ = azimuth; + this->pkt_count_ = 0; + return FRAME_SPLIT; } - int azimuth = 0; - RSDecoderResult ret = decodeMsopPkt(pkt, point_cloud_vec, height, azimuth); - if (ret != RSDecoderResult::DECODE_OK) + this->last_azimuth_ = azimuth; +#endif + +#else + if (this->pkt_count_ >= this->pkts_per_frame_) { - return ret; + this->pkt_count_ = 0; + split = true; } - this->pkt_count_++; - switch (this->param_.split_frame_mode) + + if (this->pkt_count_ >= this->param_.num_pkts_split) { - case SplitFrameMode::SPLIT_BY_ANGLE: - if (azimuth < this->last_azimuth_) - { - this->last_azimuth_ -= RS_ONE_ROUND; - } - if (this->last_azimuth_ != -36001 && this->last_azimuth_ < this->cut_angle_ && azimuth >= this->cut_angle_) - { - this->last_azimuth_ = azimuth; - this->pkt_count_ = 0; - this->trigger_index_ = 0; - this->prev_angle_diff_ = RS_ONE_ROUND; - return FRAME_SPLIT; - } - this->last_azimuth_ = azimuth; - break; - case SplitFrameMode::SPLIT_BY_FIXED_PKTS: - if (this->pkt_count_ >= this->pkts_per_frame_) - { - this->pkt_count_ = 0; - this->trigger_index_ = 0; - this->prev_angle_diff_ = RS_ONE_ROUND; - return FRAME_SPLIT; - } - break; - case SplitFrameMode::SPLIT_BY_CUSTOM_PKTS: - if (this->pkt_count_ >= this->param_.num_pkts_split) - { - this->pkt_count_ = 0; - this->trigger_index_ = 0; - this->prev_angle_diff_ = RS_ONE_ROUND; - return FRAME_SPLIT; - } - break; - default: - break; + this->pkt_count_ = 0; + split = true; } - return DECODE_OK; -} #endif -template -inline void DecoderBase::loadAngleFile(const std::string& angle_path) -{ + if (split) + { + T_PointCloud& msg = *point_cloud_; + + msg.seq = point_cloud_seq_++; + msg.timestamp = chan_ts_; + //msg.frame_id = param_.frame_id; + msg.is_dense = param_.is_dense; + if (msg.is_dense) + { + msg.height = 1; + msg.width = msg.points.size(); + } + else + { + msg.height = height_; + msg.width = msg.points.size() / msg.height; + } + + if (msg.points.size() == 0) + { +#if 0 + reportError(Error(ERRCODE_ZEROPOINTS)); +#endif + } + else + { + point_cloud_cb_put_(point_cloud_); + } + } } template @@ -348,6 +311,13 @@ inline void DecoderBase::decodeDifopCommon(const T_Difop& pkt) this->echo_mode_ = RSEchoMode::ECHO_SINGLE; } + pkts_per_frame_ = + this->lidar_const_param_.BLOCKS_PER_FRAME / this->lidar_const_param_.BLOCKS_PER_PKT; + if (this->echo_mode_ == RSEchoMode::ECHO_DUAL) + { + pkts_per_frame_ *= 2; + } + // rpm this->rpm_ = ntohs(pkt.rpm); if (this->rpm_ == 0) @@ -361,7 +331,7 @@ inline void DecoderBase::decodeDifopCommon(const T_Difop& pkt) RS_ONE_ROUND / this->lidar_const_param_.BLOCKS_PER_FRAME; // block duration - timestamp - this->time_duration_between_blocks_ = + this->block_duration_ = 60 / (this->rpm_ * this->lidar_const_param_.BLOCKS_PER_FRAME); // blind block duration @@ -371,30 +341,10 @@ inline void DecoderBase::decodeDifopCommon(const T_Difop& pkt) int fov_range = (fov_start_angle < fov_end_angle) ? (fov_end_angle - fov_start_angle) : (RS_ONE_ROUND - fov_start_angle + fov_end_angle); - this->fov_time_jump_diff_ = this->time_duration_between_blocks_ * + this->fov_time_jump_diff_ = this->block_duration_ * (fov_range / (RS_ONE_ROUND / this->lidar_const_param_.BLOCKS_PER_FRAME)); } -#if 0 -template -inline void DecoderBase::transformPoint(float& x, float& y, float& z) -{ -#ifdef ENABLE_TRANSFORM - Eigen::AngleAxisd current_rotation_x(param_.transform_param.roll, Eigen::Vector3d::UnitX()); - Eigen::AngleAxisd current_rotation_y(param_.transform_param.pitch, Eigen::Vector3d::UnitY()); - Eigen::AngleAxisd current_rotation_z(param_.transform_param.yaw, Eigen::Vector3d::UnitZ()); - Eigen::Translation3d current_translation(param_.transform_param.x, param_.transform_param.y, - param_.transform_param.z); - Eigen::Matrix4d trans = (current_translation * current_rotation_z * current_rotation_y * current_rotation_x).matrix(); - Eigen::Vector4d target_ori(x, y, z, 1); - Eigen::Vector4d target_rotate = trans * target_ori; - x = target_rotate(0); - y = target_rotate(1); - z = target_rotate(2); -#endif -} -#endif - #if 0 template inline RSEchoMode DecoderBase::getEchoMode(const LidarType& type, const uint8_t& return_mode) @@ -440,16 +390,5 @@ inline RSEchoMode DecoderBase::getEchoMode(const LidarType& type, } #endif -template -inline float DecoderBase::checkCosTable(const int& angle) -{ - return cos_lookup_table_[angle + RS_ONE_ROUND]; -} -template -inline float DecoderBase::checkSinTable(const int& angle) -{ - return sin_lookup_table_[angle + RS_ONE_ROUND]; -} - } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 58516d47..f9f1cbdf 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -589,6 +589,8 @@ class ChanAngles std::vector user_chans_; }; +//#define RS_TO_RADS(x) ((x) * (M_PI) / 180) + class Trigon { public: diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index e6a69f54..2aa5fc50 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -107,6 +107,7 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter float cut_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp bool is_dense = false; ///< true: discard NAN points; false: reserve NAN points + //std::string frame_id = "rslidar"; ///< The frame id of LiDAR message RSTransformParam transform_param; ///< Used to transform points RSCameraTriggerParam trigger_param; ///< Used to trigger camera void print() const @@ -123,6 +124,8 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter RS_INFOL << "split_frame_mode: " << split_frame_mode << RS_REND; RS_INFOL << "num_pkts_split: " << num_pkts_split << RS_REND; RS_INFOL << "cut_angle: " << cut_angle << RS_REND; + RS_INFOL << "is_dense: " << is_dense << RS_REND; + // RS_INFOL << "frame_id: " << frame_id << RS_REND; RS_INFO << "------------------------------------------------------" << RS_REND; } } RSDecoderParam; @@ -163,7 +166,6 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter RSInputParam input_param; ///< Input parameter RSDecoderParam decoder_param; ///< Decoder parameter std::string angle_path = "null"; ///< Path of angle calibration files(angle.csv).Only used for internal debugging. - std::string frame_id = "rslidar"; ///< The frame id of LiDAR message LidarType lidar_type = LidarType::RS16; ///< Lidar type bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet bool saved_by_rows = false; ///< true: the output point cloud will be saved by rows (default is saved by columns) @@ -174,7 +176,6 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter RS_INFO << "------------------------------------------------------" << RS_REND; RS_INFOL << " RoboSense Driver Parameters " << RS_REND; RS_INFOL << "angle_path: " << angle_path << RS_REND; - RS_INFOL << "frame_id: " << frame_id << RS_REND; RS_INFOL << "lidar_type: "; RS_INFO << lidarTypeToStr(lidar_type) << RS_REND; RS_INFOL << "------------------------------------------------------" << RS_REND; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 25a7a512..ee04b411 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -82,15 +82,13 @@ class LidarDriverImpl void packetPut(std::shared_ptr pkt); void processMsop(); void processDifop(); +#if 0 void setPointCloudHeader(T_PointCloud& msg, int height); +#endif void setScanMsgHeader(ScanMsg& msg); private: RSDriverParam driver_param_; -#if 0 - std::function(void)> point_cloud_cb_get_; - std::vector)>> point_cloud_cb_put_vec_; -#endif std::vector> excb_; std::vector> msop_pkt_cb_vec_; std::vector> difop_pkt_cb_vec_; @@ -108,7 +106,6 @@ class LidarDriverImpl bool init_flag_; bool start_flag_; bool difop_flag_; - uint32_t point_cloud_seq_; uint32_t scan_seq_; uint32_t ndifop_count_; }; @@ -126,7 +123,7 @@ inline std::string LidarDriverImpl::getVersion() template inline LidarDriverImpl::LidarDriverImpl() - : init_flag_(false), start_flag_(false), difop_flag_(false), point_cloud_seq_(0), scan_seq_(0), ndifop_count_(0) + : init_flag_(false), start_flag_(false), difop_flag_(false), scan_seq_(0), ndifop_count_(0) { } @@ -470,9 +467,10 @@ inline void LidarDriverImpl::setScanMsgHeader(ScanMsg& msg) msg.timestamp = lidar_decoder_ptr_->getLidarTime(msg.packets.back().packet.data()); } msg.seq = scan_seq_++; - msg.frame_id = driver_param_.frame_id; + //msg.frame_id = driver_param_.frame_id; } +#if 0 template inline void LidarDriverImpl::setPointCloudHeader(T_PointCloud& msg, int height) { @@ -490,6 +488,7 @@ inline void LidarDriverImpl::setPointCloudHeader(T_PointCloud& msg msg.width = msg.points.size() / msg.height; } } +#endif } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/msg/scan_msg.h b/src/rs_driver/msg/scan_msg.h index 15a1487b..291fd3c0 100644 --- a/src/rs_driver/msg/scan_msg.h +++ b/src/rs_driver/msg/scan_msg.h @@ -46,7 +46,7 @@ struct __attribute__((aligned(16))) ScanMsg { double timestamp = 0.0; uint32_t seq = 0; - std::string frame_id = ""; + //std::string frame_id = ""; std::vector packets; ///< A vector which store a scan of packets (the size of the vector is not fix) }; } // namespace lidar From edba5b73e0a19049116f7c7528c8dcc82229ee9d Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 29 Nov 2021 14:49:05 +0800 Subject: [PATCH 030/379] refac: refactory decoder/input factory --- demo/demo_online.cpp | 1 + demo/demo_pcap.cpp | 4 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 16 +- src/rs_driver/driver/decoder/decoder_base.hpp | 23 +-- .../driver/decoder/decoder_base_opt.hpp | 29 +++ .../driver/decoder/decoder_factory.hpp | 20 ++- src/rs_driver/driver/driver_param.h | 52 ++++-- src/rs_driver/driver/input/input_factory.hpp | 34 ++-- src/rs_driver/driver/lidar_driver_impl.hpp | 168 +++++------------- test/rs_driver_test.cpp | 45 +++++ 10 files changed, 211 insertions(+), 181 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 0cba51a8..d6b8c1e0 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -84,6 +84,7 @@ int main(int argc, char* argv[]) g_pointcloud = std::make_shared(); RSDriverParam param; ///< Create a parameter object + param.input_type = InputType::ONLINE_LIDAR; param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index be02ea42..2721493e 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -84,11 +84,11 @@ int main(int argc, char* argv[]) g_pointcloud = std::make_shared(); RSDriverParam param; ///< Create a parameter object - param.input_param.read_pcap = true; ///< Set read_pcap to true + param.input_type = InputType::PCAP_FILE; param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file directory param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct + param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct param.print(); diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index c1dd2b9b..389e3920 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -87,6 +87,9 @@ class DecoderRS32 : public DecoderBase virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size); virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size); + virtual RSDecoderResult TsMsopPkt(const uint8_t* pkt, size_t size); + virtual uint64_t usecToDelay() + {return 0;} virtual ~DecoderRS32() = default; explicit DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); @@ -139,6 +142,7 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* this->current_temperature_ = calcTemp(&(pkt.header.temp)); double block_timestamp = 0; + double chan_ts = block_timestamp; //uint64_t ts = 0; if (this->param_.use_lidar_clock) { @@ -213,7 +217,7 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* const RSChannel& channel = pkt.blocks[blk_idx].channels[channel_idx]; - this->chan_ts_ = block_timestamp + delta_ts[channel_idx]; + chan_ts = block_timestamp + delta_ts[channel_idx]; float azi_channel_ori = cur_azi + azi_diff * delta_ts[channel_idx] / delta_block; float distance = ntohs(channel.distance) * this->lidar_const_param_.DIS_RESOLUTION; @@ -254,16 +258,22 @@ inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* if (pointValid) { setRing(point, this->chan_angles_.toUserChan(channel_idx)); - setTimestamp(point, this->chan_ts_); + setTimestamp(point, chan_ts); this->point_cloud_->points.emplace_back(point); } } - this->toSplit(); + this->toSplit(cur_azi, chan_ts); } return RSDecoderResult::DECODE_OK; } +template +inline RSDecoderResult DecoderRS32::TsMsopPkt(const uint8_t* packet, size_t size) +{ + return RSDecoderResult::DECODE_OK; +} + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 49f48d0a..9f6e0268 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -96,21 +96,20 @@ class DecoderBase virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size) = 0; virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size) = 0; + virtual RSDecoderResult TsMsopPkt(const uint8_t* pkt, size_t size) = 0; + virtual uint64_t usecToDelay() = 0; virtual ~DecoderBase() = default; explicit DecoderBase(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - void toSplit(); + void toSplit(uint16_t azimuth, double chan_ts); void regRecvCallback(const std::function)>& cb_put, const std::function(void)>& cb_get) { point_cloud_cb_put_ = cb_put; - if (cb_get != nullptr) - { - point_cloud_cb_get_ = cb_get; - } + point_cloud_cb_get_ = cb_get; } std::shared_ptr getPointCloud() @@ -170,7 +169,7 @@ class DecoderBase DistanceBlock distance_block_; ChanAngles chan_angles_; ScanBlock scan_block_; - int split_angle_; + SplitAngle split_angle_; float block_duration_; uint16_t azi_diff_between_block_theoretical_; float fov_time_jump_diff_; @@ -184,7 +183,6 @@ class DecoderBase bool difop_flag_; int last_azimuth_; unsigned int pkt_count_; - double chan_ts_; int lidar_alph0_; // atan2(Ry, Rx) * 180 / M_PI * 100 float lidar_Rxy_; // sqrt(Rx*Rx + Ry*Ry) @@ -219,21 +217,18 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, , pkt_count_(0) , point_cloud_seq_(0) { - if (split_angle_ > RS_ONE_ROUND) - { - split_angle_ = 0; - } - /* Calulate the lidar_alph0 and lidar_Rxy */ lidar_alph0_ = std::atan2(lidar_const_param_.RY, lidar_const_param_.RX) * 180 / M_PI * 100; lidar_Rxy_ = std::sqrt(lidar_const_param_.RX * lidar_const_param_.RX + lidar_const_param_.RY * lidar_const_param_.RY); } template -inline void DecoderBase::toSplit() +inline void DecoderBase::toSplit(uint16_t azimuth, double chan_ts) { bool split = false; + split = split_angle_.toSplit(azimuth); + #if 1 #if 0 if (azimuth < this->last_azimuth_) @@ -271,7 +266,7 @@ inline void DecoderBase::toSplit() T_PointCloud& msg = *point_cloud_; msg.seq = point_cloud_seq_++; - msg.timestamp = chan_ts_; + msg.timestamp = chan_ts; //msg.frame_id = param_.frame_id; msg.is_dense = param_.is_dense; if (msg.is_dense) diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index f9f1cbdf..85d5ccea 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -641,5 +641,34 @@ class Trigon std::vector coss_; }; +class SplitAngle +{ +public: + SplitAngle (uint16_t split_angle) + : split_angle_(split_angle), + prev_angle_(split_angle) + { + } + + bool toSplit(uint16_t angle) + { + if (angle < prev_angle_) + prev_angle_ -= 36000; + + bool v = ((prev_angle_ < split_angle_) && (split_angle_ <= angle)); + prev_angle_ = angle; + return v; + } + + uint16_t value() + { + return split_angle_; + } + +private: + uint16_t split_angle_; + int16_t prev_angle_; +}; + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 10bf4593..31be523f 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -49,9 +49,9 @@ template class DecoderFactory { public: - DecoderFactory() = default; - ~DecoderFactory() = default; - static std::shared_ptr> createDecoder(const RSDriverParam& param); + + static std::shared_ptr> createDecoder(LidarType type, + const RSDecoderParam& param); private: static const LidarConstantParameter getRS32ConstantParam(); @@ -68,10 +68,11 @@ class DecoderFactory template inline std::shared_ptr> -DecoderFactory::createDecoder(const RSDriverParam& param) +DecoderFactory::createDecoder(LidarType type, const RSDecoderParam& param) { std::shared_ptr> ret_ptr; - switch (param.lidar_type) + + switch (type) { #if 0 case LidarType::RS16: @@ -79,7 +80,7 @@ DecoderFactory::createDecoder(const RSDriverParam& param) break; #endif case LidarType::RS32: - ret_ptr = std::make_shared>(param.decoder_param, getRS32ConstantParam()); + ret_ptr = std::make_shared>(param, getRS32ConstantParam()); break; #if 0 case LidarType::RSBP: @@ -105,7 +106,12 @@ DecoderFactory::createDecoder(const RSDriverParam& param) RS_ERROR << "Wrong LiDAR Type. Please check your LiDAR Version! " << RS_REND; exit(-1); } - ret_ptr->loadAngleFile(param.angle_path); + + if (param.config_from_file) + { + ret_ptr->loadAngleFile(param.angle_path); + } + return ret_ptr; } diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index 2aa5fc50..20bcf74a 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -50,6 +50,13 @@ enum LidarType ///< LiDAR type RSM1 = 10 }; +enum InputType +{ + ONLINE_LIDAR = 1, + PCAP_FILE, + RAW_PACKET +}; + enum SplitFrameMode { SPLIT_BY_ANGLE = 1, @@ -57,6 +64,7 @@ enum SplitFrameMode SPLIT_BY_CUSTOM_PKTS }; +#if 0 typedef struct RSCameraTriggerParam ///< Camera trigger parameters { std::map trigger_map; ///< Map stored the trigger angle and camera frame id @@ -93,29 +101,39 @@ typedef struct RSTransformParam ///< The Point transform parameter RS_INFO << "------------------------------------------------------" << RS_REND; } } RSTransformParam; +#endif typedef struct RSDecoderParam ///< LiDAR decoder parameter { + bool config_from_file = false; + std::string angle_path = ""; ///< Path of angle calibration files(angle.csv). Only used for internal debugging. float max_distance = 200.0f; ///< Max distance of point cloud range float min_distance = 0.2f; ///< Minimum distance of point cloud range float start_angle = 0.0f; ///< Start angle of point cloud float end_angle = 360.0f; ///< End angle of point cloud + SplitFrameMode split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; ///< 1: Split frames by cut_angle; ///< 2: Split frames by fixed number of packets; - ///< 3: Split frames by custom number of packets (num_pkts_split) + ///< 3: Split frames by custom number of packets (num_pkts_split) uint32_t num_pkts_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 float cut_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 + bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp bool is_dense = false; ///< true: discard NAN points; false: reserve NAN points - //std::string frame_id = "rslidar"; ///< The frame id of LiDAR message +#if 0 RSTransformParam transform_param; ///< Used to transform points RSCameraTriggerParam trigger_param; ///< Used to trigger camera +#endif + void print() const { +#if 0 transform_param.print(); trigger_param.print(); +#endif RS_INFO << "------------------------------------------------------" << RS_REND; RS_INFO << " RoboSense Decoder Parameters " << RS_REND; + RS_INFOL << "angle_path: " << angle_path << RS_REND; RS_INFOL << "max_distance: " << max_distance << RS_REND; RS_INFOL << "min_distance: " << min_distance << RS_REND; RS_INFOL << "start_angle: " << start_angle << RS_REND; @@ -125,23 +143,20 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter RS_INFOL << "num_pkts_split: " << num_pkts_split << RS_REND; RS_INFOL << "cut_angle: " << cut_angle << RS_REND; RS_INFOL << "is_dense: " << is_dense << RS_REND; - // RS_INFOL << "frame_id: " << frame_id << RS_REND; RS_INFO << "------------------------------------------------------" << RS_REND; } + } RSDecoderParam; typedef struct RSInputParam ///< The LiDAR input parameter { - std::string device_ip = "192.168.1.200"; ///< Ip of LiDAR - std::string multi_cast_address = "0.0.0.0"; ///< Address of multicast - std::string host_address = "0.0.0.0"; ///< Address of host uint16_t msop_port = 6699; ///< Msop packet port number uint16_t difop_port = 7788; ///< Difop packet port number - bool read_pcap = false; ///< true: The driver will process the pcap through pcap_path. false: The driver will - ///< Get data from online LiDAR - double pcap_rate = 1; ///< Rate to read the pcap file - bool pcap_repeat = true; ///< true: The pcap bag will repeat play + std::string host_address = "0.0.0.0"; ///< Address of host + std::string multi_cast_address = "0.0.0.0"; ///< Address of multicast std::string pcap_path = "null"; ///< Absolute path of pcap file + bool pcap_repeat = true; ///< true: The pcap bag will repeat play + double pcap_rate = 1; ///< Rate to read the pcap file bool use_vlan = false; ///< Vlan on-off bool use_someip = false; ///< Someip on-off void print() const @@ -152,7 +167,6 @@ typedef struct RSInputParam ///< The LiDAR input parameter RS_INFOL << "host_address: " << host_address << RS_REND; RS_INFOL << "msop_port: " << msop_port << RS_REND; RS_INFOL << "difop_port: " << difop_port << RS_REND; - RS_INFOL << "read_pcap: " << read_pcap << RS_REND; RS_INFOL << "pcap_repeat: " << pcap_repeat << RS_REND; RS_INFOL << "pcap_path: " << pcap_path << RS_REND; RS_INFOL << "use_vlan: " << use_vlan << RS_REND; @@ -163,23 +177,23 @@ typedef struct RSInputParam ///< The LiDAR input parameter typedef struct RSDriverParam ///< The LiDAR driver parameter { + LidarType lidar_type = LidarType::RS16; ///< Lidar type + InputType input_type = InputType::ONLINE_LIDAR; ///< Input type RSInputParam input_param; ///< Input parameter RSDecoderParam decoder_param; ///< Decoder parameter - std::string angle_path = "null"; ///< Path of angle calibration files(angle.csv).Only used for internal debugging. - LidarType lidar_type = LidarType::RS16; ///< Lidar type - bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet - bool saved_by_rows = false; ///< true: the output point cloud will be saved by rows (default is saved by columns) + bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + void print() const { input_param.print(); decoder_param.print(); RS_INFO << "------------------------------------------------------" << RS_REND; RS_INFOL << " RoboSense Driver Parameters " << RS_REND; - RS_INFOL << "angle_path: " << angle_path << RS_REND; - RS_INFOL << "lidar_type: "; - RS_INFO << lidarTypeToStr(lidar_type) << RS_REND; + RS_INFOL << "lidar_type: " << lidarTypeToStr(lidar_type) << RS_REND; + RS_INFOL << "input type: " << (int)input_type << RS_REND; RS_INFOL << "------------------------------------------------------" << RS_REND; } + static std::string lidarTypeToStr(const LidarType& type) { std::string str = ""; @@ -256,6 +270,8 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter exit(-1); } } + } RSDriverParam; + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 39217fe7..d1de08c1 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -38,6 +38,7 @@ namespace robosense { namespace lidar { +#if 0 inline long long msecToDelay(LidarType type, double replay_rate) { constexpr double RS16_PCAP_SLEEP_DURATION = 1200; ///< us @@ -81,28 +82,37 @@ inline long long msecToDelay(LidarType type, double replay_rate) return static_cast(duration / replay_rate); } +#endif class InputFactory { public: - static std::shared_ptr createInput(const RSDriverParam& driver_param, - const std::function& excb); + static std::shared_ptr createInput(InputType type, + const RSInputParam& param, const std::function& excb); }; -inline std::shared_ptr InputFactory::createInput(const RSDriverParam& driver_param, - const std::function& excb) +inline std::shared_ptr InputFactory::createInput(InputType type, + const RSInputParam& param, const std::function& excb) { - const RSInputParam& input_param = driver_param.input_param; std::shared_ptr input; - if (input_param.read_pcap) + switch(type) { - long long msec = msecToDelay(driver_param.lidar_type, input_param.pcap_rate); - input = std::make_shared(input_param, excb, msec); - } - else - { - input = std::make_shared(input_param, excb); + case InputType::ONLINE_LIDAR: + { + input = std::make_shared(param, excb); + } + case InputType::PCAP_FILE: + { + //long long msec = msecToDelay(driver_param.lidar_type, input_param.pcap_rate); + long long msec = 0;//msecToDelay(driver_param.lidar_type, input_param.pcap_rate); + input = std::make_shared(param, excb, msec); + } + case InputType::RAW_PACKET: + { + } + default: + break; } return input; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index ee04b411..e1784f5e 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -63,39 +63,35 @@ class LidarDriverImpl void stop(); void regRecvCallback(const std::function)>& cb_put, const std::function(void)>& cb_get); - void regRecvCallback(const std::function& callback); void regRecvCallback(const std::function& callback); void regExceptionCallback(const std::function& callback); +#if 0 bool decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg); - void decodeDifopPkt(const PacketMsg& msg); +#endif + void decodePacket(const PacketMsg& msg); bool getLidarTemperature(double& input_temperature); private: void runCallBack(std::shared_ptr msg); - void runCallBack(const ScanMsg& msg); - void runCallBack(const PacketMsg& msg); + void runCallBack(std::shared_ptr& pkt); void reportError(const Error& error); + void msopCallback(std::shared_ptr msg); void difopCallback(std::shared_ptr msg); std::shared_ptr packetGet(size_t size); void packetPut(std::shared_ptr pkt); + void processMsop(); void processDifop(); -#if 0 - void setPointCloudHeader(T_PointCloud& msg, int height); -#endif - void setScanMsgHeader(ScanMsg& msg); private: RSDriverParam driver_param_; - std::vector> excb_; - std::vector> msop_pkt_cb_vec_; - std::vector> difop_pkt_cb_vec_; + std::function pkt_cb_; + std::function err_cb_; + std::shared_ptr input_ptr_; std::shared_ptr> lidar_decoder_ptr_; - std::shared_ptr point_cloud_; - ScanMsg scan_ptr_; SyncQueue> free_pkt_queue_; SyncQueue> msop_pkt_queue_; SyncQueue> difop_pkt_queue_; @@ -106,7 +102,7 @@ class LidarDriverImpl bool init_flag_; bool start_flag_; bool difop_flag_; - uint32_t scan_seq_; + uint32_t pkt_seq_; uint32_t ndifop_count_; }; @@ -123,7 +119,7 @@ inline std::string LidarDriverImpl::getVersion() template inline LidarDriverImpl::LidarDriverImpl() - : init_flag_(false), start_flag_(false), difop_flag_(false), scan_seq_(0), ndifop_count_(0) + : init_flag_(false), start_flag_(false), difop_flag_(false), pkt_seq_(0), ndifop_count_(0) { } @@ -141,12 +137,11 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) return true; } - driver_param_ = param; - - lidar_decoder_ptr_ = DecoderFactory::createDecoder(driver_param_); + lidar_decoder_ptr_ = DecoderFactory::createDecoder + (param.lidar_type, param.decoder_param); input_ptr_ = InputFactory::createInput( - driver_param_, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); + param.input_type, param.input_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); input_ptr_->regRecvCallback(std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), std::bind(&LidarDriverImpl::msopCallback, this, std::placeholders::_1), std::bind(&LidarDriverImpl::difopCallback, this, std::placeholders::_1)); @@ -156,6 +151,7 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) goto failInputInit; } + driver_param_ = param; init_flag_ = true; return true; @@ -206,38 +202,35 @@ template inline void LidarDriverImpl::regRecvCallback(const std::function)>& cb_put, const std::function(void)>& cb_get) { -#if 0 - point_cloud_cb_put_vec_.emplace_back(cb_put); - if (cb_get != nullptr) - { - point_cloud_cb_get_ = cb_get; - } -#endif -} -template -inline void LidarDriverImpl::regRecvCallback(const std::function& callback) -{ - msop_pkt_cb_vec_.emplace_back(callback); + lidar_decoder_ptr_->regRecvCallback(cb_put, cb_get); } template inline void LidarDriverImpl::regRecvCallback(const std::function& callback) { - difop_pkt_cb_vec_.emplace_back(callback); + pkt_cb_ = callback; } template inline void LidarDriverImpl::regExceptionCallback(const std::function& callback) { - excb_.emplace_back(callback); + err_cb_ = callback; } template -inline void LidarDriverImpl::decodeDifopPkt(const PacketMsg& pkt) +inline void LidarDriverImpl::decodePacket(const PacketMsg& pkt) { -// lidar_decoder_ptr_->processDifopPkt(pkt.packet.data(), pkt.packet.size()); -// difop_flag_ = true; +#if 0 + if (1) + { + lidar_decoder_ptr_->processDifopPkt(pkt.packet.data(), pkt.packet.size()); + difop_flag_ = true; + } + else + { + } +#endif } template @@ -252,47 +245,31 @@ inline bool LidarDriverImpl::getLidarTemperature(double& input_tem } template -inline void LidarDriverImpl::runCallBack(const ScanMsg& msg) +inline void LidarDriverImpl::runCallBack(std::shared_ptr& pkt) { - if (msg.seq != 0) + if (pkt_cb_) { - for (auto& it : msop_pkt_cb_vec_) - { - it(msg); - } - } -} -template -inline void LidarDriverImpl::runCallBack(const PacketMsg& msg) -{ - for (auto& it : difop_pkt_cb_vec_) - { - it(msg); - } -} - -template -inline void LidarDriverImpl::runCallBack(std::shared_ptr msg) -{ #if 0 - if (msg->seq != 0) - { - for (auto& it : point_cloud_cb_put_vec_) + msg.timestamp = getTime(); + if (driver_param_.decoder_param.use_lidar_clock == true) { - it(msg); + msg.timestamp = lidar_decoder_ptr_->getLidarTime(msg.packets.back().packet.data()); } - } + msg.seq = pkt_seq_++; #endif + + PacketMsg msg(pkt->len()); + memcpy (msg.packet.data(), pkt->data(), pkt->len()); + + pkt_cb_(msg); + } } template inline void LidarDriverImpl::reportError(const Error& error) { - for (auto& it : excb_) - { - it(error); - } + err_cb_(error); } template @@ -331,29 +308,6 @@ inline void LidarDriverImpl::difopCallback(std::shared_ptr difop_pkt_queue_.push(pkt); } -#if 0 -template -inline std::shared_ptr LidarDriverImpl::getPointCloud() -{ - std::shared_ptr pc; - - while (1) - { - if (point_cloud_cb_get_ != nullptr) - pc = point_cloud_cb_get_(); - - if (pc) - { - pc->points.resize(0); - return pc; - } - - reportError(Error(ERRCODE_POINTCLOUDNULL)); - std::this_thread::sleep_for(std::chrono::milliseconds(300)); - }; -} -#endif - template inline void LidarDriverImpl::processMsop() { @@ -448,47 +402,11 @@ inline void LidarDriverImpl::processDifop() lidar_decoder_ptr_->processDifopPkt(pkt->data(), pkt->len()); difop_flag_ = true; -#ifdef ENABLE_PUBLISH_RAW_MSG - PacketMsg msg(pkt->len()); - memcpy (msg.packet.data(), pkt->data(), pkt->len()); - runCallBack(msg); -#endif + runCallBack(pkt); packetPut(pkt); } } -template -inline void LidarDriverImpl::setScanMsgHeader(ScanMsg& msg) -{ - msg.timestamp = getTime(); - if (driver_param_.decoder_param.use_lidar_clock == true) - { - msg.timestamp = lidar_decoder_ptr_->getLidarTime(msg.packets.back().packet.data()); - } - msg.seq = scan_seq_++; - //msg.frame_id = driver_param_.frame_id; -} - -#if 0 -template -inline void LidarDriverImpl::setPointCloudHeader(T_PointCloud& msg, int height) -{ - msg.seq = point_cloud_seq_++; - msg.frame_id = driver_param_.frame_id; - msg.is_dense = driver_param_.decoder_param.is_dense; - if (msg.is_dense) - { - msg.height = 1; - msg.width = msg.points.size(); - } - else - { - msg.height = height; - msg.width = msg.points.size() / msg.height; - } -} -#endif - } // namespace lidar } // namespace robosense diff --git a/test/rs_driver_test.cpp b/test/rs_driver_test.cpp index 6493710e..87cf51e5 100644 --- a/test/rs_driver_test.cpp +++ b/test/rs_driver_test.cpp @@ -197,6 +197,51 @@ TEST(TestTrigon, ctor) #endif } +TEST(TestSplitAngle, toSplit) +{ + { + SplitAngle sa(10); + ASSERT_FALSE(sa.toSplit(5)); + ASSERT_TRUE(sa.toSplit(15)); + } + + { + SplitAngle sa(10); + ASSERT_FALSE(sa.toSplit(5)); + ASSERT_TRUE(sa.toSplit(10)); + ASSERT_FALSE(sa.toSplit(15)); + } + + { + SplitAngle sa(10); + ASSERT_FALSE(sa.toSplit(10)); + ASSERT_FALSE(sa.toSplit(15)); + } +} + +TEST(TestSplitAngle, toSplit_Zero) +{ + { + SplitAngle sa(0); + ASSERT_FALSE(sa.toSplit(35999)); + ASSERT_TRUE(sa.toSplit(1)); + ASSERT_FALSE(sa.toSplit(2)); + } + + { + SplitAngle sa(0); + ASSERT_FALSE(sa.toSplit(35999)); + ASSERT_TRUE(sa.toSplit(0)); + ASSERT_FALSE(sa.toSplit(2)); + } + + { + SplitAngle sa(0); + ASSERT_FALSE(sa.toSplit(0)); + ASSERT_FALSE(sa.toSplit(2)); + } +} + int main(int argc, char** argv) { ::testing::InitGoogleTest(&argc, argv); From acadafeb8358ceb48e7b37630a986da3a6e1e0ce Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 29 Nov 2021 17:22:49 +0800 Subject: [PATCH 031/379] refac: refactory decoder/input --- demo/demo_online.cpp | 2 +- .../decoder/{decoder_base.hpp => decoder.hpp} | 48 +++++++++--- src/rs_driver/driver/decoder/decoder_RS32.hpp | 12 +-- .../driver/decoder/decoder_factory.hpp | 11 +-- src/rs_driver/driver/driver_param.h | 3 +- src/rs_driver/driver/input/input.hpp | 22 ++---- src/rs_driver/driver/input/input_factory.hpp | 18 +++-- .../input/{pcap_input.hpp => input_pcap.hpp} | 16 ++-- src/rs_driver/driver/input/input_raw.hpp | 74 +++++++++++++++++++ .../input/{sock_input.hpp => input_sock.hpp} | 20 ++--- src/rs_driver/driver/lidar_driver_impl.hpp | 47 ++++++------ 11 files changed, 177 insertions(+), 96 deletions(-) rename src/rs_driver/driver/decoder/{decoder_base.hpp => decoder.hpp} (90%) rename src/rs_driver/driver/input/{pcap_input.hpp => input_pcap.hpp} (94%) create mode 100644 src/rs_driver/driver/input/input_raw.hpp rename src/rs_driver/driver/input/{sock_input.hpp => input_sock.hpp} (93%) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index d6b8c1e0..39fd3702 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -88,7 +88,7 @@ int main(int argc, char* argv[]) param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct - param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + param.decoder_param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet param.print(); LidarDriver driver; diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder.hpp similarity index 90% rename from src/rs_driver/driver/decoder/decoder_base.hpp rename to src/rs_driver/driver/decoder/decoder.hpp index 9f6e0268..8c073fbd 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -86,21 +86,23 @@ enum RSDecoderResult WRONG_PKT_HEADER = -1, WRONG_PKT_LENGTH = -2, PKT_NULL = -3, - DISCARD_PKT = -4 + DISCARD_PKT = -4, + DIFOP_NOT_READY = -5 }; template -class DecoderBase +class Decoder { public: + virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size); + virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size) = 0; - virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size) = 0; + virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual RSDecoderResult TsMsopPkt(const uint8_t* pkt, size_t size) = 0; - virtual uint64_t usecToDelay() = 0; - virtual ~DecoderBase() = default; + virtual ~Decoder() = default; - explicit DecoderBase(const RSDecoderParam& param, + explicit Decoder(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); void toSplit(uint16_t azimuth, double chan_ts); @@ -144,6 +146,11 @@ class DecoderBase return current_temperature_; } + uint64_t msecToDelay() + { + return msec_to_delay_; + } + void loadAngleFile(const std::string& angle_path) { } @@ -162,6 +169,7 @@ class DecoderBase const LidarConstantParameter lidar_const_param_; RSDecoderParam param_; uint16_t height_; + uint64_t msec_to_delay_; uint32_t msop_pkt_len_; uint32_t difop_pkt_len_; @@ -180,7 +188,7 @@ class DecoderBase RSEchoMode echo_mode_; double current_temperature_; - bool difop_flag_; + bool difop_ready_; int last_azimuth_; unsigned int pkt_count_; @@ -194,7 +202,7 @@ class DecoderBase }; template -inline DecoderBase::DecoderBase(const RSDecoderParam& param, +inline Decoder::Decoder(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) : lidar_const_param_(lidar_const_param) , param_(param) @@ -212,7 +220,7 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, , rpm_(600) , echo_mode_(ECHO_SINGLE) , current_temperature_(0) - , difop_flag_(false) + , difop_ready_(false) , last_azimuth_(-36001) , pkt_count_(0) , point_cloud_seq_(0) @@ -220,10 +228,26 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, /* Calulate the lidar_alph0 and lidar_Rxy */ lidar_alph0_ = std::atan2(lidar_const_param_.RY, lidar_const_param_.RX) * 180 / M_PI * 100; lidar_Rxy_ = std::sqrt(lidar_const_param_.RX * lidar_const_param_.RX + lidar_const_param_.RY * lidar_const_param_.RY); + + if (param.config_from_file) + { + loadAngleFile(param.angle_path); + } +} + +template +RSDecoderResult Decoder::processMsopPkt(const uint8_t* pkt, size_t size) +{ + if (param_.wait_for_difop && !difop_ready_) + { + return RSDecoderResult::DIFOP_NOT_READY; + } + + return decodeMsopPkt(pkt, size); } template -inline void DecoderBase::toSplit(uint16_t azimuth, double chan_ts) +inline void Decoder::toSplit(uint16_t azimuth, double chan_ts) { bool split = false; @@ -295,7 +319,7 @@ inline void DecoderBase::toSplit(uint16_t azimuth, double chan_ts) template template -inline void DecoderBase::decodeDifopCommon(const T_Difop& pkt) +inline void Decoder::decodeDifopCommon(const T_Difop& pkt) { // return mode switch (pkt.return_mode) @@ -342,7 +366,7 @@ inline void DecoderBase::decodeDifopCommon(const T_Difop& pkt) #if 0 template -inline RSEchoMode DecoderBase::getEchoMode(const LidarType& type, const uint8_t& return_mode) +inline RSEchoMode Decoder::getEchoMode(const LidarType& type, const uint8_t& return_mode) { switch (type) { diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 389e3920..45a6dd83 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -30,7 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include +#include namespace robosense { @@ -81,12 +81,12 @@ typedef struct #pragma pack(pop) template -class DecoderRS32 : public DecoderBase +class DecoderRS32 : public Decoder { public: virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size); - virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size); + virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, size_t size); virtual RSDecoderResult TsMsopPkt(const uint8_t* pkt, size_t size); virtual uint64_t usecToDelay() {return 0;} @@ -99,7 +99,7 @@ class DecoderRS32 : public DecoderBase template inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) + : Decoder(param, lidar_const_param) { } @@ -117,7 +117,7 @@ inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* this->template decodeDifopCommon(pkt); - if (!this->difop_flag_) + if (!this->difop_ready_) { this->chan_angles_.loadFromDifop(pkt.ver_angle_cali, pkt.hori_angle_cali, 32); } @@ -126,7 +126,7 @@ inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* } template -inline RSDecoderResult DecoderRS32::processMsopPkt(const uint8_t* packet, size_t size) +inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* packet, size_t size) { uint8_t id[] = {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0}; uint8_t block_id[] = {0xFF, 0xEE}; diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 31be523f..fedd39d8 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -50,7 +50,7 @@ class DecoderFactory { public: - static std::shared_ptr> createDecoder(LidarType type, + static std::shared_ptr> createDecoder(LidarType type, const RSDecoderParam& param); private: @@ -67,10 +67,10 @@ class DecoderFactory }; template -inline std::shared_ptr> +inline std::shared_ptr> DecoderFactory::createDecoder(LidarType type, const RSDecoderParam& param) { - std::shared_ptr> ret_ptr; + std::shared_ptr> ret_ptr; switch (type) { @@ -107,11 +107,6 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam exit(-1); } - if (param.config_from_file) - { - ret_ptr->loadAngleFile(param.angle_path); - } - return ret_ptr; } diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index 20bcf74a..5bc40ab5 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -118,6 +118,7 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter uint32_t num_pkts_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 float cut_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 + bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp bool is_dense = false; ///< true: discard NAN points; false: reserve NAN points #if 0 @@ -138,6 +139,7 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter RS_INFOL << "min_distance: " << min_distance << RS_REND; RS_INFOL << "start_angle: " << start_angle << RS_REND; RS_INFOL << "end_angle: " << end_angle << RS_REND; + RS_INFOL << "wait_for_difop: " << wait_for_difop << RS_REND; RS_INFOL << "use_lidar_clock: " << use_lidar_clock << RS_REND; RS_INFOL << "split_frame_mode: " << split_frame_mode << RS_REND; RS_INFOL << "num_pkts_split: " << num_pkts_split << RS_REND; @@ -181,7 +183,6 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter InputType input_type = InputType::ONLINE_LIDAR; ///< Input type RSInputParam input_param; ///< Input parameter RSDecoderParam decoder_param; ///< Decoder parameter - bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet void print() const { diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index ee800f4c..77da84fa 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -52,8 +52,7 @@ class Input Input(const RSInputParam& input_param, const std::function& excb); inline void regRecvCallback(const std::function(size_t)>& cb_get, - const std::function)>& cb_put_msop, - const std::function)>& cb_put_difop); + const std::function)>& cb_put); virtual bool init() = 0; virtual bool start() = 0; @@ -67,8 +66,7 @@ class Input RSInputParam input_param_; std::function(size_t size)> cb_get_; - std::function)> cb_put_msop_; - std::function)> cb_put_difop_; + std::function)> cb_put_; std::function excb_; std::thread recv_thread_; bool to_exit_recv_; @@ -82,12 +80,10 @@ inline Input::Input(const RSInputParam& input_param, const std::function(size_t)>& cb_get, - const std::function)>& cb_put_msop, - const std::function)>& cb_put_difop) + const std::function)>& cb_put) { cb_get_ = cb_get; - cb_put_msop_ = cb_put_msop; - cb_put_difop_ = cb_put_difop; + cb_put_ = cb_put; } inline void Input::stop() @@ -103,15 +99,7 @@ inline void Input::stop() inline void Input::pushPacket(std::shared_ptr pkt) { - uint8_t* id = pkt->data(); - if (*id == 0x55) - { - cb_put_msop_(pkt); - } - else if (*id == 0xA5) - { - cb_put_difop_(pkt); - } + cb_put_(pkt); } } // namespace lidar diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index d1de08c1..446f9ca5 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -31,8 +31,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #include -#include -#include +#include +#include +#include namespace robosense { @@ -88,11 +89,13 @@ class InputFactory { public: static std::shared_ptr createInput(InputType type, - const RSInputParam& param, const std::function& excb); + const RSInputParam& param, const std::function& excb, + uint64_t msec_to_delay); }; inline std::shared_ptr InputFactory::createInput(InputType type, - const RSInputParam& param, const std::function& excb) + const RSInputParam& param, + const std::function& excb, uint64_t msec_to_delay) { std::shared_ptr input; @@ -100,16 +103,15 @@ inline std::shared_ptr InputFactory::createInput(InputType type, { case InputType::ONLINE_LIDAR: { - input = std::make_shared(param, excb); + input = std::make_shared(param, excb); } case InputType::PCAP_FILE: { - //long long msec = msecToDelay(driver_param.lidar_type, input_param.pcap_rate); - long long msec = 0;//msecToDelay(driver_param.lidar_type, input_param.pcap_rate); - input = std::make_shared(param, excb, msec); + input = std::make_shared(param, excb, msec_to_delay); } case InputType::RAW_PACKET: { + input = std::make_shared(param, excb); } default: break; diff --git a/src/rs_driver/driver/input/pcap_input.hpp b/src/rs_driver/driver/input/input_pcap.hpp similarity index 94% rename from src/rs_driver/driver/input/pcap_input.hpp rename to src/rs_driver/driver/input/input_pcap.hpp index f2575b8c..bea6e3e8 100644 --- a/src/rs_driver/driver/input/pcap_input.hpp +++ b/src/rs_driver/driver/input/input_pcap.hpp @@ -42,10 +42,10 @@ namespace robosense { namespace lidar { -class PcapInput : public Input +class InputPcap : public Input { public: - PcapInput(const RSInputParam& input_param, const std::function& excb, long long msec_to_delay) + InputPcap(const RSInputParam& input_param, const std::function& excb, long long msec_to_delay) : Input(input_param, excb), pcap_offset_(ETH_HDR_LEN), difop_filter_valid_(false), msec_to_delay_(msec_to_delay) { if (input_param.use_vlan) @@ -69,7 +69,7 @@ class PcapInput : public Input virtual bool init(); virtual bool start(); - virtual ~PcapInput(); + virtual ~InputPcap(); private: void recvPacket(); @@ -85,7 +85,7 @@ class PcapInput : public Input long long msec_to_delay_; }; -inline bool PcapInput::init() +inline bool InputPcap::init() { if (init_flag_) return true; @@ -110,7 +110,7 @@ inline bool PcapInput::init() return true; } -inline bool PcapInput::start() +inline bool InputPcap::start() { if (start_flag_) return true; @@ -122,13 +122,13 @@ inline bool PcapInput::start() } to_exit_recv_ = false; - recv_thread_ = std::thread(std::bind(&PcapInput::recvPacket, this)); + recv_thread_ = std::thread(std::bind(&InputPcap::recvPacket, this)); start_flag_ = true; return true; } -inline PcapInput::~PcapInput() +inline InputPcap::~InputPcap() { stop(); @@ -136,7 +136,7 @@ inline PcapInput::~PcapInput() pcap_close(pcap_); } -inline void PcapInput::recvPacket() +inline void InputPcap::recvPacket() { while (!to_exit_recv_) { diff --git a/src/rs_driver/driver/input/input_raw.hpp b/src/rs_driver/driver/input/input_raw.hpp new file mode 100644 index 00000000..2b71141f --- /dev/null +++ b/src/rs_driver/driver/input/input_raw.hpp @@ -0,0 +1,74 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include + +namespace robosense +{ +namespace lidar +{ +class InputRaw : public Input +{ +public: + + virtual bool init(){return true;} + virtual bool start(){return true;}; + virtual void stop(){} + virtual ~InputRaw(){} + + void recvPacket(std::shared_ptr pkt); + + InputRaw(const RSInputParam& input_param, const std::function& excb) + : Input(input_param, excb), pcap_offset_(ETH_HDR_LEN), difop_filter_valid_(false) + { + } + +private: + pcap_t* pcap_; + size_t pcap_offset_; + std::string msop_filter_str_; + std::string difop_filter_str_; + bpf_program msop_filter_; + bpf_program difop_filter_; + bool difop_filter_valid_; + long long msec_to_delay_; +}; + +inline void InputRaw::recvPacket(std::shared_ptr pkt) +{ + pushPacket(pkt); +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/input_sock.hpp similarity index 93% rename from src/rs_driver/driver/input/sock_input.hpp rename to src/rs_driver/driver/input/input_sock.hpp index 37abd63f..844f28f0 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/input_sock.hpp @@ -56,10 +56,10 @@ namespace robosense { namespace lidar { -class SockInput : public Input +class InputSock : public Input { public: - SockInput(const RSInputParam& input_param, const std::function& excb) + InputSock(const RSInputParam& input_param, const std::function& excb) : Input(input_param, excb), sock_offset_(0) { if (input_param.use_someip) @@ -68,7 +68,7 @@ class SockInput : public Input virtual bool init(); virtual bool start(); - virtual ~SockInput(); + virtual ~InputSock(); private: inline void recvPacket(); @@ -80,7 +80,7 @@ class SockInput : public Input size_t sock_offset_; }; -inline void SockInput::higherThreadPrioty(std::thread::native_handle_type handle) +inline void InputSock::higherThreadPrioty(std::thread::native_handle_type handle) { #ifdef ENABLE_HIGH_PRIORITY_THREAD int policy; @@ -95,7 +95,7 @@ inline void SockInput::higherThreadPrioty(std::thread::native_handle_type handle #endif } -inline bool SockInput::init() +inline bool InputSock::init() { if (init_flag_) return true; @@ -125,7 +125,7 @@ inline bool SockInput::init() return false; } -inline bool SockInput::start() +inline bool InputSock::start() { if (start_flag_) return true; @@ -136,7 +136,7 @@ inline bool SockInput::start() return false; } - recv_thread_ = std::thread(std::bind(&SockInput::recvPacket, this)); + recv_thread_ = std::thread(std::bind(&InputSock::recvPacket, this)); higherThreadPrioty(recv_thread_.native_handle()); @@ -144,7 +144,7 @@ inline bool SockInput::start() return true; } -inline SockInput::~SockInput() +inline InputSock::~InputSock() { stop(); @@ -153,7 +153,7 @@ inline SockInput::~SockInput() close(fds_[1]); } -inline int SockInput::createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp) +inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp) { int fd; int flags; @@ -213,7 +213,7 @@ inline int SockInput::createSocket(uint16_t port, const std::string& hostIp, con return -1; } -inline void SockInput::recvPacket() +inline void InputSock::recvPacket() { fd_set rfds; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index e1784f5e..191129db 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -65,9 +65,6 @@ class LidarDriverImpl const std::function(void)>& cb_get); void regRecvCallback(const std::function& callback); void regExceptionCallback(const std::function& callback); -#if 0 - bool decodeMsopScan(const ScanMsg& scan_msg, T_PointCloud& point_cloud_msg); -#endif void decodePacket(const PacketMsg& msg); bool getLidarTemperature(double& input_temperature); @@ -77,8 +74,6 @@ class LidarDriverImpl void runCallBack(std::shared_ptr& pkt); void reportError(const Error& error); - void msopCallback(std::shared_ptr msg); - void difopCallback(std::shared_ptr msg); std::shared_ptr packetGet(size_t size); void packetPut(std::shared_ptr pkt); @@ -90,8 +85,10 @@ class LidarDriverImpl std::function pkt_cb_; std::function err_cb_; + std::shared_ptr> lidar_decoder_ptr_; + std::shared_ptr input_ptr_; - std::shared_ptr> lidar_decoder_ptr_; + std::function)> feed_pkt_cb_; SyncQueue> free_pkt_queue_; SyncQueue> msop_pkt_queue_; SyncQueue> difop_pkt_queue_; @@ -141,10 +138,9 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) (param.lidar_type, param.decoder_param); input_ptr_ = InputFactory::createInput( - param.input_type, param.input_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); + param.input_type, param.input_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1), 0); input_ptr_->regRecvCallback(std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), - std::bind(&LidarDriverImpl::msopCallback, this, std::placeholders::_1), - std::bind(&LidarDriverImpl::difopCallback, this, std::placeholders::_1)); + std::bind(&LidarDriverImpl::packetPut, this, std::placeholders::_1)); if (!input_ptr_->init()) { @@ -287,27 +283,28 @@ inline std::shared_ptr LidarDriverImpl::packetGet(size_t s template inline void LidarDriverImpl::packetPut(std::shared_ptr pkt) { - free_pkt_queue_.push(pkt); -} + SyncQueue>* queue; + + uint8_t* id = pkt->data(); + if (*id == 0x55) + { + queue = &msop_pkt_queue_; + } + else if (*id == 0xA5) + { + queue = &difop_pkt_queue_; + } -template -inline void LidarDriverImpl::msopCallback(std::shared_ptr pkt) -{ static const int PACKET_POOL_MAX = 1024; - size_t sz = msop_pkt_queue_.push(pkt); + + size_t sz = queue->push(pkt); if (sz > PACKET_POOL_MAX) { reportError(Error(ERRCODE_PKTBUFOVERFLOW)); - msop_pkt_queue_.clear(); + queue->clear(); } } -template -inline void LidarDriverImpl::difopCallback(std::shared_ptr pkt) -{ - difop_pkt_queue_.push(pkt); -} - template inline void LidarDriverImpl::processMsop() { @@ -329,7 +326,7 @@ inline void LidarDriverImpl::processMsop() ndifop_count_ = 0; } - packetPut(pkt); + free_pkt_queue_.push(pkt); continue; } @@ -385,7 +382,7 @@ inline void LidarDriverImpl::processMsop() std::this_thread::sleep_for(std::chrono::milliseconds(300)); } - packetPut(pkt); + free_pkt_queue_.push(pkt); } #endif } @@ -404,7 +401,7 @@ inline void LidarDriverImpl::processDifop() runCallBack(pkt); - packetPut(pkt); + free_pkt_queue_.push(pkt); } } From 7d58405680f1a93918c9e75546ad4940d72e53d3 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 30 Nov 2021 11:27:30 +0800 Subject: [PATCH 032/379] refac: refac input --- src/rs_driver/api/lidar_driver.h | 20 +- src/rs_driver/driver/input/input_raw.hpp | 7 +- src/rs_driver/driver/input/input_sock.hpp | 6 +- src/rs_driver/driver/lidar_driver_impl.hpp | 36 +-- src/rs_driver/msg/packet.h | 38 ++-- test/CMakeLists.txt | 3 +- test/decoder_test.cpp | 244 +++++++++++++++++++++ test/packet_test.cpp | 15 ++ test/rs_driver_test.cpp | 241 -------------------- 9 files changed, 312 insertions(+), 298 deletions(-) create mode 100644 test/decoder_test.cpp create mode 100644 test/packet_test.cpp diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index 1c7a29e9..9244b600 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -103,22 +103,12 @@ class LidarDriver driver_ptr_->regRecvCallback(cb_put, cb_get); } - /** - * @brief Register the lidar scan message callback function to driver.When lidar scan message is ready, this function - * will be called - * @param callback The callback function - */ - inline void regRecvCallback(const std::function& callback) - { - driver_ptr_->regRecvCallback(callback); - } - /** * @brief Register the lidar difop packet message callback function to driver. When lidar difop packet message is * ready, this function will be called * @param callback The callback function */ - inline void regRecvCallback(const std::function& callback) + inline void regRecvCallback(const std::function& callback) { driver_ptr_->regRecvCallback(callback); } @@ -133,12 +123,12 @@ class LidarDriver } /** - * @brief Decode lidar difop messages - * @param pkt_msg The lidar difop packet + * @brief Decode lidar msop/difop messages + * @param pkt_msg The lidar msop/difop packet */ - inline void decodeDifopPkt(const PacketMsg& pkt_msg) + inline void decodePacket(const uint8_t* pkt, size_t size) { - driver_ptr_->decodeDifopPkt(pkt_msg); + driver_ptr_->decodePacket(pkt, size); } /** diff --git a/src/rs_driver/driver/input/input_raw.hpp b/src/rs_driver/driver/input/input_raw.hpp index 2b71141f..02f1f6dd 100644 --- a/src/rs_driver/driver/input/input_raw.hpp +++ b/src/rs_driver/driver/input/input_raw.hpp @@ -47,7 +47,7 @@ class InputRaw : public Input virtual void stop(){} virtual ~InputRaw(){} - void recvPacket(std::shared_ptr pkt); + void feedPacket(const uint8_t* data, size_t size); InputRaw(const RSInputParam& input_param, const std::function& excb) : Input(input_param, excb), pcap_offset_(ETH_HDR_LEN), difop_filter_valid_(false) @@ -65,8 +65,11 @@ class InputRaw : public Input long long msec_to_delay_; }; -inline void InputRaw::recvPacket(std::shared_ptr pkt) +inline void InputRaw::feedPacket(const uint8_t* data, size_t size) { + std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); + memcpy(pkt->data(), data, size); + pkt->setData(0, size); pushPacket(pkt); } diff --git a/src/rs_driver/driver/input/input_sock.hpp b/src/rs_driver/driver/input/input_sock.hpp index 844f28f0..f8ccd2a3 100644 --- a/src/rs_driver/driver/input/input_sock.hpp +++ b/src/rs_driver/driver/input/input_sock.hpp @@ -245,8 +245,7 @@ inline void InputSock::recvPacket() if (FD_ISSET(fds_[0], &rfds)) { std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); - pkt->resetData(); - ssize_t ret = recvfrom(fds_[0], pkt->data(), MAX_PKT_LEN, 0, NULL, NULL); + ssize_t ret = recvfrom(fds_[0], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret <= 0) { std::cout << "recv failed" << std::endl; @@ -259,8 +258,7 @@ inline void InputSock::recvPacket() else if (FD_ISSET(fds_[1], &rfds)) { std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); - pkt->resetData(); - ssize_t ret = recvfrom(fds_[1], pkt->data(), MAX_PKT_LEN, 0, NULL, NULL); + ssize_t ret = recvfrom(fds_[1], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret <= 0) break; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 191129db..319de842 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -63,9 +63,9 @@ class LidarDriverImpl void stop(); void regRecvCallback(const std::function)>& cb_put, const std::function(void)>& cb_get); - void regRecvCallback(const std::function& callback); + void regRecvCallback(const std::function& callback); void regExceptionCallback(const std::function& callback); - void decodePacket(const PacketMsg& msg); + void decodePacket(const uint8_t* pkt, size_t size); bool getLidarTemperature(double& input_temperature); private: @@ -82,13 +82,11 @@ class LidarDriverImpl private: RSDriverParam driver_param_; - std::function pkt_cb_; + std::function pkt_cb_; std::function err_cb_; - + std::function feed_pkt_cb_; std::shared_ptr> lidar_decoder_ptr_; - std::shared_ptr input_ptr_; - std::function)> feed_pkt_cb_; SyncQueue> free_pkt_queue_; SyncQueue> msop_pkt_queue_; SyncQueue> difop_pkt_queue_; @@ -142,6 +140,12 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) input_ptr_->regRecvCallback(std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), std::bind(&LidarDriverImpl::packetPut, this, std::placeholders::_1)); + if (param.input_type == InputType::RAW_PACKET) + { + InputRaw* inputRaw = dynamic_cast(input_ptr_.get()); + feed_pkt_cb_ = std::bind(&InputRaw::feedPacket, inputRaw, std::placeholders::_1, std::placeholders::_2); + } + if (!input_ptr_->init()) { goto failInputInit; @@ -203,7 +207,7 @@ inline void LidarDriverImpl::regRecvCallback(const std::function -inline void LidarDriverImpl::regRecvCallback(const std::function& callback) +inline void LidarDriverImpl::regRecvCallback(const std::function& callback) { pkt_cb_ = callback; } @@ -215,18 +219,9 @@ inline void LidarDriverImpl::regExceptionCallback(const std::funct } template -inline void LidarDriverImpl::decodePacket(const PacketMsg& pkt) +inline void LidarDriverImpl::decodePacket(const uint8_t* pkt, size_t size) { -#if 0 - if (1) - { - lidar_decoder_ptr_->processDifopPkt(pkt.packet.data(), pkt.packet.size()); - difop_flag_ = true; - } - else - { - } -#endif + feed_pkt_cb_(pkt, size); } template @@ -245,6 +240,7 @@ inline void LidarDriverImpl::runCallBack(std::shared_ptr& { if (pkt_cb_) { + pkt_cb_(pkt->data(), pkt->dataSize()); #if 0 msg.timestamp = getTime(); @@ -255,10 +251,12 @@ inline void LidarDriverImpl::runCallBack(std::shared_ptr& msg.seq = pkt_seq_++; #endif +#if 0 PacketMsg msg(pkt->len()); memcpy (msg.packet.data(), pkt->data(), pkt->len()); pkt_cb_(msg); +#endif } } @@ -390,6 +388,7 @@ inline void LidarDriverImpl::processMsop() template inline void LidarDriverImpl::processDifop() { +#if 0 while (!to_exit_difop_handle_) { std::shared_ptr pkt = difop_pkt_queue_.popWait(500000); @@ -403,6 +402,7 @@ inline void LidarDriverImpl::processDifop() free_pkt_queue_.push(pkt); } +#endif } } // namespace lidar diff --git a/src/rs_driver/msg/packet.h b/src/rs_driver/msg/packet.h index 270497a2..29f97f6d 100644 --- a/src/rs_driver/msg/packet.h +++ b/src/rs_driver/msg/packet.h @@ -32,8 +32,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once +#include #include -#include +#include namespace robosense { @@ -42,41 +43,44 @@ namespace lidar class Packet { public: - Packet(size_t cap) : off_(0), len_(0) + + Packet(size_t buf_size) { - buf_ = (uint8_t*)malloc(cap); + buf_.resize(buf_size); + buf_size_ = buf_size; } - void setData(size_t off, size_t len) + uint8_t* buf() { - off_ = off; - len_ = len; + return buf_.data(); } - void resetData() + size_t bufSize() const { - setData(0, 0); + return buf_size_; } - const uint8_t* data() const + uint8_t* data() { - return buf_ + off_; + return buf() + data_off_; } - uint8_t* data() + size_t dataSize() const { - return buf_ + off_; + return data_size_; } - size_t len() const + void setData(size_t data_off, size_t data_size) { - return len_; + data_off_ = data_off; + data_size_ = data_size; } private: - uint8_t* buf_; - size_t off_; - size_t len_; + std::vector buf_; + size_t buf_size_; + size_t data_off_; + size_t data_size_; }; } // namespace lidar } // namespace robosense diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 7c538ae6..04c077c8 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -8,7 +8,8 @@ include_directories(${GTEST_INCLUDE_DIRS}) include_directories(${DRIVER_INCLUDE_DIRS}) add_executable(rs_driver_test - rs_driver_test.cpp) + rs_driver_test.cpp + decoder_test.cpp) target_link_libraries(rs_driver_test ${GTEST_LIBRARIES} diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp new file mode 100644 index 00000000..0fe8800b --- /dev/null +++ b/test/decoder_test.cpp @@ -0,0 +1,244 @@ + +#include + +#include + +using namespace robosense::lidar; + +TEST(TestParseTime, calcTimeUTC) +{ + RSTimestampUTC2 ts = + {{0x01, 0x02, 0x03, 0x04, 0x05, 0x06}, {0x11, 0x22, 0x33, 0x44}}; + + ASSERT_EQ(calcTimeUTCWithNs(&ts), 0x010203040506 * 1000000 + 0x11223344/1000); + ASSERT_EQ(calcTimeUTCWithUs(&ts), 0x010203040506 * 1000000 + 0x11223344); + ASSERT_EQ(calcTimeUTCWithMs(&ts), 0x010203040506 * 1000000 + 0x1122 * 1000 + 0x3344); +} + +TEST(TestParseTime, calcTimeYMD) +{ + uint8_t ts[] = {0x15, 0x0a, 0x01, 0x01, 0x02, 0x03, 0x11, 0x22, 0x33, 0x44}; + + ASSERT_EQ(calcTimeYMD((RSTimestampYMD*)&ts), 1633021327399124); +} + +TEST(TestParseTime, calcTimeHost) +{ + calcTimeHost(); +} + +TEST(TestParseTemp, calcTemp) +{ + { + uint8_t temp[] = {0x18, 0x01}; + ASSERT_EQ(calcTemp((RsTemp*)&temp), 35); + } + + { + uint8_t temp[] = {0x18, 0x81}; + ASSERT_EQ(calcTemp((RsTemp*)&temp), -35); + } +} + +TEST(TestScanBlock, ctor) +{ + ScanBlock blk(10, 20); + ASSERT_EQ(blk.start(), 10); + ASSERT_EQ(blk.end(), 20); + + ASSERT_FALSE(blk.in(5)); + ASSERT_TRUE(blk.in(10)); + ASSERT_TRUE(blk.in(15)); + ASSERT_FALSE(blk.in(20)); + ASSERT_FALSE(blk.in(25)); +} + +TEST(TestScanBlock, ctorCrossZero) +{ + ScanBlock blk(35000, 10); + ASSERT_EQ(blk.start(), 35000); + ASSERT_EQ(blk.end(), 10); + + ASSERT_FALSE(blk.in(34999)); + ASSERT_TRUE(blk.in(35000)); + ASSERT_TRUE(blk.in(0)); + ASSERT_FALSE(blk.in(10)); + ASSERT_FALSE(blk.in(15)); +} + +TEST(TestScanBlock, ctorBeyondRound) +{ + ScanBlock blk(36100, 36200); + ASSERT_EQ(blk.start(), 100); + ASSERT_EQ(blk.end(), 200); +} + +TEST(TestDistanceBlock, ctor) +{ + DistanceBlock blk(0.5, 200, 0.75, 150); + ASSERT_EQ(blk.min(), 0.75); + ASSERT_EQ(blk.max(), 150); + + ASSERT_FALSE(blk.in(0.45)); + ASSERT_TRUE(blk.in(0.75)); + ASSERT_TRUE(blk.in(0.8)); + ASSERT_TRUE(blk.in(150)); + ASSERT_FALSE(blk.in(150.5)); +} + +TEST(TestDistanceBlock, ctorNoUseBlock) +{ + DistanceBlock blk(0.5, 200, 0.0, 200.5); + ASSERT_EQ(blk.min(), 0.5); + ASSERT_EQ(blk.max(), 200); +} + +TEST(TestChanAngles, genUserChan) +{ + std::vector vert_angles; + std::vector user_chans; + + vert_angles.push_back(100); + vert_angles.push_back(0); + vert_angles.push_back(-100); + vert_angles.push_back(200); + + ChanAngles::genUserChan (vert_angles, user_chans); + ASSERT_EQ(user_chans.size(), 4); + ASSERT_EQ(user_chans[0], 2); + ASSERT_EQ(user_chans[1], 1); + ASSERT_EQ(user_chans[2], 0); + ASSERT_EQ(user_chans[3], 3); +} + +TEST(TestChanAngles, loadFromFile) +{ + std::vector vert_angles, horiz_angles; + + ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); + ASSERT_EQ(vert_angles[0], 500); + ASSERT_EQ(vert_angles[1], 250); + ASSERT_EQ(vert_angles[2], 0); + ASSERT_EQ(vert_angles[3], -250); + + ASSERT_EQ(horiz_angles[0], 10); + ASSERT_EQ(horiz_angles[1], -20); + ASSERT_EQ(horiz_angles[2], 0); + ASSERT_EQ(horiz_angles[3], -100); + + ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); +} + +TEST(TestChanAngles, memberLoadFromFile) +{ + ChanAngles angles; + + ASSERT_EQ(angles.loadFromFile ("../rs_driver/test/res/angle.csv"), 0); + ASSERT_EQ(angles.chanSize(), 4); + ASSERT_EQ(angles.toUserChan(0), 3); + ASSERT_EQ(angles.toUserChan(1), 2); + ASSERT_EQ(angles.toUserChan(2), 1); + ASSERT_EQ(angles.toUserChan(3), 0); +} + +TEST(TestChanAngles, loadFromDifop) +{ + uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, + 0x01, 0x03, 0x04, + 0x01, 0x05, 0x06, + 0x00, 0x07, 0x08}; + uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, + 0x01, 0x33, 0x44, + 0x00, 0x55, 0x66, + 0x01, 0x77, 0x88}; + + std::vector vert_angles, horiz_angles; + + ASSERT_EQ(ChanAngles::loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4, + vert_angles, + horiz_angles), 0); + + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); + ASSERT_EQ(vert_angles[0], 258); + ASSERT_EQ(vert_angles[1], -772); + ASSERT_EQ(vert_angles[2], -1286); + ASSERT_EQ(vert_angles[3], 1800); + + ASSERT_EQ(horiz_angles[0], 4386); + ASSERT_EQ(horiz_angles[1], -13124); + ASSERT_EQ(horiz_angles[2], 21862); + ASSERT_EQ(horiz_angles[3], -30600); + + ASSERT_EQ(ChanAngles::loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4, + vert_angles, + horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); +} + +TEST(TestTrigon, ctor) +{ + Trigon trigon; + ASSERT_EQ(trigon.cos(6000), 0.5); + ASSERT_EQ(trigon.sin(3000), 0.5); +#if 0 + trigon.print(); +#endif +} + +TEST(TestSplitAngle, toSplit) +{ + { + SplitAngle sa(10); + ASSERT_FALSE(sa.toSplit(5)); + ASSERT_TRUE(sa.toSplit(15)); + } + + { + SplitAngle sa(10); + ASSERT_FALSE(sa.toSplit(5)); + ASSERT_TRUE(sa.toSplit(10)); + ASSERT_FALSE(sa.toSplit(15)); + } + + { + SplitAngle sa(10); + ASSERT_FALSE(sa.toSplit(10)); + ASSERT_FALSE(sa.toSplit(15)); + } +} + +TEST(TestSplitAngle, toSplit_Zero) +{ + { + SplitAngle sa(0); + ASSERT_FALSE(sa.toSplit(35999)); + ASSERT_TRUE(sa.toSplit(1)); + ASSERT_FALSE(sa.toSplit(2)); + } + + { + SplitAngle sa(0); + ASSERT_FALSE(sa.toSplit(35999)); + ASSERT_TRUE(sa.toSplit(0)); + ASSERT_FALSE(sa.toSplit(2)); + } + + { + SplitAngle sa(0); + ASSERT_FALSE(sa.toSplit(0)); + ASSERT_FALSE(sa.toSplit(2)); + } +} + diff --git a/test/packet_test.cpp b/test/packet_test.cpp new file mode 100644 index 00000000..c6ae5294 --- /dev/null +++ b/test/packet_test.cpp @@ -0,0 +1,15 @@ + +#include + +#include + +using namespace robosense::lidar; + +TEST(TestPacket, ctor) +{ + PacketMsg msg(100); + ASSERT(msg.) + + //ASSERT_EQ(calcTimeUTCWithMs(&ts), 0x010203040506 * 1000000 + 0x1122 * 1000 + 0x3344); +} + diff --git a/test/rs_driver_test.cpp b/test/rs_driver_test.cpp index 87cf51e5..9efd6294 100644 --- a/test/rs_driver_test.cpp +++ b/test/rs_driver_test.cpp @@ -1,247 +1,6 @@ #include -#include - -using namespace robosense::lidar; - -TEST(TestParseTime, calcTimeUTC) -{ - RSTimestampUTC2 ts = - {{0x01, 0x02, 0x03, 0x04, 0x05, 0x06}, {0x11, 0x22, 0x33, 0x44}}; - - ASSERT_EQ(calcTimeUTCWithNs(&ts), 0x010203040506 * 1000000 + 0x11223344/1000); - ASSERT_EQ(calcTimeUTCWithUs(&ts), 0x010203040506 * 1000000 + 0x11223344); - ASSERT_EQ(calcTimeUTCWithMs(&ts), 0x010203040506 * 1000000 + 0x1122 * 1000 + 0x3344); -} - -TEST(TestParseTime, calcTimeYMD) -{ - uint8_t ts[] = {0x15, 0x0a, 0x01, 0x01, 0x02, 0x03, 0x11, 0x22, 0x33, 0x44}; - - ASSERT_EQ(calcTimeYMD((RSTimestampYMD*)&ts), 1633021327399124); -} - -TEST(TestParseTime, calcTimeHost) -{ - calcTimeHost(); -} - -TEST(TestParseTemp, calcTemp) -{ - { - uint8_t temp[] = {0x18, 0x01}; - ASSERT_EQ(calcTemp((RsTemp*)&temp), 35); - } - - { - uint8_t temp[] = {0x18, 0x81}; - ASSERT_EQ(calcTemp((RsTemp*)&temp), -35); - } -} - -TEST(TestScanBlock, ctor) -{ - ScanBlock blk(10, 20); - ASSERT_EQ(blk.start(), 10); - ASSERT_EQ(blk.end(), 20); - - ASSERT_FALSE(blk.in(5)); - ASSERT_TRUE(blk.in(10)); - ASSERT_TRUE(blk.in(15)); - ASSERT_FALSE(blk.in(20)); - ASSERT_FALSE(blk.in(25)); -} - -TEST(TestScanBlock, ctorCrossZero) -{ - ScanBlock blk(35000, 10); - ASSERT_EQ(blk.start(), 35000); - ASSERT_EQ(blk.end(), 10); - - ASSERT_FALSE(blk.in(34999)); - ASSERT_TRUE(blk.in(35000)); - ASSERT_TRUE(blk.in(0)); - ASSERT_FALSE(blk.in(10)); - ASSERT_FALSE(blk.in(15)); -} - -TEST(TestScanBlock, ctorBeyondRound) -{ - ScanBlock blk(36100, 36200); - ASSERT_EQ(blk.start(), 100); - ASSERT_EQ(blk.end(), 200); -} - -TEST(TestDistanceBlock, ctor) -{ - DistanceBlock blk(0.5, 200, 0.75, 150); - ASSERT_EQ(blk.min(), 0.75); - ASSERT_EQ(blk.max(), 150); - - ASSERT_FALSE(blk.in(0.45)); - ASSERT_TRUE(blk.in(0.75)); - ASSERT_TRUE(blk.in(0.8)); - ASSERT_TRUE(blk.in(150)); - ASSERT_FALSE(blk.in(150.5)); -} - -TEST(TestDistanceBlock, ctorNoUseBlock) -{ - DistanceBlock blk(0.5, 200, 0.0, 200.5); - ASSERT_EQ(blk.min(), 0.5); - ASSERT_EQ(blk.max(), 200); -} - -TEST(TestChanAngles, genUserChan) -{ - std::vector vert_angles; - std::vector user_chans; - - vert_angles.push_back(100); - vert_angles.push_back(0); - vert_angles.push_back(-100); - vert_angles.push_back(200); - - ChanAngles::genUserChan (vert_angles, user_chans); - ASSERT_EQ(user_chans.size(), 4); - ASSERT_EQ(user_chans[0], 2); - ASSERT_EQ(user_chans[1], 1); - ASSERT_EQ(user_chans[2], 0); - ASSERT_EQ(user_chans[3], 3); -} - -TEST(TestChanAngles, loadFromFile) -{ - std::vector vert_angles, horiz_angles; - - ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); - ASSERT_EQ(vert_angles.size(), 4); - ASSERT_EQ(horiz_angles.size(), 4); - ASSERT_EQ(vert_angles[0], 500); - ASSERT_EQ(vert_angles[1], 250); - ASSERT_EQ(vert_angles[2], 0); - ASSERT_EQ(vert_angles[3], -250); - - ASSERT_EQ(horiz_angles[0], 10); - ASSERT_EQ(horiz_angles[1], -20); - ASSERT_EQ(horiz_angles[2], 0); - ASSERT_EQ(horiz_angles[3], -100); - - ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); - ASSERT_EQ(vert_angles.size(), 4); - ASSERT_EQ(horiz_angles.size(), 4); -} - -TEST(TestChanAngles, memberLoadFromFile) -{ - ChanAngles angles; - - ASSERT_EQ(angles.loadFromFile ("../rs_driver/test/res/angle.csv"), 0); - ASSERT_EQ(angles.chanSize(), 4); - ASSERT_EQ(angles.toUserChan(0), 3); - ASSERT_EQ(angles.toUserChan(1), 2); - ASSERT_EQ(angles.toUserChan(2), 1); - ASSERT_EQ(angles.toUserChan(3), 0); -} - -TEST(TestChanAngles, loadFromDifop) -{ - uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, - 0x01, 0x03, 0x04, - 0x01, 0x05, 0x06, - 0x00, 0x07, 0x08}; - uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, - 0x01, 0x33, 0x44, - 0x00, 0x55, 0x66, - 0x01, 0x77, 0x88}; - - std::vector vert_angles, horiz_angles; - - ASSERT_EQ(ChanAngles::loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4, - vert_angles, - horiz_angles), 0); - - ASSERT_EQ(vert_angles.size(), 4); - ASSERT_EQ(horiz_angles.size(), 4); - ASSERT_EQ(vert_angles[0], 258); - ASSERT_EQ(vert_angles[1], -772); - ASSERT_EQ(vert_angles[2], -1286); - ASSERT_EQ(vert_angles[3], 1800); - - ASSERT_EQ(horiz_angles[0], 4386); - ASSERT_EQ(horiz_angles[1], -13124); - ASSERT_EQ(horiz_angles[2], 21862); - ASSERT_EQ(horiz_angles[3], -30600); - - ASSERT_EQ(ChanAngles::loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4, - vert_angles, - horiz_angles), 0); - ASSERT_EQ(vert_angles.size(), 4); - ASSERT_EQ(horiz_angles.size(), 4); -} - -TEST(TestTrigon, ctor) -{ - Trigon trigon; - ASSERT_EQ(trigon.cos(6000), 0.5); - ASSERT_EQ(trigon.sin(3000), 0.5); -#if 0 - trigon.print(); -#endif -} - -TEST(TestSplitAngle, toSplit) -{ - { - SplitAngle sa(10); - ASSERT_FALSE(sa.toSplit(5)); - ASSERT_TRUE(sa.toSplit(15)); - } - - { - SplitAngle sa(10); - ASSERT_FALSE(sa.toSplit(5)); - ASSERT_TRUE(sa.toSplit(10)); - ASSERT_FALSE(sa.toSplit(15)); - } - - { - SplitAngle sa(10); - ASSERT_FALSE(sa.toSplit(10)); - ASSERT_FALSE(sa.toSplit(15)); - } -} - -TEST(TestSplitAngle, toSplit_Zero) -{ - { - SplitAngle sa(0); - ASSERT_FALSE(sa.toSplit(35999)); - ASSERT_TRUE(sa.toSplit(1)); - ASSERT_FALSE(sa.toSplit(2)); - } - - { - SplitAngle sa(0); - ASSERT_FALSE(sa.toSplit(35999)); - ASSERT_TRUE(sa.toSplit(0)); - ASSERT_FALSE(sa.toSplit(2)); - } - - { - SplitAngle sa(0); - ASSERT_FALSE(sa.toSplit(0)); - ASSERT_FALSE(sa.toSplit(2)); - } -} - int main(int argc, char** argv) { ::testing::InitGoogleTest(&argc, argv); From d7962d6dd2e0fb523622fe7ce3acbfc1ed6c4073 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 30 Nov 2021 14:33:46 +0800 Subject: [PATCH 033/379] refac: refactory driver_impl --- src/rs_driver/driver/decoder/decoder.hpp | 75 +++++++----- src/rs_driver/driver/decoder/decoder_RS32.hpp | 2 +- src/rs_driver/driver/lidar_driver_impl.hpp | 115 +++--------------- 3 files changed, 57 insertions(+), 135 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 8c073fbd..abbe7b4c 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -49,10 +49,12 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #define _USE_MATH_DEFINES // for VC++, required to use const M_IP in #endif +#if 0 /*Eigen*/ #ifdef ENABLE_TRANSFORM #include #endif +#endif namespace robosense { @@ -96,45 +98,17 @@ class Decoder public: virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size); - virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size) = 0; virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual RSDecoderResult TsMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual ~Decoder() = default; - explicit Decoder(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param); - void toSplit(uint16_t azimuth, double chan_ts); void regRecvCallback(const std::function)>& cb_put, - const std::function(void)>& cb_get) - { - point_cloud_cb_put_ = cb_put; - point_cloud_cb_get_ = cb_get; - } + const std::function(void)>& cb_get); - std::shared_ptr getPointCloud() - { - std::shared_ptr pc; - - while (1) - { - if (point_cloud_cb_get_ != nullptr) - pc = point_cloud_cb_get_(); - - if (pc) - { - pc->points.resize(0); - return pc; - } - -#if 0 - reportError(Error(ERRCODE_POINTCLOUDNULL)); - std::this_thread::sleep_for(std::chrono::milliseconds(300)); -#endif - }; - } + std::shared_ptr getPointCloud(); uint16_t height() { @@ -143,7 +117,7 @@ class Decoder double getLidarTemperature() { - return current_temperature_; + return temperature_; } uint64_t msecToDelay() @@ -155,6 +129,9 @@ class Decoder { } + explicit Decoder(const RSDecoderParam& param, + const LidarConstantParameter& lidar_const_param); + protected: #if 0 @@ -186,7 +163,7 @@ class Decoder unsigned int protocol_ver_; unsigned int rpm_; RSEchoMode echo_mode_; - double current_temperature_; + double temperature_; bool difop_ready_; int last_azimuth_; @@ -219,7 +196,7 @@ inline Decoder::Decoder(const RSDecoderParam& param, , protocol_ver_(0) , rpm_(600) , echo_mode_(ECHO_SINGLE) - , current_temperature_(0) + , temperature_(0) , difop_ready_(false) , last_azimuth_(-36001) , pkt_count_(0) @@ -235,6 +212,38 @@ inline Decoder::Decoder(const RSDecoderParam& param, } } +template +void Decoder::regRecvCallback( + const std::function)>& cb_put, + const std::function(void)>& cb_get) +{ + point_cloud_cb_put_ = cb_put; + point_cloud_cb_get_ = cb_get; +} + +template +std::shared_ptr Decoder::getPointCloud() +{ + std::shared_ptr pc; + + while (1) + { + if (point_cloud_cb_get_ != nullptr) + pc = point_cloud_cb_get_(); + + if (pc) + { + pc->points.resize(0); + return pc; + } + +#if 0 + reportError(Error(ERRCODE_POINTCLOUDNULL)); + std::this_thread::sleep_for(std::chrono::milliseconds(300)); +#endif + }; +} + template RSDecoderResult Decoder::processMsopPkt(const uint8_t* pkt, size_t size) { diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 45a6dd83..4591372a 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -139,7 +139,7 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p return RSDecoderResult::WRONG_PKT_HEADER; } - this->current_temperature_ = calcTemp(&(pkt.header.temp)); + this->temperature_ = calcTemp(&(pkt.header.temp)); double block_timestamp = 0; double chan_ts = block_timestamp; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 319de842..75a0eb98 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -70,8 +70,7 @@ class LidarDriverImpl private: - void runCallBack(std::shared_ptr msg); - void runCallBack(std::shared_ptr& pkt); + void runCallBack(std::shared_ptr pkt); void reportError(const Error& error); std::shared_ptr packetGet(size_t size); @@ -92,11 +91,9 @@ class LidarDriverImpl SyncQueue> difop_pkt_queue_; std::thread msop_handle_thread_; std::thread difop_handle_thread_; - bool to_exit_msop_handle_; - bool to_exit_difop_handle_; + bool to_exit_handle_; bool init_flag_; bool start_flag_; - bool difop_flag_; uint32_t pkt_seq_; uint32_t ndifop_count_; }; @@ -114,7 +111,7 @@ inline std::string LidarDriverImpl::getVersion() template inline LidarDriverImpl::LidarDriverImpl() - : init_flag_(false), start_flag_(false), difop_flag_(false), pkt_seq_(0), ndifop_count_(0) + : init_flag_(false), start_flag_(false), pkt_seq_(0), ndifop_count_(0) { } @@ -170,9 +167,8 @@ inline bool LidarDriverImpl::start() if (!init_flag_) return false; - to_exit_msop_handle_ = false; + to_exit_handle_ = false; msop_handle_thread_ = std::thread(std::bind(&LidarDriverImpl::processMsop, this)); - to_exit_difop_handle_ = false; difop_handle_thread_ = std::thread(std::bind(&LidarDriverImpl::processDifop, this)); input_ptr_->start(); @@ -189,8 +185,7 @@ inline void LidarDriverImpl::stop() if (start_flag_) { - to_exit_msop_handle_ = true; - to_exit_difop_handle_ = true; + to_exit_handle_ = true; msop_handle_thread_.join(); difop_handle_thread_.join(); @@ -236,34 +231,21 @@ inline bool LidarDriverImpl::getLidarTemperature(double& input_tem } template -inline void LidarDriverImpl::runCallBack(std::shared_ptr& pkt) +inline void LidarDriverImpl::runCallBack(std::shared_ptr pkt) { if (pkt_cb_) { pkt_cb_(pkt->data(), pkt->dataSize()); - -#if 0 - msg.timestamp = getTime(); - if (driver_param_.decoder_param.use_lidar_clock == true) - { - msg.timestamp = lidar_decoder_ptr_->getLidarTime(msg.packets.back().packet.data()); - } - msg.seq = pkt_seq_++; -#endif - -#if 0 - PacketMsg msg(pkt->len()); - memcpy (msg.packet.data(), pkt->data(), pkt->len()); - - pkt_cb_(msg); -#endif } } template inline void LidarDriverImpl::reportError(const Error& error) { + if (err_cb_) + { err_cb_(error); + } } template @@ -306,103 +288,34 @@ inline void LidarDriverImpl::packetPut(std::shared_ptr pkt template inline void LidarDriverImpl::processMsop() { -#if 0 - //point_cloud_ = getPointCloud(); - - while (!to_exit_msop_handle_) + while (!to_exit_handle_) { std::shared_ptr pkt = msop_pkt_queue_.popWait(1000); if (pkt.get() == NULL) continue; - if (!difop_flag_ && driver_param_.wait_for_difop) - { - ndifop_count_++; - if (ndifop_count_ > 240) - { - reportError(Error(ERRCODE_NODIFOPRECV)); - ndifop_count_ = 0; - } - - free_pkt_queue_.push(pkt); - continue; - } - - int height = 1; - int ret = lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->len(), point_cloud_->points, height); - -#ifdef ENABLE_PUBLISH_RAW_MSG - PacketMsg msg(pkt->len()); - memcpy (msg.packet.data(), pkt->data(), pkt->len()); - scan_ptr_.packets.emplace_back(msg); -#endif - - if (ret >= 0) - { - if (ret == FRAME_SPLIT) - { - T_PointCloud& msg = *point_cloud_; - setPointCloudHeader(msg, height); - if (driver_param_.decoder_param.use_lidar_clock == true) - { - msg.timestamp = lidar_decoder_ptr_->getLidarTime(pkt->data()); - } - else - { - msg.timestamp = getTime(); - } - - if (msg.points.size() == 0) - { - reportError(Error(ERRCODE_ZEROPOINTS)); - } - else - { - runCallBack(point_cloud_); - } - -#ifdef ENABLE_PUBLISH_RAW_MSG - setScanMsgHeader(scan_ptr_); - runCallBack(scan_ptr_); - scan_ptr_.packets.resize(0); -#endif - - //point_cloud_ = getPointCloud(); - } - } - else if (ret < 0) - { - if (ret == WRONG_PKT_LENGTH) - reportError(Error(ERRCODE_WRONGPKTLENGTH)); - else - reportError(Error(ERRCODE_WRONGPKTHEADER)); - - std::this_thread::sleep_for(std::chrono::milliseconds(300)); - } + lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); + runCallBack(pkt); free_pkt_queue_.push(pkt); } -#endif } template inline void LidarDriverImpl::processDifop() { -#if 0 - while (!to_exit_difop_handle_) + while (!to_exit_handle_) { std::shared_ptr pkt = difop_pkt_queue_.popWait(500000); if (pkt.get() == NULL) continue; - lidar_decoder_ptr_->processDifopPkt(pkt->data(), pkt->len()); - difop_flag_ = true; + lidar_decoder_ptr_->processDifopPkt(pkt->data(), pkt->dataSize()); runCallBack(pkt); free_pkt_queue_.push(pkt); } -#endif } } // namespace lidar From ddbc807be328235682d94de34526d9a564f0f3cf Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 30 Nov 2021 16:11:08 +0800 Subject: [PATCH 034/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 41 ++++++++++--- src/rs_driver/driver/decoder/decoder_RS32.hpp | 33 ++++++++-- .../driver/decoder/decoder_base_opt.hpp | 26 -------- .../driver/decoder/decoder_factory.hpp | 30 +++------ src/rs_driver/msg/packet.h | 1 + test/CMakeLists.txt | 2 + test/packet_test.cpp | 15 +++-- test/sync_queue_test.cpp | 61 +++++++++++++++++++ 8 files changed, 144 insertions(+), 65 deletions(-) create mode 100644 test/sync_queue_test.cpp diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index abbe7b4c..a0ed5944 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -38,12 +38,12 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include -#include -#include -#include #include +#include +#include #include #include +#include #ifndef _USE_MATH_DEFINES #define _USE_MATH_DEFINES // for VC++, required to use const M_IP in @@ -92,6 +92,33 @@ enum RSDecoderResult DIFOP_NOT_READY = -5 }; +typedef struct +{ + // identity + uint64_t MSOP_ID; + uint64_t DIFOP_ID; + uint64_t BLOCK_ID; + + // duration + uint32_t PKT_RATE; // to be deleted + uint16_t BLOCKS_PER_PKT; + uint16_t BLOCKS_PER_FRAME; + uint16_t CHANNELS_PER_BLOCK; + uint16_t LASER_NUM; + + // firing + float DSR_TOFFSET; // to be deleted + float FIRING_FREQUENCY; // to be deleted + + // distance + float DIS_RESOLUTION; + + // lens center + float RX; + float RY; + float RZ; +} LidarConstParam; + template class Decoder { @@ -130,7 +157,7 @@ class Decoder } explicit Decoder(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param); + const LidarConstParam& lidar_const_param); protected: @@ -143,7 +170,7 @@ class Decoder protected: - const LidarConstantParameter lidar_const_param_; + LidarConstParam lidar_const_param_; RSDecoderParam param_; uint16_t height_; uint64_t msec_to_delay_; @@ -179,8 +206,8 @@ class Decoder }; template -inline Decoder::Decoder(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param) +inline Decoder::Decoder(const RSDecoderParam& param, + const LidarConstParam& lidar_const_param) : lidar_const_param_(lidar_const_param) , param_(param) , height_(0) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 4591372a..c3fb77a8 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -88,18 +88,39 @@ class DecoderRS32 : public Decoder virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size); virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, size_t size); virtual RSDecoderResult TsMsopPkt(const uint8_t* pkt, size_t size); - virtual uint64_t usecToDelay() - {return 0;} + virtual uint64_t usecToDelay() {return 0;} virtual ~DecoderRS32() = default; - explicit DecoderRS32(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); + explicit DecoderRS32(const RSDecoderParam& param); + + static LidarConstParam getConstParam() + { + LidarConstParam param; + param.MSOP_ID = 0xA050A55A0A05AA55; + param.DIFOP_ID = 0x555511115A00FFA5; + param.BLOCK_ID = 0xEEFF; + param.PKT_RATE = 1500; + param.BLOCKS_PER_PKT = 12; + + param.CHANNELS_PER_BLOCK = 32; + param.LASER_NUM = 32; + + param.DSR_TOFFSET = 1.44; + param.FIRING_FREQUENCY = 0.018; + param.DIS_RESOLUTION = 0.005; + + param.RX = 0.03997; + param.RY = -0.01087; + param.RZ = 0; + + return param; + } }; template -inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param) - : Decoder(param, lidar_const_param) +inline DecoderRS32::DecoderRS32(const RSDecoderParam& param) + : Decoder(param, getConstParam()) { } diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 85d5ccea..2ca5a560 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -49,32 +49,6 @@ namespace lidar { #pragma pack(push, 1) -typedef struct -{ - // identity - uint64_t MSOP_ID; - uint64_t DIFOP_ID; - uint64_t BLOCK_ID; - - // duration - uint32_t PKT_RATE; // to be deleted - uint16_t BLOCKS_PER_PKT; - uint16_t BLOCKS_PER_FRAME; - uint16_t CHANNELS_PER_BLOCK; - uint16_t LASER_NUM; - - // firing - float DSR_TOFFSET; // to be deleted - float FIRING_FREQUENCY; // to be deleted - - // distance - float DIS_RESOLUTION; - - // lens center - float RX; - float RY; - float RZ; -} LidarConstantParameter; typedef struct { diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index fedd39d8..656fe19c 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -52,18 +52,6 @@ class DecoderFactory static std::shared_ptr> createDecoder(LidarType type, const RSDecoderParam& param); - -private: - static const LidarConstantParameter getRS32ConstantParam(); -#if 0 - static const LidarConstantParameter getRS16ConstantParam(); - static const LidarConstantParameter getRSBPConstantParam(); - static const LidarConstantParameter getRS80ConstantParam(); - static const LidarConstantParameter getRS128ConstantParam(); - static const LidarConstantParameter getRSM1ConstantParam(); - static const LidarConstantParameter getRSHELIOSConstantParam(); - static const LidarConstantParameter getRSROCKConstantParam(); -#endif }; template @@ -76,30 +64,30 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam { #if 0 case LidarType::RS16: - ret_ptr = std::make_shared>(param.decoder_param, getRS16ConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param); break; #endif case LidarType::RS32: - ret_ptr = std::make_shared>(param, getRS32ConstantParam()); + ret_ptr = std::make_shared>(param); break; #if 0 case LidarType::RSBP: - ret_ptr = std::make_shared>(param.decoder_param, getRSBPConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param); break; case LidarType::RS128: - ret_ptr = std::make_shared>(param.decoder_param, getRS128ConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param); break; case LidarType::RS80: - ret_ptr = std::make_shared>(param.decoder_param, getRS80ConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param); break; case LidarType::RSM1: - ret_ptr = std::make_shared>(param.decoder_param, getRSM1ConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param); break; case LidarType::RSHELIOS: - ret_ptr = std::make_shared>(param.decoder_param, getRSHELIOSConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param); break; case LidarType::RSROCK: - ret_ptr = std::make_shared>(param.decoder_param, getRSROCKConstantParam()); + ret_ptr = std::make_shared>(param.decoder_param); break; #endif default: @@ -130,7 +118,6 @@ inline const LidarConstantParameter DecoderFactory::getRS16Constan ret_param.RZ = 0; return ret_param; } -#endif template inline const LidarConstantParameter DecoderFactory::getRS32ConstantParam() @@ -156,7 +143,6 @@ inline const LidarConstantParameter DecoderFactory::getRS32Constan return ret_param; } -#if 0 template inline const LidarConstantParameter DecoderFactory::getRSBPConstantParam() { diff --git a/src/rs_driver/msg/packet.h b/src/rs_driver/msg/packet.h index 29f97f6d..929e8239 100644 --- a/src/rs_driver/msg/packet.h +++ b/src/rs_driver/msg/packet.h @@ -45,6 +45,7 @@ class Packet public: Packet(size_t buf_size) + : data_off_(0), data_size_(0) { buf_.resize(buf_size); buf_size_ = buf_size; diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 04c077c8..e911d59b 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -9,6 +9,8 @@ include_directories(${DRIVER_INCLUDE_DIRS}) add_executable(rs_driver_test rs_driver_test.cpp + packet_test.cpp + sync_queue_test.cpp decoder_test.cpp) target_link_libraries(rs_driver_test diff --git a/test/packet_test.cpp b/test/packet_test.cpp index c6ae5294..219d908b 100644 --- a/test/packet_test.cpp +++ b/test/packet_test.cpp @@ -1,15 +1,22 @@ #include -#include +#include using namespace robosense::lidar; TEST(TestPacket, ctor) { - PacketMsg msg(100); - ASSERT(msg.) + Packet pkt(100); - //ASSERT_EQ(calcTimeUTCWithMs(&ts), 0x010203040506 * 1000000 + 0x1122 * 1000 + 0x3344); + ASSERT_TRUE(pkt.buf() != NULL); + ASSERT_EQ(pkt.bufSize(), 100); + + ASSERT_EQ(pkt.data(), pkt.buf()); + ASSERT_EQ(pkt.dataSize(), 0); + + pkt.setData(5, 10); + ASSERT_EQ(pkt.data(), pkt.buf()+5); + ASSERT_EQ(pkt.dataSize(), 10); } diff --git a/test/sync_queue_test.cpp b/test/sync_queue_test.cpp new file mode 100644 index 00000000..af5931f3 --- /dev/null +++ b/test/sync_queue_test.cpp @@ -0,0 +1,61 @@ + +#include + +#include + +using namespace robosense::lidar; + +TEST(TestSyncQueue, emptyPop) +{ + SyncQueue> queue; + + ASSERT_TRUE(queue.pop().get() == NULL); + ASSERT_TRUE(queue.popWait(1000).get() == NULL); +} + +TEST(TestSyncQueue, nulPtrPop) +{ + SyncQueue> queue; + + { + std::shared_ptr n_ptr; + ASSERT_EQ(queue.push(n_ptr), 1); + ASSERT_TRUE(queue.pop().get() == NULL); + } + + { + std::shared_ptr n_ptr; + ASSERT_EQ(queue.push(n_ptr), 1); + ASSERT_TRUE(queue.popWait(1000).get() == NULL); + } +} + +TEST(TestSyncQueue, valPtrPop) +{ + SyncQueue> queue; + + { + std::shared_ptr v_ptr = std::make_shared(100); + ASSERT_EQ(queue.push(v_ptr), 1); + ASSERT_TRUE(queue.pop().get() != NULL); + } + + { + std::shared_ptr v_ptr = std::make_shared(100); + ASSERT_EQ(queue.push(v_ptr), 1); + ASSERT_TRUE(queue.popWait(1000).get() != NULL); + } +} + +TEST(TestSyncQueue, clear) +{ + SyncQueue> queue; + + { + std::shared_ptr v_ptr = std::make_shared(100); + ASSERT_EQ(queue.push(v_ptr), 1); + ASSERT_EQ(queue.push(v_ptr), 2); + queue.clear(); + ASSERT_EQ(queue.push(v_ptr), 1); + } +} From cf4921ecf84ee6900c3492df601bd07e49d8199c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 2 Dec 2021 10:43:49 +0800 Subject: [PATCH 035/379] feat: update version to 1.4.2 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 072ebbd5..408d9914 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.4.1) +project(rs_driver VERSION 1.4.2) #============================= # Compile Demos&Tools From cf79ec8e28b93beee636937bd6bd7e934bee35e8 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 3 Dec 2021 09:35:26 +0800 Subject: [PATCH 036/379] refac: refac decoder --- CMakeLists.txt | 4 +- src/rs_driver/driver/decoder/decoder.hpp | 135 ++++++++---------- src/rs_driver/driver/decoder/decoder_RS32.hpp | 20 ++- .../driver/decoder/decoder_factory.hpp | 7 +- src/rs_driver/driver/driver_param.h | 18 ++- src/rs_driver/driver/lidar_driver_impl.hpp | 2 +- 6 files changed, 85 insertions(+), 101 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 7f836b2d..dfa7b59c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -26,7 +26,9 @@ option(ENABLE_TRANSFORM "Enable transform functions" OFF) #======================== # Project setup #======================== -set(CMAKE_BUILD_TYPE Release) +if (CMAKE_BUILD_TYPE STREQUAL "") + set(CMAKE_BUILD_TYPE Release) +endif() #======================== # Platform cross setup diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index a0ed5944..bbc35ced 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -49,13 +49,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #define _USE_MATH_DEFINES // for VC++, required to use const M_IP in #endif -#if 0 -/*Eigen*/ -#ifdef ENABLE_TRANSFORM -#include -#endif -#endif - namespace robosense { namespace lidar @@ -67,9 +60,6 @@ const size_t MEMS_MSOP_LEN = 1210; const size_t MEMS_DIFOP_LEN = 256; const size_t ROCK_MSOP_LEN = 1236; -constexpr float RS_ANGLE_RESOLUTION = 0.01; -constexpr float MICRO = 1000000.0; -constexpr float NANO = 1000000000.0; constexpr int RS_ONE_ROUND = 36000; constexpr uint16_t PROTOCOL_VER_0 = 0x00; @@ -127,7 +117,6 @@ class Decoder virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size); virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size) = 0; virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; - virtual RSDecoderResult TsMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual ~Decoder() = default; void toSplit(uint16_t azimuth, double chan_ts); @@ -137,15 +126,19 @@ class Decoder std::shared_ptr getPointCloud(); + void putPointCloud(std::shared_ptr msg, double chan_ts); + +#if 0 uint16_t height() { return height_; } - double getLidarTemperature() + double getTemperature() { return temperature_; } +#endif uint64_t msecToDelay() { @@ -157,14 +150,11 @@ class Decoder } explicit Decoder(const RSDecoderParam& param, + const std::function& excb, const LidarConstParam& lidar_const_param); protected: -#if 0 - RSEchoMode getEchoMode(const LidarType& type, const uint8_t& return_mode); -#endif - template void decodeDifopCommon(const T_Difop& pkt); @@ -172,6 +162,7 @@ class Decoder LidarConstParam lidar_const_param_; RSDecoderParam param_; + std::function excb_; uint16_t height_; uint64_t msec_to_delay_; uint32_t msop_pkt_len_; @@ -207,15 +198,17 @@ class Decoder template inline Decoder::Decoder(const RSDecoderParam& param, + const std::function& excb, const LidarConstParam& lidar_const_param) : lidar_const_param_(lidar_const_param) , param_(param) + , excb_(excb) , height_(0) , msop_pkt_len_(MECH_PKT_LEN) , difop_pkt_len_(MECH_PKT_LEN) , distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance) , scan_block_(param.start_angle * 100, param.end_angle * 100) - , split_angle_(param.cut_angle * 100) + , split_angle_(param.split_angle * 100) , block_duration_(0) , azi_diff_between_block_theoretical_(20) , fov_time_jump_diff_(0) @@ -264,93 +257,87 @@ std::shared_ptr Decoder::getPointCloud() return pc; } -#if 0 - reportError(Error(ERRCODE_POINTCLOUDNULL)); - std::this_thread::sleep_for(std::chrono::milliseconds(300)); -#endif + excb_(Error(ERRCODE_POINTCLOUDNULL)); + //std::this_thread::sleep_for(std::chrono::milliseconds(300)); }; } -template -RSDecoderResult Decoder::processMsopPkt(const uint8_t* pkt, size_t size) -{ - if (param_.wait_for_difop && !difop_ready_) - { - return RSDecoderResult::DIFOP_NOT_READY; - } - - return decodeMsopPkt(pkt, size); -} - template inline void Decoder::toSplit(uint16_t azimuth, double chan_ts) { bool split = false; - split = split_angle_.toSplit(azimuth); - -#if 1 -#if 0 - if (azimuth < this->last_azimuth_) + switch (param_.split_frame_mode) { - this->last_azimuth_ -= RS_ONE_ROUND; - } + case SplitFrameMode::SPLIT_BY_ANGLE: + split = split_angle_.toSplit(azimuth); + break; - if ((this->last_azimuth_ != -36001) && - (this->last_azimuth_ < this->cut_angle_) && (azimuth >= this->cut_angle_)) - { - this->last_azimuth_ = azimuth; - this->pkt_count_ = 0; - return FRAME_SPLIT; - } + case SplitFrameMode::SPLIT_BY_FIXED_PKTS: - this->last_azimuth_ = azimuth; -#endif + if (this->pkt_count_ >= this->pkts_per_frame_) + { + this->pkt_count_ = 0; + split = true; + } -#else - if (this->pkt_count_ >= this->pkts_per_frame_) - { - this->pkt_count_ = 0; - split = true; - } + break; + case SplitFrameMode::SPLIT_BY_CUSTOM_PKTS: - if (this->pkt_count_ >= this->param_.num_pkts_split) - { - this->pkt_count_ = 0; - split = true; + if (this->pkt_count_ >= this->param_.num_pkts_split) + { + this->pkt_count_ = 0; + split = true; + } + + break; + + default: + break; } -#endif if (split) { - T_PointCloud& msg = *point_cloud_; + putPointCloud(point_cloud_, chan_ts); + } +} - msg.seq = point_cloud_seq_++; - msg.timestamp = chan_ts; - //msg.frame_id = param_.frame_id; - msg.is_dense = param_.is_dense; - if (msg.is_dense) +template +void Decoder::putPointCloud(std::shared_ptr msg, double chan_ts) +{ + msg->seq = point_cloud_seq_++; + msg->timestamp = chan_ts; + msg->is_dense = param_.dense_points; + if (msg->is_dense) { - msg.height = 1; - msg.width = msg.points.size(); + msg->height = 1; + msg->width = msg->points.size(); } else { - msg.height = height_; - msg.width = msg.points.size() / msg.height; + msg->height = height_; + msg->width = msg->points.size() / msg->height; } - if (msg.points.size() == 0) + if (msg->points.size() == 0) { -#if 0 - reportError(Error(ERRCODE_ZEROPOINTS)); -#endif + excb_(Error(ERRCODE_ZEROPOINTS)); } else { - point_cloud_cb_put_(point_cloud_); + point_cloud_cb_put_(msg); } +} + +template +RSDecoderResult Decoder::processMsopPkt(const uint8_t* pkt, size_t size) +{ + if (param_.wait_for_difop && !difop_ready_) + { + return RSDecoderResult::DIFOP_NOT_READY; } + + return decodeMsopPkt(pkt, size); } template diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index c3fb77a8..61e485ba 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -87,11 +87,11 @@ class DecoderRS32 : public Decoder virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size); virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, size_t size); - virtual RSDecoderResult TsMsopPkt(const uint8_t* pkt, size_t size); virtual uint64_t usecToDelay() {return 0;} virtual ~DecoderRS32() = default; - explicit DecoderRS32(const RSDecoderParam& param); + explicit DecoderRS32(const RSDecoderParam& param, + const std::function& excb); static LidarConstParam getConstParam() { @@ -119,8 +119,9 @@ class DecoderRS32 : public Decoder }; template -inline DecoderRS32::DecoderRS32(const RSDecoderParam& param) - : Decoder(param, getConstParam()) +inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, + const std::function& excb) + : Decoder(param, excb, getConstParam()) { } @@ -186,6 +187,8 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p uint16_t cur_azi = ntohs(block.azimuth); + this->toSplit(cur_azi, chan_ts); + #if 0 if (this->echo_mode_ == ECHO_DUAL) { @@ -267,7 +270,7 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p setIntensity(point, intensity); pointValid = true; } - else if (!this->param_.is_dense) + else if (!this->param_.dense_points) { setX(point, NAN); setY(point, NAN); @@ -284,17 +287,10 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p } } - this->toSplit(cur_azi, chan_ts); } return RSDecoderResult::DECODE_OK; } -template -inline RSDecoderResult DecoderRS32::TsMsopPkt(const uint8_t* packet, size_t size) -{ - return RSDecoderResult::DECODE_OK; -} - } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 656fe19c..97d32954 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -51,12 +51,13 @@ class DecoderFactory public: static std::shared_ptr> createDecoder(LidarType type, - const RSDecoderParam& param); + const RSDecoderParam& param, const std::function& excb); }; template inline std::shared_ptr> -DecoderFactory::createDecoder(LidarType type, const RSDecoderParam& param) +DecoderFactory::createDecoder(LidarType type, const RSDecoderParam& param, + const std::function& excb) { std::shared_ptr> ret_ptr; @@ -68,7 +69,7 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam break; #endif case LidarType::RS32: - ret_ptr = std::make_shared>(param); + ret_ptr = std::make_shared>(param, excb); break; #if 0 case LidarType::RSBP: diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index 5bc40ab5..f5ab9d04 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -107,20 +107,18 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter { bool config_from_file = false; std::string angle_path = ""; ///< Path of angle calibration files(angle.csv). Only used for internal debugging. - float max_distance = 200.0f; ///< Max distance of point cloud range float min_distance = 0.2f; ///< Minimum distance of point cloud range + float max_distance = 200.0f; ///< Max distance of point cloud range float start_angle = 0.0f; ///< Start angle of point cloud float end_angle = 360.0f; ///< End angle of point cloud - SplitFrameMode split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; ///< 1: Split frames by cut_angle; ///< 2: Split frames by fixed number of packets; ///< 3: Split frames by custom number of packets (num_pkts_split) - uint32_t num_pkts_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 - float cut_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 - - bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet - bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp - bool is_dense = false; ///< true: discard NAN points; false: reserve NAN points + float split_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 + uint32_t num_pkts_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 + bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp + bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points #if 0 RSTransformParam transform_param; ///< Used to transform points RSCameraTriggerParam trigger_param; ///< Used to trigger camera @@ -142,9 +140,9 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter RS_INFOL << "wait_for_difop: " << wait_for_difop << RS_REND; RS_INFOL << "use_lidar_clock: " << use_lidar_clock << RS_REND; RS_INFOL << "split_frame_mode: " << split_frame_mode << RS_REND; + RS_INFOL << "split_angle: " << split_angle << RS_REND; RS_INFOL << "num_pkts_split: " << num_pkts_split << RS_REND; - RS_INFOL << "cut_angle: " << cut_angle << RS_REND; - RS_INFOL << "is_dense: " << is_dense << RS_REND; + RS_INFOL << "dense_points: " << dense_points << RS_REND; RS_INFO << "------------------------------------------------------" << RS_REND; } diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 75a0eb98..19129ccc 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -130,7 +130,7 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) } lidar_decoder_ptr_ = DecoderFactory::createDecoder - (param.lidar_type, param.decoder_param); + (param.lidar_type, param.decoder_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); input_ptr_ = InputFactory::createInput( param.input_type, param.input_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1), 0); From 8a8d0733fedfd1ed6ddd62bdffb6a3737a056505 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 3 Dec 2021 11:04:06 +0800 Subject: [PATCH 037/379] refac: refac decoder --- src/rs_driver/api/lidar_driver.h | 6 +- src/rs_driver/driver/decoder/decoder.hpp | 114 ++++++++---------- src/rs_driver/driver/decoder/decoder_RS32.hpp | 14 +-- src/rs_driver/driver/driver_param.h | 8 +- src/rs_driver/driver/input/input.hpp | 3 +- src/rs_driver/driver/input/input_pcap.hpp | 1 - src/rs_driver/driver/lidar_driver_impl.hpp | 12 +- 7 files changed, 71 insertions(+), 87 deletions(-) diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index 9244b600..257ac4cb 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -133,12 +133,12 @@ class LidarDriver /** * @brief Get the current lidar temperature - * @param input_temperature The variable to store lidar temperature + * @param temp The variable to store lidar temperature * @return if get temperature successfully, return true; else return false */ - inline bool getLidarTemperature(double& input_temperature) + inline bool getTemperature(float& temp) { - return driver_ptr_->getLidarTemperature(input_temperature); + return driver_ptr_->getTemperature(temp); } private: diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index bbc35ced..502209aa 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -38,6 +38,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include + #include #include #include @@ -119,8 +120,6 @@ class Decoder virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual ~Decoder() = default; - void toSplit(uint16_t azimuth, double chan_ts); - void regRecvCallback(const std::function)>& cb_put, const std::function(void)>& cb_get); @@ -128,21 +127,14 @@ class Decoder void putPointCloud(std::shared_ptr msg, double chan_ts); -#if 0 - uint16_t height() - { - return height_; - } - - double getTemperature() + float getTemperature() { return temperature_; } -#endif - uint64_t msecToDelay() + uint64_t packetDiff() { - return msec_to_delay_; + return 0; } void loadAngleFile(const std::string& angle_path) @@ -155,6 +147,8 @@ class Decoder protected: + void toSplit(uint16_t azimuth, double chan_ts); + template void decodeDifopCommon(const T_Difop& pkt); @@ -163,29 +157,28 @@ class Decoder LidarConstParam lidar_const_param_; RSDecoderParam param_; std::function excb_; - uint16_t height_; - uint64_t msec_to_delay_; - uint32_t msop_pkt_len_; - uint32_t difop_pkt_len_; + uint16_t height_; // to be deleted + uint32_t msop_pkt_len_; // to be moved + uint32_t difop_pkt_len_; // to be moved Trigon trigon_; - DistanceBlock distance_block_; ChanAngles chan_angles_; + DistanceBlock distance_block_; ScanBlock scan_block_; SplitAngle split_angle_; - float block_duration_; - uint16_t azi_diff_between_block_theoretical_; - float fov_time_jump_diff_; - uint32_t pkts_per_frame_; + + float block_ts_diff_; + uint16_t block_azi_diff_; + float fov_blind_ts_diff_; unsigned int protocol_ver_; - unsigned int rpm_; + //unsigned int rpm_; + uint16_t rps_; RSEchoMode echo_mode_; - double temperature_; + float temperature_; bool difop_ready_; - int last_azimuth_; - unsigned int pkt_count_; + uint16_t num_blks_; int lidar_alph0_; // atan2(Ry, Rx) * 180 / M_PI * 100 float lidar_Rxy_; // sqrt(Rx*Rx + Ry*Ry) @@ -209,17 +202,15 @@ inline Decoder::Decoder(const RSDecoderParam& param, , distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance) , scan_block_(param.start_angle * 100, param.end_angle * 100) , split_angle_(param.split_angle * 100) - , block_duration_(0) - , azi_diff_between_block_theoretical_(20) - , fov_time_jump_diff_(0) - , pkts_per_frame_(0) + , block_ts_diff_(0) + , block_azi_diff_(20) + , fov_blind_ts_diff_(0) , protocol_ver_(0) - , rpm_(600) + , rps_(10) , echo_mode_(ECHO_SINGLE) - , temperature_(0) + , temperature_(0.0) , difop_ready_(false) - , last_azimuth_(-36001) - , pkt_count_(0) + , num_blks_(0) , point_cloud_seq_(0) { /* Calulate the lidar_alph0 and lidar_Rxy */ @@ -273,23 +264,22 @@ inline void Decoder::toSplit(uint16_t azimuth, double chan_ts) split = split_angle_.toSplit(azimuth); break; - case SplitFrameMode::SPLIT_BY_FIXED_PKTS: + case SplitFrameMode::SPLIT_BY_FIXED_BLKS: - if (this->pkt_count_ >= this->pkts_per_frame_) + if (this->num_blks_ >= lidar_const_param_.BLOCKS_PER_FRAME) { - this->pkt_count_ = 0; + this->num_blks_ = 0; split = true; } - break; - case SplitFrameMode::SPLIT_BY_CUSTOM_PKTS: - if (this->pkt_count_ >= this->param_.num_pkts_split) + case SplitFrameMode::SPLIT_BY_CUSTOM_BLKS: + + if (this->num_blks_ >= this->param_.num_blks_split) { - this->pkt_count_ = 0; + this->num_blks_ = 0; split = true; } - break; default: @@ -353,38 +343,30 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) this->echo_mode_ = RSEchoMode::ECHO_SINGLE; } - pkts_per_frame_ = - this->lidar_const_param_.BLOCKS_PER_FRAME / this->lidar_const_param_.BLOCKS_PER_PKT; - if (this->echo_mode_ == RSEchoMode::ECHO_DUAL) - { - pkts_per_frame_ *= 2; - } - - // rpm - this->rpm_ = ntohs(pkt.rpm); - if (this->rpm_ == 0) + // rounds per second + this->rps_ = ntohs(pkt.rpm) / 60; + if (this->rps_ == 0) { - RS_WARNING << "LiDAR RPM is 0" << RS_REND; - this->rpm_ = 600; + RS_WARNING << "LiDAR RPM is 0. Use default value 600." << RS_REND; + this->rps_ = 10; } - // block duration - azimuth - this->azi_diff_between_block_theoretical_ = - RS_ONE_ROUND / this->lidar_const_param_.BLOCKS_PER_FRAME; + // block diff of azimuth + this->block_azi_diff_ = RS_ONE_ROUND / this->lidar_const_param_.BLOCKS_PER_FRAME; - // block duration - timestamp - this->block_duration_ = - 60 / (this->rpm_ * this->lidar_const_param_.BLOCKS_PER_FRAME); + // block diff of timestamp + this->block_ts_diff_ = 1 / (this->rps_ * this->lidar_const_param_.BLOCKS_PER_FRAME); - // blind block duration - int fov_start_angle = ntohs(pkt.fov.start_angle); - int fov_end_angle = ntohs(pkt.fov.end_angle); + // fov related + uint16_t fov_start_angle = ntohs(pkt.fov.start_angle); + uint16_t fov_end_angle = ntohs(pkt.fov.end_angle); - int fov_range = (fov_start_angle < fov_end_angle) ? (fov_end_angle - fov_start_angle) : - (RS_ONE_ROUND - fov_start_angle + fov_end_angle); + uint16_t fov_range = (fov_start_angle < fov_end_angle) ? + (fov_end_angle - fov_start_angle) : (fov_end_angle + RS_ONE_ROUND - fov_start_angle); + uint16_t fov_blind_range = RS_ONE_ROUND - fov_range; - this->fov_time_jump_diff_ = this->block_duration_ * - (fov_range / (RS_ONE_ROUND / this->lidar_const_param_.BLOCKS_PER_FRAME)); + // fov blind diff of timestamp + this->fov_blind_ts_diff_ = this->block_ts_diff_ * (fov_blind_range / this->block_azi_diff_); } #if 0 diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 61e485ba..798a86f6 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -128,7 +128,7 @@ inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, template inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* packet, size_t size) { - uint8_t id[] = {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55}; + static uint8_t id[] = {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55}; const RS32DifopPkt& pkt = *(const RS32DifopPkt*)(packet); @@ -150,8 +150,8 @@ inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* template inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* packet, size_t size) { - uint8_t id[] = {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0}; - uint8_t block_id[] = {0xFF, 0xEE}; + static uint8_t id[] = {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0}; + static uint8_t block_id[] = {0xFF, 0xEE}; static const size_t BLOCKS_PER_PKT = 12; const RS32MsopPkt& pkt = *(const RS32MsopPkt*)(packet); @@ -204,7 +204,7 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p azi_diff = static_cast( (RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(pkt.blocks[blk_idx - 2].azimuth)) % RS_ONE_ROUND); block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->block_duration_); + (block_timestamp + this->block_ts_diff_); } } } @@ -224,12 +224,12 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p if (blk_idx > 0) { - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->block_duration_); + block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_blind_ts_diff_) : + (block_timestamp + this->block_ts_diff_); } } - azi_diff = (azi_diff > 100) ? this->azi_diff_between_block_theoretical_ : azi_diff; + azi_diff = (azi_diff > 100) ? this->block_azi_diff_ : azi_diff; for (uint16_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) { diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index f5ab9d04..9b3ab270 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -60,8 +60,8 @@ enum InputType enum SplitFrameMode { SPLIT_BY_ANGLE = 1, - SPLIT_BY_FIXED_PKTS, - SPLIT_BY_CUSTOM_PKTS + SPLIT_BY_FIXED_BLKS, + SPLIT_BY_CUSTOM_BLKS }; #if 0 @@ -115,7 +115,7 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter ///< 2: Split frames by fixed number of packets; ///< 3: Split frames by custom number of packets (num_pkts_split) float split_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 - uint32_t num_pkts_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 + uint32_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points @@ -141,7 +141,7 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter RS_INFOL << "use_lidar_clock: " << use_lidar_clock << RS_REND; RS_INFOL << "split_frame_mode: " << split_frame_mode << RS_REND; RS_INFOL << "split_angle: " << split_angle << RS_REND; - RS_INFOL << "num_pkts_split: " << num_pkts_split << RS_REND; + RS_INFOL << "num_blks_split: " << num_blks_split << RS_REND; RS_INFOL << "dense_points: " << dense_points << RS_REND; RS_INFO << "------------------------------------------------------" << RS_REND; } diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index 77da84fa..f3de7e21 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -34,8 +34,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include -#include + #include +#include #define MAX_PKT_LEN 1500 #define ETH_HDR_LEN 42 diff --git a/src/rs_driver/driver/input/input_pcap.hpp b/src/rs_driver/driver/input/input_pcap.hpp index bea6e3e8..6fdf0fac 100644 --- a/src/rs_driver/driver/input/input_pcap.hpp +++ b/src/rs_driver/driver/input/input_pcap.hpp @@ -35,7 +35,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include - #include namespace robosense diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 19129ccc..176c070f 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -66,7 +66,7 @@ class LidarDriverImpl void regRecvCallback(const std::function& callback); void regExceptionCallback(const std::function& callback); void decodePacket(const uint8_t* pkt, size_t size); - bool getLidarTemperature(double& input_temperature); + bool getTemperature(float& temp); private: @@ -197,8 +197,10 @@ template inline void LidarDriverImpl::regRecvCallback(const std::function)>& cb_put, const std::function(void)>& cb_get) { - - lidar_decoder_ptr_->regRecvCallback(cb_put, cb_get); + if (lidar_decoder_ptr_ != nullptr) + { + lidar_decoder_ptr_->regRecvCallback(cb_put, cb_get); + } } template @@ -220,11 +222,11 @@ inline void LidarDriverImpl::decodePacket(const uint8_t* pkt, size } template -inline bool LidarDriverImpl::getLidarTemperature(double& input_temperature) +inline bool LidarDriverImpl::getTemperature(float& temp) { if (lidar_decoder_ptr_ != nullptr) { - input_temperature = lidar_decoder_ptr_->getLidarTemperature(); + temp = lidar_decoder_ptr_->getTemperature(); return true; } return false; From 91ef3f989f9f84f23ac40f02f8eda6de0117f0fc Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 3 Dec 2021 14:28:40 +0800 Subject: [PATCH 038/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 112 +++++++----------- src/rs_driver/driver/decoder/decoder_RS32.hpp | 36 ++++-- src/rs_driver/driver/input/input_factory.hpp | 45 ------- src/rs_driver/driver/lidar_driver_impl.hpp | 46 +++++-- 4 files changed, 101 insertions(+), 138 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 502209aa..c0439097 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -91,15 +91,10 @@ typedef struct uint64_t BLOCK_ID; // duration - uint32_t PKT_RATE; // to be deleted - uint16_t BLOCKS_PER_PKT; uint16_t BLOCKS_PER_FRAME; + uint16_t BLOCKS_PER_PKT; uint16_t CHANNELS_PER_BLOCK; - uint16_t LASER_NUM; - - // firing - float DSR_TOFFSET; // to be deleted - float FIRING_FREQUENCY; // to be deleted + //uint16_t LASER_NUM; // diff from CHANNELS_PER_BLOCK ? // distance float DIS_RESOLUTION; @@ -108,7 +103,7 @@ typedef struct float RX; float RY; float RZ; -} LidarConstParam; +} RSDecoderConstParam; template class Decoder @@ -120,21 +115,26 @@ class Decoder virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual ~Decoder() = default; - void regRecvCallback(const std::function)>& cb_put, - const std::function(void)>& cb_get); - - std::shared_ptr getPointCloud(); - - void putPointCloud(std::shared_ptr msg, double chan_ts); + void regRecvCallback(const std::function(void)>& cb_get, + const std::function)>& cb_put); float getTemperature() { return temperature_; } - uint64_t packetDiff() + uint64_t getPacketDiff() { - return 0; + // Actual value of rps and echo_mode is unavailable, + // so use default value, rps = 10, echo_mode_ = ECHO_SINGLE. + // Instead, use RSInputParam.pcap_rate to change the playback speed. + uint64_t diff = block_ts_diff_ * const_param_.BLOCKS_PER_PKT; + if (this->echo_mode_ == RSEchoMode::ECHO_DUAL) + { + diff /= 2; + } + + return diff; } void loadAngleFile(const std::string& angle_path) @@ -143,18 +143,19 @@ class Decoder explicit Decoder(const RSDecoderParam& param, const std::function& excb, - const LidarConstParam& lidar_const_param); + const RSDecoderConstParam& lidar_const_param); protected: void toSplit(uint16_t azimuth, double chan_ts); + void setPointCloudHeader(std::shared_ptr msg, double chan_ts); template void decodeDifopCommon(const T_Difop& pkt); protected: - LidarConstParam lidar_const_param_; + RSDecoderConstParam const_param_; RSDecoderParam param_; std::function excb_; uint16_t height_; // to be deleted @@ -172,7 +173,6 @@ class Decoder float fov_blind_ts_diff_; unsigned int protocol_ver_; - //unsigned int rpm_; uint16_t rps_; RSEchoMode echo_mode_; float temperature_; @@ -192,8 +192,8 @@ class Decoder template inline Decoder::Decoder(const RSDecoderParam& param, const std::function& excb, - const LidarConstParam& lidar_const_param) - : lidar_const_param_(lidar_const_param) + const RSDecoderConstParam& lidar_const_param) + : const_param_(lidar_const_param) , param_(param) , excb_(excb) , height_(0) @@ -214,43 +214,24 @@ inline Decoder::Decoder(const RSDecoderParam& param, , point_cloud_seq_(0) { /* Calulate the lidar_alph0 and lidar_Rxy */ - lidar_alph0_ = std::atan2(lidar_const_param_.RY, lidar_const_param_.RX) * 180 / M_PI * 100; - lidar_Rxy_ = std::sqrt(lidar_const_param_.RX * lidar_const_param_.RX + lidar_const_param_.RY * lidar_const_param_.RY); + lidar_alph0_ = std::atan2(const_param_.RY, const_param_.RX) * 180 / M_PI * 100; + lidar_Rxy_ = std::sqrt(const_param_.RX * const_param_.RX + const_param_.RY * const_param_.RY); if (param.config_from_file) { loadAngleFile(param.angle_path); } + + point_cloud_ = point_cloud_cb_get_(); } template void Decoder::regRecvCallback( - const std::function)>& cb_put, - const std::function(void)>& cb_get) + const std::function(void)>& cb_get, + const std::function)>& cb_put) { - point_cloud_cb_put_ = cb_put; point_cloud_cb_get_ = cb_get; -} - -template -std::shared_ptr Decoder::getPointCloud() -{ - std::shared_ptr pc; - - while (1) - { - if (point_cloud_cb_get_ != nullptr) - pc = point_cloud_cb_get_(); - - if (pc) - { - pc->points.resize(0); - return pc; - } - - excb_(Error(ERRCODE_POINTCLOUDNULL)); - //std::this_thread::sleep_for(std::chrono::milliseconds(300)); - }; + point_cloud_cb_put_ = cb_put; } template @@ -266,7 +247,7 @@ inline void Decoder::toSplit(uint16_t azimuth, double chan_ts) case SplitFrameMode::SPLIT_BY_FIXED_BLKS: - if (this->num_blks_ >= lidar_const_param_.BLOCKS_PER_FRAME) + if (this->num_blks_ >= const_param_.BLOCKS_PER_FRAME) { this->num_blks_ = 0; split = true; @@ -288,12 +269,21 @@ inline void Decoder::toSplit(uint16_t azimuth, double chan_ts) if (split) { - putPointCloud(point_cloud_, chan_ts); + if (point_cloud_->points.size() > 0) + { + setPointCloudHeader(point_cloud_, chan_ts); + point_cloud_cb_put_(point_cloud_); + point_cloud_ = point_cloud_cb_get_(); + } + else + { + excb_(Error(ERRCODE_ZEROPOINTS)); + } } } template -void Decoder::putPointCloud(std::shared_ptr msg, double chan_ts) +void Decoder::setPointCloudHeader(std::shared_ptr msg, double chan_ts) { msg->seq = point_cloud_seq_++; msg->timestamp = chan_ts; @@ -308,15 +298,6 @@ void Decoder::putPointCloud(std::shared_ptr msg, dou msg->height = height_; msg->width = msg->points.size() / msg->height; } - - if (msg->points.size() == 0) - { - excb_(Error(ERRCODE_ZEROPOINTS)); - } - else - { - point_cloud_cb_put_(msg); - } } template @@ -334,15 +315,6 @@ template template inline void Decoder::decodeDifopCommon(const T_Difop& pkt) { - // return mode - switch (pkt.return_mode) - { - case 0x00: - this->echo_mode_ = RSEchoMode::ECHO_DUAL; - default: - this->echo_mode_ = RSEchoMode::ECHO_SINGLE; - } - // rounds per second this->rps_ = ntohs(pkt.rpm) / 60; if (this->rps_ == 0) @@ -352,10 +324,10 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) } // block diff of azimuth - this->block_azi_diff_ = RS_ONE_ROUND / this->lidar_const_param_.BLOCKS_PER_FRAME; + this->block_azi_diff_ = RS_ONE_ROUND / this->const_param_.BLOCKS_PER_FRAME; // block diff of timestamp - this->block_ts_diff_ = 1 / (this->rps_ * this->lidar_const_param_.BLOCKS_PER_FRAME); + this->block_ts_diff_ = 1 / (this->rps_ * this->const_param_.BLOCKS_PER_FRAME); // fov related uint16_t fov_start_angle = ntohs(pkt.fov.start_angle); diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 798a86f6..1e283a4e 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -93,20 +93,15 @@ class DecoderRS32 : public Decoder explicit DecoderRS32(const RSDecoderParam& param, const std::function& excb); - static LidarConstParam getConstParam() + static RSDecoderConstParam getConstParam() { - LidarConstParam param; + RSDecoderConstParam param; param.MSOP_ID = 0xA050A55A0A05AA55; param.DIFOP_ID = 0x555511115A00FFA5; param.BLOCK_ID = 0xEEFF; - param.PKT_RATE = 1500; + param.BLOCKS_PER_FRAME = 0; param.BLOCKS_PER_PKT = 12; - param.CHANNELS_PER_BLOCK = 32; - param.LASER_NUM = 32; - - param.DSR_TOFFSET = 1.44; - param.FIRING_FREQUENCY = 0.018; param.DIS_RESOLUTION = 0.005; param.RX = 0.03997; @@ -116,6 +111,19 @@ class DecoderRS32 : public Decoder return param; } + RSEchoMode getEchoMode(uint8_t mode) + { + switch (mode) + { + case 0x00: + return RSEchoMode::ECHO_DUAL; + case 0x01: + case 0x02: + default: + return RSEchoMode::ECHO_SINGLE; + } + } + }; template @@ -137,6 +145,8 @@ inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* return RSDecoderResult::WRONG_PKT_HEADER; } + this->echo_mode_ = getEchoMode (pkt.return_mode); + this->template decodeDifopCommon(pkt); if (!this->difop_ready_) @@ -231,7 +241,7 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p azi_diff = (azi_diff > 100) ? this->block_azi_diff_ : azi_diff; - for (uint16_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) + for (uint16_t channel_idx = 0; channel_idx < this->const_param_.CHANNELS_PER_BLOCK; channel_idx++) { static const float delta_ts[] = { 0.00, 2.88, 5.76, 8.64, 11.52, 14.40, 17.28, 20.16, 23.04, 25.92, 28.80, 31.68, 34.56, 37.44, 40.32, 44.64, @@ -244,7 +254,7 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p chan_ts = block_timestamp + delta_ts[channel_idx]; float azi_channel_ori = cur_azi + azi_diff * delta_ts[channel_idx] / delta_block; - float distance = ntohs(channel.distance) * this->lidar_const_param_.DIS_RESOLUTION; + float distance = ntohs(channel.distance) * this->const_param_.DIS_RESOLUTION; uint16_t azi_channel_final = this->chan_angles_.horizAdjust(channel_idx, (int32_t)azi_channel_ori); @@ -259,9 +269,9 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p if (this->distance_block_.in(distance) && this->scan_block_.in(azi_channel_final)) { - float x = distance * COS(angle_vert) * COS(azi_channel_final) + this->lidar_const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(azi_channel_final) - this->lidar_const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->lidar_const_param_.RZ; + float x = distance * COS(angle_vert) * COS(azi_channel_final) + this->const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(azi_channel_final) - this->const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->const_param_.RZ; uint8_t intensity = channel.intensity; setX(point, x); diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 446f9ca5..9b8f72cb 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -39,51 +39,6 @@ namespace robosense { namespace lidar { -#if 0 -inline long long msecToDelay(LidarType type, double replay_rate) -{ - constexpr double RS16_PCAP_SLEEP_DURATION = 1200; ///< us - constexpr double RS32_PCAP_SLEEP_DURATION = 530; ///< us - constexpr double RSBP_PCAP_SLEEP_DURATION = 530; ///< us - constexpr double RS128_PCAP_SLEEP_DURATION = 100; ///< us - constexpr double RS80_PCAP_SLEEP_DURATION = 135; ///< us - constexpr double RSM1_PCAP_SLEEP_DURATION = 90; ///< us - constexpr double RSHELIOS_PCAP_SLEEP_DURATION = 530; ///< us - constexpr double RSROCK_PCAP_SLEEP_DURATION = 530; ///< us TODO - - double duration; - switch (type) - { - case LidarType::RS16: - duration = RS16_PCAP_SLEEP_DURATION; - break; - case LidarType::RS32: - duration = RS32_PCAP_SLEEP_DURATION; - break; - case LidarType::RSBP: - duration = RSBP_PCAP_SLEEP_DURATION; - break; - case LidarType::RS128: - duration = RS128_PCAP_SLEEP_DURATION; - break; - case LidarType::RS80: - duration = RS80_PCAP_SLEEP_DURATION; - break; - case LidarType::RSM1: - duration = RSM1_PCAP_SLEEP_DURATION; - break; - case LidarType::RSHELIOS: - duration = RSHELIOS_PCAP_SLEEP_DURATION; - break; - case LidarType::RSROCK: - default: - duration = RSROCK_PCAP_SLEEP_DURATION; - break; - } - - return static_cast(duration / replay_rate); -} -#endif class InputFactory { diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 176c070f..36503a92 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -75,15 +75,18 @@ class LidarDriverImpl std::shared_ptr packetGet(size_t size); void packetPut(std::shared_ptr pkt); + std::shared_ptr getPointCloud(); void processMsop(); void processDifop(); private: RSDriverParam driver_param_; + std::function(void)> point_cloud_cb_get_; + std::function)> point_cloud_cb_put_; std::function pkt_cb_; - std::function err_cb_; std::function feed_pkt_cb_; + std::function err_cb_; std::shared_ptr> lidar_decoder_ptr_; std::shared_ptr input_ptr_; SyncQueue> free_pkt_queue_; @@ -129,11 +132,18 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) return true; } - lidar_decoder_ptr_ = DecoderFactory::createDecoder - (param.lidar_type, param.decoder_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); + lidar_decoder_ptr_ = DecoderFactory::createDecoder( + param.lidar_type, param.decoder_param, + std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); + + lidar_decoder_ptr_->regRecvCallback( + std::bind(&LidarDriverImpl::getPointCloud, this), point_cloud_cb_put_); + + uint64_t packet_diff = lidar_decoder_ptr_->getPacketDiff(); + + input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, + std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1), packet_diff); - input_ptr_ = InputFactory::createInput( - param.input_type, param.input_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1), 0); input_ptr_->regRecvCallback(std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), std::bind(&LidarDriverImpl::packetPut, this, std::placeholders::_1)); @@ -194,13 +204,29 @@ inline void LidarDriverImpl::stop() } template -inline void LidarDriverImpl::regRecvCallback(const std::function)>& cb_put, - const std::function(void)>& cb_get) +std::shared_ptr LidarDriverImpl::getPointCloud() { - if (lidar_decoder_ptr_ != nullptr) + while (1) { - lidar_decoder_ptr_->regRecvCallback(cb_put, cb_get); - } + std::shared_ptr pc = point_cloud_cb_get_(); + if (pc) + { + pc->points.resize(0); + return pc; + } + + reportError(Error(ERRCODE_POINTCLOUDNULL)); + std::this_thread::sleep_for(std::chrono::milliseconds(300)); + }; +} + +template +inline void LidarDriverImpl::regRecvCallback( + const std::function)>& cb_put, + const std::function(void)>& cb_get) +{ + point_cloud_cb_get_ = cb_get; + point_cloud_cb_put_ = cb_put; } template From 9d9204234d4da36b55119974c10b07600dfb985a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 3 Dec 2021 17:10:24 +0800 Subject: [PATCH 039/379] refac: refactory driver_impl --- CMakeLists.txt | 14 ++-- demo/demo_online.cpp | 2 +- demo/demo_pcap.cpp | 2 +- src/rs_driver/api/lidar_driver.h | 39 ++++++----- src/rs_driver/driver/lidar_driver_impl.hpp | 77 +++++++++++++++------- 5 files changed, 83 insertions(+), 51 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index dfa7b59c..596fee35 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -19,9 +19,7 @@ option(COMPILE_TESTS "Build rs_driver unit tests" ON) # Compile Features #============================= option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) -option(ENABLE_PUBLISH_RAW_MSG "Publish raw messages" OFF) -option(ENABLE_PUBLISH_CAM_MSG "Publish camera trigger messages" OFF) -option(ENABLE_TRANSFORM "Enable transform functions" OFF) +option(ENABLE_POINT_CLOUD_POOL "Enable user point cloud pool" ON) #======================== # Project setup @@ -115,13 +113,9 @@ if(${ENABLE_HIGH_PRIORITY_THREAD}) add_definitions("-DENABLE_HIGH_PRIORITY_THREAD") endif(${ENABLE_HIGH_PRIORITY_THREAD}) -if(${ENABLE_PUBLISH_RAW_MSG}) - add_definitions("-DENABLE_PUBLISH_RAW_MSG") -endif(${ENABLE_PUBLISH_RAW_MSG}) - -if(${ENABLE_PUBLISH_CAM_MSG}) - add_definitions("-DENABLE_PUBLISH_CAM_MSG") -endif(${ENABLE_PUBLISH_CAM_MSG}) +if(${ENABLE_POINT_CLOUD_POOL}) + add_definitions("-DENABLE_POINT_CLOUD_POOL") +endif(${ENABLE_POINT_CLOUD_POOL}) #======================== # Build Demos diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 39fd3702..74fff094 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -92,7 +92,7 @@ int main(int argc, char* argv[]) param.print(); LidarDriver driver; - driver.regRecvCallback(pointCloudPutCallback, nullptr/*pointCloudGetCallback*/); ///< Register the point cloud callback function into the driver + driver.regRecvCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback function into the driver driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver if (!driver.init(param)) ///< Call the init function and pass the parameter { diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 2721493e..6316669f 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -93,7 +93,7 @@ int main(int argc, char* argv[]) param.print(); LidarDriver driver; ///< Declare the driver object - driver.regRecvCallback(pointCloudPutCallback, pointCloudGetCallback); ///< Register the point cloud callback function into the driver + driver.regRecvCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback function into the driver driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver if (!driver.init(param)) ///< Call the init function and pass the parameter { diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index 257ac4cb..f893cfe4 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -53,14 +53,8 @@ class LidarDriver /** * @brief Constructor, instanciate the driver pointer */ - LidarDriver() : driver_ptr_(std::make_shared>()) - { - } - - /** - * @brief Deconstructor, stop all threads - */ - ~LidarDriver() + LidarDriver() + : driver_ptr_(std::make_shared>()) { } @@ -92,27 +86,32 @@ class LidarDriver driver_ptr_->stop(); } +#ifdef ENABLE_POINT_CLOUD_POOL /** * @brief Register the lidar point cloud callback function to driver. When point cloud is ready, this function will be * called * @param callback The callback function */ - inline void regRecvCallback(const std::function)>& cb_put, - const std::function(void)>& cb_get = nullptr) + inline void regRecvCallback(const std::function(void)>& cb_get, + const std::function)>& cb_put) { - driver_ptr_->regRecvCallback(cb_put, cb_get); + driver_ptr_->regRecvCallback(cb_get, cb_put); } +#else + /** - * @brief Register the lidar difop packet message callback function to driver. When lidar difop packet message is - * ready, this function will be called + * @brief Register the lidar point cloud callback function to driver. When point cloud is ready, this function will be + * called * @param callback The callback function */ - inline void regRecvCallback(const std::function& callback) + inline void regRecvCallback(const std::function& cb_put) { - driver_ptr_->regRecvCallback(callback); + driver_ptr_->regRecvCallback(cb_put); } +#endif + /** * @brief Register the exception message callback function to driver. When error occurs, this function will be called * @param callback The callback function @@ -122,6 +121,16 @@ class LidarDriver driver_ptr_->regExceptionCallback(callback); } + /** + * @brief Register the lidar difop packet message callback function to driver. When lidar difop packet message is + * ready, this function will be called + * @param callback The callback function + */ + inline void regRecvCallback(const std::function& callback) + { + driver_ptr_->regRecvCallback(callback); + } + /** * @brief Decode lidar msop/difop messages * @param pkt_msg The lidar msop/difop packet diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 36503a92..843282ad 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -61,8 +61,27 @@ class LidarDriverImpl bool init(const RSDriverParam& param); bool start(); void stop(); - void regRecvCallback(const std::function)>& cb_put, - const std::function(void)>& cb_get); + +#ifdef ENABLE_POINT_CLOUD_POOL + void regRecvCallback(const std::function(void)>& cb_get, + const std::function)>& cb_put) + { + point_cloud_cb_get_ = cb_get; + point_cloud_cb_put_ = cb_put; + } + + std::function(void)> point_cloud_cb_get_; + std::function)> point_cloud_cb_put_; +#else + void regRecvCallback(const std::function& cb_put) + { + point_cloud_cb_put_ = cb_put; + } + + std::function point_cloud_cb_put_; + std::shared_ptr point_cloud_; +#endif + void regRecvCallback(const std::function& callback); void regExceptionCallback(const std::function& callback); void decodePacket(const uint8_t* pkt, size_t size); @@ -70,20 +89,20 @@ class LidarDriverImpl private: + std::shared_ptr getPointCloud(); + void putPointCloud(std::shared_ptr pc); + void runCallBack(std::shared_ptr pkt); void reportError(const Error& error); std::shared_ptr packetGet(size_t size); void packetPut(std::shared_ptr pkt); - std::shared_ptr getPointCloud(); void processMsop(); void processDifop(); private: RSDriverParam driver_param_; - std::function(void)> point_cloud_cb_get_; - std::function)> point_cloud_cb_put_; std::function pkt_cb_; std::function feed_pkt_cb_; std::function err_cb_; @@ -116,6 +135,9 @@ template inline LidarDriverImpl::LidarDriverImpl() : init_flag_(false), start_flag_(false), pkt_seq_(0), ndifop_count_(0) { +#ifndef ENABLE_POINT_CLOUD_POOL + point_cloud_ = std::make_shared(); +#endif } template @@ -137,7 +159,8 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); lidar_decoder_ptr_->regRecvCallback( - std::bind(&LidarDriverImpl::getPointCloud, this), point_cloud_cb_put_); + std::bind(&LidarDriverImpl::getPointCloud, this), + std::bind(&LidarDriverImpl::putPointCloud, this, std::placeholders::_1)); uint64_t packet_diff = lidar_decoder_ptr_->getPacketDiff(); @@ -203,12 +226,29 @@ inline void LidarDriverImpl::stop() } } +template +inline void LidarDriverImpl::regRecvCallback(const std::function& callback) +{ + pkt_cb_ = callback; +} + +template +inline void LidarDriverImpl::regExceptionCallback(const std::function& callback) +{ + err_cb_ = callback; +} + template std::shared_ptr LidarDriverImpl::getPointCloud() { while (1) { +#ifdef ENABLE_POINT_CLOUD_POOL std::shared_ptr pc = point_cloud_cb_get_(); +#else + std::shared_ptr pc = point_cloud_; +#endif + if (pc) { pc->points.resize(0); @@ -217,28 +257,17 @@ std::shared_ptr LidarDriverImpl::getPointCloud() reportError(Error(ERRCODE_POINTCLOUDNULL)); std::this_thread::sleep_for(std::chrono::milliseconds(300)); - }; -} - -template -inline void LidarDriverImpl::regRecvCallback( - const std::function)>& cb_put, - const std::function(void)>& cb_get) -{ - point_cloud_cb_get_ = cb_get; - point_cloud_cb_put_ = cb_put; -} - -template -inline void LidarDriverImpl::regRecvCallback(const std::function& callback) -{ - pkt_cb_ = callback; + } } template -inline void LidarDriverImpl::regExceptionCallback(const std::function& callback) +void LidarDriverImpl::putPointCloud(std::shared_ptr pc) { - err_cb_ = callback; +#ifdef ENABLE_POINT_CLOUD_POOL + point_cloud_cb_put_(pc); +#else + point_cloud_cb_put_(*pc); +#endif } template From aa3c08b40441b3aafd787fa6d78b4930fa293d58 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sat, 4 Dec 2021 11:31:04 +0800 Subject: [PATCH 040/379] refac: add const param BLOCK_TS --- src/rs_driver/driver/decoder/decoder.hpp | 43 ++-- src/rs_driver/driver/decoder/decoder_RS32.hpp | 206 ++++++++++++------ 2 files changed, 165 insertions(+), 84 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index c0439097..7599a80a 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -86,12 +86,11 @@ enum RSDecoderResult typedef struct { // identity - uint64_t MSOP_ID; - uint64_t DIFOP_ID; - uint64_t BLOCK_ID; + uint8_t MSOP_ID[8]; + uint8_t DIFOP_ID[8]; + uint8_t BLOCK_ID[2]; // duration - uint16_t BLOCKS_PER_FRAME; uint16_t BLOCKS_PER_PKT; uint16_t CHANNELS_PER_BLOCK; //uint16_t LASER_NUM; // diff from CHANNELS_PER_BLOCK ? @@ -99,10 +98,15 @@ typedef struct // distance float DIS_RESOLUTION; + // firing_ts/block_chan_ts + float CHAN_TS[128]; + float BLOCK_TS; + // lens center float RX; float RY; float RZ; + } RSDecoderConstParam; template @@ -125,16 +129,9 @@ class Decoder uint64_t getPacketDiff() { - // Actual value of rps and echo_mode is unavailable, - // so use default value, rps = 10, echo_mode_ = ECHO_SINGLE. - // Instead, use RSInputParam.pcap_rate to change the playback speed. - uint64_t diff = block_ts_diff_ * const_param_.BLOCKS_PER_PKT; - if (this->echo_mode_ == RSEchoMode::ECHO_DUAL) - { - diff /= 2; - } - - return diff; + // Assume echo_mode is ECHO_SINGLE. + // If it is ECHO_DUAL, use RSInputParam.pcap_rate = 2 to change the playback speed. + return this->const_param_.BLOCK_TS * const_param_.BLOCKS_PER_PKT; } void loadAngleFile(const std::string& angle_path) @@ -163,12 +160,14 @@ class Decoder uint32_t difop_pkt_len_; // to be moved Trigon trigon_; +#define SIN(angle) this->trigon_.sin(angle) +#define COS(angle) this->trigon_.cos(angle) ChanAngles chan_angles_; DistanceBlock distance_block_; ScanBlock scan_block_; SplitAngle split_angle_; - float block_ts_diff_; + uint16_t blks_per_frame_; uint16_t block_azi_diff_; float fov_blind_ts_diff_; @@ -202,7 +201,7 @@ inline Decoder::Decoder(const RSDecoderParam& param, , distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance) , scan_block_(param.start_angle * 100, param.end_angle * 100) , split_angle_(param.split_angle * 100) - , block_ts_diff_(0) + , blks_per_frame_(1/(10*lidar_const_param.BLOCK_TS)) , block_azi_diff_(20) , fov_blind_ts_diff_(0) , protocol_ver_(0) @@ -247,7 +246,7 @@ inline void Decoder::toSplit(uint16_t azimuth, double chan_ts) case SplitFrameMode::SPLIT_BY_FIXED_BLKS: - if (this->num_blks_ >= const_param_.BLOCKS_PER_FRAME) + if (this->num_blks_ >= this->blks_per_frame_) { this->num_blks_ = 0; split = true; @@ -323,11 +322,11 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) this->rps_ = 10; } - // block diff of azimuth - this->block_azi_diff_ = RS_ONE_ROUND / this->const_param_.BLOCKS_PER_FRAME; + // blocks per frame + blks_per_frame_ = 1 / (this->rps_ * this->const_param_.BLOCK_TS); - // block diff of timestamp - this->block_ts_diff_ = 1 / (this->rps_ * this->const_param_.BLOCKS_PER_FRAME); + // block diff of azimuth + this->block_azi_diff_ = RS_ONE_ROUND * this->rps_ * this->const_param_.BLOCK_TS; // fov related uint16_t fov_start_angle = ntohs(pkt.fov.start_angle); @@ -338,7 +337,7 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) uint16_t fov_blind_range = RS_ONE_ROUND - fov_range; // fov blind diff of timestamp - this->fov_blind_ts_diff_ = this->block_ts_diff_ * (fov_blind_range / this->block_azi_diff_); + this->fov_blind_ts_diff_ = fov_blind_range / (RS_ONE_ROUND * this->rps_); } #if 0 diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 1e283a4e..760cd535 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -95,18 +95,27 @@ class DecoderRS32 : public Decoder static RSDecoderConstParam getConstParam() { - RSDecoderConstParam param; - param.MSOP_ID = 0xA050A55A0A05AA55; - param.DIFOP_ID = 0x555511115A00FFA5; - param.BLOCK_ID = 0xEEFF; - param.BLOCKS_PER_FRAME = 0; - param.BLOCKS_PER_PKT = 12; - param.CHANNELS_PER_BLOCK = 32; - param.DIS_RESOLUTION = 0.005; - - param.RX = 0.03997; - param.RY = -0.01087; - param.RZ = 0; + RSDecoderConstParam param = + { + {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 12 // blocks per packet + , 32 // channels per block + , 0.005 // distance resolution + + // firing_ts + , { 0.00, 2.88, 5.76, 8.64, 11.52, 14.40, 17.28, 20.16, + 23.04, 25.92, 28.80, 31.68, 34.56, 37.44, 40.32, 44.64, + 1.44, 4.32, 7.20, 10.08, 12.96, 15.84, 18.72, 21.60, + 24.48, 27.36, 30.24, 33.12, 36.00, 38.88, 41.76, 46.08} + , 55.52 + + // lens center + , 0.03997 // RX + , -0.01087 // RY + , 0 // RZ + }; return param; } @@ -136,11 +145,9 @@ inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, template inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* packet, size_t size) { - static uint8_t id[] = {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55}; - const RS32DifopPkt& pkt = *(const RS32DifopPkt*)(packet); - if (memcmp(id, &(pkt.id), sizeof(id)) != 0) + if (memcmp(this->const_param_.DIFOP_ID, &(pkt.id), 8) != 0) { return RSDecoderResult::WRONG_PKT_HEADER; } @@ -157,6 +164,84 @@ inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* return RSDecoderResult::DECODE_OK; } +#if 0 +template +class PacketTraverser +{ +public: + + PacketTraverser(uint64_t pkt_ts) + : bi_(0), ci_(0) + { + ts_ = pkt_ts; + azi_ = pkt_.blocks[0].azimuth; + } + + void toNext() + { + static const float delta_ts[] = + { 0.00, 2.88, 5.76, 8.64, 11.52, 14.40, 17.28, 20.16, + 23.04, 25.92, 28.80, 31.68, 34.56, 37.44, 40.32, 44.64, + 1.44, 4.32, 7.20, 10.08, 12.96, 15.84, 18.72, 21.60, + 24.48, 27.36, 30.24, 33.12, 36.00, 38.88, 41.76, 46.08 + }; + + static const float delta_block = 55.52; + + ci++; + if (ci_ < CHAN_PER_BLOCK) + { + ts_ += delta_ts[ci_] - delta_ts[ci_-1]; + azi_ += azi_diff * delta_ts[ci] / delta_block; + } + else + { + bi_ ++; + ci_ = 0; + + blk_ts_ += block_diff + ts_ += delta_block - delta_ts[CHAN_PER_BLOCK-1]; + azi_ = pkt_.blocks[bi_].azimuth; + } + } + + bool isLast() + { + return (bi_ >= BLOCKS_PER_PACKET); + } + + void getPos(size_t& blk, size_t& chan) + { + blk = blk_; + chan = chan_; + } + + uint16_t azi() + { + return azi_; + } + + uint64_t ts() + { + return ts_; + } + +private: + + void calc() + { + } + + Packet pkt_; + size_t bi_; + size_t ci_; + uint64_t blk_ts_; + uint16_t blk_azi_; + uint64_t chan_ts_; + uint16_t chan_azi_; +}; +#endif + template inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* packet, size_t size) { @@ -173,31 +258,30 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p this->temperature_ = calcTemp(&(pkt.header.temp)); - double block_timestamp = 0; - double chan_ts = block_timestamp; - //uint64_t ts = 0; + double chan_ts; + double pkt_ts = 0; if (this->param_.use_lidar_clock) { - block_timestamp = calcTimeYMD(&pkt.header.timestamp); + pkt_ts = calcTimeYMD(&pkt.header.timestamp); } else { - block_timestamp = calcTimeHost(); + pkt_ts = calcTimeHost(); } - float azi_diff = 0; + double block_ts = pkt_ts; + uint16_t azi_diff = 0; for (size_t blk_idx = 0; blk_idx < BLOCKS_PER_PKT; blk_idx++) { const RS32MsopBlock& block = pkt.blocks[blk_idx]; - if (memcmp(&(block.id), block_id, sizeof(block_id))) { break; } - uint16_t cur_azi = ntohs(block.azimuth); + uint16_t block_azi = ntohs(block.azimuth); - this->toSplit(cur_azi, chan_ts); + this->toSplit(block_azi, chan_ts); #if 0 if (this->echo_mode_ == ECHO_DUAL) @@ -207,14 +291,14 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p if (blk_idx == 0) { azi_diff = static_cast( - (RS_ONE_ROUND + RS_SWAP_SHORT(pkt.blocks[blk_idx + 2].azimuth) - cur_azi) % RS_ONE_ROUND); + (RS_ONE_ROUND + RS_SWAP_SHORT(pkt.blocks[blk_idx + 2].azimuth) - block_azi) % RS_ONE_ROUND); } else { azi_diff = static_cast( - (RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(pkt.blocks[blk_idx - 2].azimuth)) % RS_ONE_ROUND); - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->block_ts_diff_); + (RS_ONE_ROUND + block_azi - RS_SWAP_SHORT(pkt.blocks[blk_idx - 2].azimuth)) % RS_ONE_ROUND); + block_ts = (azi_diff > 100) ? (block_ts + this->fov_time_jump_diff_) : + (block_ts + this->block_ts_diff_); } } } @@ -223,80 +307,78 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p { if (blk_idx < (BLOCKS_PER_PKT - 1)) { - azi_diff = static_cast((RS_ONE_ROUND + ntohs(pkt.blocks[blk_idx + 1].azimuth) - cur_azi) % - RS_ONE_ROUND); + azi_diff = static_cast((RS_ONE_ROUND + ntohs(pkt.blocks[blk_idx + 1].azimuth) - block_azi) % + RS_ONE_ROUND); } else { - azi_diff = static_cast((RS_ONE_ROUND + cur_azi - ntohs(pkt.blocks[blk_idx - 1].azimuth)) % - RS_ONE_ROUND); + azi_diff = static_cast((RS_ONE_ROUND + block_azi - ntohs(pkt.blocks[blk_idx - 1].azimuth)) % + RS_ONE_ROUND); } if (blk_idx > 0) { - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_blind_ts_diff_) : - (block_timestamp + this->block_ts_diff_); + block_ts = (azi_diff > 100) ? (block_ts + this->fov_blind_ts_diff_) : + (block_ts + this->const_param_.BLOCK_TS); } } - azi_diff = (azi_diff > 100) ? this->block_azi_diff_ : azi_diff; + //azi_diff = (azi_diff > 100) ? this->block_azi_diff_ : azi_diff; - for (uint16_t channel_idx = 0; channel_idx < this->const_param_.CHANNELS_PER_BLOCK; channel_idx++) + for (uint16_t chan_idx = 0; chan_idx < this->const_param_.CHANNELS_PER_BLOCK; chan_idx++) { - static const float delta_ts[] = { 0.00, 2.88, 5.76, 8.64, 11.52, 14.40, 17.28, 20.16, - 23.04, 25.92, 28.80, 31.68, 34.56, 37.44, 40.32, 44.64, - 1.44, 4.32, 7.20, 10.08, 12.96, 15.84, 18.72, 21.60, - 24.48, 27.36, 30.24, 33.12, 36.00, 38.88, 41.76, 46.08}; - static const float delta_block = 55.52; + static const float delta_ts[] = + { 0.00, 2.88, 5.76, 8.64, 11.52, 14.40, 17.28, 20.16, + 23.04, 25.92, 28.80, 31.68, 34.56, 37.44, 40.32, 44.64, + 1.44, 4.32, 7.20, 10.08, 12.96, 15.84, 18.72, 21.60, + 24.48, 27.36, 30.24, 33.12, 36.00, 38.88, 41.76, 46.08 + }; - const RSChannel& channel = pkt.blocks[blk_idx].channels[channel_idx]; + static const float delta_block = 55.52; - chan_ts = block_timestamp + delta_ts[channel_idx]; - float azi_channel_ori = cur_azi + azi_diff * delta_ts[channel_idx] / delta_block; + const RSChannel& chan = block.channels[chan_idx]; - float distance = ntohs(channel.distance) * this->const_param_.DIS_RESOLUTION; + chan_ts = block_ts + delta_ts[chan_idx]; - uint16_t azi_channel_final = this->chan_angles_.horizAdjust(channel_idx, (int32_t)azi_channel_ori); + float chan_ori_azi = block_azi + azi_diff * (delta_ts[chan_idx] / delta_block); - uint16_t angle_horiz = azi_channel_ori; - uint16_t angle_vert = this->chan_angles_.vertAdjust(channel_idx); + float distance = ntohs(chan.distance) * this->const_param_.DIS_RESOLUTION; - typename T_PointCloud::PointT point; - bool pointValid = false; + uint16_t azi_channel_final = this->chan_angles_.horizAdjust(chan_idx, (int32_t)chan_ori_azi); -#define SIN(angle) this->trigon_.sin(angle) -#define COS(angle) this->trigon_.cos(angle) + uint16_t angle_horiz = chan_ori_azi; + uint16_t angle_vert = this->chan_angles_.vertAdjust(chan_idx); - if (this->distance_block_.in(distance) && this->scan_block_.in(azi_channel_final)) + if (this->distance_block_.in(distance) && this->scan_block_.in(azi_channel_final)) { float x = distance * COS(angle_vert) * COS(azi_channel_final) + this->const_param_.RX * COS(angle_horiz); float y = -distance * COS(angle_vert) * SIN(azi_channel_final) - this->const_param_.RX * SIN(angle_horiz); float z = distance * SIN(angle_vert) + this->const_param_.RZ; - uint8_t intensity = channel.intensity; + uint8_t intensity = chan.intensity; + + typename T_PointCloud::PointT point; setX(point, x); setY(point, y); setZ(point, z); setIntensity(point, intensity); - pointValid = true; + + setRing(point, this->chan_angles_.toUserChan(chan_idx)); + setTimestamp(point, chan_ts); + this->point_cloud_->points.emplace_back(point); } else if (!this->param_.dense_points) { + typename T_PointCloud::PointT point; setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); - pointValid = true; - } - - if (pointValid) - { - setRing(point, this->chan_angles_.toUserChan(channel_idx)); + setRing(point, this->chan_angles_.toUserChan(chan_idx)); setTimestamp(point, chan_ts); this->point_cloud_->points.emplace_back(point); } } - } return RSDecoderResult::DECODE_OK; From 2ec6a56d39b6a63e5788b9d13ebff6d9ccb2585e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 6 Dec 2021 16:32:42 +0800 Subject: [PATCH 041/379] feat: add packet traverser --- src/rs_driver/driver/decoder/decoder.hpp | 17 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 141 ++++++-------- .../driver/decoder/packet_traverser.hpp | 179 ++++++++++++++++++ test/CMakeLists.txt | 6 +- test/dual_return_packet_traverser_test.cpp | 155 +++++++++++++++ test/single_return_packet_traverser_test.cpp | 124 ++++++++++++ 6 files changed, 525 insertions(+), 97 deletions(-) create mode 100644 src/rs_driver/driver/decoder/packet_traverser.hpp create mode 100644 test/dual_return_packet_traverser_test.cpp create mode 100644 test/single_return_packet_traverser_test.cpp diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 7599a80a..572d273c 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -34,6 +34,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include +#include #include #include @@ -95,12 +96,12 @@ typedef struct uint16_t CHANNELS_PER_BLOCK; //uint16_t LASER_NUM; // diff from CHANNELS_PER_BLOCK ? - // distance + // distance resolution float DIS_RESOLUTION; - // firing_ts/block_chan_ts - float CHAN_TS[128]; - float BLOCK_TS; + // firing_ts / block_ts, chan_ts + float CHAN_TSS[128]; + float BLOCK_DURATION; // lens center float RX; @@ -131,7 +132,7 @@ class Decoder { // Assume echo_mode is ECHO_SINGLE. // If it is ECHO_DUAL, use RSInputParam.pcap_rate = 2 to change the playback speed. - return this->const_param_.BLOCK_TS * const_param_.BLOCKS_PER_PKT; + return this->const_param_.BLOCK_DURATION * const_param_.BLOCKS_PER_PKT; } void loadAngleFile(const std::string& angle_path) @@ -201,7 +202,7 @@ inline Decoder::Decoder(const RSDecoderParam& param, , distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance) , scan_block_(param.start_angle * 100, param.end_angle * 100) , split_angle_(param.split_angle * 100) - , blks_per_frame_(1/(10*lidar_const_param.BLOCK_TS)) + , blks_per_frame_(1/(10*lidar_const_param.BLOCK_DURATION)) , block_azi_diff_(20) , fov_blind_ts_diff_(0) , protocol_ver_(0) @@ -323,10 +324,10 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) } // blocks per frame - blks_per_frame_ = 1 / (this->rps_ * this->const_param_.BLOCK_TS); + blks_per_frame_ = 1 / (this->rps_ * this->const_param_.BLOCK_DURATION); // block diff of azimuth - this->block_azi_diff_ = RS_ONE_ROUND * this->rps_ * this->const_param_.BLOCK_TS; + this->block_azi_diff_ = RS_ONE_ROUND * this->rps_ * this->const_param_.BLOCK_DURATION; // fov related uint16_t fov_start_angle = ntohs(pkt.fov.start_angle); diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 760cd535..74af5bca 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -31,6 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #include +#include namespace robosense { @@ -55,7 +56,8 @@ typedef struct typedef struct { - uint64_t id; + uint8_t id[8]; + //uint64_t id; uint16_t rpm; RSEthNet eth; RSFOV fov; @@ -147,7 +149,7 @@ inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* { const RS32DifopPkt& pkt = *(const RS32DifopPkt*)(packet); - if (memcmp(this->const_param_.DIFOP_ID, &(pkt.id), 8) != 0) + if (memcmp(this->const_param_.DIFOP_ID, pkt.id, 8) != 0) { return RSDecoderResult::WRONG_PKT_HEADER; } @@ -164,101 +166,18 @@ inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* return RSDecoderResult::DECODE_OK; } -#if 0 -template -class PacketTraverser -{ -public: - - PacketTraverser(uint64_t pkt_ts) - : bi_(0), ci_(0) - { - ts_ = pkt_ts; - azi_ = pkt_.blocks[0].azimuth; - } - - void toNext() - { - static const float delta_ts[] = - { 0.00, 2.88, 5.76, 8.64, 11.52, 14.40, 17.28, 20.16, - 23.04, 25.92, 28.80, 31.68, 34.56, 37.44, 40.32, 44.64, - 1.44, 4.32, 7.20, 10.08, 12.96, 15.84, 18.72, 21.60, - 24.48, 27.36, 30.24, 33.12, 36.00, 38.88, 41.76, 46.08 - }; - - static const float delta_block = 55.52; - - ci++; - if (ci_ < CHAN_PER_BLOCK) - { - ts_ += delta_ts[ci_] - delta_ts[ci_-1]; - azi_ += azi_diff * delta_ts[ci] / delta_block; - } - else - { - bi_ ++; - ci_ = 0; - - blk_ts_ += block_diff - ts_ += delta_block - delta_ts[CHAN_PER_BLOCK-1]; - azi_ = pkt_.blocks[bi_].azimuth; - } - } - - bool isLast() - { - return (bi_ >= BLOCKS_PER_PACKET); - } - - void getPos(size_t& blk, size_t& chan) - { - blk = blk_; - chan = chan_; - } - - uint16_t azi() - { - return azi_; - } - - uint64_t ts() - { - return ts_; - } - -private: - - void calc() - { - } - - Packet pkt_; - size_t bi_; - size_t ci_; - uint64_t blk_ts_; - uint16_t blk_azi_; - uint64_t chan_ts_; - uint16_t chan_azi_; -}; -#endif - template inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* packet, size_t size) { - static uint8_t id[] = {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0}; - static uint8_t block_id[] = {0xFF, 0xEE}; - static const size_t BLOCKS_PER_PKT = 12; - const RS32MsopPkt& pkt = *(const RS32MsopPkt*)(packet); - if (memcpy((uint8_t*)&(pkt.header.id), id, sizeof(id)) != 0) + if (memcmp(this->const_param_.MSOP_ID, pkt.header.id, 8) != 0) { return RSDecoderResult::WRONG_PKT_HEADER; } this->temperature_ = calcTemp(&(pkt.header.temp)); - double chan_ts; double pkt_ts = 0; if (this->param_.use_lidar_clock) { @@ -269,6 +188,53 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p pkt_ts = calcTimeHost(); } + SingleReturnPacketTraverser traverser(this->const_param_, pkt, pkt_ts); + + for (; !traverser.isLast(); traverser.toNext()) + { + uint16_t blk, chan; + traverser.getPos (blk, chan); + + const RSChannel& channel = pkt.blocks[blk].channels[chan]; + float distance = ntohs(channel.distance) * this->const_param_.DIS_RESOLUTION; + uint8_t intensity = channel.intensity; + int16_t angle_vert = this->chan_angles_.vertAdjust(chan); + + int16_t angle_horiz; + double chan_ts; + traverser.getValue (angle_horiz, chan_ts); + int16_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + + if (this->distance_block_.in(distance) && this->scan_block_.in(angle_horiz_final)) + { + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->const_param_.RZ; + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, intensity); + + setRing(point, this->chan_angles_.toUserChan(chan)); + setTimestamp(point, chan_ts); + this->point_cloud_->points.emplace_back(point); + } + else if (!this->param_.dense_points) + { + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setRing(point, this->chan_angles_.toUserChan(chan)); + setTimestamp(point, chan_ts); + this->point_cloud_->points.emplace_back(point); + } + } + +#if 0 double block_ts = pkt_ts; uint16_t azi_diff = 0; for (size_t blk_idx = 0; blk_idx < BLOCKS_PER_PKT; blk_idx++) @@ -319,7 +285,7 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p if (blk_idx > 0) { block_ts = (azi_diff > 100) ? (block_ts + this->fov_blind_ts_diff_) : - (block_ts + this->const_param_.BLOCK_TS); + (block_ts + this->const_param_.BLOCK_DURATION); } } @@ -380,6 +346,7 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p } } } +#endif return RSDecoderResult::DECODE_OK; } diff --git a/src/rs_driver/driver/decoder/packet_traverser.hpp b/src/rs_driver/driver/decoder/packet_traverser.hpp new file mode 100644 index 00000000..7ee1488d --- /dev/null +++ b/src/rs_driver/driver/decoder/packet_traverser.hpp @@ -0,0 +1,179 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#include + +namespace robosense +{ +namespace lidar +{ + +template +class SingleReturnPacketTraverser +{ +public: + + SingleReturnPacketTraverser(const RSDecoderConstParam const_param, const T_Packet& pkt, double pkt_ts) + : const_param_(const_param), pkt_(pkt), bi_(0), ci_(0) + { + // calc initial values + blk_ts_ = pkt_ts; + blk_azi_ = pkt_.blocks[bi_].azimuth; + blk_azi_diff_ = pkt.blocks[bi_+1].azimuth - pkt.blocks[bi_].azimuth; + } + + void toNext() + { + ci_++; + if (ci_ >= const_param_.CHANNELS_PER_BLOCK) + { + ci_ = 0; + bi_++; + + // calc next values + if (bi_ < const_param_.BLOCKS_PER_PKT) + { + blk_ts_ += const_param_.BLOCK_DURATION; + blk_azi_ = pkt_.blocks[bi_].azimuth; + if (bi_ < (const_param_.BLOCKS_PER_PKT - 1)) + { + blk_azi_diff_ = pkt_.blocks[bi_+1].azimuth - pkt_.blocks[bi_].azimuth; + } + } + } + } + + bool isLast() + { + return (bi_ >= const_param_.BLOCKS_PER_PKT); + } + + bool getValue(int16_t& azi, double& ts) + { + if (bi_ >= const_param_.BLOCKS_PER_PKT) + return false; + + ts = blk_ts_ + const_param_.CHAN_TSS[ci_]; + azi = blk_azi_ + + blk_azi_diff_ * (const_param_.CHAN_TSS[ci_] / const_param_.BLOCK_DURATION); + return true; + } + + void getPos(uint16_t& blk, uint16_t& chan) + { + blk = bi_; + chan = ci_; + } + +private: + + const RSDecoderConstParam const_param_; + const T_Packet& pkt_; + uint16_t bi_; + uint16_t ci_; + double blk_ts_; + int16_t blk_azi_diff_; + int16_t blk_azi_; +}; + +template +class DualReturnPacketTraverser +{ +public: + + DualReturnPacketTraverser(const RSDecoderConstParam const_param, const T_Packet& pkt, double pkt_ts) + : const_param_(const_param), pkt_(pkt), bi_(0), ci_(0) + { + // calc initial values + blk_ts_ = pkt_ts; + + blk_azi_ = pkt_.blocks[bi_].azimuth; + blk_azi_diff_ = pkt.blocks[bi_+2].azimuth - pkt.blocks[bi_].azimuth; + } + + void toNext() + { + ci_++; + if (ci_ >= const_param_.CHANNELS_PER_BLOCK) + { + ci_ = 0; + bi_++; + + // calc next values + if ((bi_ < const_param_.BLOCKS_PER_PKT) && (bi_ % 2 == 0)) + { + blk_ts_ += const_param_.BLOCK_DURATION; + + blk_azi_ = pkt_.blocks[bi_].azimuth; + if (bi_ < (const_param_.BLOCKS_PER_PKT-2)) + { + blk_azi_diff_ = pkt_.blocks[bi_+2].azimuth - pkt_.blocks[bi_].azimuth; + } + } + } + } + + bool isLast() + { + return (bi_ >= const_param_.BLOCKS_PER_PKT); + } + + bool getValue(int16_t& azi, double& ts) + { + if (bi_ >= const_param_.BLOCKS_PER_PKT) + return false; + + ts = blk_ts_ + const_param_.CHAN_TSS[ci_]; + azi = blk_azi_ + + blk_azi_diff_ * (const_param_.CHAN_TSS[ci_] / const_param_.BLOCK_DURATION); + return true; + } + + void getPos(uint16_t& blk, uint16_t& chan) + { + blk = bi_; + chan = ci_; + } + +private: + + const RSDecoderConstParam const_param_; + const T_Packet& pkt_; + uint16_t bi_; + uint16_t ci_; + double blk_ts_; + int16_t blk_azi_diff_; + int16_t blk_azi_; +}; + +} // namespace lidar +} // namespace robosense diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index e911d59b..32f103d1 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -8,10 +8,12 @@ include_directories(${GTEST_INCLUDE_DIRS}) include_directories(${DRIVER_INCLUDE_DIRS}) add_executable(rs_driver_test - rs_driver_test.cpp packet_test.cpp + rs_driver_test.cpp sync_queue_test.cpp - decoder_test.cpp) + decoder_test.cpp + single_return_packet_traverser_test.cpp + dual_return_packet_traverser_test.cpp) target_link_libraries(rs_driver_test ${GTEST_LIBRARIES} diff --git a/test/dual_return_packet_traverser_test.cpp b/test/dual_return_packet_traverser_test.cpp new file mode 100644 index 00000000..837a2a4d --- /dev/null +++ b/test/dual_return_packet_traverser_test.cpp @@ -0,0 +1,155 @@ + +#include + +#include +#include + +using namespace robosense::lidar; + +typedef struct +{ + uint16_t distance; + uint8_t intensity; +} MyChannel; + +typedef struct +{ + uint16_t azimuth; + MyChannel channels[2]; +} MyBlock; + +typedef struct +{ + MyBlock blocks[6]; +} MyPacket; + +TEST(TestDualPacketTraverser, toNext) +{ + RSDecoderConstParam const_param = + { + {0x00} // msop id + , {0x00} // difop id + , {0x00} // block id + , 6 // blocks per packet + , 2 // channels per block + , 0.25 // distance resolution + + // firing_ts + , {0.0, 0.25} // chan_tss + , 0.50 // block_duration + + // lens center + , 0 // RX + , 0 // RY + , 0 // RZ + }; + + MyPacket pkt = + { + 1, 0x00, 0x00, 0x00, 0x00 + , 0, 0x00, 0x00, 0x00, 0x00 + , 21, 0x00, 0x00, 0x00, 0x00 + , 0, 0x00, 0x00, 0x00, 0x00 + , 51, 0x00, 0x00, 0x00, 0x00 + , 0, 0x00, 0x00, 0x00, 0x00 + }; + + int16_t azi; + double ts; + uint16_t blk, chan; + DualReturnPacketTraverser traverser(const_param, pkt, 0.25); + + // blk 0, chan 0 + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 0); + ASSERT_EQ(chan, 0); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 1); + ASSERT_EQ(ts, 0.25); + + // blk 0, chan 1 + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 0); + ASSERT_EQ(chan, 1); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 11); + ASSERT_EQ(ts, 0.50); + + // blk 1, chan 0. 2nd return + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 1); + ASSERT_EQ(chan, 0); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 1); + ASSERT_EQ(ts, 0.25); + + // blk 1, chan 1. 2nd return + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 1); + ASSERT_EQ(chan, 1); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 11); + ASSERT_EQ(ts, 0.50); + + // blk 2, chan 0 + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 2); + ASSERT_EQ(chan, 0); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 21); + ASSERT_EQ(ts, 0.75); + + // blk 2, chan 1 + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 2); + ASSERT_EQ(chan, 1); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 36); + ASSERT_EQ(ts, 1.0); + + // blk 3, chan 0. 2nd return. + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 3); + ASSERT_EQ(chan, 0); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 21); + ASSERT_EQ(ts, 0.75); + + // blk 3, chan 1. 2nd return + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + + // blk 4, chan 0. + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 4); + ASSERT_EQ(chan, 0); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 51); + ASSERT_EQ(ts, 1.25); + + // blk 4, chan 1. + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 4); + ASSERT_EQ(chan, 1); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 66); + ASSERT_EQ(ts, 1.5); +} + diff --git a/test/single_return_packet_traverser_test.cpp b/test/single_return_packet_traverser_test.cpp new file mode 100644 index 00000000..9b091891 --- /dev/null +++ b/test/single_return_packet_traverser_test.cpp @@ -0,0 +1,124 @@ + +#include + +#include +#include + +using namespace robosense::lidar; + +typedef struct +{ + uint16_t distance; + uint8_t intensity; +} MyChannel; + +typedef struct +{ + uint16_t azimuth; + MyChannel channels[2]; +} MyBlock; + +typedef struct +{ + MyBlock blocks[3]; +} MyPacket; + +TEST(TestSingleReturnPacketTraverser, toNext) +{ + RSDecoderConstParam const_param = + { + {0x00} // msop id + , {0x00} // difop id + , {0x00} // block id + , 3 // blocks per packet + , 2 // channels per block + , 0.25 // distance resolution + + // firing_ts + , {0.0, 0.25} // chan_tss + , 0.50 // block_duration + + // lens center + , 0 // RX + , 0 // RY + , 0 // RZ + }; + + MyPacket pkt = + { + 1, 0x00, 0x00, 0x00, 0x00 + , 21, 0x00, 0x00, 0x00, 0x00 + , 51, 0x00, 0x00, 0x00, 0x00 + }; + + int16_t azi; + double ts; + uint16_t blk, chan; + SingleReturnPacketTraverser traverser(const_param, pkt, 0.25); + + // blk 0, chan 0 + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 0); + ASSERT_EQ(chan, 0); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 1); + ASSERT_EQ(ts, 0.25); + + // blk 0, chan 1 + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 0); + ASSERT_EQ(chan, 1); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 11); + ASSERT_EQ(ts, 0.50); + + // cross block. + // blk 1, chan 0 + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 1); + ASSERT_EQ(chan, 0); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 21); + ASSERT_EQ(ts, 0.75); + + // blk 1, chan 1 + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 1); + ASSERT_EQ(chan, 1); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 36); + ASSERT_EQ(ts, 1.0); + + // cross block. + // blk 2, chan 0 + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 2); + ASSERT_EQ(chan, 0); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 51); + ASSERT_EQ(ts, 1.25); + + // blk 2, chan 1 + traverser.toNext(); + ASSERT_FALSE(traverser.isLast()); + traverser.getPos(blk, chan); + ASSERT_EQ(blk, 2); + ASSERT_EQ(chan, 1); + ASSERT_TRUE(traverser.getValue(azi, ts)); + ASSERT_EQ(azi, 66); + ASSERT_EQ(ts, 1.5); + + traverser.toNext(); + ASSERT_TRUE(traverser.isLast()); + ASSERT_FALSE(traverser.getValue(azi, ts)); +} + From e178569b657c5c3435169e19170971c6a81f9f0e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 6 Dec 2021 18:37:22 +0800 Subject: [PATCH 042/379] refac: refactor packet traverser --- src/rs_driver/driver/decoder/decoder_RS32.hpp | 8 +- .../driver/decoder/packet_traverser.hpp | 119 +++++++----------- test/dual_return_packet_traverser_test.cpp | 27 ++-- test/single_return_packet_traverser_test.cpp | 20 ++- 4 files changed, 66 insertions(+), 108 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 74af5bca..b89b37ac 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -193,16 +193,14 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p for (; !traverser.isLast(); traverser.toNext()) { uint16_t blk, chan; - traverser.getPos (blk, chan); + int16_t angle_horiz; + double chan_ts; + traverser.get (blk, chan, angle_horiz, chan_ts); const RSChannel& channel = pkt.blocks[blk].channels[chan]; float distance = ntohs(channel.distance) * this->const_param_.DIS_RESOLUTION; uint8_t intensity = channel.intensity; int16_t angle_vert = this->chan_angles_.vertAdjust(chan); - - int16_t angle_horiz; - double chan_ts; - traverser.getValue (angle_horiz, chan_ts); int16_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); if (this->distance_block_.in(distance) && this->scan_block_.in(angle_horiz_final)) diff --git a/src/rs_driver/driver/decoder/packet_traverser.hpp b/src/rs_driver/driver/decoder/packet_traverser.hpp index 7ee1488d..fcdf2678 100644 --- a/src/rs_driver/driver/decoder/packet_traverser.hpp +++ b/src/rs_driver/driver/decoder/packet_traverser.hpp @@ -38,17 +38,17 @@ namespace lidar { template -class SingleReturnPacketTraverser +class PacketTraverser { public: - SingleReturnPacketTraverser(const RSDecoderConstParam const_param, const T_Packet& pkt, double pkt_ts) + virtual void toNextBlock() = 0; + + PacketTraverser(const RSDecoderConstParam const_param, const T_Packet& pkt, double pkt_ts) : const_param_(const_param), pkt_(pkt), bi_(0), ci_(0) { - // calc initial values blk_ts_ = pkt_ts; blk_azi_ = pkt_.blocks[bi_].azimuth; - blk_azi_diff_ = pkt.blocks[bi_+1].azimuth - pkt.blocks[bi_].azimuth; } void toNext() @@ -59,16 +59,7 @@ class SingleReturnPacketTraverser ci_ = 0; bi_++; - // calc next values - if (bi_ < const_param_.BLOCKS_PER_PKT) - { - blk_ts_ += const_param_.BLOCK_DURATION; - blk_azi_ = pkt_.blocks[bi_].azimuth; - if (bi_ < (const_param_.BLOCKS_PER_PKT - 1)) - { - blk_azi_diff_ = pkt_.blocks[bi_+1].azimuth - pkt_.blocks[bi_].azimuth; - } - } + toNextBlock(); } } @@ -77,24 +68,20 @@ class SingleReturnPacketTraverser return (bi_ >= const_param_.BLOCKS_PER_PKT); } - bool getValue(int16_t& azi, double& ts) + bool get(uint16_t& blk, uint16_t& chan, int16_t& azi, double& ts) { if (bi_ >= const_param_.BLOCKS_PER_PKT) return false; - ts = blk_ts_ + const_param_.CHAN_TSS[ci_]; - azi = blk_azi_ + - blk_azi_diff_ * (const_param_.CHAN_TSS[ci_] / const_param_.BLOCK_DURATION); - return true; - } - - void getPos(uint16_t& blk, uint16_t& chan) - { blk = bi_; chan = ci_; + + ts = blk_ts_ + const_param_.CHAN_TSS[ci_]; + azi = blk_azi_ + blk_azi_diff_ * (const_param_.CHAN_TSS[ci_] / const_param_.BLOCK_DURATION); + return true; } -private: +protected: const RSDecoderConstParam const_param_; const T_Packet& pkt_; @@ -106,73 +93,61 @@ class SingleReturnPacketTraverser }; template -class DualReturnPacketTraverser +class SingleReturnPacketTraverser : public PacketTraverser { public: - DualReturnPacketTraverser(const RSDecoderConstParam const_param, const T_Packet& pkt, double pkt_ts) - : const_param_(const_param), pkt_(pkt), bi_(0), ci_(0) + SingleReturnPacketTraverser(const RSDecoderConstParam const_param, + const T_Packet& pkt, double pkt_ts) + : PacketTraverser(const_param, pkt, pkt_ts) { - // calc initial values - blk_ts_ = pkt_ts; - - blk_azi_ = pkt_.blocks[bi_].azimuth; - blk_azi_diff_ = pkt.blocks[bi_+2].azimuth - pkt.blocks[bi_].azimuth; + this->blk_azi_diff_ = + this->pkt_.blocks[this->bi_+1].azimuth - this->pkt_.blocks[this->bi_].azimuth; } - void toNext() + virtual void toNextBlock() { - ci_++; - if (ci_ >= const_param_.CHANNELS_PER_BLOCK) + if (this->bi_ < this->const_param_.BLOCKS_PER_PKT) { - ci_ = 0; - bi_++; - - // calc next values - if ((bi_ < const_param_.BLOCKS_PER_PKT) && (bi_ % 2 == 0)) + this->blk_ts_ += this->const_param_.BLOCK_DURATION; + this->blk_azi_ = this->pkt_.blocks[this->bi_].azimuth; + if (this->bi_ < (this->const_param_.BLOCKS_PER_PKT - 1)) { - blk_ts_ += const_param_.BLOCK_DURATION; - - blk_azi_ = pkt_.blocks[bi_].azimuth; - if (bi_ < (const_param_.BLOCKS_PER_PKT-2)) - { - blk_azi_diff_ = pkt_.blocks[bi_+2].azimuth - pkt_.blocks[bi_].azimuth; - } + this->blk_azi_diff_ = + this->pkt_.blocks[this->bi_+1].azimuth - this->pkt_.blocks[this->bi_].azimuth; } } } +}; - bool isLast() - { - return (bi_ >= const_param_.BLOCKS_PER_PKT); - } - - bool getValue(int16_t& azi, double& ts) - { - if (bi_ >= const_param_.BLOCKS_PER_PKT) - return false; +template +class DualReturnPacketTraverser : public PacketTraverser - ts = blk_ts_ + const_param_.CHAN_TSS[ci_]; - azi = blk_azi_ + - blk_azi_diff_ * (const_param_.CHAN_TSS[ci_] / const_param_.BLOCK_DURATION); - return true; - } +{ +public: - void getPos(uint16_t& blk, uint16_t& chan) + DualReturnPacketTraverser(const RSDecoderConstParam const_param, + const T_Packet& pkt, double pkt_ts) + : PacketTraverser(const_param, pkt, pkt_ts) { - blk = bi_; - chan = ci_; + this->blk_azi_diff_ = + this->pkt_.blocks[this->bi_+2].azimuth - this->pkt_.blocks[this->bi_].azimuth; } -private: + virtual void toNextBlock() + { + if ((this->bi_ < this->const_param_.BLOCKS_PER_PKT) && (this->bi_ % 2 == 0)) + { + this->blk_ts_ += this->const_param_.BLOCK_DURATION; - const RSDecoderConstParam const_param_; - const T_Packet& pkt_; - uint16_t bi_; - uint16_t ci_; - double blk_ts_; - int16_t blk_azi_diff_; - int16_t blk_azi_; + this->blk_azi_ = this->pkt_.blocks[this->bi_].azimuth; + if (this->bi_ < (this->const_param_.BLOCKS_PER_PKT-2)) + { + this->blk_azi_diff_ = + this->pkt_.blocks[this->bi_+2].azimuth - this->pkt_.blocks[this->bi_].azimuth; + } + } + } }; } // namespace lidar diff --git a/test/dual_return_packet_traverser_test.cpp b/test/dual_return_packet_traverser_test.cpp index 837a2a4d..370ef4eb 100644 --- a/test/dual_return_packet_traverser_test.cpp +++ b/test/dual_return_packet_traverser_test.cpp @@ -61,70 +61,63 @@ TEST(TestDualPacketTraverser, toNext) // blk 0, chan 0 ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 0); ASSERT_EQ(chan, 0); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 1); ASSERT_EQ(ts, 0.25); // blk 0, chan 1 traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 0); ASSERT_EQ(chan, 1); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 11); ASSERT_EQ(ts, 0.50); // blk 1, chan 0. 2nd return traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 1); ASSERT_EQ(chan, 0); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 1); ASSERT_EQ(ts, 0.25); // blk 1, chan 1. 2nd return traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 1); ASSERT_EQ(chan, 1); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 11); ASSERT_EQ(ts, 0.50); // blk 2, chan 0 traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 2); ASSERT_EQ(chan, 0); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 21); ASSERT_EQ(ts, 0.75); // blk 2, chan 1 traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 2); ASSERT_EQ(chan, 1); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 36); ASSERT_EQ(ts, 1.0); // blk 3, chan 0. 2nd return. traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 3); ASSERT_EQ(chan, 0); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 21); ASSERT_EQ(ts, 0.75); @@ -135,20 +128,18 @@ TEST(TestDualPacketTraverser, toNext) // blk 4, chan 0. traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 4); ASSERT_EQ(chan, 0); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 51); ASSERT_EQ(ts, 1.25); // blk 4, chan 1. traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 4); ASSERT_EQ(chan, 1); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 66); ASSERT_EQ(ts, 1.5); } diff --git a/test/single_return_packet_traverser_test.cpp b/test/single_return_packet_traverser_test.cpp index 9b091891..9e8d7501 100644 --- a/test/single_return_packet_traverser_test.cpp +++ b/test/single_return_packet_traverser_test.cpp @@ -58,20 +58,18 @@ TEST(TestSingleReturnPacketTraverser, toNext) // blk 0, chan 0 ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 0); ASSERT_EQ(chan, 0); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 1); ASSERT_EQ(ts, 0.25); // blk 0, chan 1 traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 0); ASSERT_EQ(chan, 1); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 11); ASSERT_EQ(ts, 0.50); @@ -79,20 +77,18 @@ TEST(TestSingleReturnPacketTraverser, toNext) // blk 1, chan 0 traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 1); ASSERT_EQ(chan, 0); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 21); ASSERT_EQ(ts, 0.75); // blk 1, chan 1 traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 1); ASSERT_EQ(chan, 1); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 36); ASSERT_EQ(ts, 1.0); @@ -100,25 +96,23 @@ TEST(TestSingleReturnPacketTraverser, toNext) // blk 2, chan 0 traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 2); ASSERT_EQ(chan, 0); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 51); ASSERT_EQ(ts, 1.25); // blk 2, chan 1 traverser.toNext(); ASSERT_FALSE(traverser.isLast()); - traverser.getPos(blk, chan); + ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); ASSERT_EQ(blk, 2); ASSERT_EQ(chan, 1); - ASSERT_TRUE(traverser.getValue(azi, ts)); ASSERT_EQ(azi, 66); ASSERT_EQ(ts, 1.5); traverser.toNext(); ASSERT_TRUE(traverser.isLast()); - ASSERT_FALSE(traverser.getValue(azi, ts)); + ASSERT_FALSE(traverser.get(blk, chan, azi, ts)); } From 3219477cc48d0fd6b46ec11cdb118ccdb8503e04 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 6 Dec 2021 20:21:46 +0800 Subject: [PATCH 043/379] feat: use old ip_mreq structure for compatibility --- src/rs_driver/driver/input/sock_input.hpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index b7c19ebd..eba449eb 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -167,10 +167,16 @@ inline int SockInput::createSocket(uint16_t port, const std::string& hostIp, con if (grpIp != "0.0.0.0") { +#if 0 struct ip_mreqn ipm; memset(&ipm, 0, sizeof(ipm)); inet_pton(AF_INET, grpIp.c_str(), &(ipm.imr_multiaddr)); inet_pton(AF_INET, hostIp.c_str(), &(ipm.imr_address)); +#else + struct ip_mreq ipm; + inet_pton(AF_INET, grpIp.c_str(), &(ipm.imr_multiaddr)); + inet_pton(AF_INET, hostIp.c_str(), &(ipm.imr_interface)); +#endif ret = setsockopt(fd, IPPROTO_IP, IP_ADD_MEMBERSHIP, &ipm, sizeof(ipm)); if (ret < 0) { From 00c985bfb6922e220af9ddae220e35ca0e3cebe4 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 7 Dec 2021 17:46:43 +0800 Subject: [PATCH 044/379] format: format files --- src/rs_driver/common/common_header.h | 3 --- src/rs_driver/driver/input/input.hpp | 1 - src/rs_driver/driver/input/pcap_input.hpp | 1 + 3 files changed, 1 insertion(+), 4 deletions(-) diff --git a/src/rs_driver/common/common_header.h b/src/rs_driver/common/common_header.h index ca85d81e..5d97abe0 100644 --- a/src/rs_driver/common/common_header.h +++ b/src/rs_driver/common/common_header.h @@ -86,9 +86,6 @@ inline void setConsoleColor(WORD c) } #endif -/*Pcap*/ -#include - /*Camera*/ typedef std::pair CameraTrigger; diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index 13aa3da3..f8ddad72 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -46,7 +46,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include #include #include #include diff --git a/src/rs_driver/driver/input/pcap_input.hpp b/src/rs_driver/driver/input/pcap_input.hpp index 98f3ba9d..8f1769f7 100644 --- a/src/rs_driver/driver/input/pcap_input.hpp +++ b/src/rs_driver/driver/input/pcap_input.hpp @@ -32,6 +32,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include "input.hpp" +#include "pcap.h" namespace robosense { From 719f4fec0a0f4bc6724f1e9771f8e90e28f35d36 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 7 Dec 2021 19:52:20 +0800 Subject: [PATCH 045/379] refac: refac decoder --- demo/demo_pcap.cpp | 7 +- src/rs_driver/api/lidar_driver.h | 8 +- src/rs_driver/driver/decoder/decoder.hpp | 4 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 128 ++---------------- .../driver/decoder/decoder_base_opt.hpp | 14 +- src/rs_driver/driver/driver_param.h | 101 +++++++++++++- src/rs_driver/driver/input/input.hpp | 6 +- src/rs_driver/driver/input/input_factory.hpp | 10 +- src/rs_driver/driver/input/input_pcap.hpp | 6 +- src/rs_driver/driver/lidar_driver_impl.hpp | 10 +- test/decoder_test.cpp | 4 +- 11 files changed, 148 insertions(+), 150 deletions(-) diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 6316669f..b638cb78 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -77,18 +77,17 @@ void exceptionCallback(const Error& code) int main(int argc, char* argv[]) { RS_TITLE << "------------------------------------------------------" << RS_REND; - RS_TITLE << " RS_Driver Core Version: v" << RSLIDAR_VERSION_MAJOR << "." << RSLIDAR_VERSION_MINOR << "." - << RSLIDAR_VERSION_PATCH << RS_REND; + RS_TITLE << " RS_Driver Core Version: v" << getDriverVersion() << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; g_pointcloud = std::make_shared(); RSDriverParam param; ///< Create a parameter object param.input_type = InputType::PCAP_FILE; - param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file directory + param.input_param.pcap_path = "/mnt/share/pcap/RS32/Rs32.pcap"; ///< Set the pcap file directory param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct + param.lidar_type = LidarType::RS32; ///< Set the lidar type. Make sure this type is correct param.print(); diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index f893cfe4..7ba26471 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -37,6 +37,9 @@ namespace robosense { namespace lidar { + +std::string getDriverVersion(); + /** * @brief This is the RoboSense LiDAR driver interface class */ @@ -45,11 +48,6 @@ class LidarDriver { public: - static std::string getVersion() - { - return LidarDriverImpl::getVersion(); - } - /** * @brief Constructor, instanciate the driver pointer */ diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 572d273c..3d755f8c 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -221,8 +221,6 @@ inline Decoder::Decoder(const RSDecoderParam& param, { loadAngleFile(param.angle_path); } - - point_cloud_ = point_cloud_cb_get_(); } template @@ -232,6 +230,8 @@ void Decoder::regRecvCallback( { point_cloud_cb_get_ = cb_get; point_cloud_cb_put_ = cb_put; + + point_cloud_ = point_cloud_cb_get_(); } template diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index b89b37ac..df5f8d67 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -41,14 +41,14 @@ namespace lidar #pragma pack(push, 1) typedef struct { - uint16_t id; + uint8_t id[2]; uint16_t azimuth; RSChannel channels[32]; } RS32MsopBlock; typedef struct { - RSMsopHeader header; + RSMsopHeaderV1 header; RS32MsopBlock blocks[12]; unsigned int index; uint16_t tail; @@ -57,7 +57,6 @@ typedef struct typedef struct { uint8_t id[8]; - //uint64_t id; uint16_t rpm; RSEthNet eth; RSFOV fov; @@ -197,7 +196,14 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p double chan_ts; traverser.get (blk, chan, angle_horiz, chan_ts); - const RSChannel& channel = pkt.blocks[blk].channels[chan]; + const RS32MsopBlock& block = pkt.blocks[blk]; + const RSChannel& channel = block.channels[chan]; + + if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) + { + return RSDecoderResult::WRONG_PKT_HEADER; + } + float distance = ntohs(channel.distance) * this->const_param_.DIS_RESOLUTION; uint8_t intensity = channel.intensity; int16_t angle_vert = this->chan_angles_.vertAdjust(chan); @@ -232,120 +238,6 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p } } -#if 0 - double block_ts = pkt_ts; - uint16_t azi_diff = 0; - for (size_t blk_idx = 0; blk_idx < BLOCKS_PER_PKT; blk_idx++) - { - const RS32MsopBlock& block = pkt.blocks[blk_idx]; - if (memcmp(&(block.id), block_id, sizeof(block_id))) - { - break; - } - - uint16_t block_azi = ntohs(block.azimuth); - - this->toSplit(block_azi, chan_ts); - -#if 0 - if (this->echo_mode_ == ECHO_DUAL) - { - if (blk_idx % 2 == 0) - { - if (blk_idx == 0) - { - azi_diff = static_cast( - (RS_ONE_ROUND + RS_SWAP_SHORT(pkt.blocks[blk_idx + 2].azimuth) - block_azi) % RS_ONE_ROUND); - } - else - { - azi_diff = static_cast( - (RS_ONE_ROUND + block_azi - RS_SWAP_SHORT(pkt.blocks[blk_idx - 2].azimuth)) % RS_ONE_ROUND); - block_ts = (azi_diff > 100) ? (block_ts + this->fov_time_jump_diff_) : - (block_ts + this->block_ts_diff_); - } - } - } - else -#endif - { - if (blk_idx < (BLOCKS_PER_PKT - 1)) - { - azi_diff = static_cast((RS_ONE_ROUND + ntohs(pkt.blocks[blk_idx + 1].azimuth) - block_azi) % - RS_ONE_ROUND); - } - else - { - azi_diff = static_cast((RS_ONE_ROUND + block_azi - ntohs(pkt.blocks[blk_idx - 1].azimuth)) % - RS_ONE_ROUND); - } - - if (blk_idx > 0) - { - block_ts = (azi_diff > 100) ? (block_ts + this->fov_blind_ts_diff_) : - (block_ts + this->const_param_.BLOCK_DURATION); - } - } - - //azi_diff = (azi_diff > 100) ? this->block_azi_diff_ : azi_diff; - - for (uint16_t chan_idx = 0; chan_idx < this->const_param_.CHANNELS_PER_BLOCK; chan_idx++) - { - static const float delta_ts[] = - { 0.00, 2.88, 5.76, 8.64, 11.52, 14.40, 17.28, 20.16, - 23.04, 25.92, 28.80, 31.68, 34.56, 37.44, 40.32, 44.64, - 1.44, 4.32, 7.20, 10.08, 12.96, 15.84, 18.72, 21.60, - 24.48, 27.36, 30.24, 33.12, 36.00, 38.88, 41.76, 46.08 - }; - - static const float delta_block = 55.52; - - const RSChannel& chan = block.channels[chan_idx]; - - chan_ts = block_ts + delta_ts[chan_idx]; - - float chan_ori_azi = block_azi + azi_diff * (delta_ts[chan_idx] / delta_block); - - float distance = ntohs(chan.distance) * this->const_param_.DIS_RESOLUTION; - - uint16_t azi_channel_final = this->chan_angles_.horizAdjust(chan_idx, (int32_t)chan_ori_azi); - - uint16_t angle_horiz = chan_ori_azi; - uint16_t angle_vert = this->chan_angles_.vertAdjust(chan_idx); - - if (this->distance_block_.in(distance) && this->scan_block_.in(azi_channel_final)) - { - float x = distance * COS(angle_vert) * COS(azi_channel_final) + this->const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(azi_channel_final) - this->const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->const_param_.RZ; - - uint8_t intensity = chan.intensity; - - typename T_PointCloud::PointT point; - setX(point, x); - setY(point, y); - setZ(point, z); - setIntensity(point, intensity); - - setRing(point, this->chan_angles_.toUserChan(chan_idx)); - setTimestamp(point, chan_ts); - this->point_cloud_->points.emplace_back(point); - } - else if (!this->param_.dense_points) - { - typename T_PointCloud::PointT point; - setX(point, NAN); - setY(point, NAN); - setZ(point, NAN); - setIntensity(point, 0); - setRing(point, this->chan_angles_.toUserChan(chan_idx)); - setTimestamp(point, chan_ts); - this->point_cloud_->points.emplace_back(point); - } - } - } -#endif - return RSDecoderResult::DECODE_OK; } diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 2ca5a560..9d291797 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -84,29 +84,27 @@ typedef struct typedef struct { uint8_t tt[2]; -} RsTemp; +} RsTemprature; typedef struct { uint8_t id[8]; -// uint64_t id; uint8_t reserved_1[12]; RSTimestampYMD timestamp; uint8_t lidar_type; uint8_t reserved_2[7]; - RsTemp temp; + RsTemprature temp; //uint16_t temp_raw; uint8_t reserved_3[2]; -} RSMsopHeader; +} RSMsopHeaderV1; typedef struct { uint8_t id[4]; -// uint32_t id; uint16_t protocol_version; uint8_t reserved_1; uint8_t wave_mode; - RsTemp temp; + RsTemprature temp; #if 0 uint8_t temp_low; uint8_t temp_high; @@ -115,7 +113,7 @@ typedef struct uint8_t reserved_2[10]; uint8_t lidar_type; uint8_t reserved_3[49]; -} RSMsopHeaderNew; +} RSMsopHeaderV2; typedef struct { @@ -342,7 +340,7 @@ inline uint64_t calcTimeHost(void) #define RS_TEMP_RESOLUTION 0.0625f -inline int16_t calcTemp(const RsTemp* tmp) +inline int16_t calcTemp(const RsTemprature* tmp) { // | lsb | padding | neg | msb | // | 5 | 3 | 1 | 7 | (in bits) diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index 9b3ab270..cdb2434a 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -50,6 +50,84 @@ enum LidarType ///< LiDAR type RSM1 = 10 }; +inline std::string lidarTypeToStr(const LidarType& type) +{ + std::string str = ""; + switch (type) + { + case LidarType::RS16: + str = "RS16"; + break; + case LidarType::RS32: + str = "RS32"; + break; + case LidarType::RSBP: + str = "RSBP"; + break; + case LidarType::RS128: + str = "RS128"; + break; + case LidarType::RS80: + str = "RS80"; + break; + case LidarType::RSM1: + str = "RSM1"; + break; + case LidarType::RSHELIOS: + str = "RSHELIOS"; + break; + case LidarType::RSROCK: + str = "RSROCK"; + break; + default: + str = "ERROR"; + RS_ERROR << "RS_ERROR" << RS_REND; + } + return str; +} + +inline LidarType strToLidarType(const std::string& type) +{ + if (type == "RS16") + { + return lidar::LidarType::RS16; + } + else if (type == "RS32") + { + return lidar::LidarType::RS32; + } + else if (type == "RSBP") + { + return lidar::LidarType::RSBP; + } + else if (type == "RS128") + { + return lidar::LidarType::RS128; + } + else if (type == "RS80") + { + return lidar::LidarType::RS80; + } + else if (type == "RSM1") + { + return lidar::LidarType::RSM1; + } + else if (type == "RSHELIOS") + { + return lidar::LidarType::RSHELIOS; + } + else if (type == "RSROCK") + { + return lidar::LidarType::RSROCK; + } + else + { + RS_ERROR << "Wrong lidar type: " << type << RS_REND; + RS_ERROR << "Please setup the correct type: RS16, RS32, RSBP, RS128, RS80, RSM1, RSHELIOS" << RS_REND; + exit(-1); + } +} + enum InputType { ONLINE_LIDAR = 1, @@ -57,6 +135,27 @@ enum InputType RAW_PACKET }; +inline std::string inputTypeToStr(const InputType& type) +{ + std::string str = ""; + switch (type) + { + case InputType::ONLINE_LIDAR: + str = "ONLINE_LIDAR"; + break; + case InputType::PCAP_FILE: + str = "PCAP_FILE"; + break; + case InputType::RAW_PACKET: + str = "RAW_PACKET"; + break; + default: + str = "ERROR"; + RS_ERROR << "RS_ERROR" << RS_REND; + } + return str; +} + enum SplitFrameMode { SPLIT_BY_ANGLE = 1, @@ -189,7 +288,7 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter RS_INFO << "------------------------------------------------------" << RS_REND; RS_INFOL << " RoboSense Driver Parameters " << RS_REND; RS_INFOL << "lidar_type: " << lidarTypeToStr(lidar_type) << RS_REND; - RS_INFOL << "input type: " << (int)input_type << RS_REND; + RS_INFOL << "input type: " << inputTypeToStr(input_type) << RS_REND; RS_INFOL << "------------------------------------------------------" << RS_REND; } diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index f3de7e21..f2425c3d 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -75,8 +75,10 @@ class Input bool start_flag_; }; -inline Input::Input(const RSInputParam& input_param, const std::function& excb) - : input_param_(input_param), excb_(excb), to_exit_recv_(false), init_flag_(false), start_flag_(false) +inline Input::Input(const RSInputParam& input_param, + const std::function& excb) + : input_param_(input_param), excb_(excb), to_exit_recv_(false), + init_flag_(false), start_flag_(false) { } diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 9b8f72cb..c6ad0564 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -49,8 +49,8 @@ class InputFactory }; inline std::shared_ptr InputFactory::createInput(InputType type, - const RSInputParam& param, - const std::function& excb, uint64_t msec_to_delay) + const RSInputParam& param, const std::function& excb, + uint64_t msec_to_delay) { std::shared_ptr input; @@ -60,14 +60,20 @@ inline std::shared_ptr InputFactory::createInput(InputType type, { input = std::make_shared(param, excb); } + break; + case InputType::PCAP_FILE: { input = std::make_shared(param, excb, msec_to_delay); } + break; + case InputType::RAW_PACKET: { input = std::make_shared(param, excb); } + break; + default: break; } diff --git a/src/rs_driver/driver/input/input_pcap.hpp b/src/rs_driver/driver/input/input_pcap.hpp index 6fdf0fac..2e414089 100644 --- a/src/rs_driver/driver/input/input_pcap.hpp +++ b/src/rs_driver/driver/input/input_pcap.hpp @@ -44,8 +44,10 @@ namespace lidar class InputPcap : public Input { public: - InputPcap(const RSInputParam& input_param, const std::function& excb, long long msec_to_delay) - : Input(input_param, excb), pcap_offset_(ETH_HDR_LEN), difop_filter_valid_(false), msec_to_delay_(msec_to_delay) + InputPcap(const RSInputParam& input_param, + const std::function& excb, long long msec_to_delay) + : Input(input_param, excb), pcap_offset_(ETH_HDR_LEN), + difop_filter_valid_(false), msec_to_delay_(msec_to_delay) { if (input_param.use_vlan) pcap_offset_ += VLAN_LEN; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 843282ad..b21dd47e 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -35,7 +35,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include +#include #include #include #include @@ -120,8 +120,7 @@ class LidarDriverImpl uint32_t ndifop_count_; }; -template -inline std::string LidarDriverImpl::getVersion() +inline std::string getDriverVersion() { std::stringstream stream; stream << RSLIDAR_VERSION_MAJOR << "." @@ -165,7 +164,8 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) uint64_t packet_diff = lidar_decoder_ptr_->getPacketDiff(); input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, - std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1), packet_diff); + std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1), + packet_diff); input_ptr_->regRecvCallback(std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), std::bind(&LidarDriverImpl::packetPut, this, std::placeholders::_1)); @@ -322,6 +322,8 @@ inline void LidarDriverImpl::packetPut(std::shared_ptr pkt { SyncQueue>* queue; + hexdump (pkt->data(), 16, "pkt"); + uint8_t* id = pkt->data(); if (*id == 0x55) { diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 0fe8800b..33910539 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -31,12 +31,12 @@ TEST(TestParseTemp, calcTemp) { { uint8_t temp[] = {0x18, 0x01}; - ASSERT_EQ(calcTemp((RsTemp*)&temp), 35); + ASSERT_EQ(calcTemp((RsTemprature*)&temp), 35); } { uint8_t temp[] = {0x18, 0x81}; - ASSERT_EQ(calcTemp((RsTemp*)&temp), -35); + ASSERT_EQ(calcTemp((RsTemprature*)&temp), -35); } } From 611c0dce05a4dabbbbaf9f8eba45701409bf8897 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 8 Dec 2021 08:52:10 +0800 Subject: [PATCH 046/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 42 +++++++++++++------ src/rs_driver/driver/decoder/decoder_RS32.hpp | 35 +++++++++------- src/rs_driver/driver/lidar_driver_impl.hpp | 2 +- test/dual_return_packet_traverser_test.cpp | 6 ++- test/single_return_packet_traverser_test.cpp | 6 ++- 5 files changed, 60 insertions(+), 31 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 3d755f8c..753a6e5b 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -56,11 +56,12 @@ namespace robosense namespace lidar { -/*Packet Length*/ +#if 0 const size_t MECH_PKT_LEN = 1248; const size_t MEMS_MSOP_LEN = 1210; const size_t MEMS_DIFOP_LEN = 256; const size_t ROCK_MSOP_LEN = 1236; +#endif constexpr int RS_ONE_ROUND = 36000; constexpr uint16_t PROTOCOL_VER_0 = 0x00; @@ -86,7 +87,12 @@ enum RSDecoderResult typedef struct { + uint16_t MSOP_LEN; + uint16_t DIFOP_LEN; + // identity + uint8_t MSOP_ID_LEN; + uint8_t DIFOP_ID_LEN; uint8_t MSOP_ID[8]; uint8_t DIFOP_ID[8]; uint8_t BLOCK_ID[2]; @@ -115,9 +121,9 @@ class Decoder { public: - virtual RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size); - virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size) = 0; - virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; + virtual void processMsopPkt(const uint8_t* pkt, size_t size); + virtual void processDifopPkt(const uint8_t* pkt, size_t size) = 0; + virtual void decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual ~Decoder() = default; void regRecvCallback(const std::function(void)>& cb_get, @@ -157,8 +163,6 @@ class Decoder RSDecoderParam param_; std::function excb_; uint16_t height_; // to be deleted - uint32_t msop_pkt_len_; // to be moved - uint32_t difop_pkt_len_; // to be moved Trigon trigon_; #define SIN(angle) this->trigon_.sin(angle) @@ -197,8 +201,6 @@ inline Decoder::Decoder(const RSDecoderParam& param, , param_(param) , excb_(excb) , height_(0) - , msop_pkt_len_(MECH_PKT_LEN) - , difop_pkt_len_(MECH_PKT_LEN) , distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance) , scan_block_(param.start_angle * 100, param.end_angle * 100) , split_angle_(param.split_angle * 100) @@ -301,14 +303,30 @@ void Decoder::setPointCloudHeader(std::shared_ptr ms } template -RSDecoderResult Decoder::processMsopPkt(const uint8_t* pkt, size_t size) +void Decoder::processMsopPkt(const uint8_t* pkt, size_t size) { if (param_.wait_for_difop && !difop_ready_) { - return RSDecoderResult::DIFOP_NOT_READY; + excb_(Error(ERRCODE_NODIFOPRECV)); } - return decodeMsopPkt(pkt, size); + if (size != this->const_param_.MSOP_LEN) + { + this->excb_(Error(ERRCODE_WRONGPKTLENGTH)); + } + + if (memcmp(pkt, this->const_param_.MSOP_ID, const_param_.MSOP_ID_LEN) != 0) + { + this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + } + + decodeMsopPkt(pkt, size); +} + +template +void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) +{ + } template @@ -324,7 +342,7 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) } // blocks per frame - blks_per_frame_ = 1 / (this->rps_ * this->const_param_.BLOCK_DURATION); + this->blks_per_frame_ = 1 / (this->rps_ * this->const_param_.BLOCK_DURATION); // block diff of azimuth this->block_azi_diff_ = RS_ONE_ROUND * this->rps_ * this->const_param_.BLOCK_DURATION; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index df5f8d67..d42278bc 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -86,8 +86,8 @@ class DecoderRS32 : public Decoder { public: - virtual RSDecoderResult processDifopPkt(const uint8_t* pkt, size_t size); - virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual void processDifopPkt(const uint8_t* pkt, size_t size); + virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); virtual uint64_t usecToDelay() {return 0;} virtual ~DecoderRS32() = default; @@ -98,7 +98,11 @@ class DecoderRS32 : public Decoder { RSDecoderConstParam param = { - {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + 1248 + , 1248 + , 8 + , 8 + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id , 12 // blocks per packet @@ -144,13 +148,20 @@ inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, } template -inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* packet, size_t size) +inline void DecoderRS32::processDifopPkt(const uint8_t* packet, size_t size) { const RS32DifopPkt& pkt = *(const RS32DifopPkt*)(packet); + hexdump (packet, size, "difop"); + + if (size != this->const_param_.DIFOP_LEN) + { + this->excb_(Error(ERRCODE_WRONGPKTLENGTH)); + } + if (memcmp(this->const_param_.DIFOP_ID, pkt.id, 8) != 0) { - return RSDecoderResult::WRONG_PKT_HEADER; + this->excb_(Error(ERRCODE_WRONGPKTHEADER)); } this->echo_mode_ = getEchoMode (pkt.return_mode); @@ -161,20 +172,13 @@ inline RSDecoderResult DecoderRS32::processDifopPkt(const uint8_t* { this->chan_angles_.loadFromDifop(pkt.ver_angle_cali, pkt.hori_angle_cali, 32); } - - return RSDecoderResult::DECODE_OK; } template -inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* packet, size_t size) +inline void DecoderRS32::decodeMsopPkt(const uint8_t* packet, size_t size) { const RS32MsopPkt& pkt = *(const RS32MsopPkt*)(packet); - if (memcmp(this->const_param_.MSOP_ID, pkt.header.id, 8) != 0) - { - return RSDecoderResult::WRONG_PKT_HEADER; - } - this->temperature_ = calcTemp(&(pkt.header.temp)); double pkt_ts = 0; @@ -201,7 +205,8 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { - return RSDecoderResult::WRONG_PKT_HEADER; + this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + //return RSDecoderResult::WRONG_PKT_HEADER; } float distance = ntohs(channel.distance) * this->const_param_.DIS_RESOLUTION; @@ -237,8 +242,6 @@ inline RSDecoderResult DecoderRS32::decodeMsopPkt(const uint8_t* p this->point_cloud_->points.emplace_back(point); } } - - return RSDecoderResult::DECODE_OK; } } // namespace lidar diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index b21dd47e..d17c5067 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -322,11 +322,11 @@ inline void LidarDriverImpl::packetPut(std::shared_ptr pkt { SyncQueue>* queue; - hexdump (pkt->data(), 16, "pkt"); uint8_t* id = pkt->data(); if (*id == 0x55) { + return; queue = &msop_pkt_queue_; } else if (*id == 0xA5) diff --git a/test/dual_return_packet_traverser_test.cpp b/test/dual_return_packet_traverser_test.cpp index 370ef4eb..1ec7add6 100644 --- a/test/dual_return_packet_traverser_test.cpp +++ b/test/dual_return_packet_traverser_test.cpp @@ -27,7 +27,11 @@ TEST(TestDualPacketTraverser, toNext) { RSDecoderConstParam const_param = { - {0x00} // msop id + 0 + , 0 + , 0 + , 0 + , {0x00} // msop id , {0x00} // difop id , {0x00} // block id , 6 // blocks per packet diff --git a/test/single_return_packet_traverser_test.cpp b/test/single_return_packet_traverser_test.cpp index 9e8d7501..10e936f2 100644 --- a/test/single_return_packet_traverser_test.cpp +++ b/test/single_return_packet_traverser_test.cpp @@ -27,7 +27,11 @@ TEST(TestSingleReturnPacketTraverser, toNext) { RSDecoderConstParam const_param = { - {0x00} // msop id + 0 // msop len + , 0 // difop len + , 0 + , 0 + , {0x00} // msop id , {0x00} // difop id , {0x00} // block id , 3 // blocks per packet From c13b66c83ba98fae0685dad85b1440eac11f42e0 Mon Sep 17 00:00:00 2001 From: zhangbaoxian Date: Wed, 8 Dec 2021 18:05:25 +0800 Subject: [PATCH 047/379] refactor: move two msg.h to msg fold --- demo/demo_online.cpp | 7 ++++--- demo/demo_pcap.cpp | 7 ++++--- {demo => src/rs_driver/msg}/pcl_point_cloud_msg.h | 0 {demo => src/rs_driver/msg}/point_cloud_msg.h | 0 4 files changed, 8 insertions(+), 6 deletions(-) rename {demo => src/rs_driver/msg}/pcl_point_cloud_msg.h (100%) rename {demo => src/rs_driver/msg}/point_cloud_msg.h (100%) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 7814e0e5..08fbbfbe 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -35,9 +35,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #define PCL_POINTCLOUD #ifdef PCL_POINTCLOUD -#include "pcl_point_cloud_msg.h" +#include #else -#include "point_cloud_msg.h" +#include #endif typedef PointCloudT PointCloudMsg; @@ -91,7 +91,8 @@ int main(int argc, char* argv[]) param.print(); LidarDriver driver; - driver.regRecvCallback(pointCloudPutCallback, pointCloudGetCallback); ///< Register the point cloud callback function into the driver + driver.regRecvCallback(pointCloudPutCallback, + pointCloudGetCallback); ///< Register the point cloud callback function into the driver driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver if (!driver.init(param)) ///< Call the init function and pass the parameter { diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index be02ea42..319c5922 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -35,9 +35,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #define PCL_POINTCLOUD #ifdef PCL_POINTCLOUD -#include "pcl_point_cloud_msg.h" +#include #else -#include "point_cloud_msg.h" +#include #endif typedef PointCloudT PointCloudMsg; @@ -93,7 +93,8 @@ int main(int argc, char* argv[]) param.print(); LidarDriver driver; ///< Declare the driver object - driver.regRecvCallback(pointCloudPutCallback, pointCloudGetCallback); ///< Register the point cloud callback function into the driver + driver.regRecvCallback(pointCloudPutCallback, + pointCloudGetCallback); ///< Register the point cloud callback function into the driver driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver if (!driver.init(param)) ///< Call the init function and pass the parameter { diff --git a/demo/pcl_point_cloud_msg.h b/src/rs_driver/msg/pcl_point_cloud_msg.h similarity index 100% rename from demo/pcl_point_cloud_msg.h rename to src/rs_driver/msg/pcl_point_cloud_msg.h diff --git a/demo/point_cloud_msg.h b/src/rs_driver/msg/point_cloud_msg.h similarity index 100% rename from demo/point_cloud_msg.h rename to src/rs_driver/msg/point_cloud_msg.h From ba0b086c247f390e468b51534bfbaf39afb327df Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 9 Dec 2021 15:39:39 +0800 Subject: [PATCH 048/379] fix: fix non self contain include files --- demo/demo_online.cpp | 1 + demo/demo_pcap.cpp | 1 + src/rs_driver/msg/pcl_point_cloud_msg.h | 14 +++----------- src/rs_driver/msg/point_cloud_msg.h | 11 ++--------- 4 files changed, 7 insertions(+), 20 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 08fbbfbe..e2c5ba22 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -40,6 +40,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #endif +typedef PointXYZI PointT; typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 319c5922..2aa1d0b6 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -40,6 +40,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #endif +typedef PointXYZI PointT; typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; diff --git a/src/rs_driver/msg/pcl_point_cloud_msg.h b/src/rs_driver/msg/pcl_point_cloud_msg.h index cef350a8..ca622bdf 100644 --- a/src/rs_driver/msg/pcl_point_cloud_msg.h +++ b/src/rs_driver/msg/pcl_point_cloud_msg.h @@ -35,13 +35,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include -#if 1 +typedef pcl::PointXYZI PointXYZI; -typedef pcl::PointXYZI PointT; - -#else - -struct RsPointXYZIRT +struct PointXYZIRT { PCL_ADD_POINT4D; uint8_t intensity; @@ -50,13 +46,9 @@ struct RsPointXYZIRT EIGEN_MAKE_ALIGNED_OPERATOR_NEW } EIGEN_ALIGN16; -POINT_CLOUD_REGISTER_POINT_STRUCT(RsPointXYZIRT, (float, x, x)(float, y, y)(float, z, z)(uint8_t, intensity, intensity)( +POINT_CLOUD_REGISTER_POINT_STRUCT(PointXYZIRT, (float, x, x)(float, y, y)(float, z, z)(uint8_t, intensity, intensity)( uint16_t, ring, ring)(double, timestamp, timestamp)) -typedef RsPointXYZIRT PointT; - -#endif - template class PointCloudT : public pcl::PointCloud { diff --git a/src/rs_driver/msg/point_cloud_msg.h b/src/rs_driver/msg/point_cloud_msg.h index e340df35..b405f00f 100644 --- a/src/rs_driver/msg/point_cloud_msg.h +++ b/src/rs_driver/msg/point_cloud_msg.h @@ -32,7 +32,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#if 1 +#include +#include struct PointXYZI { @@ -42,10 +43,6 @@ struct PointXYZI uint8_t intensity; }; -typedef PointXYZI PointT; - -#else - struct PointXYZIRT { float x; @@ -56,10 +53,6 @@ struct PointXYZIRT double timestamp; }; -typedef PointXYZIRT PointT; - -#endif - template class PointCloudT { From 54c7d59110386294911284dbad0abbc7fc975bd6 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 9 Dec 2021 16:29:03 +0800 Subject: [PATCH 049/379] fix: add pragma once --- src/rs_driver/driver/decoder/decoder_RS128.hpp | 1 + src/rs_driver/driver/decoder/decoder_RS16.hpp | 1 + src/rs_driver/driver/decoder/decoder_RS32.hpp | 1 + src/rs_driver/driver/decoder/decoder_RS80.hpp | 1 + src/rs_driver/driver/decoder/decoder_RSBP.hpp | 1 + src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp | 1 + src/rs_driver/driver/decoder/decoder_RSM1.hpp | 1 + src/rs_driver/driver/decoder/decoder_RSROCK.hpp | 1 + src/rs_driver/driver/decoder/decoder_factory.hpp | 1 + src/rs_driver/driver/input/input_factory.hpp | 1 + 10 files changed, 10 insertions(+) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index def2ca12..2c8971b8 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense { diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 7362e420..3a873c65 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense { diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 4388cede..eecc678b 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense { diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index fea5cfd2..9e144deb 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense { diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index e545acb5..b5b0d313 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense { diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index c6559ad4..0b4c4c71 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense { diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 6797fa2b..adbc858a 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp index c49f4988..1176105f 100644 --- a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense { diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 3007dd7d..5e3814a9 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include #include #include diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 39217fe7..85fcd44d 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include #include #include From 0a2150b33cdf167cf880290efd4beecfa407f434 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 13 Dec 2021 09:56:34 +0800 Subject: [PATCH 050/379] fix: fix coredump in case of incorrect msop port --- src/rs_driver/driver/input/pcap_input.hpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/rs_driver/driver/input/pcap_input.hpp b/src/rs_driver/driver/input/pcap_input.hpp index 8f1769f7..0a86882b 100644 --- a/src/rs_driver/driver/input/pcap_input.hpp +++ b/src/rs_driver/driver/input/pcap_input.hpp @@ -42,7 +42,7 @@ class PcapInput : public Input { public: PcapInput(const RSInputParam& input_param, const std::function& excb, long long msec_to_delay) - : Input(input_param, excb), pcap_offset_(ETH_HDR_LEN), difop_filter_valid_(false), msec_to_delay_(msec_to_delay) + : Input(input_param, excb), pcap_(NULL), pcap_offset_(ETH_HDR_LEN), difop_filter_valid_(false), msec_to_delay_(msec_to_delay) { if (input_param.use_vlan) pcap_offset_ += VLAN_LEN; @@ -129,7 +129,9 @@ inline PcapInput::~PcapInput() stop(); if (pcap_ != NULL) + { pcap_close(pcap_); + } } inline void PcapInput::recvPacket() @@ -141,6 +143,8 @@ inline void PcapInput::recvPacket() int ret = pcap_next_ex(pcap_, &header, &pkt_data); if (ret < 0) // reach file end. { + pcap_close(pcap_); + if (input_param_.pcap_repeat) { excb_(Error(ERRCODE_PCAPREPEAT)); From 570865db4a4d6647fad5ed28507c3374091fea81 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 13 Dec 2021 09:57:17 +0800 Subject: [PATCH 051/379] feat: change to version 1.4.3 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 408d9914..55368c24 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.4.2) +project(rs_driver VERSION 1.4.3) #============================= # Compile Demos&Tools From 72208b857b2ee536db58b3012277411cf44a971b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 13 Dec 2021 12:02:01 +0800 Subject: [PATCH 052/379] feat: always allocate point cloud in demos --- demo/demo_online.cpp | 6 +----- demo/demo_pcap.cpp | 6 +----- 2 files changed, 2 insertions(+), 10 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index e2c5ba22..4fcfd5fa 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -45,11 +45,9 @@ typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; -std::shared_ptr g_pointcloud; - std::shared_ptr pointCloudGetCallback(void) { - return g_pointcloud; + return std::make_shared(); } /** @@ -82,8 +80,6 @@ int main(int argc, char* argv[]) << RSLIDAR_VERSION_PATCH << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; - g_pointcloud = std::make_shared(); - RSDriverParam param; ///< Create a parameter object param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 2aa1d0b6..9bd71788 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -45,11 +45,9 @@ typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; -std::shared_ptr g_pointcloud; - std::shared_ptr pointCloudGetCallback(void) { - return g_pointcloud; + return std::make_shared(); } /** @@ -82,8 +80,6 @@ int main(int argc, char* argv[]) << RSLIDAR_VERSION_PATCH << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; - g_pointcloud = std::make_shared(); - RSDriverParam param; ///< Create a parameter object param.input_param.read_pcap = true; ///< Set read_pcap to true param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file directory From b6ce2a0e8b97a1f4a42b434523bfcae1bc3a409f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 13 Dec 2021 15:58:44 +0800 Subject: [PATCH 053/379] feat: add BlockDiff classes --- src/rs_driver/driver/decoder/block_diff.hpp | 132 +++++++++++++++ src/rs_driver/driver/decoder/decoder.hpp | 63 +++---- src/rs_driver/driver/decoder/decoder_RS32.hpp | 109 ++++++++----- .../driver/decoder/packet_traverser.hpp | 154 ------------------ test/CMakeLists.txt | 5 +- test/dual_return_block_diff_test.cpp | 72 ++++++++ test/dual_return_packet_traverser_test.cpp | 150 ----------------- test/single_return_block_diff_test.cpp | 67 ++++++++ test/single_return_packet_traverser_test.cpp | 122 -------------- 9 files changed, 374 insertions(+), 500 deletions(-) create mode 100644 src/rs_driver/driver/decoder/block_diff.hpp delete mode 100644 src/rs_driver/driver/decoder/packet_traverser.hpp create mode 100644 test/dual_return_block_diff_test.cpp delete mode 100644 test/dual_return_packet_traverser_test.cpp create mode 100644 test/single_return_block_diff_test.cpp delete mode 100644 test/single_return_packet_traverser_test.cpp diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp new file mode 100644 index 00000000..d5d7f9e0 --- /dev/null +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -0,0 +1,132 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +namespace robosense +{ +namespace lidar +{ + +template +class BlockDiff +{ +public: + + virtual float ts(uint16_t blk) = 0; + virtual int16_t azimuth(uint16_t blk) = 0; + + BlockDiff(const RSDecoderConstParam const_param, const T_Packet& pkt) + : const_param_(const_param), pkt_(pkt) + { + } + +protected: + const RSDecoderConstParam const_param_; + const T_Packet& pkt_; +}; + +template +class SingleReturnBlockDiff : public BlockDiff +{ +public: + + virtual float ts(uint16_t blk) + { + float ret = 0.0f; + if (blk > 0) + { + ret = this->const_param_.BLOCK_DURATION; + } + + return ret; + } + + virtual int16_t azimuth(uint16_t blk) + { + int16_t azi= 0; + + if (blk < (this->const_param_.BLOCKS_PER_PKT - 1)) + azi = this->pkt_.blocks[blk+1].azimuth - this->pkt_.blocks[blk].azimuth; + else + azi = this->pkt_.blocks[blk].azimuth - this->pkt_.blocks[blk-1].azimuth; + + return azi; + } + + SingleReturnBlockDiff(const RSDecoderConstParam const_param, const T_Packet& pkt) + : BlockDiff(const_param, pkt) + { + } +}; + +template +class DualReturnBlockDiff : public BlockDiff + +{ +public: + + virtual float ts(uint16_t blk) + { + float ret = 0.0f; + + if ((blk % 2 == 0) && (blk != 0)) + { + ret = this->const_param_.BLOCK_DURATION; + } + + return ret; + } + + virtual int16_t azimuth(uint16_t blk) + { + int16_t azi = 0; + + if (blk >= (this->const_param_.BLOCKS_PER_PKT - 2)) + { + azi = this->pkt_.blocks[blk].azimuth - this->pkt_.blocks[blk-2].azimuth; + } + else + { + azi = this->pkt_.blocks[blk+2].azimuth - this->pkt_.blocks[blk].azimuth; + } + + return azi; + } + + DualReturnBlockDiff(const RSDecoderConstParam const_param, const T_Packet& pkt) + : BlockDiff(const_param, pkt) + { + } +}; + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 753a6e5b..d83bed31 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -32,8 +32,40 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once +typedef struct +{ + uint16_t MSOP_LEN; + uint16_t DIFOP_LEN; + + // identity + uint8_t MSOP_ID_LEN; + uint8_t DIFOP_ID_LEN; + uint8_t MSOP_ID[8]; + uint8_t DIFOP_ID[8]; + uint8_t BLOCK_ID[2]; + + // duration + uint16_t BLOCKS_PER_PKT; + uint16_t CHANNELS_PER_BLOCK; + //uint16_t LASER_NUM; // diff from CHANNELS_PER_BLOCK ? + + // distance resolution + float DIS_RESOLUTION; + + // firing_ts / block_ts, chan_ts + float CHAN_TSS[128]; + float BLOCK_DURATION; + + // lens center + float RX; + float RY; + float RZ; + +} RSDecoderConstParam; + #include #include +#include #include #include #include @@ -85,37 +117,6 @@ enum RSDecoderResult DIFOP_NOT_READY = -5 }; -typedef struct -{ - uint16_t MSOP_LEN; - uint16_t DIFOP_LEN; - - // identity - uint8_t MSOP_ID_LEN; - uint8_t DIFOP_ID_LEN; - uint8_t MSOP_ID[8]; - uint8_t DIFOP_ID[8]; - uint8_t BLOCK_ID[2]; - - // duration - uint16_t BLOCKS_PER_PKT; - uint16_t CHANNELS_PER_BLOCK; - //uint16_t LASER_NUM; // diff from CHANNELS_PER_BLOCK ? - - // distance resolution - float DIS_RESOLUTION; - - // firing_ts / block_ts, chan_ts - float CHAN_TSS[128]; - float BLOCK_DURATION; - - // lens center - float RX; - float RY; - float RZ; - -} RSDecoderConstParam; - template class Decoder { diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index d42278bc..dfd1e744 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -31,7 +31,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #include -#include namespace robosense { @@ -88,6 +87,10 @@ class DecoderRS32 : public Decoder virtual void processDifopPkt(const uint8_t* pkt, size_t size); virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + + template + void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + virtual uint64_t usecToDelay() {return 0;} virtual ~DecoderRS32() = default; @@ -175,7 +178,21 @@ inline void DecoderRS32::processDifopPkt(const uint8_t* packet, si } template -inline void DecoderRS32::decodeMsopPkt(const uint8_t* packet, size_t size) +inline void DecoderRS32::decodeMsopPkt(const uint8_t* pkt, size_t size) +{ + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) + { + internDecodeMsopPkt>(pkt, size); + } + else + { + internDecodeMsopPkt>(pkt, size); + } +} + +template +template +inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS32MsopPkt& pkt = *(const RS32MsopPkt*)(packet); @@ -191,55 +208,65 @@ inline void DecoderRS32::decodeMsopPkt(const uint8_t* packet, size pkt_ts = calcTimeHost(); } - SingleReturnPacketTraverser traverser(this->const_param_, pkt, pkt_ts); - - for (; !traverser.isLast(); traverser.toNext()) - { - uint16_t blk, chan; - int16_t angle_horiz; - double chan_ts; - traverser.get (blk, chan, angle_horiz, chan_ts); + T_BlockDiff diff(this->const_param_, pkt); + double block_ts = pkt_ts; + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + { const RS32MsopBlock& block = pkt.blocks[blk]; - const RSChannel& channel = block.channels[chan]; if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { this->excb_(Error(ERRCODE_WRONGPKTHEADER)); - //return RSDecoderResult::WRONG_PKT_HEADER; + break; } - float distance = ntohs(channel.distance) * this->const_param_.DIS_RESOLUTION; - uint8_t intensity = channel.intensity; - int16_t angle_vert = this->chan_angles_.vertAdjust(chan); - int16_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + block_ts += diff.ts(blk); - if (this->distance_block_.in(distance) && this->scan_block_.in(angle_horiz_final)) - { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->const_param_.RZ; - - typename T_PointCloud::PointT point; - setX(point, x); - setY(point, y); - setZ(point, z); - setIntensity(point, intensity); - - setRing(point, this->chan_angles_.toUserChan(chan)); - setTimestamp(point, chan_ts); - this->point_cloud_->points.emplace_back(point); - } - else if (!this->param_.dense_points) + int block_az = ntohs(block.azimuth); + int16_t block_azi_diff = diff.azimuth(blk); + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { - typename T_PointCloud::PointT point; - setX(point, NAN); - setY(point, NAN); - setZ(point, NAN); - setIntensity(point, 0); - setRing(point, this->chan_angles_.toUserChan(chan)); - setTimestamp(point, chan_ts); - this->point_cloud_->points.emplace_back(point); + const RSChannel& channel = block.channels[chan]; + + float chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + int16_t angle_horiz = block_az + + block_azi_diff * this->const_param_.CHAN_TSS[chan] / this->const_param_.BLOCK_DURATION; + + int16_t angle_vert = this->chan_angles_.vertAdjust(chan); + int16_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + + float distance = ntohs(channel.distance) * this->const_param_.DIS_RESOLUTION; + uint8_t intensity = channel.intensity; + + if (this->distance_block_.in(distance) && this->scan_block_.in(angle_horiz_final)) + { + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->const_param_.RZ; + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, intensity); + + setRing(point, this->chan_angles_.toUserChan(chan)); + setTimestamp(point, chan_ts); + this->point_cloud_->points.emplace_back(point); + } + else if (!this->param_.dense_points) + { + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setRing(point, this->chan_angles_.toUserChan(chan)); + setTimestamp(point, chan_ts); + this->point_cloud_->points.emplace_back(point); + } } } } diff --git a/src/rs_driver/driver/decoder/packet_traverser.hpp b/src/rs_driver/driver/decoder/packet_traverser.hpp deleted file mode 100644 index fcdf2678..00000000 --- a/src/rs_driver/driver/decoder/packet_traverser.hpp +++ /dev/null @@ -1,154 +0,0 @@ -/********************************************************************************************************************* -Copyright (c) 2020 RoboSense -All rights reserved - -By downloading, copying, installing or using the software you agree to this license. If you do not agree to this -license, do not download, install, copy or use the software. - -License Agreement -For RoboSense LiDAR SDK Library -(3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials provided with the distribution. - -3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used -to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*********************************************************************************************************************/ - -#include - -namespace robosense -{ -namespace lidar -{ - -template -class PacketTraverser -{ -public: - - virtual void toNextBlock() = 0; - - PacketTraverser(const RSDecoderConstParam const_param, const T_Packet& pkt, double pkt_ts) - : const_param_(const_param), pkt_(pkt), bi_(0), ci_(0) - { - blk_ts_ = pkt_ts; - blk_azi_ = pkt_.blocks[bi_].azimuth; - } - - void toNext() - { - ci_++; - if (ci_ >= const_param_.CHANNELS_PER_BLOCK) - { - ci_ = 0; - bi_++; - - toNextBlock(); - } - } - - bool isLast() - { - return (bi_ >= const_param_.BLOCKS_PER_PKT); - } - - bool get(uint16_t& blk, uint16_t& chan, int16_t& azi, double& ts) - { - if (bi_ >= const_param_.BLOCKS_PER_PKT) - return false; - - blk = bi_; - chan = ci_; - - ts = blk_ts_ + const_param_.CHAN_TSS[ci_]; - azi = blk_azi_ + blk_azi_diff_ * (const_param_.CHAN_TSS[ci_] / const_param_.BLOCK_DURATION); - return true; - } - -protected: - - const RSDecoderConstParam const_param_; - const T_Packet& pkt_; - uint16_t bi_; - uint16_t ci_; - double blk_ts_; - int16_t blk_azi_diff_; - int16_t blk_azi_; -}; - -template -class SingleReturnPacketTraverser : public PacketTraverser -{ -public: - - SingleReturnPacketTraverser(const RSDecoderConstParam const_param, - const T_Packet& pkt, double pkt_ts) - : PacketTraverser(const_param, pkt, pkt_ts) - { - this->blk_azi_diff_ = - this->pkt_.blocks[this->bi_+1].azimuth - this->pkt_.blocks[this->bi_].azimuth; - } - - virtual void toNextBlock() - { - if (this->bi_ < this->const_param_.BLOCKS_PER_PKT) - { - this->blk_ts_ += this->const_param_.BLOCK_DURATION; - this->blk_azi_ = this->pkt_.blocks[this->bi_].azimuth; - if (this->bi_ < (this->const_param_.BLOCKS_PER_PKT - 1)) - { - this->blk_azi_diff_ = - this->pkt_.blocks[this->bi_+1].azimuth - this->pkt_.blocks[this->bi_].azimuth; - } - } - } -}; - -template -class DualReturnPacketTraverser : public PacketTraverser - -{ -public: - - DualReturnPacketTraverser(const RSDecoderConstParam const_param, - const T_Packet& pkt, double pkt_ts) - : PacketTraverser(const_param, pkt, pkt_ts) - { - this->blk_azi_diff_ = - this->pkt_.blocks[this->bi_+2].azimuth - this->pkt_.blocks[this->bi_].azimuth; - } - - virtual void toNextBlock() - { - if ((this->bi_ < this->const_param_.BLOCKS_PER_PKT) && (this->bi_ % 2 == 0)) - { - this->blk_ts_ += this->const_param_.BLOCK_DURATION; - - this->blk_azi_ = this->pkt_.blocks[this->bi_].azimuth; - if (this->bi_ < (this->const_param_.BLOCKS_PER_PKT-2)) - { - this->blk_azi_diff_ = - this->pkt_.blocks[this->bi_+2].azimuth - this->pkt_.blocks[this->bi_].azimuth; - } - } - } -}; - -} // namespace lidar -} // namespace robosense diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 32f103d1..1f0700e9 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -12,8 +12,9 @@ add_executable(rs_driver_test rs_driver_test.cpp sync_queue_test.cpp decoder_test.cpp - single_return_packet_traverser_test.cpp - dual_return_packet_traverser_test.cpp) + single_return_block_diff_test.cpp + dual_return_block_diff_test.cpp) + target_link_libraries(rs_driver_test ${GTEST_LIBRARIES} diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_diff_test.cpp new file mode 100644 index 00000000..68617016 --- /dev/null +++ b/test/dual_return_block_diff_test.cpp @@ -0,0 +1,72 @@ + +#include + +#include +#include + +using namespace robosense::lidar; + +typedef struct +{ + uint16_t distance; + uint8_t intensity; +} MyChannel; + +typedef struct +{ + uint16_t azimuth; + MyChannel channels[2]; +} MyBlock; + +typedef struct +{ + MyBlock blocks[6]; +} MyPacket; + +TEST(TestDualPacketTraverser, toNext) +{ + RSDecoderConstParam const_param = + { + 0 + , 0 + , 0 + , 0 + , {0x00} // msop id + , {0x00} // difop id + , {0x00} // block id + , 6 // blocks per packet + , 2 // channels per block + , 0.25 // distance resolution + + // firing_ts + , {0.0, 0.25} // chan_tss + , 0.50 // block_duration + + // lens center + , 0 // RX + , 0 // RY + , 0 // RZ + }; + + MyPacket pkt = + { + 1, 0x00, 0x00, 0x00, 0x00 + , 1, 0x00, 0x00, 0x00, 0x00 + , 21, 0x00, 0x00, 0x00, 0x00 + , 21, 0x00, 0x00, 0x00, 0x00 + , 51, 0x00, 0x00, 0x00, 0x00 + , 51, 0x00, 0x00, 0x00, 0x00 + }; + + DualReturnBlockDiff diff(const_param, pkt); + + ASSERT_EQ(diff.ts(0), 0.0f); + ASSERT_EQ(diff.ts(1), 0.0f); + ASSERT_EQ(diff.ts(2), 0.5f); + + ASSERT_EQ(diff.azimuth(0), 20); + ASSERT_EQ(diff.azimuth(1), 20); + ASSERT_EQ(diff.azimuth(4), 30); + ASSERT_EQ(diff.azimuth(5), 30); +} + diff --git a/test/dual_return_packet_traverser_test.cpp b/test/dual_return_packet_traverser_test.cpp deleted file mode 100644 index 1ec7add6..00000000 --- a/test/dual_return_packet_traverser_test.cpp +++ /dev/null @@ -1,150 +0,0 @@ - -#include - -#include -#include - -using namespace robosense::lidar; - -typedef struct -{ - uint16_t distance; - uint8_t intensity; -} MyChannel; - -typedef struct -{ - uint16_t azimuth; - MyChannel channels[2]; -} MyBlock; - -typedef struct -{ - MyBlock blocks[6]; -} MyPacket; - -TEST(TestDualPacketTraverser, toNext) -{ - RSDecoderConstParam const_param = - { - 0 - , 0 - , 0 - , 0 - , {0x00} // msop id - , {0x00} // difop id - , {0x00} // block id - , 6 // blocks per packet - , 2 // channels per block - , 0.25 // distance resolution - - // firing_ts - , {0.0, 0.25} // chan_tss - , 0.50 // block_duration - - // lens center - , 0 // RX - , 0 // RY - , 0 // RZ - }; - - MyPacket pkt = - { - 1, 0x00, 0x00, 0x00, 0x00 - , 0, 0x00, 0x00, 0x00, 0x00 - , 21, 0x00, 0x00, 0x00, 0x00 - , 0, 0x00, 0x00, 0x00, 0x00 - , 51, 0x00, 0x00, 0x00, 0x00 - , 0, 0x00, 0x00, 0x00, 0x00 - }; - - int16_t azi; - double ts; - uint16_t blk, chan; - DualReturnPacketTraverser traverser(const_param, pkt, 0.25); - - // blk 0, chan 0 - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 0); - ASSERT_EQ(chan, 0); - ASSERT_EQ(azi, 1); - ASSERT_EQ(ts, 0.25); - - // blk 0, chan 1 - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 0); - ASSERT_EQ(chan, 1); - ASSERT_EQ(azi, 11); - ASSERT_EQ(ts, 0.50); - - // blk 1, chan 0. 2nd return - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 1); - ASSERT_EQ(chan, 0); - ASSERT_EQ(azi, 1); - ASSERT_EQ(ts, 0.25); - - // blk 1, chan 1. 2nd return - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 1); - ASSERT_EQ(chan, 1); - ASSERT_EQ(azi, 11); - ASSERT_EQ(ts, 0.50); - - // blk 2, chan 0 - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 2); - ASSERT_EQ(chan, 0); - ASSERT_EQ(azi, 21); - ASSERT_EQ(ts, 0.75); - - // blk 2, chan 1 - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 2); - ASSERT_EQ(chan, 1); - ASSERT_EQ(azi, 36); - ASSERT_EQ(ts, 1.0); - - // blk 3, chan 0. 2nd return. - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 3); - ASSERT_EQ(chan, 0); - ASSERT_EQ(azi, 21); - ASSERT_EQ(ts, 0.75); - - // blk 3, chan 1. 2nd return - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - - // blk 4, chan 0. - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 4); - ASSERT_EQ(chan, 0); - ASSERT_EQ(azi, 51); - ASSERT_EQ(ts, 1.25); - - // blk 4, chan 1. - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 4); - ASSERT_EQ(chan, 1); - ASSERT_EQ(azi, 66); - ASSERT_EQ(ts, 1.5); -} - diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_diff_test.cpp new file mode 100644 index 00000000..c197a690 --- /dev/null +++ b/test/single_return_block_diff_test.cpp @@ -0,0 +1,67 @@ + +#include + +#include +#include + +using namespace robosense::lidar; + +typedef struct +{ + uint16_t distance; + uint8_t intensity; +} MyChannel; + +typedef struct +{ + uint16_t azimuth; + MyChannel channels[2]; +} MyBlock; + +typedef struct +{ + MyBlock blocks[3]; +} MyPacket; + +TEST(TestSingleReturnPacketTraverser, toNext) +{ + RSDecoderConstParam const_param = + { + 0 // msop len + , 0 // difop len + , 0 + , 0 + , {0x00} // msop id + , {0x00} // difop id + , {0x00} // block id + , 3 // blocks per packet + , 2 // channels per block + , 0.25 // distance resolution + + // firing_ts + , {0.0, 0.25} // chan_tss + , 0.50 // block_duration + + // lens center + , 0 // RX + , 0 // RY + , 0 // RZ + }; + + MyPacket pkt = + { + 1, 0x00, 0x00, 0x00, 0x00 + , 21, 0x00, 0x00, 0x00, 0x00 + , 51, 0x00, 0x00, 0x00, 0x00 + }; + + SingleReturnBlockDiff diff(const_param, pkt); + + ASSERT_EQ(diff.ts(0), 0.0f); + ASSERT_EQ(diff.ts(1), 0.5f); + + ASSERT_EQ(diff.azimuth(0), 20); + ASSERT_EQ(diff.azimuth(1), 30); + ASSERT_EQ(diff.azimuth(2), 30); +} + diff --git a/test/single_return_packet_traverser_test.cpp b/test/single_return_packet_traverser_test.cpp deleted file mode 100644 index 10e936f2..00000000 --- a/test/single_return_packet_traverser_test.cpp +++ /dev/null @@ -1,122 +0,0 @@ - -#include - -#include -#include - -using namespace robosense::lidar; - -typedef struct -{ - uint16_t distance; - uint8_t intensity; -} MyChannel; - -typedef struct -{ - uint16_t azimuth; - MyChannel channels[2]; -} MyBlock; - -typedef struct -{ - MyBlock blocks[3]; -} MyPacket; - -TEST(TestSingleReturnPacketTraverser, toNext) -{ - RSDecoderConstParam const_param = - { - 0 // msop len - , 0 // difop len - , 0 - , 0 - , {0x00} // msop id - , {0x00} // difop id - , {0x00} // block id - , 3 // blocks per packet - , 2 // channels per block - , 0.25 // distance resolution - - // firing_ts - , {0.0, 0.25} // chan_tss - , 0.50 // block_duration - - // lens center - , 0 // RX - , 0 // RY - , 0 // RZ - }; - - MyPacket pkt = - { - 1, 0x00, 0x00, 0x00, 0x00 - , 21, 0x00, 0x00, 0x00, 0x00 - , 51, 0x00, 0x00, 0x00, 0x00 - }; - - int16_t azi; - double ts; - uint16_t blk, chan; - SingleReturnPacketTraverser traverser(const_param, pkt, 0.25); - - // blk 0, chan 0 - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 0); - ASSERT_EQ(chan, 0); - ASSERT_EQ(azi, 1); - ASSERT_EQ(ts, 0.25); - - // blk 0, chan 1 - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 0); - ASSERT_EQ(chan, 1); - ASSERT_EQ(azi, 11); - ASSERT_EQ(ts, 0.50); - - // cross block. - // blk 1, chan 0 - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 1); - ASSERT_EQ(chan, 0); - ASSERT_EQ(azi, 21); - ASSERT_EQ(ts, 0.75); - - // blk 1, chan 1 - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 1); - ASSERT_EQ(chan, 1); - ASSERT_EQ(azi, 36); - ASSERT_EQ(ts, 1.0); - - // cross block. - // blk 2, chan 0 - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 2); - ASSERT_EQ(chan, 0); - ASSERT_EQ(azi, 51); - ASSERT_EQ(ts, 1.25); - - // blk 2, chan 1 - traverser.toNext(); - ASSERT_FALSE(traverser.isLast()); - ASSERT_TRUE(traverser.get(blk, chan, azi, ts)); - ASSERT_EQ(blk, 2); - ASSERT_EQ(chan, 1); - ASSERT_EQ(azi, 66); - ASSERT_EQ(ts, 1.5); - - traverser.toNext(); - ASSERT_TRUE(traverser.isLast()); - ASSERT_FALSE(traverser.get(blk, chan, azi, ts)); -} - From d4e8239b75b191e516d103a266dbb14f9c47e5c4 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 13 Dec 2021 16:50:40 +0800 Subject: [PATCH 054/379] feat: disable non user_point_cloud way --- CMakeLists.txt | 5 ----- demo/demo_online.cpp | 6 +----- demo/demo_pcap.cpp | 6 +----- src/rs_driver/api/lidar_driver.h | 15 --------------- src/rs_driver/driver/lidar_driver_impl.hpp | 22 ---------------------- 5 files changed, 2 insertions(+), 52 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 596fee35..3f4e9c30 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -19,7 +19,6 @@ option(COMPILE_TESTS "Build rs_driver unit tests" ON) # Compile Features #============================= option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) -option(ENABLE_POINT_CLOUD_POOL "Enable user point cloud pool" ON) #======================== # Project setup @@ -113,10 +112,6 @@ if(${ENABLE_HIGH_PRIORITY_THREAD}) add_definitions("-DENABLE_HIGH_PRIORITY_THREAD") endif(${ENABLE_HIGH_PRIORITY_THREAD}) -if(${ENABLE_POINT_CLOUD_POOL}) - add_definitions("-DENABLE_POINT_CLOUD_POOL") -endif(${ENABLE_POINT_CLOUD_POOL}) - #======================== # Build Demos #======================== diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 74fff094..b5eed053 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -44,11 +44,9 @@ typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; -std::shared_ptr g_pointcloud; - std::shared_ptr pointCloudGetCallback(void) { - return g_pointcloud; + return std::make_shared(); } /** @@ -81,8 +79,6 @@ int main(int argc, char* argv[]) << RSLIDAR_VERSION_PATCH << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; - g_pointcloud = std::make_shared(); - RSDriverParam param; ///< Create a parameter object param.input_type = InputType::ONLINE_LIDAR; param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index b638cb78..b2cd6296 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -44,11 +44,9 @@ typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; -std::shared_ptr g_pointcloud; - std::shared_ptr pointCloudGetCallback(void) { - return g_pointcloud; + return std::make_shared(); } /** @@ -80,8 +78,6 @@ int main(int argc, char* argv[]) RS_TITLE << " RS_Driver Core Version: v" << getDriverVersion() << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; - g_pointcloud = std::make_shared(); - RSDriverParam param; ///< Create a parameter object param.input_type = InputType::PCAP_FILE; param.input_param.pcap_path = "/mnt/share/pcap/RS32/Rs32.pcap"; ///< Set the pcap file directory diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index 7ba26471..c2bd439a 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -84,7 +84,6 @@ class LidarDriver driver_ptr_->stop(); } -#ifdef ENABLE_POINT_CLOUD_POOL /** * @brief Register the lidar point cloud callback function to driver. When point cloud is ready, this function will be * called @@ -96,20 +95,6 @@ class LidarDriver driver_ptr_->regRecvCallback(cb_get, cb_put); } -#else - - /** - * @brief Register the lidar point cloud callback function to driver. When point cloud is ready, this function will be - * called - * @param callback The callback function - */ - inline void regRecvCallback(const std::function& cb_put) - { - driver_ptr_->regRecvCallback(cb_put); - } - -#endif - /** * @brief Register the exception message callback function to driver. When error occurs, this function will be called * @param callback The callback function diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index d17c5067..2ecfb04c 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -62,7 +62,6 @@ class LidarDriverImpl bool start(); void stop(); -#ifdef ENABLE_POINT_CLOUD_POOL void regRecvCallback(const std::function(void)>& cb_get, const std::function)>& cb_put) { @@ -72,15 +71,6 @@ class LidarDriverImpl std::function(void)> point_cloud_cb_get_; std::function)> point_cloud_cb_put_; -#else - void regRecvCallback(const std::function& cb_put) - { - point_cloud_cb_put_ = cb_put; - } - - std::function point_cloud_cb_put_; - std::shared_ptr point_cloud_; -#endif void regRecvCallback(const std::function& callback); void regExceptionCallback(const std::function& callback); @@ -134,9 +124,6 @@ template inline LidarDriverImpl::LidarDriverImpl() : init_flag_(false), start_flag_(false), pkt_seq_(0), ndifop_count_(0) { -#ifndef ENABLE_POINT_CLOUD_POOL - point_cloud_ = std::make_shared(); -#endif } template @@ -243,12 +230,7 @@ std::shared_ptr LidarDriverImpl::getPointCloud() { while (1) { -#ifdef ENABLE_POINT_CLOUD_POOL std::shared_ptr pc = point_cloud_cb_get_(); -#else - std::shared_ptr pc = point_cloud_; -#endif - if (pc) { pc->points.resize(0); @@ -263,11 +245,7 @@ std::shared_ptr LidarDriverImpl::getPointCloud() template void LidarDriverImpl::putPointCloud(std::shared_ptr pc) { -#ifdef ENABLE_POINT_CLOUD_POOL point_cloud_cb_put_(pc); -#else - point_cloud_cb_put_(*pc); -#endif } template From 2e62d21cdbe717f7db7b93b778093078d26c09bf Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 13 Dec 2021 16:54:07 +0800 Subject: [PATCH 055/379] feat: update BlockDiff classes --- src/rs_driver/driver/decoder/block_diff.hpp | 38 ++++++++------------- 1 file changed, 14 insertions(+), 24 deletions(-) diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index d5d7f9e0..9a4f95d0 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -37,25 +37,7 @@ namespace lidar { template -class BlockDiff -{ -public: - - virtual float ts(uint16_t blk) = 0; - virtual int16_t azimuth(uint16_t blk) = 0; - - BlockDiff(const RSDecoderConstParam const_param, const T_Packet& pkt) - : const_param_(const_param), pkt_(pkt) - { - } - -protected: - const RSDecoderConstParam const_param_; - const T_Packet& pkt_; -}; - -template -class SingleReturnBlockDiff : public BlockDiff +class SingleReturnBlockDiff { public: @@ -83,18 +65,22 @@ class SingleReturnBlockDiff : public BlockDiff } SingleReturnBlockDiff(const RSDecoderConstParam const_param, const T_Packet& pkt) - : BlockDiff(const_param, pkt) + : const_param_(const_param), pkt_(pkt) { } + +protected: + const RSDecoderConstParam const_param_; + const T_Packet& pkt_; }; template -class DualReturnBlockDiff : public BlockDiff +class DualReturnBlockDiff { public: - virtual float ts(uint16_t blk) + float ts(uint16_t blk) { float ret = 0.0f; @@ -106,7 +92,7 @@ class DualReturnBlockDiff : public BlockDiff return ret; } - virtual int16_t azimuth(uint16_t blk) + int16_t azimuth(uint16_t blk) { int16_t azi = 0; @@ -123,9 +109,13 @@ class DualReturnBlockDiff : public BlockDiff } DualReturnBlockDiff(const RSDecoderConstParam const_param, const T_Packet& pkt) - : BlockDiff(const_param, pkt) + : const_param_(const_param), pkt_(pkt) { } + +protected: + const RSDecoderConstParam const_param_; + const T_Packet& pkt_; }; } // namespace lidar From 0c7d754ca4c4098abe703a5bbc1fcad505a904a7 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 13 Dec 2021 16:59:52 +0800 Subject: [PATCH 056/379] test: start to test --- demo/demo_online.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index b5eed053..1f620887 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -75,16 +75,15 @@ void exceptionCallback(const Error& code) int main(int argc, char* argv[]) { RS_TITLE << "------------------------------------------------------" << RS_REND; - RS_TITLE << " RS_Driver Core Version: v" << RSLIDAR_VERSION_MAJOR << "." << RSLIDAR_VERSION_MINOR << "." - << RSLIDAR_VERSION_PATCH << RS_REND; + RS_TITLE << " RS_Driver Core Version: v" << getDriverVersion() << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; RSDriverParam param; ///< Create a parameter object param.input_type = InputType::ONLINE_LIDAR; param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct - param.decoder_param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + param.lidar_type = LidarType::RS32; ///< Set the lidar type. Make sure this type is correct + param.decoder_param.wait_for_difop = false; ///< true: start sending point cloud until receive difop packet param.print(); LidarDriver driver; From a295ec37ac50d7e4908bcd55b31f92714ae20dac Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 13 Dec 2021 19:17:41 +0800 Subject: [PATCH 057/379] refac: refac decoder --- demo/point_cloud_msg.h | 1 - src/rs_driver/driver/decoder/decoder.hpp | 27 +++++++- src/rs_driver/driver/decoder/decoder_RS32.hpp | 31 +++------- test/CMakeLists.txt | 7 ++- test/decoder_rs32_test.cpp | 62 +++++++++++++++++++ 5 files changed, 97 insertions(+), 31 deletions(-) create mode 100644 test/decoder_rs32_test.cpp diff --git a/demo/point_cloud_msg.h b/demo/point_cloud_msg.h index e340df35..67a9b9a9 100644 --- a/demo/point_cloud_msg.h +++ b/demo/point_cloud_msg.h @@ -75,4 +75,3 @@ class PointCloudT uint32_t seq = 0; ///< Sequence number of message VectorT points; -}; diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index d83bed31..e3436ff9 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -122,9 +122,12 @@ class Decoder { public: - virtual void processMsopPkt(const uint8_t* pkt, size_t size); - virtual void processDifopPkt(const uint8_t* pkt, size_t size) = 0; + void processDifopPkt(const uint8_t* pkt, size_t size); + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size) = 0; + + void processMsopPkt(const uint8_t* pkt, size_t size); virtual void decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; + virtual ~Decoder() = default; void regRecvCallback(const std::function(void)>& cb_get, @@ -327,7 +330,19 @@ void Decoder::processMsopPkt(const uint8_t* pkt, size_t size) template void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) { - + if (size != this->const_param_.DIFOP_LEN) + { + this->excb_(Error(ERRCODE_WRONGPKTLENGTH)); + return; + } + + if (memcmp(pkt, this->const_param_.DIFOP_ID, const_param_.DIFOP_ID_LEN) != 0) + { + this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + return; + } + + decodeDifopPkt(pkt, size); } template @@ -358,6 +373,12 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) // fov blind diff of timestamp this->fov_blind_ts_diff_ = fov_blind_range / (RS_ONE_ROUND * this->rps_); + + if (!this->difop_ready_) + { + this->chan_angles_.loadFromDifop(pkt.ver_angle_cali, pkt.hori_angle_cali, + this->const_param_.CHANNELS_PER_BLOCK); + } } #if 0 diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index dfd1e744..73f149a8 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -85,18 +85,17 @@ class DecoderRS32 : public Decoder { public: - virtual void processDifopPkt(const uint8_t* pkt, size_t size); + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); - template - void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - virtual uint64_t usecToDelay() {return 0;} virtual ~DecoderRS32() = default; explicit DecoderRS32(const RSDecoderParam& param, const std::function& excb); +protected: + static RSDecoderConstParam getConstParam() { RSDecoderConstParam param = @@ -141,6 +140,8 @@ class DecoderRS32 : public Decoder } } + template + void internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; template @@ -151,30 +152,12 @@ inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, } template -inline void DecoderRS32::processDifopPkt(const uint8_t* packet, size_t size) +inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, size_t size) { const RS32DifopPkt& pkt = *(const RS32DifopPkt*)(packet); - - hexdump (packet, size, "difop"); - - if (size != this->const_param_.DIFOP_LEN) - { - this->excb_(Error(ERRCODE_WRONGPKTLENGTH)); - } - - if (memcmp(this->const_param_.DIFOP_ID, pkt.id, 8) != 0) - { - this->excb_(Error(ERRCODE_WRONGPKTHEADER)); - } - - this->echo_mode_ = getEchoMode (pkt.return_mode); - this->template decodeDifopCommon(pkt); - if (!this->difop_ready_) - { - this->chan_angles_.loadFromDifop(pkt.ver_angle_cali, pkt.hori_angle_cali, 32); - } + this->echo_mode_ = getEchoMode (pkt.return_mode); } template diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 1f0700e9..c2969ce3 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -8,12 +8,13 @@ include_directories(${GTEST_INCLUDE_DIRS}) include_directories(${DRIVER_INCLUDE_DIRS}) add_executable(rs_driver_test - packet_test.cpp rs_driver_test.cpp + packet_test.cpp sync_queue_test.cpp - decoder_test.cpp single_return_block_diff_test.cpp - dual_return_block_diff_test.cpp) + dual_return_block_diff_test.cpp + decoder_test.cpp + decoder_rs32_test.cpp) target_link_libraries(rs_driver_test diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp new file mode 100644 index 00000000..fc67262d --- /dev/null +++ b/test/decoder_rs32_test.cpp @@ -0,0 +1,62 @@ + +#include + +#include + +using namespace robosense::lidar; + +struct PointXYZIRT +{ + float x; + float y; + float z; + uint8_t intensity; + uint16_t ring; + double timestamp; +}; + +template +class PointCloudT +{ +public: + typedef T_Point PointT; + typedef std::vector VectorT; + + uint32_t height = 0; ///< Height of point cloud + uint32_t width = 0; ///< Width of point cloud + bool is_dense = false; ///< If is_dense=true, the point cloud does not contain NAN points + double timestamp = 0.0; + uint32_t seq = 0; ///< Sequence number of message + VectorT points; +}; + +typedef PointCloudT PointCloud; + +ErrCode errCode = ERRCODE_SUCCESS; + +void errCallback(const Error& err) +{ + errCode = err.error_code; +} + +TEST(TestDecoder, processDifopPkt_Error) +{ + RSDecoderParam param; + DecoderRS32 decoder(param, errCallback); + + RS32DifopPkt pkt; + decoder.processDifopPkt((const uint8_t*)&pkt, 2); + ASSERT_EQ(errCode, ERRCODE_WRONGPKTLENGTH); + + decoder.processDifopPkt((const uint8_t*)&pkt, sizeof(pkt)); + ASSERT_EQ(errCode, ERRCODE_WRONGPKTHEADER); +} + +TEST(TestDecoderRS32, decodeDifopPkt) +{ + RSDecoderParam param; + DecoderRS32 decoder(param, errCallback); + + RS32DifopPkt pkt; +} + From 7d2599116d3e3a2e21a7fe6ca0a1330dd19fc90b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 13 Dec 2021 19:43:13 +0800 Subject: [PATCH 058/379] refac: refac decoder --- demo/demo_online.cpp | 5 +- demo/demo_pcap.cpp | 5 +- .../rs_driver/msg}/pcl_point_cloud_msg.h | 16 +- {demo => src/rs_driver/msg}/point_cloud_msg.h | 12 +- test/CMakeLists.txt | 5 +- test/decoder_opt_test.cpp | 244 +++++++++++++++++ test/decoder_rs32_test.cpp | 38 --- test/decoder_test.cpp | 246 +++--------------- 8 files changed, 292 insertions(+), 279 deletions(-) rename {demo => src/rs_driver/msg}/pcl_point_cloud_msg.h (88%) rename {demo => src/rs_driver/msg}/point_cloud_msg.h (97%) create mode 100644 test/decoder_opt_test.cpp diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 1f620887..4c7f248f 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -35,11 +35,12 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #define PCL_POINTCLOUD #ifdef PCL_POINTCLOUD -#include "pcl_point_cloud_msg.h" +#include "rs_driver/msg/pcl_point_cloud_msg.h" #else -#include "point_cloud_msg.h" +#include "rs_driver/msg/point_cloud_msg.h" #endif +typedef PointXYZI PointT; typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index b2cd6296..05f3e8b9 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -35,11 +35,12 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #define PCL_POINTCLOUD #ifdef PCL_POINTCLOUD -#include "pcl_point_cloud_msg.h" +#include "rs_driver/msg/pcl_point_cloud_msg.h" #else -#include "point_cloud_msg.h" +#include "rs_driver/msg/point_cloud_msg.h" #endif +typedef PointXYZI PointT; typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; diff --git a/demo/pcl_point_cloud_msg.h b/src/rs_driver/msg/pcl_point_cloud_msg.h similarity index 88% rename from demo/pcl_point_cloud_msg.h rename to src/rs_driver/msg/pcl_point_cloud_msg.h index cef350a8..6d4dcb62 100644 --- a/demo/pcl_point_cloud_msg.h +++ b/src/rs_driver/msg/pcl_point_cloud_msg.h @@ -35,13 +35,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include -#if 1 +typedef pcl::PointXYZI PointXYZI; -typedef pcl::PointXYZI PointT; - -#else - -struct RsPointXYZIRT +struct PointXYZIRT { PCL_ADD_POINT4D; uint8_t intensity; @@ -50,12 +46,8 @@ struct RsPointXYZIRT EIGEN_MAKE_ALIGNED_OPERATOR_NEW } EIGEN_ALIGN16; -POINT_CLOUD_REGISTER_POINT_STRUCT(RsPointXYZIRT, (float, x, x)(float, y, y)(float, z, z)(uint8_t, intensity, intensity)( - uint16_t, ring, ring)(double, timestamp, timestamp)) - -typedef RsPointXYZIRT PointT; - -#endif +POINT_CLOUD_REGISTER_POINT_STRUCT(PointXYZIRT, (float, x, x)(float, y, y)(float, z, z) + (uint8_t, intensity, intensity)(uint16_t, ring, ring)(double, timestamp, timestamp)) template class PointCloudT : public pcl::PointCloud diff --git a/demo/point_cloud_msg.h b/src/rs_driver/msg/point_cloud_msg.h similarity index 97% rename from demo/point_cloud_msg.h rename to src/rs_driver/msg/point_cloud_msg.h index 67a9b9a9..52e8c1a3 100644 --- a/demo/point_cloud_msg.h +++ b/src/rs_driver/msg/point_cloud_msg.h @@ -32,8 +32,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#if 1 - struct PointXYZI { float x; @@ -42,10 +40,6 @@ struct PointXYZI uint8_t intensity; }; -typedef PointXYZI PointT; - -#else - struct PointXYZIRT { float x; @@ -56,10 +50,6 @@ struct PointXYZIRT double timestamp; }; -typedef PointXYZIRT PointT; - -#endif - template class PointCloudT { @@ -75,3 +65,5 @@ class PointCloudT uint32_t seq = 0; ///< Sequence number of message VectorT points; +}; + diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index c2969ce3..426bec1e 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -13,8 +13,9 @@ add_executable(rs_driver_test sync_queue_test.cpp single_return_block_diff_test.cpp dual_return_block_diff_test.cpp - decoder_test.cpp - decoder_rs32_test.cpp) + decoder_opt_test.cpp + decoder_test.cpp) + #decoder_rs32_test.cpp) target_link_libraries(rs_driver_test diff --git a/test/decoder_opt_test.cpp b/test/decoder_opt_test.cpp new file mode 100644 index 00000000..33910539 --- /dev/null +++ b/test/decoder_opt_test.cpp @@ -0,0 +1,244 @@ + +#include + +#include + +using namespace robosense::lidar; + +TEST(TestParseTime, calcTimeUTC) +{ + RSTimestampUTC2 ts = + {{0x01, 0x02, 0x03, 0x04, 0x05, 0x06}, {0x11, 0x22, 0x33, 0x44}}; + + ASSERT_EQ(calcTimeUTCWithNs(&ts), 0x010203040506 * 1000000 + 0x11223344/1000); + ASSERT_EQ(calcTimeUTCWithUs(&ts), 0x010203040506 * 1000000 + 0x11223344); + ASSERT_EQ(calcTimeUTCWithMs(&ts), 0x010203040506 * 1000000 + 0x1122 * 1000 + 0x3344); +} + +TEST(TestParseTime, calcTimeYMD) +{ + uint8_t ts[] = {0x15, 0x0a, 0x01, 0x01, 0x02, 0x03, 0x11, 0x22, 0x33, 0x44}; + + ASSERT_EQ(calcTimeYMD((RSTimestampYMD*)&ts), 1633021327399124); +} + +TEST(TestParseTime, calcTimeHost) +{ + calcTimeHost(); +} + +TEST(TestParseTemp, calcTemp) +{ + { + uint8_t temp[] = {0x18, 0x01}; + ASSERT_EQ(calcTemp((RsTemprature*)&temp), 35); + } + + { + uint8_t temp[] = {0x18, 0x81}; + ASSERT_EQ(calcTemp((RsTemprature*)&temp), -35); + } +} + +TEST(TestScanBlock, ctor) +{ + ScanBlock blk(10, 20); + ASSERT_EQ(blk.start(), 10); + ASSERT_EQ(blk.end(), 20); + + ASSERT_FALSE(blk.in(5)); + ASSERT_TRUE(blk.in(10)); + ASSERT_TRUE(blk.in(15)); + ASSERT_FALSE(blk.in(20)); + ASSERT_FALSE(blk.in(25)); +} + +TEST(TestScanBlock, ctorCrossZero) +{ + ScanBlock blk(35000, 10); + ASSERT_EQ(blk.start(), 35000); + ASSERT_EQ(blk.end(), 10); + + ASSERT_FALSE(blk.in(34999)); + ASSERT_TRUE(blk.in(35000)); + ASSERT_TRUE(blk.in(0)); + ASSERT_FALSE(blk.in(10)); + ASSERT_FALSE(blk.in(15)); +} + +TEST(TestScanBlock, ctorBeyondRound) +{ + ScanBlock blk(36100, 36200); + ASSERT_EQ(blk.start(), 100); + ASSERT_EQ(blk.end(), 200); +} + +TEST(TestDistanceBlock, ctor) +{ + DistanceBlock blk(0.5, 200, 0.75, 150); + ASSERT_EQ(blk.min(), 0.75); + ASSERT_EQ(blk.max(), 150); + + ASSERT_FALSE(blk.in(0.45)); + ASSERT_TRUE(blk.in(0.75)); + ASSERT_TRUE(blk.in(0.8)); + ASSERT_TRUE(blk.in(150)); + ASSERT_FALSE(blk.in(150.5)); +} + +TEST(TestDistanceBlock, ctorNoUseBlock) +{ + DistanceBlock blk(0.5, 200, 0.0, 200.5); + ASSERT_EQ(blk.min(), 0.5); + ASSERT_EQ(blk.max(), 200); +} + +TEST(TestChanAngles, genUserChan) +{ + std::vector vert_angles; + std::vector user_chans; + + vert_angles.push_back(100); + vert_angles.push_back(0); + vert_angles.push_back(-100); + vert_angles.push_back(200); + + ChanAngles::genUserChan (vert_angles, user_chans); + ASSERT_EQ(user_chans.size(), 4); + ASSERT_EQ(user_chans[0], 2); + ASSERT_EQ(user_chans[1], 1); + ASSERT_EQ(user_chans[2], 0); + ASSERT_EQ(user_chans[3], 3); +} + +TEST(TestChanAngles, loadFromFile) +{ + std::vector vert_angles, horiz_angles; + + ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); + ASSERT_EQ(vert_angles[0], 500); + ASSERT_EQ(vert_angles[1], 250); + ASSERT_EQ(vert_angles[2], 0); + ASSERT_EQ(vert_angles[3], -250); + + ASSERT_EQ(horiz_angles[0], 10); + ASSERT_EQ(horiz_angles[1], -20); + ASSERT_EQ(horiz_angles[2], 0); + ASSERT_EQ(horiz_angles[3], -100); + + ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); +} + +TEST(TestChanAngles, memberLoadFromFile) +{ + ChanAngles angles; + + ASSERT_EQ(angles.loadFromFile ("../rs_driver/test/res/angle.csv"), 0); + ASSERT_EQ(angles.chanSize(), 4); + ASSERT_EQ(angles.toUserChan(0), 3); + ASSERT_EQ(angles.toUserChan(1), 2); + ASSERT_EQ(angles.toUserChan(2), 1); + ASSERT_EQ(angles.toUserChan(3), 0); +} + +TEST(TestChanAngles, loadFromDifop) +{ + uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, + 0x01, 0x03, 0x04, + 0x01, 0x05, 0x06, + 0x00, 0x07, 0x08}; + uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, + 0x01, 0x33, 0x44, + 0x00, 0x55, 0x66, + 0x01, 0x77, 0x88}; + + std::vector vert_angles, horiz_angles; + + ASSERT_EQ(ChanAngles::loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4, + vert_angles, + horiz_angles), 0); + + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); + ASSERT_EQ(vert_angles[0], 258); + ASSERT_EQ(vert_angles[1], -772); + ASSERT_EQ(vert_angles[2], -1286); + ASSERT_EQ(vert_angles[3], 1800); + + ASSERT_EQ(horiz_angles[0], 4386); + ASSERT_EQ(horiz_angles[1], -13124); + ASSERT_EQ(horiz_angles[2], 21862); + ASSERT_EQ(horiz_angles[3], -30600); + + ASSERT_EQ(ChanAngles::loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4, + vert_angles, + horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); +} + +TEST(TestTrigon, ctor) +{ + Trigon trigon; + ASSERT_EQ(trigon.cos(6000), 0.5); + ASSERT_EQ(trigon.sin(3000), 0.5); +#if 0 + trigon.print(); +#endif +} + +TEST(TestSplitAngle, toSplit) +{ + { + SplitAngle sa(10); + ASSERT_FALSE(sa.toSplit(5)); + ASSERT_TRUE(sa.toSplit(15)); + } + + { + SplitAngle sa(10); + ASSERT_FALSE(sa.toSplit(5)); + ASSERT_TRUE(sa.toSplit(10)); + ASSERT_FALSE(sa.toSplit(15)); + } + + { + SplitAngle sa(10); + ASSERT_FALSE(sa.toSplit(10)); + ASSERT_FALSE(sa.toSplit(15)); + } +} + +TEST(TestSplitAngle, toSplit_Zero) +{ + { + SplitAngle sa(0); + ASSERT_FALSE(sa.toSplit(35999)); + ASSERT_TRUE(sa.toSplit(1)); + ASSERT_FALSE(sa.toSplit(2)); + } + + { + SplitAngle sa(0); + ASSERT_FALSE(sa.toSplit(35999)); + ASSERT_TRUE(sa.toSplit(0)); + ASSERT_FALSE(sa.toSplit(2)); + } + + { + SplitAngle sa(0); + ASSERT_FALSE(sa.toSplit(0)); + ASSERT_FALSE(sa.toSplit(2)); + } +} + diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index fc67262d..cc857354 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -5,31 +5,6 @@ using namespace robosense::lidar; -struct PointXYZIRT -{ - float x; - float y; - float z; - uint8_t intensity; - uint16_t ring; - double timestamp; -}; - -template -class PointCloudT -{ -public: - typedef T_Point PointT; - typedef std::vector VectorT; - - uint32_t height = 0; ///< Height of point cloud - uint32_t width = 0; ///< Width of point cloud - bool is_dense = false; ///< If is_dense=true, the point cloud does not contain NAN points - double timestamp = 0.0; - uint32_t seq = 0; ///< Sequence number of message - VectorT points; -}; - typedef PointCloudT PointCloud; ErrCode errCode = ERRCODE_SUCCESS; @@ -39,19 +14,6 @@ void errCallback(const Error& err) errCode = err.error_code; } -TEST(TestDecoder, processDifopPkt_Error) -{ - RSDecoderParam param; - DecoderRS32 decoder(param, errCallback); - - RS32DifopPkt pkt; - decoder.processDifopPkt((const uint8_t*)&pkt, 2); - ASSERT_EQ(errCode, ERRCODE_WRONGPKTLENGTH); - - decoder.processDifopPkt((const uint8_t*)&pkt, sizeof(pkt)); - ASSERT_EQ(errCode, ERRCODE_WRONGPKTHEADER); -} - TEST(TestDecoderRS32, decodeDifopPkt) { RSDecoderParam param; diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 33910539..58efa345 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -1,244 +1,64 @@ #include -#include +#include +#include using namespace robosense::lidar; -TEST(TestParseTime, calcTimeUTC) -{ - RSTimestampUTC2 ts = - {{0x01, 0x02, 0x03, 0x04, 0x05, 0x06}, {0x11, 0x22, 0x33, 0x44}}; - - ASSERT_EQ(calcTimeUTCWithNs(&ts), 0x010203040506 * 1000000 + 0x11223344/1000); - ASSERT_EQ(calcTimeUTCWithUs(&ts), 0x010203040506 * 1000000 + 0x11223344); - ASSERT_EQ(calcTimeUTCWithMs(&ts), 0x010203040506 * 1000000 + 0x1122 * 1000 + 0x3344); -} - -TEST(TestParseTime, calcTimeYMD) -{ - uint8_t ts[] = {0x15, 0x0a, 0x01, 0x01, 0x02, 0x03, 0x11, 0x22, 0x33, 0x44}; - - ASSERT_EQ(calcTimeYMD((RSTimestampYMD*)&ts), 1633021327399124); -} - -TEST(TestParseTime, calcTimeHost) -{ - calcTimeHost(); -} - -TEST(TestParseTemp, calcTemp) +template +class MyDecoder : public Decoder { +public: + MyDecoder(const RSDecoderParam& param, + const std::function& excb, + const RSDecoderConstParam& const_param) + : Decoder(param, excb, const_param) { - uint8_t temp[] = {0x18, 0x01}; - ASSERT_EQ(calcTemp((RsTemprature*)&temp), 35); } + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size) { - uint8_t temp[] = {0x18, 0x81}; - ASSERT_EQ(calcTemp((RsTemprature*)&temp), -35); } -} - -TEST(TestScanBlock, ctor) -{ - ScanBlock blk(10, 20); - ASSERT_EQ(blk.start(), 10); - ASSERT_EQ(blk.end(), 20); - - ASSERT_FALSE(blk.in(5)); - ASSERT_TRUE(blk.in(10)); - ASSERT_TRUE(blk.in(15)); - ASSERT_FALSE(blk.in(20)); - ASSERT_FALSE(blk.in(25)); -} - -TEST(TestScanBlock, ctorCrossZero) -{ - ScanBlock blk(35000, 10); - ASSERT_EQ(blk.start(), 35000); - ASSERT_EQ(blk.end(), 10); - - ASSERT_FALSE(blk.in(34999)); - ASSERT_TRUE(blk.in(35000)); - ASSERT_TRUE(blk.in(0)); - ASSERT_FALSE(blk.in(10)); - ASSERT_FALSE(blk.in(15)); -} - -TEST(TestScanBlock, ctorBeyondRound) -{ - ScanBlock blk(36100, 36200); - ASSERT_EQ(blk.start(), 100); - ASSERT_EQ(blk.end(), 200); -} - -TEST(TestDistanceBlock, ctor) -{ - DistanceBlock blk(0.5, 200, 0.75, 150); - ASSERT_EQ(blk.min(), 0.75); - ASSERT_EQ(blk.max(), 150); - - ASSERT_FALSE(blk.in(0.45)); - ASSERT_TRUE(blk.in(0.75)); - ASSERT_TRUE(blk.in(0.8)); - ASSERT_TRUE(blk.in(150)); - ASSERT_FALSE(blk.in(150.5)); -} -TEST(TestDistanceBlock, ctorNoUseBlock) -{ - DistanceBlock blk(0.5, 200, 0.0, 200.5); - ASSERT_EQ(blk.min(), 0.5); - ASSERT_EQ(blk.max(), 200); -} + virtual void decodeMsopPkt(const uint8_t* pkt, size_t size) + { + } -TEST(TestChanAngles, genUserChan) -{ - std::vector vert_angles; - std::vector user_chans; - - vert_angles.push_back(100); - vert_angles.push_back(0); - vert_angles.push_back(-100); - vert_angles.push_back(200); - - ChanAngles::genUserChan (vert_angles, user_chans); - ASSERT_EQ(user_chans.size(), 4); - ASSERT_EQ(user_chans[0], 2); - ASSERT_EQ(user_chans[1], 1); - ASSERT_EQ(user_chans[2], 0); - ASSERT_EQ(user_chans[3], 3); -} +}; -TEST(TestChanAngles, loadFromFile) +struct MyDifopPkt { - std::vector vert_angles, horiz_angles; - - ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); - ASSERT_EQ(vert_angles.size(), 4); - ASSERT_EQ(horiz_angles.size(), 4); - ASSERT_EQ(vert_angles[0], 500); - ASSERT_EQ(vert_angles[1], 250); - ASSERT_EQ(vert_angles[2], 0); - ASSERT_EQ(vert_angles[3], -250); - - ASSERT_EQ(horiz_angles[0], 10); - ASSERT_EQ(horiz_angles[1], -20); - ASSERT_EQ(horiz_angles[2], 0); - ASSERT_EQ(horiz_angles[3], -100); - - ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); - ASSERT_EQ(vert_angles.size(), 4); - ASSERT_EQ(horiz_angles.size(), 4); -} +}; -TEST(TestChanAngles, memberLoadFromFile) -{ - ChanAngles angles; - - ASSERT_EQ(angles.loadFromFile ("../rs_driver/test/res/angle.csv"), 0); - ASSERT_EQ(angles.chanSize(), 4); - ASSERT_EQ(angles.toUserChan(0), 3); - ASSERT_EQ(angles.toUserChan(1), 2); - ASSERT_EQ(angles.toUserChan(2), 1); - ASSERT_EQ(angles.toUserChan(3), 0); -} +typedef PointCloudT PointCloud; -TEST(TestChanAngles, loadFromDifop) -{ - uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, - 0x01, 0x03, 0x04, - 0x01, 0x05, 0x06, - 0x00, 0x07, 0x08}; - uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, - 0x01, 0x33, 0x44, - 0x00, 0x55, 0x66, - 0x01, 0x77, 0x88}; - - std::vector vert_angles, horiz_angles; - - ASSERT_EQ(ChanAngles::loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4, - vert_angles, - horiz_angles), 0); - - ASSERT_EQ(vert_angles.size(), 4); - ASSERT_EQ(horiz_angles.size(), 4); - ASSERT_EQ(vert_angles[0], 258); - ASSERT_EQ(vert_angles[1], -772); - ASSERT_EQ(vert_angles[2], -1286); - ASSERT_EQ(vert_angles[3], 1800); - - ASSERT_EQ(horiz_angles[0], 4386); - ASSERT_EQ(horiz_angles[1], -13124); - ASSERT_EQ(horiz_angles[2], 21862); - ASSERT_EQ(horiz_angles[3], -30600); - - ASSERT_EQ(ChanAngles::loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4, - vert_angles, - horiz_angles), 0); - ASSERT_EQ(vert_angles.size(), 4); - ASSERT_EQ(horiz_angles.size(), 4); -} +ErrCode errCode = ERRCODE_SUCCESS; -TEST(TestTrigon, ctor) +void errCallback(const Error& err) { - Trigon trigon; - ASSERT_EQ(trigon.cos(6000), 0.5); - ASSERT_EQ(trigon.sin(3000), 0.5); -#if 0 - trigon.print(); -#endif + errCode = err.error_code; } -TEST(TestSplitAngle, toSplit) +TEST(TestDecoder, processDifopPkt_Error) { - { - SplitAngle sa(10); - ASSERT_FALSE(sa.toSplit(5)); - ASSERT_TRUE(sa.toSplit(15)); - } + RSDecoderParam param; + RSDecoderConstParam const_param; + MyDecoder decoder(param, errCallback, const_param); - { - SplitAngle sa(10); - ASSERT_FALSE(sa.toSplit(5)); - ASSERT_TRUE(sa.toSplit(10)); - ASSERT_FALSE(sa.toSplit(15)); - } + MyDifopPkt pkt; + decoder.processDifopPkt((const uint8_t*)&pkt, 2); + ASSERT_EQ(errCode, ERRCODE_WRONGPKTLENGTH); - { - SplitAngle sa(10); - ASSERT_FALSE(sa.toSplit(10)); - ASSERT_FALSE(sa.toSplit(15)); - } + decoder.processDifopPkt((const uint8_t*)&pkt, sizeof(pkt)); + ASSERT_EQ(errCode, ERRCODE_WRONGPKTHEADER); } -TEST(TestSplitAngle, toSplit_Zero) +TEST(TestDecoderRS32, decodeDifopPkt) { - { - SplitAngle sa(0); - ASSERT_FALSE(sa.toSplit(35999)); - ASSERT_TRUE(sa.toSplit(1)); - ASSERT_FALSE(sa.toSplit(2)); - } - - { - SplitAngle sa(0); - ASSERT_FALSE(sa.toSplit(35999)); - ASSERT_TRUE(sa.toSplit(0)); - ASSERT_FALSE(sa.toSplit(2)); - } + RSDecoderParam param; + DecoderRS32 decoder(param, errCallback); - { - SplitAngle sa(0); - ASSERT_FALSE(sa.toSplit(0)); - ASSERT_FALSE(sa.toSplit(2)); - } + RS32DifopPkt pkt; } From 18d80d31b5589f807b5b2d39a50fd7967bf5731b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 13 Dec 2021 20:52:56 +0800 Subject: [PATCH 059/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 6 ++ src/rs_driver/driver/decoder/decoder_RS32.hpp | 9 +- test/decoder_test.cpp | 82 +++++++++++++++---- 3 files changed, 78 insertions(+), 19 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index e3436ff9..eae58a54 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -153,6 +153,11 @@ class Decoder const std::function& excb, const RSDecoderConstParam& lidar_const_param); + uint16_t rps() + { + return rps_; + } + protected: void toSplit(uint16_t azimuth, double chan_ts); @@ -357,6 +362,7 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) this->rps_ = 10; } + // blocks per frame this->blks_per_frame_ = 1 / (this->rps_ * this->const_param_.BLOCK_DURATION); diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 73f149a8..1eb7bfba 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense @@ -100,10 +101,10 @@ class DecoderRS32 : public Decoder { RSDecoderConstParam param = { - 1248 - , 1248 - , 8 - , 8 + 1248 // msop len + , 1248 // difop len + , 8 // msop id len + , 8 // difop id len , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 58efa345..45cb176e 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -1,11 +1,30 @@ #include -#include -#include +#include "rs_driver/msg/point_cloud_msg.h" +#include +#include using namespace robosense::lidar; +typedef PointCloudT PointCloud; + +#pragma pack(push, 1) +struct MyMsopPkt +{ + uint8_t id[8]; +}; + +struct MyDifopPkt +{ + uint8_t id[8]; + uint16_t rpm; + RSFOV fov; + RSCalibrationAngle ver_angle_cali[2]; + RSCalibrationAngle hori_angle_cali[2]; +}; +#pragma pack(pop) + template class MyDecoder : public Decoder { @@ -17,8 +36,10 @@ class MyDecoder : public Decoder { } - virtual void decodeDifopPkt(const uint8_t* pkt, size_t size) + virtual void decodeDifopPkt(const uint8_t* packet, size_t size) { + const MyDifopPkt& pkt = *(const MyDifopPkt*)(packet); + this->template decodeDifopCommon(pkt); } virtual void decodeMsopPkt(const uint8_t* pkt, size_t size) @@ -27,12 +48,6 @@ class MyDecoder : public Decoder }; -struct MyDifopPkt -{ -}; - -typedef PointCloudT PointCloud; - ErrCode errCode = ERRCODE_SUCCESS; void errCallback(const Error& err) @@ -40,25 +55,62 @@ void errCallback(const Error& err) errCode = err.error_code; } -TEST(TestDecoder, processDifopPkt_Error) +TEST(TestDecoder, processDifopPkt_fail) { + RSDecoderConstParam const_param = + { + sizeof(MyMsopPkt) // msop len + , sizeof(MyDifopPkt) // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 12 // blocks per packet + , 32 // channels per block + }; + RSDecoderParam param; - RSDecoderConstParam const_param; MyDecoder decoder(param, errCallback, const_param); MyDifopPkt pkt; - decoder.processDifopPkt((const uint8_t*)&pkt, 2); + errCode = ERRCODE_SUCCESS; + decoder.processDifopPkt((const uint8_t*)&pkt, 10); ASSERT_EQ(errCode, ERRCODE_WRONGPKTLENGTH); + errCode = ERRCODE_SUCCESS; decoder.processDifopPkt((const uint8_t*)&pkt, sizeof(pkt)); ASSERT_EQ(errCode, ERRCODE_WRONGPKTHEADER); } -TEST(TestDecoderRS32, decodeDifopPkt) +TEST(TestDecoder, processDifopPkt) { + RSDecoderConstParam const_param = + { + sizeof(MyMsopPkt) // msop len + , sizeof(MyDifopPkt) // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 12 // blocks per packet + , 32 // channels per block + }; + RSDecoderParam param; - DecoderRS32 decoder(param, errCallback); + MyDecoder decoder(param, errCallback, const_param); + + uint8_t pkt[] = + { + 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // msop len + , 0x02, 0x58 // rpm + }; + + errCode = ERRCODE_SUCCESS; + decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); - RS32DifopPkt pkt; + ASSERT_EQ(decoder.rps(), 10); } From 6941ababc05db89c54cd72b86f58f4708474d938 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 14 Dec 2021 10:52:53 +0800 Subject: [PATCH 060/379] feat: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 18 ++-- src/rs_driver/driver/decoder/decoder_RS32.hpp | 101 ++++++++++-------- test/CMakeLists.txt | 2 + test/decoder_test.cpp | 36 ++++++- test/dual_return_block_diff_test.cpp | 9 +- test/single_return_block_diff_test.cpp | 13 +-- 6 files changed, 114 insertions(+), 65 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index eae58a54..b087d64a 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -52,15 +52,16 @@ typedef struct // distance resolution float DIS_RESOLUTION; - // firing_ts / block_ts, chan_ts - float CHAN_TSS[128]; - float BLOCK_DURATION; - // lens center float RX; float RY; float RZ; + // firing_ts / block_ts, chan_ts + float CHAN_AZIS[128]; + double CHAN_TSS[128]; + double BLOCK_DURATION; + } RSDecoderConstParam; #include @@ -153,12 +154,9 @@ class Decoder const std::function& excb, const RSDecoderConstParam& lidar_const_param); - uint16_t rps() - { - return rps_; - } - +#ifndef UNIT_TEST protected: +#endif void toSplit(uint16_t azimuth, double chan_ts); void setPointCloudHeader(std::shared_ptr msg, double chan_ts); @@ -166,8 +164,6 @@ class Decoder template void decodeDifopCommon(const T_Difop& pkt); -protected: - RSDecoderConstParam const_param_; RSDecoderParam param_; std::function excb_; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 1eb7bfba..59bde5fa 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -92,58 +92,73 @@ class DecoderRS32 : public Decoder virtual uint64_t usecToDelay() {return 0;} virtual ~DecoderRS32() = default; - explicit DecoderRS32(const RSDecoderParam& param, + explicit DecoderRS32(const RSDecoderParam& param, const std::function& excb); protected: - static RSDecoderConstParam getConstParam() + static RSDecoderConstParam getConstParam(); + RSEchoMode getEchoMode(uint8_t mode); + + template + void internDecodeMsopPkt(const uint8_t* pkt, size_t size); +}; + +template +RSDecoderConstParam DecoderRS32::getConstParam() +{ + RSDecoderConstParam param = { - RSDecoderConstParam param = - { - 1248 // msop len - , 1248 // difop len - , 8 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id - , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0xFF, 0xEE} // block id - , 12 // blocks per packet - , 32 // channels per block - , 0.005 // distance resolution - - // firing_ts - , { 0.00, 2.88, 5.76, 8.64, 11.52, 14.40, 17.28, 20.16, - 23.04, 25.92, 28.80, 31.68, 34.56, 37.44, 40.32, 44.64, - 1.44, 4.32, 7.20, 10.08, 12.96, 15.84, 18.72, 21.60, - 24.48, 27.36, 30.24, 33.12, 36.00, 38.88, 41.76, 46.08} - , 55.52 - - // lens center - , 0.03997 // RX - , -0.01087 // RY - , 0 // RZ - }; - - return param; - } + 1248 // msop len + , 1248 // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 12 // blocks per packet + , 32 // channels per block + , 0.005 // distance resolution + + // lens center + , 0.03997 // RX + , -0.01087 // RY + , 0 // RZ + }; + + float firing_tss[] = + { + 0.00, 2.88, 5.76, 8.64, 11.52, 14.40, 17.28, 20.16, + 23.04, 25.92, 28.80, 31.68, 34.56, 37.44, 40.32, 44.64, + 1.44, 4.32, 7.20, 10.08, 12.96, 15.84, 18.72, 21.60, + 24.48, 27.36, 30.24, 33.12, 36.00, 38.88, 41.76, 46.08 + }; + + float blk_ts = 55.52; - RSEchoMode getEchoMode(uint8_t mode) + param.BLOCK_DURATION = blk_ts / 1000000; + for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) { - switch (mode) - { - case 0x00: - return RSEchoMode::ECHO_DUAL; - case 0x01: - case 0x02: - default: - return RSEchoMode::ECHO_SINGLE; - } + param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; + param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; } - template - void internDecodeMsopPkt(const uint8_t* pkt, size_t size); -}; + return param; +} + +template +inline RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) +{ + switch (mode) + { + case 0x00: + return RSEchoMode::ECHO_DUAL; + case 0x01: + case 0x02: + default: + return RSEchoMode::ECHO_SINGLE; + } +} template inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 426bec1e..b9af456d 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -7,6 +7,8 @@ find_package(GTest REQUIRED) include_directories(${GTEST_INCLUDE_DIRS}) include_directories(${DRIVER_INCLUDE_DIRS}) +add_definitions("-DUNIT_TEST") + add_executable(rs_driver_test rs_driver_test.cpp packet_test.cpp diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 45cb176e..e3518b22 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -111,6 +111,40 @@ TEST(TestDecoder, processDifopPkt) decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); ASSERT_EQ(errCode, ERRCODE_SUCCESS); - ASSERT_EQ(decoder.rps(), 10); + ASSERT_EQ(decoder.rps_, 10); } +TEST(TestDecoder, processDifopPkt_invalid_rpm) +{ + RSDecoderConstParam const_param = + { + sizeof(MyMsopPkt) // msop len + , sizeof(MyDifopPkt) // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 12 // blocks per packet + , 32 // channels per block + }; + + RSDecoderParam param; + MyDecoder decoder(param, errCallback, const_param); + + uint8_t pkt[] = + { + 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // msop len + , 0x00, 0x00 // rpm + }; + + errCode = ERRCODE_SUCCESS; + decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); + + ASSERT_EQ(decoder.rps_, 10); + //ASSERT_EQ(decoder.blk_per_frame, 10); +} + + + diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_diff_test.cpp index 68617016..bcf3f18b 100644 --- a/test/dual_return_block_diff_test.cpp +++ b/test/dual_return_block_diff_test.cpp @@ -38,14 +38,15 @@ TEST(TestDualPacketTraverser, toNext) , 2 // channels per block , 0.25 // distance resolution - // firing_ts - , {0.0, 0.25} // chan_tss - , 0.50 // block_duration - // lens center , 0 // RX , 0 // RY , 0 // RZ + + // firing_ts + , {0.0} // chan_azis + , {0.0, 0.25} // chan_tss + , 0.50 // block_duration }; MyPacket pkt = diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_diff_test.cpp index c197a690..77392835 100644 --- a/test/single_return_block_diff_test.cpp +++ b/test/single_return_block_diff_test.cpp @@ -23,7 +23,7 @@ typedef struct MyBlock blocks[3]; } MyPacket; -TEST(TestSingleReturnPacketTraverser, toNext) +TEST(TestSingleReturnBlockDiff, ctor) { RSDecoderConstParam const_param = { @@ -38,14 +38,15 @@ TEST(TestSingleReturnPacketTraverser, toNext) , 2 // channels per block , 0.25 // distance resolution - // firing_ts - , {0.0, 0.25} // chan_tss - , 0.50 // block_duration - - // lens center + // lens center , 0 // RX , 0 // RY , 0 // RZ + + // firing_ts + , {0.0} // chan_azis + , {0.0, 0.25} // chan_tss + , 0.50 // block_duration }; MyPacket pkt = From 6b9c6b35f210a7005364db07e013941419481681 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 14 Dec 2021 11:48:27 +0800 Subject: [PATCH 061/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 12 +++--- src/rs_driver/driver/decoder/decoder_RS32.hpp | 3 +- .../driver/decoder/decoder_base_opt.hpp | 2 + test/decoder_test.cpp | 38 ++++++++++++------- test/dual_return_block_diff_test.cpp | 4 +- test/single_return_block_diff_test.cpp | 4 +- 6 files changed, 37 insertions(+), 26 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index b087d64a..702c0769 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -58,9 +58,9 @@ typedef struct float RZ; // firing_ts / block_ts, chan_ts - float CHAN_AZIS[128]; - double CHAN_TSS[128]; double BLOCK_DURATION; + double CHAN_TSS[128]; + float CHAN_AZIS[128]; } RSDecoderConstParam; @@ -358,23 +358,23 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) this->rps_ = 10; } - // blocks per frame this->blks_per_frame_ = 1 / (this->rps_ * this->const_param_.BLOCK_DURATION); // block diff of azimuth - this->block_azi_diff_ = RS_ONE_ROUND * this->rps_ * this->const_param_.BLOCK_DURATION; + this->block_azi_diff_ = + std::round(RS_ONE_ROUND * this->rps_ * this->const_param_.BLOCK_DURATION); // fov related uint16_t fov_start_angle = ntohs(pkt.fov.start_angle); uint16_t fov_end_angle = ntohs(pkt.fov.end_angle); - uint16_t fov_range = (fov_start_angle < fov_end_angle) ? (fov_end_angle - fov_start_angle) : (fov_end_angle + RS_ONE_ROUND - fov_start_angle); uint16_t fov_blind_range = RS_ONE_ROUND - fov_range; // fov blind diff of timestamp - this->fov_blind_ts_diff_ = fov_blind_range / (RS_ONE_ROUND * this->rps_); + this->fov_blind_ts_diff_ = + (float)fov_blind_range / ((float)RS_ONE_ROUND * (float)this->rps_); if (!this->difop_ready_) { diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 59bde5fa..a2f9ed1b 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -126,6 +126,7 @@ RSDecoderConstParam DecoderRS32::getConstParam() , 0 // RZ }; + float blk_ts = 55.52; float firing_tss[] = { 0.00, 2.88, 5.76, 8.64, 11.52, 14.40, 17.28, 20.16, @@ -134,8 +135,6 @@ RSDecoderConstParam DecoderRS32::getConstParam() 24.48, 27.36, 30.24, 33.12, 36.00, 38.88, 41.76, 46.08 }; - float blk_ts = 55.52; - param.BLOCK_DURATION = blk_ts / 1000000; for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) { diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 9d291797..19893a45 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -555,7 +555,9 @@ class ChanAngles return ((vert_angles.size() > 0) ? 0 : -1); } +#ifndef UNIT_TEST private: +#endif std::vector vert_angles_; std::vector horiz_angles_; std::vector user_chans_; diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index e3518b22..72d00fa9 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -65,9 +65,6 @@ TEST(TestDecoder, processDifopPkt_fail) , 8 // difop id len , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0xFF, 0xEE} // block id - , 12 // blocks per packet - , 32 // channels per block }; RSDecoderParam param; @@ -85,26 +82,34 @@ TEST(TestDecoder, processDifopPkt_fail) TEST(TestDecoder, processDifopPkt) { - RSDecoderConstParam const_param = - { - sizeof(MyMsopPkt) // msop len + RSDecoderConstParam const_param = + { + sizeof(MyMsopPkt) // msop len , sizeof(MyDifopPkt) // difop len , 8 // msop id len , 8 // difop id len , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id - , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0xFF, 0xEE} // block id - , 12 // blocks per packet - , 32 // channels per block - }; + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 0 // blocks per packet + , 2 // channels per block + }; + + const_param.BLOCK_DURATION = 55.52 / 1000000; RSDecoderParam param; MyDecoder decoder(param, errCallback, const_param); uint8_t pkt[] = { - 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // msop len + 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // msop len , 0x02, 0x58 // rpm + , 0x23, 0x28 // start angle = 9000 + , 0x46, 0x50 // end angle = 18000 + , 0x00, 0x00, 0x10 // vert angles + , 0x01, 0x00, 0x20 + , 0x00, 0x00, 0x01 // horiz angles + , 0x01, 0x00, 0x02 }; errCode = ERRCODE_SUCCESS; @@ -112,6 +117,12 @@ TEST(TestDecoder, processDifopPkt) ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_EQ(decoder.rps_, 10); + ASSERT_EQ(decoder.blks_per_frame_, 1801); + ASSERT_EQ(decoder.fov_blind_ts_diff_, 0.075f); + ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); + ASSERT_EQ(decoder.chan_angles_.vert_angles_[0], 16); + ASSERT_EQ(decoder.chan_angles_.horiz_angles_.size(), 2); + ASSERT_EQ(decoder.chan_angles_.horiz_angles_[0], 1); } TEST(TestDecoder, processDifopPkt_invalid_rpm) @@ -135,7 +146,7 @@ TEST(TestDecoder, processDifopPkt_invalid_rpm) uint8_t pkt[] = { 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // msop len - , 0x00, 0x00 // rpm + , 0x00, 0x00 // rpm = 0 }; errCode = ERRCODE_SUCCESS; @@ -143,7 +154,6 @@ TEST(TestDecoder, processDifopPkt_invalid_rpm) ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_EQ(decoder.rps_, 10); - //ASSERT_EQ(decoder.blk_per_frame, 10); } diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_diff_test.cpp index bcf3f18b..35870077 100644 --- a/test/dual_return_block_diff_test.cpp +++ b/test/dual_return_block_diff_test.cpp @@ -44,9 +44,9 @@ TEST(TestDualPacketTraverser, toNext) , 0 // RZ // firing_ts - , {0.0} // chan_azis - , {0.0, 0.25} // chan_tss , 0.50 // block_duration + , {0.0, 0.25} // chan_tss + , {0.0} // chan_azis }; MyPacket pkt = diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_diff_test.cpp index 77392835..9b92350a 100644 --- a/test/single_return_block_diff_test.cpp +++ b/test/single_return_block_diff_test.cpp @@ -44,9 +44,9 @@ TEST(TestSingleReturnBlockDiff, ctor) , 0 // RZ // firing_ts - , {0.0} // chan_azis - , {0.0, 0.25} // chan_tss , 0.50 // block_duration + , {0.0, 0.25} // chan_tss + , {0.0} // chan_azis }; MyPacket pkt = From 99e308c8820d4f2d51c9cbbd87bae48ff36b4d04 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 14 Dec 2021 12:04:11 +0800 Subject: [PATCH 062/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 5 ++- test/decoder_test.cpp | 55 +++++++++++++++++------- 2 files changed, 43 insertions(+), 17 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 702c0769..a81e733f 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -310,19 +310,22 @@ void Decoder::setPointCloudHeader(std::shared_ptr ms template void Decoder::processMsopPkt(const uint8_t* pkt, size_t size) { +#if 0 if (param_.wait_for_difop && !difop_ready_) { excb_(Error(ERRCODE_NODIFOPRECV)); } - +#endif if (size != this->const_param_.MSOP_LEN) { this->excb_(Error(ERRCODE_WRONGPKTLENGTH)); + return; } if (memcmp(pkt, this->const_param_.MSOP_ID, const_param_.MSOP_ID_LEN) != 0) { this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + return; } decodeMsopPkt(pkt, size); diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 72d00fa9..f30cd90c 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -80,6 +80,37 @@ TEST(TestDecoder, processDifopPkt_fail) ASSERT_EQ(errCode, ERRCODE_WRONGPKTHEADER); } +TEST(TestDecoder, processDifopPkt_invalid_rpm) +{ + RSDecoderConstParam const_param = + { + sizeof(MyMsopPkt) // msop len + , sizeof(MyDifopPkt) // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 12 // blocks per packet + , 32 // channels per block + }; + + RSDecoderParam param; + MyDecoder decoder(param, errCallback, const_param); + + uint8_t pkt[] = + { + 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // difop len + , 0x00, 0x00 // rpm = 0 + }; + + errCode = ERRCODE_SUCCESS; + decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); + + ASSERT_EQ(decoder.rps_, 10); +} + TEST(TestDecoder, processDifopPkt) { RSDecoderConstParam const_param = @@ -102,7 +133,7 @@ TEST(TestDecoder, processDifopPkt) uint8_t pkt[] = { - 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // msop len + 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // difop id , 0x02, 0x58 // rpm , 0x23, 0x28 // start angle = 9000 , 0x46, 0x50 // end angle = 18000 @@ -125,7 +156,7 @@ TEST(TestDecoder, processDifopPkt) ASSERT_EQ(decoder.chan_angles_.horiz_angles_[0], 1); } -TEST(TestDecoder, processDifopPkt_invalid_rpm) +TEST(TestDecoder, processMsopPkt_fail) { RSDecoderConstParam const_param = { @@ -135,26 +166,18 @@ TEST(TestDecoder, processDifopPkt_invalid_rpm) , 8 // difop id len , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0xFF, 0xEE} // block id - , 12 // blocks per packet - , 32 // channels per block }; RSDecoderParam param; MyDecoder decoder(param, errCallback, const_param); - uint8_t pkt[] = - { - 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // msop len - , 0x00, 0x00 // rpm = 0 - }; - + MyMsopPkt pkt; errCode = ERRCODE_SUCCESS; - decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); - ASSERT_EQ(errCode, ERRCODE_SUCCESS); + decoder.processMsopPkt((const uint8_t*)&pkt, 2); + ASSERT_EQ(errCode, ERRCODE_WRONGPKTLENGTH); - ASSERT_EQ(decoder.rps_, 10); + errCode = ERRCODE_SUCCESS; + decoder.processMsopPkt((const uint8_t*)&pkt, sizeof(pkt)); + ASSERT_EQ(errCode, ERRCODE_WRONGPKTHEADER); } - - From 92864738e165b2b75150224cb073245961b533d5 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 14 Dec 2021 12:28:19 +0800 Subject: [PATCH 063/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 28 ++++++++++---------- src/rs_driver/driver/input/input_factory.hpp | 4 +-- src/rs_driver/driver/input/input_pcap.hpp | 6 ++--- test/decoder_test.cpp | 13 +++++++-- 4 files changed, 30 insertions(+), 21 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index a81e733f..d89651c5 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -139,7 +139,7 @@ class Decoder return temperature_; } - uint64_t getPacketDiff() + double getPacketDiff() { // Assume echo_mode is ECHO_SINGLE. // If it is ECHO_DUAL, use RSInputParam.pcap_rate = 2 to change the playback speed. @@ -292,19 +292,19 @@ inline void Decoder::toSplit(uint16_t azimuth, double chan_ts) template void Decoder::setPointCloudHeader(std::shared_ptr msg, double chan_ts) { - msg->seq = point_cloud_seq_++; - msg->timestamp = chan_ts; - msg->is_dense = param_.dense_points; - if (msg->is_dense) - { - msg->height = 1; - msg->width = msg->points.size(); - } - else - { - msg->height = height_; - msg->width = msg->points.size() / msg->height; - } + msg->seq = point_cloud_seq_++; + msg->timestamp = chan_ts; + msg->is_dense = param_.dense_points; + if (msg->is_dense) + { + msg->height = 1; + msg->width = msg->points.size(); + } + else + { + msg->height = height_; + msg->width = msg->points.size() / msg->height; + } } template diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index c6ad0564..50944d1b 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -45,12 +45,12 @@ class InputFactory public: static std::shared_ptr createInput(InputType type, const RSInputParam& param, const std::function& excb, - uint64_t msec_to_delay); + double msec_to_delay); }; inline std::shared_ptr InputFactory::createInput(InputType type, const RSInputParam& param, const std::function& excb, - uint64_t msec_to_delay) + double msec_to_delay) { std::shared_ptr input; diff --git a/src/rs_driver/driver/input/input_pcap.hpp b/src/rs_driver/driver/input/input_pcap.hpp index 2e414089..790864be 100644 --- a/src/rs_driver/driver/input/input_pcap.hpp +++ b/src/rs_driver/driver/input/input_pcap.hpp @@ -45,9 +45,9 @@ class InputPcap : public Input { public: InputPcap(const RSInputParam& input_param, - const std::function& excb, long long msec_to_delay) + const std::function& excb, double msec_to_delay) : Input(input_param, excb), pcap_offset_(ETH_HDR_LEN), - difop_filter_valid_(false), msec_to_delay_(msec_to_delay) + difop_filter_valid_(false), msec_to_delay_(msec_to_delay*1000) { if (input_param.use_vlan) pcap_offset_ += VLAN_LEN; @@ -83,7 +83,7 @@ class InputPcap : public Input bpf_program msop_filter_; bpf_program difop_filter_; bool difop_filter_valid_; - long long msec_to_delay_; + uint64_t msec_to_delay_; }; inline bool InputPcap::init() diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index f30cd90c..a3e4c2bc 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -122,11 +122,11 @@ TEST(TestDecoder, processDifopPkt) , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id - , 0 // blocks per packet + , 1000 // blocks per packet , 2 // channels per block }; - const_param.BLOCK_DURATION = 55.52 / 1000000; + const_param.BLOCK_DURATION = 55.52f / 1000000; RSDecoderParam param; MyDecoder decoder(param, errCallback, const_param); @@ -143,6 +143,8 @@ TEST(TestDecoder, processDifopPkt) , 0x01, 0x00, 0x02 }; + ASSERT_LT(decoder.getPacketDiff() - 55.52/1000, 0.00001); + errCode = ERRCODE_SUCCESS; decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); ASSERT_EQ(errCode, ERRCODE_SUCCESS); @@ -179,5 +181,12 @@ TEST(TestDecoder, processMsopPkt_fail) errCode = ERRCODE_SUCCESS; decoder.processMsopPkt((const uint8_t*)&pkt, sizeof(pkt)); ASSERT_EQ(errCode, ERRCODE_WRONGPKTHEADER); + + errCode = ERRCODE_SUCCESS; + + uint8_t id[] = {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0}; + memcpy (pkt.id, id, 8); + decoder.processMsopPkt((const uint8_t*)&pkt, sizeof(pkt)); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); } From 6badd753f3c01f858c897be1dba2b140469c542f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 14 Dec 2021 14:18:02 +0800 Subject: [PATCH 064/379] refac: refactory decoder --- src/rs_driver/driver/driver_param.h | 78 +---------------------------- 1 file changed, 1 insertion(+), 77 deletions(-) diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index cdb2434a..c1e8bf2b 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -258,6 +258,7 @@ typedef struct RSInputParam ///< The LiDAR input parameter double pcap_rate = 1; ///< Rate to read the pcap file bool use_vlan = false; ///< Vlan on-off bool use_someip = false; ///< Someip on-off + void print() const { RS_INFO << "------------------------------------------------------" << RS_REND; @@ -292,83 +293,6 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter RS_INFOL << "------------------------------------------------------" << RS_REND; } - static std::string lidarTypeToStr(const LidarType& type) - { - std::string str = ""; - switch (type) - { - case LidarType::RS16: - str = "RS16"; - break; - case LidarType::RS32: - str = "RS32"; - break; - case LidarType::RSBP: - str = "RSBP"; - break; - case LidarType::RS128: - str = "RS128"; - break; - case LidarType::RS80: - str = "RS80"; - break; - case LidarType::RSM1: - str = "RSM1"; - break; - case LidarType::RSHELIOS: - str = "RSHELIOS"; - break; - case LidarType::RSROCK: - str = "RSROCK"; - break; - default: - str = "ERROR"; - RS_ERROR << "RS_ERROR" << RS_REND; - } - return str; - } - static LidarType strToLidarType(const std::string& type) - { - if (type == "RS16") - { - return lidar::LidarType::RS16; - } - else if (type == "RS32") - { - return lidar::LidarType::RS32; - } - else if (type == "RSBP") - { - return lidar::LidarType::RSBP; - } - else if (type == "RS128") - { - return lidar::LidarType::RS128; - } - else if (type == "RS80") - { - return lidar::LidarType::RS80; - } - else if (type == "RSM1") - { - return lidar::LidarType::RSM1; - } - else if (type == "RSHELIOS") - { - return lidar::LidarType::RSHELIOS; - } - else if (type == "RSROCK") - { - return lidar::LidarType::RSROCK; - } - else - { - RS_ERROR << "Wrong lidar type: " << type << RS_REND; - RS_ERROR << "Please setup the correct type: RS16, RS32, RSBP, RS128, RS80, RSM1, RSHELIOS" << RS_REND; - exit(-1); - } - } - } RSDriverParam; } // namespace lidar From 1a8d8af4cf6bb206c7286d9c17c393b3df880079 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 14 Dec 2021 14:44:54 +0800 Subject: [PATCH 065/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 6 +-- src/rs_driver/driver/driver_param.h | 1 + test/decoder_test.cpp | 59 ++++++++++++++++++++++-- 3 files changed, 60 insertions(+), 6 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index d89651c5..e446b19f 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -310,12 +310,12 @@ void Decoder::setPointCloudHeader(std::shared_ptr ms template void Decoder::processMsopPkt(const uint8_t* pkt, size_t size) { -#if 0 if (param_.wait_for_difop && !difop_ready_) { excb_(Error(ERRCODE_NODIFOPRECV)); + return; } -#endif + if (size != this->const_param_.MSOP_LEN) { this->excb_(Error(ERRCODE_WRONGPKTLENGTH)); @@ -379,7 +379,7 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) this->fov_blind_ts_diff_ = (float)fov_blind_range / ((float)RS_ONE_ROUND * (float)this->rps_); - if (!this->difop_ready_) + if (!this->param_.config_from_file && !this->difop_ready_) { this->chan_angles_.loadFromDifop(pkt.ver_angle_cali, pkt.hori_angle_cali, this->const_param_.CHANNELS_PER_BLOCK); diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index c1e8bf2b..26babc75 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -273,6 +273,7 @@ typedef struct RSInputParam ///< The LiDAR input parameter RS_INFOL << "use_someip: " << use_someip << RS_REND; RS_INFO << "------------------------------------------------------" << RS_REND; } + } RSInputParam; typedef struct RSDriverParam ///< The LiDAR driver parameter diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index a3e4c2bc..85fbcac0 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -145,6 +145,11 @@ TEST(TestDecoder, processDifopPkt) ASSERT_LT(decoder.getPacketDiff() - 55.52/1000, 0.00001); + // + // angles from angle.csv + // + + decoder.param_.config_from_file = true; errCode = ERRCODE_SUCCESS; decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); ASSERT_EQ(errCode, ERRCODE_SUCCESS); @@ -152,6 +157,39 @@ TEST(TestDecoder, processDifopPkt) ASSERT_EQ(decoder.rps_, 10); ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.fov_blind_ts_diff_, 0.075f); + ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 0); + ASSERT_EQ(decoder.chan_angles_.horiz_angles_.size(), 0); + + // + //angles from difop. no angles in difop + // + + uint8_t pkt_no_angles[] = + { + 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // difop id + , 0x02, 0x58 // rpm + , 0x23, 0x28 // start angle = 9000 + , 0x46, 0x50 // end angle = 18000 + , 0xFF, 0xFF, 0xFF // vert angles + , 0xFF, 0xFF, 0xFF + , 0xFF, 0xFF, 0xFF // horiz angles + , 0xFF, 0xFF, 0xFF + }; + + decoder.param_.config_from_file = false; + errCode = ERRCODE_SUCCESS; + decoder.processDifopPkt(pkt_no_angles, sizeof(MyDifopPkt)); + errCode = ERRCODE_SUCCESS; + + ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 0); + ASSERT_EQ(decoder.chan_angles_.horiz_angles_.size(), 0); + + // angles from difop. + decoder.param_.config_from_file = false; + errCode = ERRCODE_SUCCESS; + decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); + errCode = ERRCODE_SUCCESS; + ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); ASSERT_EQ(decoder.chan_angles_.vert_angles_[0], 16); ASSERT_EQ(decoder.chan_angles_.horiz_angles_.size(), 2); @@ -170,22 +208,37 @@ TEST(TestDecoder, processMsopPkt_fail) , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id }; + MyMsopPkt pkt; + RSDecoderParam param; MyDecoder decoder(param, errCallback, const_param); - MyMsopPkt pkt; + // wrong msop len + decoder.param_.wait_for_difop = true; + decoder.difop_ready_ = false; + errCode = ERRCODE_SUCCESS; + decoder.processMsopPkt((const uint8_t*)&pkt, 2); + ASSERT_EQ(errCode, ERRCODE_NODIFOPRECV); + + decoder.param_.wait_for_difop = true; + decoder.difop_ready_ = true; + + // wrong msop len errCode = ERRCODE_SUCCESS; decoder.processMsopPkt((const uint8_t*)&pkt, 2); ASSERT_EQ(errCode, ERRCODE_WRONGPKTLENGTH); + decoder.param_.wait_for_difop = false; + + // wrong msop header errCode = ERRCODE_SUCCESS; decoder.processMsopPkt((const uint8_t*)&pkt, sizeof(pkt)); ASSERT_EQ(errCode, ERRCODE_WRONGPKTHEADER); - errCode = ERRCODE_SUCCESS; - + // valid msop uint8_t id[] = {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0}; memcpy (pkt.id, id, 8); + errCode = ERRCODE_SUCCESS; decoder.processMsopPkt((const uint8_t*)&pkt, sizeof(pkt)); ASSERT_EQ(errCode, ERRCODE_SUCCESS); } From 29e6a1bb83abd638580d7a7ea3f9c3f119e8e87e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 14 Dec 2021 15:35:45 +0800 Subject: [PATCH 066/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 7 ++----- src/rs_driver/driver/driver_param.h | 1 + test/decoder_test.cpp | 12 +++++++++++- 3 files changed, 14 insertions(+), 6 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index e446b19f..8203958c 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -146,10 +146,6 @@ class Decoder return this->const_param_.BLOCK_DURATION * const_param_.BLOCKS_PER_PKT; } - void loadAngleFile(const std::string& angle_path) - { - } - explicit Decoder(const RSDecoderParam& param, const std::function& excb, const RSDecoderConstParam& lidar_const_param); @@ -226,7 +222,8 @@ inline Decoder::Decoder(const RSDecoderParam& param, if (param.config_from_file) { - loadAngleFile(param.angle_path); + int ret = chan_angles_.loadFromFile(param.angle_path); + this->difop_ready_ = (ret == 0); } } diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index 26babc75..902ece8b 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -231,6 +231,7 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter #endif RS_INFO << "------------------------------------------------------" << RS_REND; RS_INFO << " RoboSense Decoder Parameters " << RS_REND; + RS_INFOL << "config_from_file: " << config_from_file << RS_REND; RS_INFOL << "angle_path: " << angle_path << RS_REND; RS_INFOL << "max_distance: " << max_distance << RS_REND; RS_INFOL << "min_distance: " << min_distance << RS_REND; diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 85fbcac0..2d9a92da 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -196,7 +196,7 @@ TEST(TestDecoder, processDifopPkt) ASSERT_EQ(decoder.chan_angles_.horiz_angles_[0], 1); } -TEST(TestDecoder, processMsopPkt_fail) +TEST(TestDecoder, processMsopPkt) { RSDecoderConstParam const_param = { @@ -243,3 +243,13 @@ TEST(TestDecoder, processMsopPkt_fail) ASSERT_EQ(errCode, ERRCODE_SUCCESS); } +TEST(TestDecoder, ctor) +{ + RSDecoderConstParam const_param; + RSDecoderParam param; + param.config_from_file = true; + param.angle_path = "../rs_driver/test/res/angle.csv"; + MyDecoder decoder(param, errCallback, const_param); + ASSERT_TRUE(decoder.difop_ready_); +} + From 8bba62e5012fcda188e14e99274f0610e36eac95 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 14 Dec 2021 17:41:33 +0800 Subject: [PATCH 067/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 25 +-- .../driver/decoder/decoder_base_opt.hpp | 4 +- test/decoder_test.cpp | 174 +++++++++++++++++- 3 files changed, 183 insertions(+), 20 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 8203958c..89dde3ff 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -106,18 +106,6 @@ enum RSEchoMode ECHO_DUAL }; -/* Decode result definition */ -enum RSDecoderResult -{ - DECODE_OK = 0, - FRAME_SPLIT = 1, - WRONG_PKT_HEADER = -1, - WRONG_PKT_LENGTH = -2, - PKT_NULL = -3, - DISCARD_PKT = -4, - DIFOP_NOT_READY = -5 -}; - template class Decoder { @@ -163,11 +151,12 @@ class Decoder RSDecoderConstParam const_param_; RSDecoderParam param_; std::function excb_; - uint16_t height_; // to be deleted + uint16_t height_; Trigon trigon_; #define SIN(angle) this->trigon_.sin(angle) #define COS(angle) this->trigon_.cos(angle) + ChanAngles chan_angles_; DistanceBlock distance_block_; ScanBlock scan_block_; @@ -197,15 +186,15 @@ class Decoder template inline Decoder::Decoder(const RSDecoderParam& param, const std::function& excb, - const RSDecoderConstParam& lidar_const_param) - : const_param_(lidar_const_param) + const RSDecoderConstParam& const_param) + : const_param_(const_param) , param_(param) , excb_(excb) - , height_(0) + , height_(const_param.CHANNELS_PER_BLOCK) , distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance) , scan_block_(param.start_angle * 100, param.end_angle * 100) , split_angle_(param.split_angle * 100) - , blks_per_frame_(1/(10*lidar_const_param.BLOCK_DURATION)) + , blks_per_frame_(1/(10*const_param.BLOCK_DURATION)) , block_azi_diff_(20) , fov_blind_ts_diff_(0) , protocol_ver_(0) @@ -251,6 +240,7 @@ inline void Decoder::toSplit(uint16_t azimuth, double chan_ts) case SplitFrameMode::SPLIT_BY_FIXED_BLKS: + this->num_blks_++; if (this->num_blks_ >= this->blks_per_frame_) { this->num_blks_ = 0; @@ -260,6 +250,7 @@ inline void Decoder::toSplit(uint16_t azimuth, double chan_ts) case SplitFrameMode::SPLIT_BY_CUSTOM_BLKS: + this->num_blks_++; if (this->num_blks_ >= this->param_.num_blks_split) { this->num_blks_ = 0; diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 19893a45..5a84281c 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -639,9 +639,11 @@ class SplitAngle return split_angle_; } +#ifndef UNIT_TEST private: +#endif uint16_t split_angle_; - int16_t prev_angle_; + int32_t prev_angle_; }; } // namespace lidar diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 2d9a92da..c9e5b186 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -7,7 +7,8 @@ using namespace robosense::lidar; -typedef PointCloudT PointCloud; +typedef PointXYZI PointT; +typedef PointCloudT PointCloud; #pragma pack(push, 1) struct MyMsopPkt @@ -243,7 +244,7 @@ TEST(TestDecoder, processMsopPkt) ASSERT_EQ(errCode, ERRCODE_SUCCESS); } -TEST(TestDecoder, ctor) +TEST(TestDecoder, angles_from_angle_file) { RSDecoderConstParam const_param; RSDecoderParam param; @@ -253,3 +254,172 @@ TEST(TestDecoder, ctor) ASSERT_TRUE(decoder.difop_ready_); } +TEST(TestDecoder, setPointCloudHeader) +{ + RSDecoderConstParam const_param = {}; + const_param.CHANNELS_PER_BLOCK = 2; + RSDecoderParam param; + param.dense_points = true; + MyDecoder decoder(param, errCallback, const_param); + ASSERT_EQ(decoder.point_cloud_seq_, 0); + ASSERT_TRUE(decoder.param_.dense_points); + + std::shared_ptr pt = std::make_shared(); + PointT point; + pt->points.emplace_back(point); + pt->points.emplace_back(point); + + { + decoder.setPointCloudHeader(pt, 0.5f); + ASSERT_EQ(pt->seq, 0); + ASSERT_EQ(pt->timestamp, 0.5f); + ASSERT_TRUE(pt->is_dense); + ASSERT_EQ(pt->height, 1); + ASSERT_EQ(pt->width, 2); + } + + decoder.param_.dense_points = false; + + { + decoder.setPointCloudHeader(pt, 0.5f); + ASSERT_EQ(pt->seq, 1); + ASSERT_EQ(pt->timestamp, 0.5f); + ASSERT_FALSE(pt->is_dense); + ASSERT_EQ(pt->height, 2); + ASSERT_EQ(pt->width, 1); + } +} + +std::shared_ptr point_cloud_to_get; +std::shared_ptr getCallback(void) +{ + return point_cloud_to_get; +} + +bool flag_point_cloud = false; +std::shared_ptr point_cloud_to_put; +void putCallback(std::shared_ptr pt) +{ + point_cloud_to_put = pt; + flag_point_cloud = true; +} + +TEST(TestDecoder, split_by_angle) +{ + RSDecoderConstParam const_param; + const_param.CHANNELS_PER_BLOCK = 2; + RSDecoderParam param; + param.split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; + param.split_angle = 0.0f; + MyDecoder decoder(param, errCallback, const_param); + ASSERT_EQ(decoder.split_angle_.split_angle_, 0); + + point_cloud_to_get = std::make_shared(); + decoder.regRecvCallback (getCallback, putCallback); + + { + errCode = ERRCODE_SUCCESS; + flag_point_cloud = false; + decoder.toSplit (35999, 0); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); + ASSERT_FALSE(flag_point_cloud); + + errCode = ERRCODE_SUCCESS; + decoder.toSplit (2, 0); + ASSERT_EQ(errCode, ERRCODE_ZEROPOINTS); + } + + { + PointT point; + point_cloud_to_get->points.emplace_back(point); + point_cloud_to_get->points.emplace_back(point); + + errCode = ERRCODE_SUCCESS; + flag_point_cloud = false; + decoder.toSplit (1, 0); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); + ASSERT_TRUE(flag_point_cloud); + ASSERT_TRUE(point_cloud_to_put.get() != NULL); + ASSERT_EQ(point_cloud_to_put->height, 2); + ASSERT_EQ(point_cloud_to_put->width, 1); + } +} + +TEST(TestDecoder, split_by_fixed_pkts) +{ + RSDecoderConstParam const_param; + const_param.CHANNELS_PER_BLOCK = 2; + RSDecoderParam param; + param.split_frame_mode = SplitFrameMode::SPLIT_BY_FIXED_BLKS; + //param.num_blks_split = 2; + MyDecoder decoder(param, errCallback, const_param); + decoder.blks_per_frame_ = 2; + ASSERT_EQ(decoder.num_blks_, 0); + + point_cloud_to_get = std::make_shared(); + decoder.regRecvCallback (getCallback, putCallback); + + PointT point; + point_cloud_to_get->points.emplace_back(point); + point_cloud_to_get->points.emplace_back(point); + + { + errCode = ERRCODE_SUCCESS; + flag_point_cloud = false; + decoder.toSplit (0, 0); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); + ASSERT_FALSE(flag_point_cloud); + } + + { + errCode = ERRCODE_SUCCESS; + flag_point_cloud = false; + decoder.toSplit (0, 0); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); + ASSERT_TRUE(flag_point_cloud); + + ASSERT_TRUE(point_cloud_to_put.get() != NULL); + ASSERT_EQ(point_cloud_to_put->height, 2); + ASSERT_EQ(point_cloud_to_put->width, 1); + } +} + +TEST(TestDecoder, split_by_custom_blks) +{ + RSDecoderConstParam const_param; + const_param.CHANNELS_PER_BLOCK = 2; + RSDecoderParam param; + param.split_frame_mode = SplitFrameMode::SPLIT_BY_CUSTOM_BLKS; + param.num_blks_split = 2; + MyDecoder decoder(param, errCallback, const_param); + decoder.blks_per_frame_ = 2; + ASSERT_EQ(decoder.num_blks_, 0); + + point_cloud_to_get = std::make_shared(); + decoder.regRecvCallback (getCallback, putCallback); + + PointT point; + point_cloud_to_get->points.emplace_back(point); + point_cloud_to_get->points.emplace_back(point); + + { + errCode = ERRCODE_SUCCESS; + flag_point_cloud = false; + decoder.toSplit (0, 0); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); + ASSERT_FALSE(flag_point_cloud); + } + + { + errCode = ERRCODE_SUCCESS; + flag_point_cloud = false; + decoder.toSplit (0, 0); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); + ASSERT_TRUE(flag_point_cloud); + + ASSERT_TRUE(point_cloud_to_put.get() != NULL); + ASSERT_EQ(point_cloud_to_put->height, 2); + ASSERT_EQ(point_cloud_to_put->width, 1); + } +} + From 007696e79f708018f79636ea6f3e781df90556fc Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 14 Dec 2021 18:02:38 +0800 Subject: [PATCH 068/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder_RS32.hpp | 8 +++--- test/CMakeLists.txt | 4 +-- test/decoder_rs32_test.cpp | 25 ++++++++++++++++--- test/decoder_test.cpp | 4 +-- 4 files changed, 29 insertions(+), 12 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index a2f9ed1b..1e60d75f 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -88,17 +88,17 @@ class DecoderRS32 : public Decoder virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); - - virtual uint64_t usecToDelay() {return 0;} virtual ~DecoderRS32() = default; explicit DecoderRS32(const RSDecoderParam& param, const std::function& excb); +#ifndef UNIT_TEST protected: +#endif static RSDecoderConstParam getConstParam(); - RSEchoMode getEchoMode(uint8_t mode); + static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); @@ -146,7 +146,7 @@ RSDecoderConstParam DecoderRS32::getConstParam() } template -inline RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) +RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) { switch (mode) { diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index b9af456d..567d7604 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -16,8 +16,8 @@ add_executable(rs_driver_test single_return_block_diff_test.cpp dual_return_block_diff_test.cpp decoder_opt_test.cpp - decoder_test.cpp) - #decoder_rs32_test.cpp) + decoder_test.cpp + decoder_rs32_test.cpp) target_link_libraries(rs_driver_test diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index cc857354..d6dcf942 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -1,24 +1,41 @@ #include +#include "rs_driver/msg/point_cloud_msg.h" #include using namespace robosense::lidar; -typedef PointCloudT PointCloud; +typedef PointXYZIRT PointT; +typedef PointCloudT PointCloud; -ErrCode errCode = ERRCODE_SUCCESS; - -void errCallback(const Error& err) +static ErrCode errCode = ERRCODE_SUCCESS; +static void errCallback(const Error& err) { errCode = err.error_code; } +TEST(TestDecoderRS32, getEchoMode) +{ + RSDecoderParam param; + DecoderRS32 decoder(param, errCallback); + + ASSERT_TRUE(decoder.getEchoMode(0) == RSEchoMode::ECHO_DUAL); + ASSERT_TRUE(decoder.getEchoMode(1) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(decoder.getEchoMode(2) == RSEchoMode::ECHO_SINGLE); +} + TEST(TestDecoderRS32, decodeDifopPkt) { RSDecoderParam param; DecoderRS32 decoder(param, errCallback); RS32DifopPkt pkt; + + pkt.rpm = htons(1200); + pkt.return_mode = 0; + decoder.decodeDifopPkt((uint8_t*)&pkt, sizeof(pkt)); + ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_DUAL); + ASSERT_EQ(decoder.rps_, 20); } diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index c9e5b186..b81a001e 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -49,9 +49,9 @@ class MyDecoder : public Decoder }; -ErrCode errCode = ERRCODE_SUCCESS; +static ErrCode errCode = ERRCODE_SUCCESS; -void errCallback(const Error& err) +static void errCallback(const Error& err) { errCode = err.error_code; } From d254d911821bc1ca5f31122bdc3649c63dd0aa91 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 15 Dec 2021 11:05:04 +0800 Subject: [PATCH 069/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 5 ++-- src/rs_driver/driver/decoder/decoder_RS32.hpp | 29 ++++++++++--------- test/decoder_rs32_test.cpp | 19 ++++++++++++ test/dual_return_block_diff_test.cpp | 1 + test/single_return_block_diff_test.cpp | 1 + 5 files changed, 40 insertions(+), 15 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 89dde3ff..c2b9d257 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -50,7 +50,8 @@ typedef struct //uint16_t LASER_NUM; // diff from CHANNELS_PER_BLOCK ? // distance resolution - float DIS_RESOLUTION; + float DISTANCE_RES; + float TEMPERATURE_RES; // lens center float RX; @@ -136,7 +137,7 @@ class Decoder explicit Decoder(const RSDecoderParam& param, const std::function& excb, - const RSDecoderConstParam& lidar_const_param); + const RSDecoderConstParam& const_param); #ifndef UNIT_TEST protected: diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 1e60d75f..7b73de56 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -118,28 +118,29 @@ RSDecoderConstParam DecoderRS32::getConstParam() , {0xFF, 0xEE} // block id , 12 // blocks per packet , 32 // channels per block - , 0.005 // distance resolution + , 0.005f // distance resolution + , 0.0625f // temperature resolution // lens center - , 0.03997 // RX - , -0.01087 // RY - , 0 // RZ + , 0.03997f // RX + , -0.01087f // RY + , 0.0f // RZ }; - float blk_ts = 55.52; + float blk_ts = 55.52f; float firing_tss[] = { - 0.00, 2.88, 5.76, 8.64, 11.52, 14.40, 17.28, 20.16, - 23.04, 25.92, 28.80, 31.68, 34.56, 37.44, 40.32, 44.64, - 1.44, 4.32, 7.20, 10.08, 12.96, 15.84, 18.72, 21.60, - 24.48, 27.36, 30.24, 33.12, 36.00, 38.88, 41.76, 46.08 + 0.00f, 2.88f, 5.76f, 8.64f, 11.52f, 14.40f, 17.28f, 20.16f, + 23.04f, 25.92f, 28.80f, 31.68f, 34.56f, 37.44f, 40.32f, 44.64f, + 1.44f, 4.32f, 7.20f, 10.08f, 12.96f, 15.84f, 18.72f, 21.60f, + 24.48f, 27.36f, 30.24f, 33.12f, 36.00f, 38.88f, 41.76f, 46.08f }; param.BLOCK_DURATION = blk_ts / 1000000; for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) { - param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; + param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; } return param; @@ -235,13 +236,15 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet int16_t angle_vert = this->chan_angles_.vertAdjust(chan); int16_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); - float distance = ntohs(channel.distance) * this->const_param_.DIS_RESOLUTION; + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; uint8_t intensity = channel.intensity; if (this->distance_block_.in(distance) && this->scan_block_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + + this->const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - + this->const_param_.RX * SIN(angle_horiz); float z = distance * SIN(angle_vert) + this->const_param_.RZ; typename T_PointCloud::PointT point; diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index d6dcf942..8238c966 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -39,3 +39,22 @@ TEST(TestDecoderRS32, decodeDifopPkt) ASSERT_EQ(decoder.rps_, 20); } +TEST(TestDecoderRS32, decodeMsopPkt) +{ + RSDecoderParam param; + DecoderRS32 decoder(param, errCallback); + + RS32MsopPkt pkt = + { + 0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0, // msop id + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // reserved_1 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // ts_YMD + 0x00, // lidar type + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // reserved_2 + 0x00, 0x00, // temprature + 0x00, 0x00 // reserved_3 + }; + + decoder.decodeMsopPkt((uint8_t*)&pkt, sizeof(pkt)); + ASSERT_EQ(decoder.getTemperature(), 0); +} diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_diff_test.cpp index 35870077..2d755bab 100644 --- a/test/dual_return_block_diff_test.cpp +++ b/test/dual_return_block_diff_test.cpp @@ -37,6 +37,7 @@ TEST(TestDualPacketTraverser, toNext) , 6 // blocks per packet , 2 // channels per block , 0.25 // distance resolution + , 0.0 // temperature resolution // lens center , 0 // RX diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_diff_test.cpp index 9b92350a..b3a17063 100644 --- a/test/single_return_block_diff_test.cpp +++ b/test/single_return_block_diff_test.cpp @@ -37,6 +37,7 @@ TEST(TestSingleReturnBlockDiff, ctor) , 3 // blocks per packet , 2 // channels per block , 0.25 // distance resolution + , 0.0 // temperature resolution // lens center , 0 // RX From 7e9f954c8d53ec8670cf4b15f53e141c59cd8be9 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 15 Dec 2021 12:21:58 +0800 Subject: [PATCH 070/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 2 - src/rs_driver/driver/decoder/decoder_RS32.hpp | 14 ++- .../driver/decoder/decoder_base_opt.hpp | 38 +------- test/decoder_opt_test.cpp | 46 ++++++--- test/decoder_rs32_test.cpp | 94 +++++++++++++++++-- 5 files changed, 140 insertions(+), 54 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index c2b9d257..ae4f30a7 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -130,8 +130,6 @@ class Decoder double getPacketDiff() { - // Assume echo_mode is ECHO_SINGLE. - // If it is ECHO_DUAL, use RSInputParam.pcap_rate = 2 to change the playback speed. return this->const_param_.BLOCK_DURATION * const_param_.BLOCKS_PER_PKT; } diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 7b73de56..59b2d524 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -32,6 +32,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include +#include namespace robosense { @@ -195,11 +196,12 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet { const RS32MsopPkt& pkt = *(const RS32MsopPkt*)(packet); - this->temperature_ = calcTemp(&(pkt.header.temp)); + this->temperature_ = calcTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; double pkt_ts = 0; if (this->param_.use_lidar_clock) { + std::cout << "cal ymd" << std::endl; pkt_ts = calcTimeYMD(&pkt.header.timestamp); } else @@ -212,6 +214,8 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { + std::cout << "blk:" << blk << std::endl; + const RS32MsopBlock& block = pkt.blocks[blk]; if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) @@ -220,25 +224,33 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet break; } + std::cout << "+ blk:" << blk << std::endl; + block_ts += diff.ts(blk); int block_az = ntohs(block.azimuth); int16_t block_azi_diff = diff.azimuth(blk); + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; + std::cout << "chan:" << chan << std::endl; + float chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; int16_t angle_horiz = block_az + block_azi_diff * this->const_param_.CHAN_TSS[chan] / this->const_param_.BLOCK_DURATION; + std::cout << "+ chan:" << chan << std::endl; + int16_t angle_vert = this->chan_angles_.vertAdjust(chan); int16_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; uint8_t intensity = channel.intensity; + if (this->distance_block_.in(distance) && this->scan_block_.in(angle_horiz_final)) { float x = distance * COS(angle_vert) * COS(angle_horiz_final) + diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 5a84281c..1cc50105 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -338,8 +338,6 @@ inline uint64_t calcTimeHost(void) return t_us.count(); } -#define RS_TEMP_RESOLUTION 0.0625f - inline int16_t calcTemp(const RsTemprature* tmp) { // | lsb | padding | neg | msb | @@ -372,17 +370,9 @@ class ScanBlock return (angle >= start_) && (angle < end_); } - uint16_t start() - { - return start_; - } - - uint16_t end() - { - return end_; - } - +#ifndef UNIT_TEST private: +#endif uint16_t start_; uint16_t end_; bool cross_zero_; @@ -401,17 +391,9 @@ class DistanceBlock return ((min_ <= distance) && (distance <= max_)); } - float min() - { - return min_; - } - - float max() - { - return max_; - } - +#ifndef UNIT_TEST private: +#endif float min_; float max_; @@ -445,11 +427,6 @@ class ChanAngles return 0; } - size_t chanSize() - { - return vert_angles_.size(); - } - uint16_t toUserChan(uint16_t chan) { return user_chans_[chan]; @@ -563,8 +540,6 @@ class ChanAngles std::vector user_chans_; }; -//#define RS_TO_RADS(x) ((x) * (M_PI) / 180) - class Trigon { public: @@ -634,11 +609,6 @@ class SplitAngle return v; } - uint16_t value() - { - return split_angle_; - } - #ifndef UNIT_TEST private: #endif diff --git a/test/decoder_opt_test.cpp b/test/decoder_opt_test.cpp index 33910539..4e8646c0 100644 --- a/test/decoder_opt_test.cpp +++ b/test/decoder_opt_test.cpp @@ -43,8 +43,8 @@ TEST(TestParseTemp, calcTemp) TEST(TestScanBlock, ctor) { ScanBlock blk(10, 20); - ASSERT_EQ(blk.start(), 10); - ASSERT_EQ(blk.end(), 20); + ASSERT_EQ(blk.start_, 10); + ASSERT_EQ(blk.end_, 20); ASSERT_FALSE(blk.in(5)); ASSERT_TRUE(blk.in(10)); @@ -56,8 +56,8 @@ TEST(TestScanBlock, ctor) TEST(TestScanBlock, ctorCrossZero) { ScanBlock blk(35000, 10); - ASSERT_EQ(blk.start(), 35000); - ASSERT_EQ(blk.end(), 10); + ASSERT_EQ(blk.start_, 35000); + ASSERT_EQ(blk.end_, 10); ASSERT_FALSE(blk.in(34999)); ASSERT_TRUE(blk.in(35000)); @@ -69,15 +69,15 @@ TEST(TestScanBlock, ctorCrossZero) TEST(TestScanBlock, ctorBeyondRound) { ScanBlock blk(36100, 36200); - ASSERT_EQ(blk.start(), 100); - ASSERT_EQ(blk.end(), 200); + ASSERT_EQ(blk.start_, 100); + ASSERT_EQ(blk.end_, 200); } TEST(TestDistanceBlock, ctor) { DistanceBlock blk(0.5, 200, 0.75, 150); - ASSERT_EQ(blk.min(), 0.75); - ASSERT_EQ(blk.max(), 150); + ASSERT_EQ(blk.min_, 0.75); + ASSERT_EQ(blk.max_, 150); ASSERT_FALSE(blk.in(0.45)); ASSERT_TRUE(blk.in(0.75)); @@ -89,8 +89,8 @@ TEST(TestDistanceBlock, ctor) TEST(TestDistanceBlock, ctorNoUseBlock) { DistanceBlock blk(0.5, 200, 0.0, 200.5); - ASSERT_EQ(blk.min(), 0.5); - ASSERT_EQ(blk.max(), 200); + ASSERT_EQ(blk.min_, 0.5); + ASSERT_EQ(blk.max_, 200); } TEST(TestChanAngles, genUserChan) @@ -138,7 +138,7 @@ TEST(TestChanAngles, memberLoadFromFile) ChanAngles angles; ASSERT_EQ(angles.loadFromFile ("../rs_driver/test/res/angle.csv"), 0); - ASSERT_EQ(angles.chanSize(), 4); + ASSERT_EQ(angles.user_chans_.size(), 4); ASSERT_EQ(angles.toUserChan(0), 3); ASSERT_EQ(angles.toUserChan(1), 2); ASSERT_EQ(angles.toUserChan(2), 1); @@ -187,6 +187,30 @@ TEST(TestChanAngles, loadFromDifop) ASSERT_EQ(horiz_angles.size(), 4); } +TEST(TestChanAngles, memberLoadFromDifop) +{ + uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, + 0x01, 0x03, 0x04, + 0x01, 0x05, 0x06, + 0x00, 0x07, 0x08}; + uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, + 0x01, 0x33, 0x44, + 0x00, 0x55, 0x66, + 0x01, 0x77, 0x88}; + + ChanAngles angles; + ASSERT_EQ(angles.loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4), 0); + + ASSERT_EQ(angles.user_chans_.size(), 4); + ASSERT_EQ(angles.toUserChan(0), 2); + ASSERT_EQ(angles.toUserChan(1), 1); + ASSERT_EQ(angles.toUserChan(2), 0); + ASSERT_EQ(angles.toUserChan(3), 3); +} + TEST(TestTrigon, ctor) { Trigon trigon; diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index 8238c966..052546ec 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -44,17 +44,99 @@ TEST(TestDecoderRS32, decodeMsopPkt) RSDecoderParam param; DecoderRS32 decoder(param, errCallback); - RS32MsopPkt pkt = + uint8_t pkt[] = { + // + // header + // 0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0, // msop id 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // reserved_1 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // ts_YMD + 0x15, 0x0a, 0x01, 0x01, 0x02, 0x03, 0x11, 0x22, 0x33, 0x44, // ts_YMD 0x00, // lidar type 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // reserved_2 - 0x00, 0x00, // temprature - 0x00, 0x00 // reserved_3 + 0x18, 0x01, // temprature + 0x00, 0x00, // reserved_3 + + // + // block_01 + // + 0xFF, 0xEE, // block id + 0x00, 0x00, // azimuth + 0x00, 0x00, // chan_00, distance + 0x00, // chan_00, intensity + 0x00, 0x00, // chan_01, distance + 0x00, // chan_01, intensity + 0x00, 0x00, // chan_02, distance + 0x00, // chan_02, intensity + 0x00, 0x00, // chan_03, distance + 0x00, // chan_03, intensity + 0x00, 0x00, // chan_04, distance + 0x00, // chan_04, intensity + 0x00, 0x00, // chan_05, distance + 0x00, // chan_05, intensity + 0x00, 0x00, // chan_06, distance + 0x00, // chan_06, intensity + 0x00, 0x00, // chan_07, distance + 0x00, // chan_07, intensity + 0x00, 0x00, // chan_08, distance + 0x00, // chan_08, intensity + 0x00, 0x00, // chan_09, distance + 0x00, // chan_09, intensity + 0x00, 0x00, // chan_10, distance + 0x00, // chan_10, intensity + 0x00, 0x00, // chan_11, distance + 0x00, // chan_11, intensity + 0x00, 0x00, // chan_12, distance + 0x00, // chan_12, intensity + 0x00, 0x00, // chan_13, distance + 0x00, // chan_13, intensity + 0x00, 0x00, // chan_14, distance + 0x00, // chan_14, intensity + 0x00, 0x00, // chan_15, distance + 0x00, // chan_15, intensity + 0x00, 0x00, // chan_16, distance + 0x00, // chan_16, intensity + 0x00, 0x00, // chan_17, distance + 0x00, // chan_17, intensity + 0x00, 0x00, // chan_18, distance + 0x00, // chan_18, intensity + 0x00, 0x00, // chan_19, distance + 0x00, // chan_19, intensity + 0x00, 0x00, // chan_20, distance + 0x00, // chan_20, intensity + 0x00, 0x00, // chan_21, distance + 0x00, // chan_21, intensity + 0x00, 0x00, // chan_22, distance + 0x00, // chan_22, intensity + 0x00, 0x00, // chan_23, distance + 0x00, // chan_23, intensity + 0x00, 0x00, // chan_24, distance + 0x00, // chan_24, intensity + 0x00, 0x00, // chan_25, distance + 0x00, // chan_25, intensity + 0x00, 0x00, // chan_26, distance + 0x00, // chan_26, intensity + 0x00, 0x00, // chan_27, distance + 0x00, // chan_27, intensity + 0x00, 0x00, // chan_28, distance + 0x00, // chan_28, intensity + 0x00, 0x00, // chan_29, distance + 0x00, // chan_29, intensity + 0x00, 0x00, // chan_30, distance + 0x00, // chan_30, intensity + 0x00, 0x00, // chan_31, distance + 0x00, // chan_31, intensity + + // + // block_02 + // + 0x00, 0x00, // block id }; - decoder.decodeMsopPkt((uint8_t*)&pkt, sizeof(pkt)); - ASSERT_EQ(decoder.getTemperature(), 0); +#if 0 + decoder.param_.use_lidar_clock = true; + decoder.decodeMsopPkt(pkt, sizeof(pkt)); + ASSERT_EQ(decoder.getTemperature(), 2.1875); + //ASSERT_EQ(decoder.getTemperature(), 2.1875); +#endif } From 05cdc1364659fcd5ed2c68615811c11bec1c2183 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 15 Dec 2021 14:15:47 +0800 Subject: [PATCH 071/379] feat: increase delay time of error NODIFOPRECV --- src/rs_driver/driver/lidar_driver_impl.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 0dc09473..a79a1733 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -437,7 +437,7 @@ inline void LidarDriverImpl::processMsop() if (!difop_flag_ && driver_param_.wait_for_difop) { ndifop_count_++; - if (ndifop_count_ > 240) + if (ndifop_count_ > 1500) { reportError(Error(ERRCODE_NODIFOPRECV)); ndifop_count_ = 0; From cc506c00717297735b636e7b16f48b41bc9c92df Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 15 Dec 2021 15:10:55 +0800 Subject: [PATCH 072/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 1 + .../driver/decoder/decoder_base_opt.hpp | 39 ++++++++++-- test/decoder_opt_test.cpp | 62 +++++++++++++++---- test/decoder_test.cpp | 13 ++-- 4 files changed, 94 insertions(+), 21 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index ae4f30a7..f1aa1047 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -190,6 +190,7 @@ inline Decoder::Decoder(const RSDecoderParam& param, , param_(param) , excb_(excb) , height_(const_param.CHANNELS_PER_BLOCK) + , chan_angles_(const_param.CHANNELS_PER_BLOCK) , distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance) , scan_block_(param.start_angle * 100, param.end_angle * 100) , split_angle_(param.split_angle * 100) diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 1cc50105..86028e78 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -403,26 +403,51 @@ class DistanceBlock class ChanAngles { public: + + ChanAngles(uint16_t chan_num) + : chan_num_(chan_num) + { + vert_angles_.resize(chan_num_); + horiz_angles_.resize(chan_num_); + user_chans_.resize(chan_num_); + } int loadFromFile(const std::string& angle_path) { - int ret = loadFromFile (angle_path, vert_angles_, horiz_angles_); + std::vector vert_angles; + std::vector horiz_angles; + int ret = loadFromFile (angle_path, vert_angles, horiz_angles); if (ret < 0) return ret; - genUserChan(vert_angles_, user_chans_); + if (vert_angles.size() != chan_num_) + { + return -1; + } + vert_angles_.swap(vert_angles); + horiz_angles_.swap(horiz_angles); + genUserChan(vert_angles_, user_chans_); return 0; } int loadFromDifop(const RSCalibrationAngle vert_angle_arr[], const RSCalibrationAngle horiz_angle_arr[], size_t size) { + std::vector vert_angles; + std::vector horiz_angles; int ret = - loadFromDifop (vert_angle_arr, horiz_angle_arr, size, vert_angles_, horiz_angles_); + loadFromDifop (vert_angle_arr, horiz_angle_arr, size, vert_angles, horiz_angles); if (ret < 0) return ret; + if (vert_angles.size() != chan_num_) + { + return -1; + } + + vert_angles_.swap(vert_angles); + horiz_angles_.swap(horiz_angles); genUserChan(vert_angles_, user_chans_); return 0; } @@ -446,6 +471,10 @@ class ChanAngles { } +#ifndef UNIT_TEST +private: +#endif + static void genUserChan(const std::vector& vert_angles, std::vector& user_chans) { @@ -532,9 +561,7 @@ class ChanAngles return ((vert_angles.size() > 0) ? 0 : -1); } -#ifndef UNIT_TEST -private: -#endif + uint16_t chan_num_; std::vector vert_angles_; std::vector horiz_angles_; std::vector user_chans_; diff --git a/test/decoder_opt_test.cpp b/test/decoder_opt_test.cpp index 4e8646c0..87b1b342 100644 --- a/test/decoder_opt_test.cpp +++ b/test/decoder_opt_test.cpp @@ -131,18 +131,11 @@ TEST(TestChanAngles, loadFromFile) ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); ASSERT_EQ(vert_angles.size(), 4); ASSERT_EQ(horiz_angles.size(), 4); -} -TEST(TestChanAngles, memberLoadFromFile) -{ - ChanAngles angles; + ASSERT_LT(ChanAngles::loadFromFile ("../rs_driver/test/res/non_exist.csv", vert_angles, horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 0); + ASSERT_EQ(horiz_angles.size(), 0); - ASSERT_EQ(angles.loadFromFile ("../rs_driver/test/res/angle.csv"), 0); - ASSERT_EQ(angles.user_chans_.size(), 4); - ASSERT_EQ(angles.toUserChan(0), 3); - ASSERT_EQ(angles.toUserChan(1), 2); - ASSERT_EQ(angles.toUserChan(2), 1); - ASSERT_EQ(angles.toUserChan(3), 0); } TEST(TestChanAngles, loadFromDifop) @@ -187,6 +180,32 @@ TEST(TestChanAngles, loadFromDifop) ASSERT_EQ(horiz_angles.size(), 4); } +TEST(TestChanAngles, memberLoadFromFile) +{ + ChanAngles angles(4); + ASSERT_EQ(angles.chan_num_, 4); + ASSERT_EQ(angles.vert_angles_.size(), 4); + ASSERT_EQ(angles.horiz_angles_.size(), 4); + ASSERT_EQ(angles.user_chans_.size(), 4); + + ASSERT_EQ(angles.loadFromFile ("../rs_driver/test/res/angle.csv"), 0); + ASSERT_EQ(angles.user_chans_.size(), 4); + ASSERT_EQ(angles.toUserChan(0), 3); + ASSERT_EQ(angles.toUserChan(1), 2); + ASSERT_EQ(angles.toUserChan(2), 1); + ASSERT_EQ(angles.toUserChan(3), 0); +} + +TEST(TestChanAngles, memberLoadFromFile_fail) +{ + ChanAngles angles(4); + ASSERT_EQ(angles.chan_num_, 4); + + ASSERT_LT(angles.loadFromFile ("../rs_driver/test/res/non_exist.csv"), 0); + ASSERT_EQ(angles.vert_angles_.size(), 4); + ASSERT_EQ(angles.vert_angles_[0], 0); +} + TEST(TestChanAngles, memberLoadFromDifop) { uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, @@ -198,7 +217,8 @@ TEST(TestChanAngles, memberLoadFromDifop) 0x00, 0x55, 0x66, 0x01, 0x77, 0x88}; - ChanAngles angles; + ChanAngles angles(4); + ASSERT_EQ(angles.chan_num_, 4); ASSERT_EQ(angles.loadFromDifop( (const RSCalibrationAngle*)vert_angle_arr, (const RSCalibrationAngle*)horiz_angle_arr, @@ -211,6 +231,26 @@ TEST(TestChanAngles, memberLoadFromDifop) ASSERT_EQ(angles.toUserChan(3), 3); } +TEST(TestChanAngles, memberLoadFromDifop_fail) +{ + uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, + 0x01, 0x03, 0x04, + 0xFF, 0x05, 0x06, + 0xFF, 0x07, 0x08}; + uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, + 0x01, 0x33, 0x44, + 0xFF, 0x55, 0x66, + 0xFF, 0x77, 0x88}; + + ChanAngles angles(4); + ASSERT_EQ(angles.chan_num_, 4); + + ASSERT_LT(angles.loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4), 0); +} + TEST(TestTrigon, ctor) { Trigon trigon; diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index b81a001e..de748284 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -158,8 +158,10 @@ TEST(TestDecoder, processDifopPkt) ASSERT_EQ(decoder.rps_, 10); ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.fov_blind_ts_diff_, 0.075f); - ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 0); - ASSERT_EQ(decoder.chan_angles_.horiz_angles_.size(), 0); + ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); + ASSERT_EQ(decoder.chan_angles_.vert_angles_[0], 0); + ASSERT_EQ(decoder.chan_angles_.horiz_angles_.size(), 2); + ASSERT_EQ(decoder.chan_angles_.horiz_angles_[0], 0); // //angles from difop. no angles in difop @@ -182,8 +184,10 @@ TEST(TestDecoder, processDifopPkt) decoder.processDifopPkt(pkt_no_angles, sizeof(MyDifopPkt)); errCode = ERRCODE_SUCCESS; - ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 0); - ASSERT_EQ(decoder.chan_angles_.horiz_angles_.size(), 0); + ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); + ASSERT_EQ(decoder.chan_angles_.vert_angles_[0], 0); + ASSERT_EQ(decoder.chan_angles_.horiz_angles_.size(), 2); + ASSERT_EQ(decoder.chan_angles_.horiz_angles_[0], 0); // angles from difop. decoder.param_.config_from_file = false; @@ -247,6 +251,7 @@ TEST(TestDecoder, processMsopPkt) TEST(TestDecoder, angles_from_angle_file) { RSDecoderConstParam const_param; + const_param.CHANNELS_PER_BLOCK = 4; RSDecoderParam param; param.config_from_file = true; param.angle_path = "../rs_driver/test/res/angle.csv"; From 6e56ab65a208efce86f493232d0e745d6e009e45 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 15 Dec 2021 18:12:15 +0800 Subject: [PATCH 073/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 5 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 28 +++++-- .../driver/decoder/decoder_base_opt.hpp | 78 +++++++++++++------ test/decoder_opt_test.cpp | 17 +++- test/decoder_rs32_test.cpp | 19 +++-- test/dual_return_block_diff_test.cpp | 2 + test/single_return_block_diff_test.cpp | 2 + 7 files changed, 107 insertions(+), 44 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index f1aa1047..c3eb02ea 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -50,6 +50,8 @@ typedef struct //uint16_t LASER_NUM; // diff from CHANNELS_PER_BLOCK ? // distance resolution + float DISTANCE_MIN; + float DISTANCE_MAX; float DISTANCE_RES; float TEMPERATURE_RES; @@ -191,7 +193,8 @@ inline Decoder::Decoder(const RSDecoderParam& param, , excb_(excb) , height_(const_param.CHANNELS_PER_BLOCK) , chan_angles_(const_param.CHANNELS_PER_BLOCK) - , distance_block_(0.4f, 200.0f, param.min_distance, param.max_distance) + , distance_block_(const_param.DISTANCE_MIN, const_param.DISTANCE_MAX, + param.min_distance, param.max_distance) , scan_block_(param.start_angle * 100, param.end_angle * 100) , split_angle_(param.split_angle * 100) , blks_per_frame_(1/(10*const_param.BLOCK_DURATION)) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 59b2d524..cfb9d6b7 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -119,6 +119,8 @@ RSDecoderConstParam DecoderRS32::getConstParam() , {0xFF, 0xEE} // block id , 12 // blocks per packet , 32 // channels per block + , 0.4f // distance min + , 200.0f // distance max , 0.005f // distance resolution , 0.0625f // temperature resolution @@ -214,7 +216,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { - std::cout << "blk:" << blk << std::endl; + // std::cout << "blk:" << blk << std::endl; const RS32MsopBlock& block = pkt.blocks[blk]; @@ -224,25 +226,24 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet break; } - std::cout << "+ blk:" << blk << std::endl; + // std::cout << "+ blk:" << blk << std::endl; block_ts += diff.ts(blk); int block_az = ntohs(block.azimuth); int16_t block_azi_diff = diff.azimuth(blk); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; - std::cout << "chan:" << chan << std::endl; + // std::cout << "chan:" << chan << std::endl; float chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; int16_t angle_horiz = block_az + block_azi_diff * this->const_param_.CHAN_TSS[chan] / this->const_param_.BLOCK_DURATION; - std::cout << "+ chan:" << chan << std::endl; +// std::cout << "+ chan:" << chan << std::endl; int16_t angle_vert = this->chan_angles_.vertAdjust(chan); int16_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -250,23 +251,32 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; uint8_t intensity = channel.intensity; - if (this->distance_block_.in(distance) && this->scan_block_.in(angle_horiz_final)) { +#if 0 + std::cout << ")) chan:" << chan << std::endl; + std::cout << "vert:" << angle_vert + << "horiz_horiz:" << angle_horiz + << "horiz_final:" << angle_horiz_final << std::endl; +#endif + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); float z = distance * SIN(angle_vert) + this->const_param_.RZ; + // std::cout << ")) )) chan:" << chan << std::endl; + typename T_PointCloud::PointT point; setX(point, x); setY(point, y); setZ(point, z); setIntensity(point, intensity); - setRing(point, this->chan_angles_.toUserChan(chan)); setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + this->point_cloud_->points.emplace_back(point); } else if (!this->param_.dense_points) @@ -276,8 +286,10 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); - setRing(point, this->chan_angles_.toUserChan(chan)); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + this->point_cloud_->points.emplace_back(point); } } diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 86028e78..913c1825 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -42,6 +42,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include namespace robosense { @@ -567,54 +568,83 @@ class ChanAngles std::vector user_chans_; }; +#define DBG + class Trigon { public: + static const int32_t MIN = -9000; + static const int32_t MAX = 45000; + Trigon() { - static bool init_ = false; + int32_t range = MAX - MIN; +#ifdef DBG + o_angles_ = (int32_t*)malloc(range * sizeof(int32_t)); +#endif + o_sins_ = (float*)malloc(range * sizeof(float)); + o_coss_ = (float*)malloc(range * sizeof(float)); - if (!init_) + for (int32_t i = MIN, j = 0; i < MAX; i++, j++) { - init_ = true; + double rads = static_cast(i) * 0.01; + rads = rads * M_PI / 180; - uint16_t RS_ONE_ROUND = 36000; - float RS_ANGLE_RESOLUTION = 0.01; +#ifdef DBG + o_angles_[j] = i; +#endif + o_sins_[j] = (float)std::sin(rads); + o_coss_[j] = (float)std::cos(rads); + } - for (size_t i = 0; i < RS_ONE_ROUND; i++) - { - double rads = static_cast(i) * RS_ANGLE_RESOLUTION; - rads = rads * M_PI / 180; +#ifdef DBG + angles_ = o_angles_ - MIN; +#endif + sins_ = o_sins_ - MIN; + coss_ = o_coss_ - MIN; + } - sins_.emplace_back((float)std::sin(rads)); - coss_.emplace_back((float)std::cos(rads)); - } - } + ~Trigon() + { + free(o_coss_); + free(o_sins_); +#ifdef DBG + free(o_angles_); +#endif } - void print() + float sin(int32_t angle) { - uint16_t RS_ONE_ROUND = 36000; - for (size_t i = 0; i < RS_ONE_ROUND; i++) - { - std::cout << i << "\t" << sins_[i] << "\t" << coss_[i] << std::endl; - } + return sins_[angle]; } - float cos(uint16_t angle) + float cos(int32_t angle) { return coss_[angle]; } - float sin(uint16_t angle) + void print() { - return sins_[angle]; + for (int32_t i = -9000; i < -8900; i++) + { + std::cout << +#ifdef DBG + angles_[i] << "\t" << +#endif + sins_[i] << "\t" << coss_[i] << std::endl; + } } private: - std::vector sins_; - std::vector coss_; +#ifdef DBG + int32_t* o_angles_; + int32_t* angles_; +#endif + float* o_sins_; + float* o_coss_; + float* sins_; + float* coss_; }; class SplitAngle diff --git a/test/decoder_opt_test.cpp b/test/decoder_opt_test.cpp index 87b1b342..31ee235a 100644 --- a/test/decoder_opt_test.cpp +++ b/test/decoder_opt_test.cpp @@ -254,10 +254,21 @@ TEST(TestChanAngles, memberLoadFromDifop_fail) TEST(TestTrigon, ctor) { Trigon trigon; - ASSERT_EQ(trigon.cos(6000), 0.5); - ASSERT_EQ(trigon.sin(3000), 0.5); -#if 0 trigon.print(); + +#if 0 + ASSERT_LT(trigon.sin(-9000) + 1.0f, 0.00001f); + ASSERT_LT(trigon.cos(-9000), 0.00001f); + + std::cout << "+ ti" << std::endl; + ASSERT_EQ(trigon.sin(0), 0.0f); + ASSERT_EQ(trigon.cos(0), 1.0f); + + ASSERT_EQ(trigon.sin(3000), 0.5f); + ASSERT_EQ(trigon.cos(6000), 0.5f); + + ASSERT_LT(trigon.sin(44999) - 1.0f, 0.00001f); + ASSERT_LT(trigon.cos(44999), 0.00001f); #endif } diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index 052546ec..bc86259a 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -41,9 +41,6 @@ TEST(TestDecoderRS32, decodeDifopPkt) TEST(TestDecoderRS32, decodeMsopPkt) { - RSDecoderParam param; - DecoderRS32 decoder(param, errCallback); - uint8_t pkt[] = { // @@ -62,8 +59,8 @@ TEST(TestDecoderRS32, decodeMsopPkt) // 0xFF, 0xEE, // block id 0x00, 0x00, // azimuth - 0x00, 0x00, // chan_00, distance - 0x00, // chan_00, intensity + 0x03, 0xE8, // chan_00, distance + 0x01, // chan_00, intensity 0x00, 0x00, // chan_01, distance 0x00, // chan_01, intensity 0x00, 0x00, // chan_02, distance @@ -133,10 +130,16 @@ TEST(TestDecoderRS32, decodeMsopPkt) 0x00, 0x00, // block id }; -#if 0 + RSDecoderParam param; + param.dense_points = false; + DecoderRS32 decoder(param, errCallback); + decoder.point_cloud_ = std::make_shared(); + decoder.param_.use_lidar_clock = true; decoder.decodeMsopPkt(pkt, sizeof(pkt)); ASSERT_EQ(decoder.getTemperature(), 2.1875); - //ASSERT_EQ(decoder.getTemperature(), 2.1875); -#endif + ASSERT_EQ(decoder.point_cloud_->points.size(), 32); + + PointT& point = decoder.point_cloud_->points[0]; + ASSERT_EQ(point.intensity, 1); } diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_diff_test.cpp index 2d755bab..af16059b 100644 --- a/test/dual_return_block_diff_test.cpp +++ b/test/dual_return_block_diff_test.cpp @@ -36,6 +36,8 @@ TEST(TestDualPacketTraverser, toNext) , {0x00} // block id , 6 // blocks per packet , 2 // channels per block + , 0.0f // distance min + , 0.0f // distance max , 0.25 // distance resolution , 0.0 // temperature resolution diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_diff_test.cpp index b3a17063..8c4af05b 100644 --- a/test/single_return_block_diff_test.cpp +++ b/test/single_return_block_diff_test.cpp @@ -36,6 +36,8 @@ TEST(TestSingleReturnBlockDiff, ctor) , {0x00} // block id , 3 // blocks per packet , 2 // channels per block + , 0.0f // distance min + , 0.0f // distance max , 0.25 // distance resolution , 0.0 // temperature resolution From 4623c01e63910b35dbf9338e4fdc831f7dcd3971 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 15 Dec 2021 18:50:33 +0800 Subject: [PATCH 074/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder_base_opt.hpp | 4 ++-- test/decoder_opt_test.cpp | 15 +++++++++------ 2 files changed, 11 insertions(+), 8 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 913c1825..cffd901e 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -568,7 +568,7 @@ class ChanAngles std::vector user_chans_; }; -#define DBG +//#define DBG class Trigon { @@ -626,7 +626,7 @@ class Trigon void print() { - for (int32_t i = -9000; i < -8900; i++) + for (int32_t i = -10; i < 10; i++) { std::cout << #ifdef DBG diff --git a/test/decoder_opt_test.cpp b/test/decoder_opt_test.cpp index 31ee235a..24a5bfc7 100644 --- a/test/decoder_opt_test.cpp +++ b/test/decoder_opt_test.cpp @@ -256,19 +256,22 @@ TEST(TestTrigon, ctor) Trigon trigon; trigon.print(); -#if 0 - ASSERT_LT(trigon.sin(-9000) + 1.0f, 0.00001f); - ASSERT_LT(trigon.cos(-9000), 0.00001f); - std::cout << "+ ti" << std::endl; + ASSERT_EQ(trigon.sin(-9000), -1.0f); + ASSERT_LT(trigon.cos(-9000), 0.0001f); + ASSERT_EQ(trigon.sin(0), 0.0f); ASSERT_EQ(trigon.cos(0), 1.0f); ASSERT_EQ(trigon.sin(3000), 0.5f); ASSERT_EQ(trigon.cos(6000), 0.5f); - ASSERT_LT(trigon.sin(44999) - 1.0f, 0.00001f); - ASSERT_LT(trigon.cos(44999), 0.00001f); + trigon.sin(44999); + trigon.cos(44999); + +#if 0 + trigon.sin(45000); + trigon.cos(45000); #endif } From 154885dec1f5f5e3a9e0201ee64af262ed81cd64 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 09:48:54 +0800 Subject: [PATCH 075/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder_RS32.hpp | 28 ++----------------- test/decoder_opt_test.cpp | 3 +- test/decoder_rs32_test.cpp | 10 +++++-- 3 files changed, 12 insertions(+), 29 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index cfb9d6b7..7f1634eb 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -203,7 +203,6 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet double pkt_ts = 0; if (this->param_.use_lidar_clock) { - std::cout << "cal ymd" << std::endl; pkt_ts = calcTimeYMD(&pkt.header.timestamp); } else @@ -216,8 +215,6 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { - // std::cout << "blk:" << blk << std::endl; - const RS32MsopBlock& block = pkt.blocks[blk]; if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) @@ -226,10 +223,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet break; } - // std::cout << "+ blk:" << blk << std::endl; - block_ts += diff.ts(blk); - int block_az = ntohs(block.azimuth); int16_t block_azi_diff = diff.azimuth(blk); @@ -237,13 +231,8 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet { const RSChannel& channel = block.channels[chan]; - // std::cout << "chan:" << chan << std::endl; - float chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; - int16_t angle_horiz = block_az + - block_azi_diff * this->const_param_.CHAN_TSS[chan] / this->const_param_.BLOCK_DURATION; - -// std::cout << "+ chan:" << chan << std::endl; + int16_t angle_horiz = block_az + block_azi_diff * this->const_param_.CHAN_AZIS[chan]; int16_t angle_vert = this->chan_angles_.vertAdjust(chan); int16_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -253,21 +242,10 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet if (this->distance_block_.in(distance) && this->scan_block_.in(angle_horiz_final)) { -#if 0 - std::cout << ")) chan:" << chan << std::endl; - std::cout << "vert:" << angle_vert - << "horiz_horiz:" << angle_horiz - << "horiz_final:" << angle_horiz_final << std::endl; -#endif - - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + - this->const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - - this->const_param_.RX * SIN(angle_horiz); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); float z = distance * SIN(angle_vert) + this->const_param_.RZ; - // std::cout << ")) )) chan:" << chan << std::endl; - typename T_PointCloud::PointT point; setX(point, x); setY(point, y); diff --git a/test/decoder_opt_test.cpp b/test/decoder_opt_test.cpp index 24a5bfc7..bfc87201 100644 --- a/test/decoder_opt_test.cpp +++ b/test/decoder_opt_test.cpp @@ -254,9 +254,8 @@ TEST(TestChanAngles, memberLoadFromDifop_fail) TEST(TestTrigon, ctor) { Trigon trigon; - trigon.print(); + //trigon.print(); - std::cout << "+ ti" << std::endl; ASSERT_EQ(trigon.sin(-9000), -1.0f); ASSERT_LT(trigon.cos(-9000), 0.0001f); diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index bc86259a..6526d4bb 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -131,15 +131,21 @@ TEST(TestDecoderRS32, decodeMsopPkt) }; RSDecoderParam param; - param.dense_points = false; DecoderRS32 decoder(param, errCallback); + ASSERT_EQ(decoder.chan_angles_.user_chans_.size(), 32); + decoder.chan_angles_.user_chans_[0] = 2; + decoder.chan_angles_.user_chans_[1] = 1; + decoder.param_.dense_points = false; + decoder.param_.use_lidar_clock = true; + decoder.point_cloud_ = std::make_shared(); - decoder.param_.use_lidar_clock = true; decoder.decodeMsopPkt(pkt, sizeof(pkt)); ASSERT_EQ(decoder.getTemperature(), 2.1875); ASSERT_EQ(decoder.point_cloud_->points.size(), 32); PointT& point = decoder.point_cloud_->points[0]; ASSERT_EQ(point.intensity, 1); + ASSERT_EQ(point.ring, 2); + ASSERT_NE(point.timestamp, 0); } From 8797b945815452d5ed3299804b08757931798a89 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 11:27:22 +0800 Subject: [PATCH 076/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 34 ++++++++++---- src/rs_driver/driver/decoder/decoder_RS32.hpp | 18 ++++++-- src/rs_driver/utility/dbg.h | 3 +- test/decoder_rs32_test.cpp | 2 +- test/decoder_test.cpp | 46 ++++++++++--------- 5 files changed, 66 insertions(+), 37 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index c3eb02ea..da32e19a 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -105,7 +105,7 @@ constexpr uint16_t PROTOCOL_VER_0 = 0x00; /* Echo mode definition */ enum RSEchoMode { - ECHO_SINGLE, + ECHO_SINGLE = 0, ECHO_DUAL }; @@ -135,6 +135,17 @@ class Decoder return this->const_param_.BLOCK_DURATION * const_param_.BLOCKS_PER_PKT; } + void print () + { + std::cout << "blks_per_frame:\t" << this->blks_per_frame_ << std::endl + << "block_azi_diff:\t" << this->block_azi_diff_ << std::endl + << "fov_blind_ts_diff:\t" << this->fov_blind_ts_diff_ << std::endl + << "rps:\t" << this->rps_ << std::endl + << "echo_mode:\t" << this->echo_mode_ << std::endl + << "angle_from_file:\t" << this->param_.config_from_file << std::endl + << "angles_ready:\t" << this->angles_ready_ << std::endl; + } + explicit Decoder(const RSDecoderParam& param, const std::function& excb, const RSDecoderConstParam& const_param); @@ -143,7 +154,7 @@ class Decoder protected: #endif - void toSplit(uint16_t azimuth, double chan_ts); + void toSplit(uint16_t azimuth); void setPointCloudHeader(std::shared_ptr msg, double chan_ts); template @@ -172,7 +183,8 @@ class Decoder RSEchoMode echo_mode_; float temperature_; - bool difop_ready_; + bool angles_ready_; + double prev_chan_ts_; uint16_t num_blks_; int lidar_alph0_; // atan2(Ry, Rx) * 180 / M_PI * 100 @@ -204,7 +216,8 @@ inline Decoder::Decoder(const RSDecoderParam& param, , rps_(10) , echo_mode_(ECHO_SINGLE) , temperature_(0.0) - , difop_ready_(false) + , angles_ready_(false) + , prev_chan_ts_(0.0) , num_blks_(0) , point_cloud_seq_(0) { @@ -215,7 +228,7 @@ inline Decoder::Decoder(const RSDecoderParam& param, if (param.config_from_file) { int ret = chan_angles_.loadFromFile(param.angle_path); - this->difop_ready_ = (ret == 0); + this->angles_ready_ = (ret == 0); } } @@ -231,7 +244,7 @@ void Decoder::regRecvCallback( } template -inline void Decoder::toSplit(uint16_t azimuth, double chan_ts) +inline void Decoder::toSplit(uint16_t azimuth) { bool split = false; @@ -269,7 +282,7 @@ inline void Decoder::toSplit(uint16_t azimuth, double chan_ts) { if (point_cloud_->points.size() > 0) { - setPointCloudHeader(point_cloud_, chan_ts); + setPointCloudHeader(point_cloud_, prev_chan_ts_); point_cloud_cb_put_(point_cloud_); point_cloud_ = point_cloud_cb_get_(); } @@ -301,7 +314,7 @@ void Decoder::setPointCloudHeader(std::shared_ptr ms template void Decoder::processMsopPkt(const uint8_t* pkt, size_t size) { - if (param_.wait_for_difop && !difop_ready_) + if (param_.wait_for_difop && !angles_ready_) { excb_(Error(ERRCODE_NODIFOPRECV)); return; @@ -370,10 +383,11 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) this->fov_blind_ts_diff_ = (float)fov_blind_range / ((float)RS_ONE_ROUND * (float)this->rps_); - if (!this->param_.config_from_file && !this->difop_ready_) + if (!this->param_.config_from_file && !this->angles_ready_) { - this->chan_angles_.loadFromDifop(pkt.ver_angle_cali, pkt.hori_angle_cali, + int ret = this->chan_angles_.loadFromDifop(pkt.ver_angle_cali, pkt.hori_angle_cali, this->const_param_.CHANNELS_PER_BLOCK); + this->angles_ready_ = (ret == 0); } } diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 7f1634eb..0e306adc 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -154,10 +154,10 @@ RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) { switch (mode) { - case 0x00: + case 0x00: // dual return return RSEchoMode::ECHO_DUAL; - case 0x01: - case 0x02: + case 0x01: // strongest return + case 0x02: // last return default: return RSEchoMode::ECHO_SINGLE; } @@ -173,10 +173,18 @@ inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, template inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, size_t size) { +// hexdump (packet, size, "difop"); + const RS32DifopPkt& pkt = *(const RS32DifopPkt*)(packet); this->template decodeDifopCommon(pkt); this->echo_mode_ = getEchoMode (pkt.return_mode); + + this->print(); + std::cout << "echo_mode:" << this->echo_mode_ + << "," << offsetof(RS32DifopPkt, return_mode) << std::endl; + + exit(-1); } template @@ -231,7 +239,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet { const RSChannel& channel = block.channels[chan]; - float chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; int16_t angle_horiz = block_az + block_azi_diff * this->const_param_.CHAN_AZIS[chan]; int16_t angle_vert = this->chan_angles_.vertAdjust(chan); @@ -270,6 +278,8 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet this->point_cloud_->points.emplace_back(point); } + + this->prev_chan_ts_ = chan_ts; } } } diff --git a/src/rs_driver/utility/dbg.h b/src/rs_driver/utility/dbg.h index b480f530..24f26ad7 100644 --- a/src/rs_driver/utility/dbg.h +++ b/src/rs_driver/utility/dbg.h @@ -37,9 +37,10 @@ namespace robosense { namespace lidar { + inline void hexdump(const unsigned char* data, size_t size, const char* desc = NULL) { - printf("\n---------------%s------------------", (desc ? desc : "")); + printf("\n---------------%s(size:%d)------------------", (desc ? desc : ""), (int)size); for (size_t i = 0; i < size; i++) { diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index 6526d4bb..2599d49b 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -33,7 +33,7 @@ TEST(TestDecoderRS32, decodeDifopPkt) RS32DifopPkt pkt; pkt.rpm = htons(1200); - pkt.return_mode = 0; + pkt.return_mode = 0; // dual return decoder.decodeDifopPkt((uint8_t*)&pkt, sizeof(pkt)); ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_DUAL); ASSERT_EQ(decoder.rps_, 20); diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index de748284..20bad7e7 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -56,6 +56,17 @@ static void errCallback(const Error& err) errCode = err.error_code; } +TEST(TestDecoder, angles_from_angle_file) +{ + RSDecoderConstParam const_param; + const_param.CHANNELS_PER_BLOCK = 4; + RSDecoderParam param; + param.config_from_file = true; + param.angle_path = "../rs_driver/test/res/angle.csv"; + MyDecoder decoder(param, errCallback, const_param); + ASSERT_TRUE(decoder.angles_ready_); +} + TEST(TestDecoder, processDifopPkt_fail) { RSDecoderConstParam const_param = @@ -131,6 +142,7 @@ TEST(TestDecoder, processDifopPkt) RSDecoderParam param; MyDecoder decoder(param, errCallback, const_param); + ASSERT_FALSE(decoder.angles_ready_); uint8_t pkt[] = { @@ -151,6 +163,7 @@ TEST(TestDecoder, processDifopPkt) // decoder.param_.config_from_file = true; + decoder.param_.angle_path = "non_exist.csv"; errCode = ERRCODE_SUCCESS; decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); ASSERT_EQ(errCode, ERRCODE_SUCCESS); @@ -158,6 +171,7 @@ TEST(TestDecoder, processDifopPkt) ASSERT_EQ(decoder.rps_, 10); ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.fov_blind_ts_diff_, 0.075f); + ASSERT_FALSE(decoder.angles_ready_); ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); ASSERT_EQ(decoder.chan_angles_.vert_angles_[0], 0); ASSERT_EQ(decoder.chan_angles_.horiz_angles_.size(), 2); @@ -184,6 +198,7 @@ TEST(TestDecoder, processDifopPkt) decoder.processDifopPkt(pkt_no_angles, sizeof(MyDifopPkt)); errCode = ERRCODE_SUCCESS; + ASSERT_FALSE(decoder.angles_ready_); ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); ASSERT_EQ(decoder.chan_angles_.vert_angles_[0], 0); ASSERT_EQ(decoder.chan_angles_.horiz_angles_.size(), 2); @@ -195,6 +210,7 @@ TEST(TestDecoder, processDifopPkt) decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); errCode = ERRCODE_SUCCESS; + ASSERT_TRUE(decoder.angles_ready_); ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); ASSERT_EQ(decoder.chan_angles_.vert_angles_[0], 16); ASSERT_EQ(decoder.chan_angles_.horiz_angles_.size(), 2); @@ -220,13 +236,13 @@ TEST(TestDecoder, processMsopPkt) // wrong msop len decoder.param_.wait_for_difop = true; - decoder.difop_ready_ = false; + decoder.angles_ready_ = false; errCode = ERRCODE_SUCCESS; decoder.processMsopPkt((const uint8_t*)&pkt, 2); ASSERT_EQ(errCode, ERRCODE_NODIFOPRECV); decoder.param_.wait_for_difop = true; - decoder.difop_ready_ = true; + decoder.angles_ready_ = true; // wrong msop len errCode = ERRCODE_SUCCESS; @@ -248,17 +264,6 @@ TEST(TestDecoder, processMsopPkt) ASSERT_EQ(errCode, ERRCODE_SUCCESS); } -TEST(TestDecoder, angles_from_angle_file) -{ - RSDecoderConstParam const_param; - const_param.CHANNELS_PER_BLOCK = 4; - RSDecoderParam param; - param.config_from_file = true; - param.angle_path = "../rs_driver/test/res/angle.csv"; - MyDecoder decoder(param, errCallback, const_param); - ASSERT_TRUE(decoder.difop_ready_); -} - TEST(TestDecoder, setPointCloudHeader) { RSDecoderConstParam const_param = {}; @@ -325,12 +330,12 @@ TEST(TestDecoder, split_by_angle) { errCode = ERRCODE_SUCCESS; flag_point_cloud = false; - decoder.toSplit (35999, 0); + decoder.toSplit (35999); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_FALSE(flag_point_cloud); errCode = ERRCODE_SUCCESS; - decoder.toSplit (2, 0); + decoder.toSplit (2); ASSERT_EQ(errCode, ERRCODE_ZEROPOINTS); } @@ -341,7 +346,7 @@ TEST(TestDecoder, split_by_angle) errCode = ERRCODE_SUCCESS; flag_point_cloud = false; - decoder.toSplit (1, 0); + decoder.toSplit (1); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_TRUE(flag_point_cloud); ASSERT_TRUE(point_cloud_to_put.get() != NULL); @@ -356,7 +361,6 @@ TEST(TestDecoder, split_by_fixed_pkts) const_param.CHANNELS_PER_BLOCK = 2; RSDecoderParam param; param.split_frame_mode = SplitFrameMode::SPLIT_BY_FIXED_BLKS; - //param.num_blks_split = 2; MyDecoder decoder(param, errCallback, const_param); decoder.blks_per_frame_ = 2; ASSERT_EQ(decoder.num_blks_, 0); @@ -371,7 +375,7 @@ TEST(TestDecoder, split_by_fixed_pkts) { errCode = ERRCODE_SUCCESS; flag_point_cloud = false; - decoder.toSplit (0, 0); + decoder.toSplit (0); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_FALSE(flag_point_cloud); } @@ -379,7 +383,7 @@ TEST(TestDecoder, split_by_fixed_pkts) { errCode = ERRCODE_SUCCESS; flag_point_cloud = false; - decoder.toSplit (0, 0); + decoder.toSplit (0); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_TRUE(flag_point_cloud); @@ -410,7 +414,7 @@ TEST(TestDecoder, split_by_custom_blks) { errCode = ERRCODE_SUCCESS; flag_point_cloud = false; - decoder.toSplit (0, 0); + decoder.toSplit (0); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_FALSE(flag_point_cloud); } @@ -418,7 +422,7 @@ TEST(TestDecoder, split_by_custom_blks) { errCode = ERRCODE_SUCCESS; flag_point_cloud = false; - decoder.toSplit (0, 0); + decoder.toSplit (0); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_TRUE(flag_point_cloud); From c2f251b06103c7e31fc10856a822d3b2579d67c3 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 11:54:17 +0800 Subject: [PATCH 077/379] refac: refactor decoder --- src/rs_driver/driver/decoder/decoder.hpp | 4 +++- src/rs_driver/driver/decoder/decoder_RS32.hpp | 10 ++-------- test/decoder_rs32_test.cpp | 16 +++++++++++++++- test/decoder_test.cpp | 3 ++- 4 files changed, 22 insertions(+), 11 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index da32e19a..662b222a 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -175,6 +175,7 @@ class Decoder SplitAngle split_angle_; uint16_t blks_per_frame_; + uint16_t split_blks_per_frame_; uint16_t block_azi_diff_; float fov_blind_ts_diff_; @@ -210,6 +211,7 @@ inline Decoder::Decoder(const RSDecoderParam& param, , scan_block_(param.start_angle * 100, param.end_angle * 100) , split_angle_(param.split_angle * 100) , blks_per_frame_(1/(10*const_param.BLOCK_DURATION)) + , split_blks_per_frame_(blks_per_frame_) , block_azi_diff_(20) , fov_blind_ts_diff_(0) , protocol_ver_(0) @@ -257,7 +259,7 @@ inline void Decoder::toSplit(uint16_t azimuth) case SplitFrameMode::SPLIT_BY_FIXED_BLKS: this->num_blks_++; - if (this->num_blks_ >= this->blks_per_frame_) + if (this->num_blks_ >= this->split_blks_per_frame_) { this->num_blks_ = 0; split = true; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 0e306adc..d3f14383 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -173,18 +173,12 @@ inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, template inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, size_t size) { -// hexdump (packet, size, "difop"); - const RS32DifopPkt& pkt = *(const RS32DifopPkt*)(packet); this->template decodeDifopCommon(pkt); this->echo_mode_ = getEchoMode (pkt.return_mode); - - this->print(); - std::cout << "echo_mode:" << this->echo_mode_ - << "," << offsetof(RS32DifopPkt, return_mode) << std::endl; - - exit(-1); + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; } template diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index 2599d49b..7c5bff17 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -29,14 +29,28 @@ TEST(TestDecoderRS32, decodeDifopPkt) { RSDecoderParam param; DecoderRS32 decoder(param, errCallback); + ASSERT_EQ(decoder.blks_per_frame_, 1801); + ASSERT_EQ(decoder.split_blks_per_frame_, 1801); RS32DifopPkt pkt; - pkt.rpm = htons(1200); + // rpm = 600 + pkt.rpm = htons(600); pkt.return_mode = 0; // dual return decoder.decodeDifopPkt((uint8_t*)&pkt, sizeof(pkt)); + ASSERT_EQ(decoder.rps_, 10); ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_DUAL); + ASSERT_EQ(decoder.blks_per_frame_, 1801); + ASSERT_EQ(decoder.split_blks_per_frame_, 3602); + + // rpm = 1200 + pkt.rpm = htons(1200); + pkt.return_mode = 1; // single return + decoder.decodeDifopPkt((uint8_t*)&pkt, sizeof(pkt)); ASSERT_EQ(decoder.rps_, 20); + ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_SINGLE); + ASSERT_EQ(decoder.blks_per_frame_, 900); + ASSERT_EQ(decoder.split_blks_per_frame_, 900); } TEST(TestDecoderRS32, decodeMsopPkt) diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 20bad7e7..1ef5ad2b 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -170,6 +170,7 @@ TEST(TestDecoder, processDifopPkt) ASSERT_EQ(decoder.rps_, 10); ASSERT_EQ(decoder.blks_per_frame_, 1801); + ASSERT_EQ(decoder.split_blks_per_frame_, 1801); ASSERT_EQ(decoder.fov_blind_ts_diff_, 0.075f); ASSERT_FALSE(decoder.angles_ready_); ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); @@ -362,7 +363,7 @@ TEST(TestDecoder, split_by_fixed_pkts) RSDecoderParam param; param.split_frame_mode = SplitFrameMode::SPLIT_BY_FIXED_BLKS; MyDecoder decoder(param, errCallback, const_param); - decoder.blks_per_frame_ = 2; + decoder.split_blks_per_frame_ = 2; ASSERT_EQ(decoder.num_blks_, 0); point_cloud_to_get = std::make_shared(); From 562026ceeb7d89185f7be5d6de1bf12b30e10c01 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 12:17:43 +0800 Subject: [PATCH 078/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 12 +++++++----- src/rs_driver/driver/decoder/decoder_RS32.hpp | 1 - test/decoder_rs32_test.cpp | 5 +++++ 3 files changed, 12 insertions(+), 6 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 662b222a..2f50580a 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -137,13 +137,15 @@ class Decoder void print () { - std::cout << "blks_per_frame:\t" << this->blks_per_frame_ << std::endl - << "block_azi_diff:\t" << this->block_azi_diff_ << std::endl + std::cout << "-----------------------------------------" << std::endl + << "rps:\t\t\t" << this->rps_ << std::endl + << "echo_mode:\t\t" << this->echo_mode_ << std::endl + << "blks_per_frame:\t\t" << this->blks_per_frame_ << std::endl + << "split_blks_per_frame:\t" << this->split_blks_per_frame_ << std::endl + << "block_azi_diff:\t\t" << this->block_azi_diff_ << std::endl << "fov_blind_ts_diff:\t" << this->fov_blind_ts_diff_ << std::endl - << "rps:\t" << this->rps_ << std::endl - << "echo_mode:\t" << this->echo_mode_ << std::endl << "angle_from_file:\t" << this->param_.config_from_file << std::endl - << "angles_ready:\t" << this->angles_ready_ << std::endl; + << "angles_ready:\t\t" << this->angles_ready_ << std::endl; } explicit Decoder(const RSDecoderParam& param, diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index d3f14383..83d10c4d 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -32,7 +32,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include -#include namespace robosense { diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index 7c5bff17..c6507e4e 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -3,6 +3,7 @@ #include "rs_driver/msg/point_cloud_msg.h" #include +#include using namespace robosense::lidar; @@ -43,6 +44,8 @@ TEST(TestDecoderRS32, decodeDifopPkt) ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.split_blks_per_frame_, 3602); + decoder.print(); + // rpm = 1200 pkt.rpm = htons(1200); pkt.return_mode = 1; // single return @@ -51,6 +54,8 @@ TEST(TestDecoderRS32, decodeDifopPkt) ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_SINGLE); ASSERT_EQ(decoder.blks_per_frame_, 900); ASSERT_EQ(decoder.split_blks_per_frame_, 900); + decoder.print(); + } TEST(TestDecoderRS32, decodeMsopPkt) From f69ac8d038571bc40b06035130f1cc94fc12490e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 15:29:09 +0800 Subject: [PATCH 079/379] refac: refactory decoder --- src/rs_driver/driver/decoder/block_diff.hpp | 8 ++-- src/rs_driver/driver/decoder/decoder.hpp | 6 ++- src/rs_driver/driver/decoder/decoder_RS32.hpp | 29 +++++++++--- .../driver/decoder/decoder_base_opt.hpp | 47 ++++++++++++++----- src/rs_driver/driver/lidar_driver_impl.hpp | 1 - test/decoder_opt_test.cpp | 24 ++++++++++ test/decoder_rs32_test.cpp | 4 -- 7 files changed, 89 insertions(+), 30 deletions(-) diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index 9a4f95d0..029ca261 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -52,9 +52,9 @@ class SingleReturnBlockDiff return ret; } - virtual int16_t azimuth(uint16_t blk) + virtual int32_t azimuth(uint16_t blk) { - int16_t azi= 0; + int32_t azi= 0; if (blk < (this->const_param_.BLOCKS_PER_PKT - 1)) azi = this->pkt_.blocks[blk+1].azimuth - this->pkt_.blocks[blk].azimuth; @@ -92,9 +92,9 @@ class DualReturnBlockDiff return ret; } - int16_t azimuth(uint16_t blk) + int32_t azimuth(uint16_t blk) { - int16_t azi = 0; + int32_t azi = 0; if (blk >= (this->const_param_.BLOCKS_PER_PKT - 2)) { diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 2f50580a..688b45ab 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -146,6 +146,8 @@ class Decoder << "fov_blind_ts_diff:\t" << this->fov_blind_ts_diff_ << std::endl << "angle_from_file:\t" << this->param_.config_from_file << std::endl << "angles_ready:\t\t" << this->angles_ready_ << std::endl; + + this->chan_angles_.print(); } explicit Decoder(const RSDecoderParam& param, @@ -156,7 +158,7 @@ class Decoder protected: #endif - void toSplit(uint16_t azimuth); + void toSplit(int32_t azimuth); void setPointCloudHeader(std::shared_ptr msg, double chan_ts); template @@ -248,7 +250,7 @@ void Decoder::regRecvCallback( } template -inline void Decoder::toSplit(uint16_t azimuth) +inline void Decoder::toSplit(int32_t azimuth) { bool split = false; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 83d10c4d..8304f98a 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -32,6 +32,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include +#include namespace robosense { @@ -178,11 +179,23 @@ inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, siz this->echo_mode_ = getEchoMode (pkt.return_mode); this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? (this->blks_per_frame_ << 1) : this->blks_per_frame_; + +// this->print(); + + this->chan_angles_.narrow(); + + //hexdump (packet, size, ""); + + //std::cout << "off:" << offsetof(RS32DifopPkt, ver_angle_cali) << std::endl; + + // this->print(); + //exit(0); } template inline void DecoderRS32::decodeMsopPkt(const uint8_t* pkt, size_t size) { + //return; if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { internDecodeMsopPkt>(pkt, size); @@ -225,18 +238,22 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet } block_ts += diff.ts(blk); - int block_az = ntohs(block.azimuth); - int16_t block_azi_diff = diff.azimuth(blk); + int32_t block_az = ntohs(block.azimuth); + + this->toSplit(block_az); + + int32_t block_azi_diff = diff.azimuth(blk); for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { - const RSChannel& channel = block.channels[chan]; + const RSChannel& channel = block.channels[chan]; double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; - int16_t angle_horiz = block_az + block_azi_diff * this->const_param_.CHAN_AZIS[chan]; + int32_t angle_horiz = block_az + + (int32_t)((float)block_azi_diff * this->const_param_.CHAN_AZIS[chan]); - int16_t angle_vert = this->chan_angles_.vertAdjust(chan); - int16_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + int32_t angle_vert = this->chan_angles_.vertAdjust(chan); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; uint8_t intensity = channel.intensity; diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index cffd901e..1287a625 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -468,8 +468,28 @@ class ChanAngles return vert_angles_[chan]; } - void narrow () + void narrow() { + for (uint16_t chan = 0; chan < chan_num_; chan++) + { + vert_angles_[chan] = std::round(vert_angles_[chan] * 0.1f); + horiz_angles_[chan] = std::round(horiz_angles_[chan] * 0.1f); + } + } + + void print() + { + std::cout << "---------------------" << std::endl + << "chan_num:" << chan_num_ << std::endl; + + std::cout << "vert_angle\thoriz_angle\tuser_chan" << std::endl; + + for (uint16_t chan = 0; chan < chan_num_; chan++) + { + std::cout << vert_angles_[chan] << "\t" + << horiz_angles_[chan] << "\t" + << user_chans_[chan] << std::endl; + } } #ifndef UNIT_TEST @@ -550,13 +570,6 @@ class ChanAngles if (horiz.sign != 0) v = -v; horiz_angles.emplace_back(v); -#if 0 - if (type == LidarType::RS32) - { - this->vert_angle_list_[i] *= 0.1f; - this->hori_angle_list_[i] *= 0.1f; - } -#endif } return ((vert_angles.size() > 0) ? 0 : -1); @@ -568,8 +581,6 @@ class ChanAngles std::vector user_chans_; }; -//#define DBG - class Trigon { public: @@ -616,11 +627,21 @@ class Trigon float sin(int32_t angle) { +#ifdef DBG + if (angle < MIN || angle >= MAX) + return 0.0f; +#endif + return sins_[angle]; } float cos(int32_t angle) { +#ifdef DBG + if (angle < MIN || angle >= MAX) + return 0.0f; +#endif + return coss_[angle]; } @@ -650,13 +671,13 @@ class Trigon class SplitAngle { public: - SplitAngle (uint16_t split_angle) + SplitAngle (int32_t split_angle) : split_angle_(split_angle), prev_angle_(split_angle) { } - bool toSplit(uint16_t angle) + bool toSplit(int32_t angle) { if (angle < prev_angle_) prev_angle_ -= 36000; @@ -669,7 +690,7 @@ class SplitAngle #ifndef UNIT_TEST private: #endif - uint16_t split_angle_; + int32_t split_angle_; int32_t prev_angle_; }; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 2ecfb04c..df35d69c 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -304,7 +304,6 @@ inline void LidarDriverImpl::packetPut(std::shared_ptr pkt uint8_t* id = pkt->data(); if (*id == 0x55) { - return; queue = &msop_pkt_queue_; } else if (*id == 0xA5) diff --git a/test/decoder_opt_test.cpp b/test/decoder_opt_test.cpp index bfc87201..49f09d62 100644 --- a/test/decoder_opt_test.cpp +++ b/test/decoder_opt_test.cpp @@ -224,6 +224,30 @@ TEST(TestChanAngles, memberLoadFromDifop) (const RSCalibrationAngle*)horiz_angle_arr, 4), 0); + ASSERT_EQ(angles.vert_angles_.size(), 4); + ASSERT_EQ(angles.vert_angles_[0], 258); + ASSERT_EQ(angles.vert_angles_[1], -772); + ASSERT_EQ(angles.vert_angles_[2], -1286); + ASSERT_EQ(angles.vert_angles_[3], 1800); + + ASSERT_EQ(angles.horiz_angles_[0], 4386); + ASSERT_EQ(angles.horiz_angles_[1], -13124); + ASSERT_EQ(angles.horiz_angles_[2], 21862); + ASSERT_EQ(angles.horiz_angles_[3], -30600); + + angles.narrow(); + + ASSERT_EQ(angles.vert_angles_.size(), 4); + ASSERT_EQ(angles.vert_angles_[0], 26); + ASSERT_EQ(angles.vert_angles_[1], -77); + ASSERT_EQ(angles.vert_angles_[2], -129); + ASSERT_EQ(angles.vert_angles_[3], 180); + + ASSERT_EQ(angles.horiz_angles_[0], 439); + ASSERT_EQ(angles.horiz_angles_[1], -1312); + ASSERT_EQ(angles.horiz_angles_[2], 2186); + ASSERT_EQ(angles.horiz_angles_[3], -3060); + ASSERT_EQ(angles.user_chans_.size(), 4); ASSERT_EQ(angles.toUserChan(0), 2); ASSERT_EQ(angles.toUserChan(1), 1); diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index c6507e4e..ae5adec8 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -44,8 +44,6 @@ TEST(TestDecoderRS32, decodeDifopPkt) ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.split_blks_per_frame_, 3602); - decoder.print(); - // rpm = 1200 pkt.rpm = htons(1200); pkt.return_mode = 1; // single return @@ -54,8 +52,6 @@ TEST(TestDecoderRS32, decodeDifopPkt) ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_SINGLE); ASSERT_EQ(decoder.blks_per_frame_, 900); ASSERT_EQ(decoder.split_blks_per_frame_, 900); - decoder.print(); - } TEST(TestDecoderRS32, decodeMsopPkt) From 0420b49bd8bdbbca5385a35a91337632363600e8 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 16:40:31 +0800 Subject: [PATCH 080/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder_RS32.hpp | 13 ++++--------- src/rs_driver/driver/decoder/decoder_base_opt.hpp | 8 ++++---- 2 files changed, 8 insertions(+), 13 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 8304f98a..571ecae5 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -180,16 +180,11 @@ inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, siz this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? (this->blks_per_frame_ << 1) : this->blks_per_frame_; -// this->print(); - + // + // RS32's channel angles is of higher resolution than the other lidars. + // fix them to the same resolution. + // this->chan_angles_.narrow(); - - //hexdump (packet, size, ""); - - //std::cout << "off:" << offsetof(RS32DifopPkt, ver_angle_cali) << std::endl; - - // this->print(); - //exit(0); } template diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 1287a625..9670612f 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -356,14 +356,14 @@ inline int16_t calcTemp(const RsTemprature* tmp) class ScanBlock { public: - ScanBlock(uint16_t start, uint16_t end) + ScanBlock(int32_t start, int32_t end) { start_ = start % 36000; end_ = (end <= 36000) ? end : (end % 36000); cross_zero_ = (start_ > end_); } - bool in(uint16_t angle) + bool in(int32_t angle) { if (cross_zero_) return (angle >= start_) || (angle < end_); @@ -374,8 +374,8 @@ class ScanBlock #ifndef UNIT_TEST private: #endif - uint16_t start_; - uint16_t end_; + int32_t start_; + int32_t end_; bool cross_zero_; }; From d8edd5d00a4f80744cc2a1619e9edfd93054f3ad Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 16:59:05 +0800 Subject: [PATCH 081/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 1 + .../driver/decoder/decoder_base_opt.hpp | 87 ------------ src/rs_driver/driver/decoder/scan_block.hpp | 100 +++++++++++++ src/rs_driver/driver/decoder/trigon.hpp | 132 ++++++++++++++++++ test/CMakeLists.txt | 1 + test/decoder_opt_test.cpp | 23 --- test/trigon_test.cpp | 32 +++++ 7 files changed, 266 insertions(+), 110 deletions(-) create mode 100644 src/rs_driver/driver/decoder/scan_block.hpp create mode 100644 src/rs_driver/driver/decoder/trigon.hpp create mode 100644 test/trigon_test.cpp diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 688b45ab..e4a52453 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -68,6 +68,7 @@ typedef struct } RSDecoderConstParam; #include +#include #include #include #include diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 9670612f..e12b4c7b 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -581,93 +581,6 @@ class ChanAngles std::vector user_chans_; }; -class Trigon -{ -public: - - static const int32_t MIN = -9000; - static const int32_t MAX = 45000; - - Trigon() - { - int32_t range = MAX - MIN; -#ifdef DBG - o_angles_ = (int32_t*)malloc(range * sizeof(int32_t)); -#endif - o_sins_ = (float*)malloc(range * sizeof(float)); - o_coss_ = (float*)malloc(range * sizeof(float)); - - for (int32_t i = MIN, j = 0; i < MAX; i++, j++) - { - double rads = static_cast(i) * 0.01; - rads = rads * M_PI / 180; - -#ifdef DBG - o_angles_[j] = i; -#endif - o_sins_[j] = (float)std::sin(rads); - o_coss_[j] = (float)std::cos(rads); - } - -#ifdef DBG - angles_ = o_angles_ - MIN; -#endif - sins_ = o_sins_ - MIN; - coss_ = o_coss_ - MIN; - } - - ~Trigon() - { - free(o_coss_); - free(o_sins_); -#ifdef DBG - free(o_angles_); -#endif - } - - float sin(int32_t angle) - { -#ifdef DBG - if (angle < MIN || angle >= MAX) - return 0.0f; -#endif - - return sins_[angle]; - } - - float cos(int32_t angle) - { -#ifdef DBG - if (angle < MIN || angle >= MAX) - return 0.0f; -#endif - - return coss_[angle]; - } - - void print() - { - for (int32_t i = -10; i < 10; i++) - { - std::cout << -#ifdef DBG - angles_[i] << "\t" << -#endif - sins_[i] << "\t" << coss_[i] << std::endl; - } - } - -private: -#ifdef DBG - int32_t* o_angles_; - int32_t* angles_; -#endif - float* o_sins_; - float* o_coss_; - float* sins_; - float* coss_; -}; - class SplitAngle { public: diff --git a/src/rs_driver/driver/decoder/scan_block.hpp b/src/rs_driver/driver/decoder/scan_block.hpp new file mode 100644 index 00000000..cfb0da97 --- /dev/null +++ b/src/rs_driver/driver/decoder/scan_block.hpp @@ -0,0 +1,100 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace robosense +{ +namespace lidar +{ + +class ScanBlock +{ +public: + ScanBlock(int32_t start, int32_t end) + { + start_ = start % 36000; + end_ = (end <= 36000) ? end : (end % 36000); + cross_zero_ = (start_ > end_); + } + + bool in(int32_t angle) + { + if (cross_zero_) + return (angle >= start_) || (angle < end_); + else + return (angle >= start_) && (angle < end_); + } + +#ifndef UNIT_TEST +private: +#endif + int32_t start_; + int32_t end_; + bool cross_zero_; +}; + +class DistanceBlock +{ +public: + DistanceBlock (float min, float max, float usr_min, float usr_max) + : min_((usr_min > min) ? usr_min : min), max_((usr_max < max) ? usr_max : max) + { + } + + bool in(float distance) + { + return ((min_ <= distance) && (distance <= max_)); + } + +#ifndef UNIT_TEST +private: +#endif + + float min_; + float max_; +}; + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/decoder/trigon.hpp b/src/rs_driver/driver/decoder/trigon.hpp new file mode 100644 index 00000000..8c3ed54d --- /dev/null +++ b/src/rs_driver/driver/decoder/trigon.hpp @@ -0,0 +1,132 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include + +namespace robosense +{ +namespace lidar +{ + +//#define DBG + +class Trigon +{ +public: + + static const int32_t MIN = -9000; + static const int32_t MAX = 45000; + + Trigon() + { + int32_t range = MAX - MIN; +#ifdef DBG + o_angles_ = (int32_t*)malloc(range * sizeof(int32_t)); +#endif + o_sins_ = (float*)malloc(range * sizeof(float)); + o_coss_ = (float*)malloc(range * sizeof(float)); + + for (int32_t i = MIN, j = 0; i < MAX; i++, j++) + { + double rads = static_cast(i) * 0.01; + rads = rads * M_PI / 180; + +#ifdef DBG + o_angles_[j] = i; +#endif + o_sins_[j] = (float)std::sin(rads); + o_coss_[j] = (float)std::cos(rads); + } + +#ifdef DBG + angles_ = o_angles_ - MIN; +#endif + sins_ = o_sins_ - MIN; + coss_ = o_coss_ - MIN; + } + + ~Trigon() + { + free(o_coss_); + free(o_sins_); +#ifdef DBG + free(o_angles_); +#endif + } + + float sin(int32_t angle) + { +#ifdef DBG + if (angle < MIN || angle >= MAX) + return 0.0f; +#endif + + return sins_[angle]; + } + + float cos(int32_t angle) + { +#ifdef DBG + if (angle < MIN || angle >= MAX) + return 0.0f; +#endif + + return coss_[angle]; + } + + void print() + { + for (int32_t i = -10; i < 10; i++) + { + std::cout << +#ifdef DBG + angles_[i] << "\t" << +#endif + sins_[i] << "\t" << coss_[i] << std::endl; + } + } + +private: +#ifdef DBG + int32_t* o_angles_; + int32_t* angles_; +#endif + float* o_sins_; + float* o_coss_; + float* sins_; + float* coss_; +}; + +} // namespace lidar +} // namespace robosense diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 567d7604..a2c90298 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -16,6 +16,7 @@ add_executable(rs_driver_test single_return_block_diff_test.cpp dual_return_block_diff_test.cpp decoder_opt_test.cpp + trigon_test.cpp decoder_test.cpp decoder_rs32_test.cpp) diff --git a/test/decoder_opt_test.cpp b/test/decoder_opt_test.cpp index 49f09d62..352974f9 100644 --- a/test/decoder_opt_test.cpp +++ b/test/decoder_opt_test.cpp @@ -275,29 +275,6 @@ TEST(TestChanAngles, memberLoadFromDifop_fail) 4), 0); } -TEST(TestTrigon, ctor) -{ - Trigon trigon; - //trigon.print(); - - ASSERT_EQ(trigon.sin(-9000), -1.0f); - ASSERT_LT(trigon.cos(-9000), 0.0001f); - - ASSERT_EQ(trigon.sin(0), 0.0f); - ASSERT_EQ(trigon.cos(0), 1.0f); - - ASSERT_EQ(trigon.sin(3000), 0.5f); - ASSERT_EQ(trigon.cos(6000), 0.5f); - - trigon.sin(44999); - trigon.cos(44999); - -#if 0 - trigon.sin(45000); - trigon.cos(45000); -#endif -} - TEST(TestSplitAngle, toSplit) { { diff --git a/test/trigon_test.cpp b/test/trigon_test.cpp new file mode 100644 index 00000000..63aa30fe --- /dev/null +++ b/test/trigon_test.cpp @@ -0,0 +1,32 @@ + +#include + +#include + +using namespace robosense::lidar; + +TEST(TestTrigon, ctor) +{ + Trigon trigon; +#if 0 + trigon.print(); +#endif + + ASSERT_EQ(trigon.sin(-9000), -1.0f); + ASSERT_LT(trigon.cos(-9000), 0.0001f); + + ASSERT_EQ(trigon.sin(0), 0.0f); + ASSERT_EQ(trigon.cos(0), 1.0f); + + ASSERT_EQ(trigon.sin(3000), 0.5f); + ASSERT_EQ(trigon.cos(6000), 0.5f); + + trigon.sin(44999); + trigon.cos(44999); + +#if 0 + trigon.sin(45000); + trigon.cos(45000); +#endif +} + From e0d000deaf120fe5bbdd380d93b3e571b09c59e5 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 17:08:20 +0800 Subject: [PATCH 082/379] refac: refactory decoder --- src/rs_driver/driver/decoder/chan_angles.hpp | 231 ++++++++++++++++++ src/rs_driver/driver/decoder/decoder.hpp | 1 + .../driver/decoder/decoder_base_opt.hpp | 181 -------------- test/CMakeLists.txt | 1 + test/chan_angles_test.cpp | 189 ++++++++++++++ test/decoder_opt_test.cpp | 182 -------------- 6 files changed, 422 insertions(+), 363 deletions(-) create mode 100644 src/rs_driver/driver/decoder/chan_angles.hpp create mode 100644 test/chan_angles_test.cpp diff --git a/src/rs_driver/driver/decoder/chan_angles.hpp b/src/rs_driver/driver/decoder/chan_angles.hpp new file mode 100644 index 00000000..c496f9d3 --- /dev/null +++ b/src/rs_driver/driver/decoder/chan_angles.hpp @@ -0,0 +1,231 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace robosense +{ +namespace lidar +{ + +class ChanAngles +{ +public: + + ChanAngles(uint16_t chan_num) + : chan_num_(chan_num) + { + vert_angles_.resize(chan_num_); + horiz_angles_.resize(chan_num_); + user_chans_.resize(chan_num_); + } + + int loadFromFile(const std::string& angle_path) + { + std::vector vert_angles; + std::vector horiz_angles; + int ret = loadFromFile (angle_path, vert_angles, horiz_angles); + if (ret < 0) + return ret; + + if (vert_angles.size() != chan_num_) + { + return -1; + } + + vert_angles_.swap(vert_angles); + horiz_angles_.swap(horiz_angles); + genUserChan(vert_angles_, user_chans_); + return 0; + } + + int loadFromDifop(const RSCalibrationAngle vert_angle_arr[], + const RSCalibrationAngle horiz_angle_arr[], size_t size) + { + std::vector vert_angles; + std::vector horiz_angles; + int ret = + loadFromDifop (vert_angle_arr, horiz_angle_arr, size, vert_angles, horiz_angles); + if (ret < 0) + return ret; + + if (vert_angles.size() != chan_num_) + { + return -1; + } + + vert_angles_.swap(vert_angles); + horiz_angles_.swap(horiz_angles); + genUserChan(vert_angles_, user_chans_); + return 0; + } + + uint16_t toUserChan(uint16_t chan) + { + return user_chans_[chan]; + } + + int32_t horizAdjust(uint16_t chan, int32_t horiz) + { + return (horiz + horiz_angles_[chan]); + } + + int32_t vertAdjust(uint16_t chan) + { + return vert_angles_[chan]; + } + + void narrow() + { + for (uint16_t chan = 0; chan < chan_num_; chan++) + { + vert_angles_[chan] = std::round(vert_angles_[chan] * 0.1f); + horiz_angles_[chan] = std::round(horiz_angles_[chan] * 0.1f); + } + } + + void print() + { + std::cout << "---------------------" << std::endl + << "chan_num:" << chan_num_ << std::endl; + + std::cout << "vert_angle\thoriz_angle\tuser_chan" << std::endl; + + for (uint16_t chan = 0; chan < chan_num_; chan++) + { + std::cout << vert_angles_[chan] << "\t" + << horiz_angles_[chan] << "\t" + << user_chans_[chan] << std::endl; + } + } + +#ifndef UNIT_TEST +private: +#endif + + static + void genUserChan(const std::vector& vert_angles, std::vector& user_chans) + { + user_chans.resize(vert_angles.size()); + + for (size_t i = 0; i < vert_angles.size(); i++) + { + int32_t angle = vert_angles[i]; + uint16_t chan = 0; + + for (size_t j = 0; j < vert_angles.size(); j++) + { + if (vert_angles[j] < angle) + { + chan++; + } + } + + user_chans[i] = chan; + } + } + + static int loadFromFile(const std::string& angle_path, + std::vector& vert_angles, std::vector& horiz_angles) + { + vert_angles.clear(); + horiz_angles.clear(); + + std::ifstream fd(angle_path.c_str(), std::ios::in); + if (!fd.is_open()) + { + std::cout << "fail to open angle file:" << angle_path << std::endl; + return -1; + } + + std::string line; + while (std::getline(fd, line)) + { + size_t pos_comma = 0; + float vert = std::stof(line, &pos_comma); + float horiz = std::stof(line.substr(pos_comma+1)); + + vert_angles.emplace_back(static_cast(vert * 100)); + horiz_angles.emplace_back(static_cast(horiz * 100)); + } + + fd.close(); + return 0; + } + + static int loadFromDifop(const RSCalibrationAngle* vert_angle_arr, + const RSCalibrationAngle* horiz_angle_arr, size_t size, + std::vector& vert_angles, std::vector& horiz_angles) + { + vert_angles.clear(); + horiz_angles.clear(); + + for (size_t i = 0; i < size; i++) + { + const RSCalibrationAngle& vert = vert_angle_arr[i]; + const RSCalibrationAngle& horiz = horiz_angle_arr[i]; + int32_t v; + + if (vert.sign == 0xFF) + break; + + v = ntohs(vert.value); + if (vert.sign != 0) v = -v; + vert_angles.emplace_back(v); + + v = ntohs(horiz.value); + if (horiz.sign != 0) v = -v; + horiz_angles.emplace_back(v); + + } + + return ((vert_angles.size() > 0) ? 0 : -1); + } + + uint16_t chan_num_; + std::vector vert_angles_; + std::vector horiz_angles_; + std::vector user_chans_; +}; + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index e4a52453..7f843431 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -69,6 +69,7 @@ typedef struct #include #include +#include #include #include #include diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index e12b4c7b..9f84ecf5 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -400,187 +400,6 @@ class DistanceBlock float max_; }; - -class ChanAngles -{ -public: - - ChanAngles(uint16_t chan_num) - : chan_num_(chan_num) - { - vert_angles_.resize(chan_num_); - horiz_angles_.resize(chan_num_); - user_chans_.resize(chan_num_); - } - - int loadFromFile(const std::string& angle_path) - { - std::vector vert_angles; - std::vector horiz_angles; - int ret = loadFromFile (angle_path, vert_angles, horiz_angles); - if (ret < 0) - return ret; - - if (vert_angles.size() != chan_num_) - { - return -1; - } - - vert_angles_.swap(vert_angles); - horiz_angles_.swap(horiz_angles); - genUserChan(vert_angles_, user_chans_); - return 0; - } - - int loadFromDifop(const RSCalibrationAngle vert_angle_arr[], - const RSCalibrationAngle horiz_angle_arr[], size_t size) - { - std::vector vert_angles; - std::vector horiz_angles; - int ret = - loadFromDifop (vert_angle_arr, horiz_angle_arr, size, vert_angles, horiz_angles); - if (ret < 0) - return ret; - - if (vert_angles.size() != chan_num_) - { - return -1; - } - - vert_angles_.swap(vert_angles); - horiz_angles_.swap(horiz_angles); - genUserChan(vert_angles_, user_chans_); - return 0; - } - - uint16_t toUserChan(uint16_t chan) - { - return user_chans_[chan]; - } - - int32_t horizAdjust(uint16_t chan, int32_t horiz) - { - return (horiz + horiz_angles_[chan]); - } - - int32_t vertAdjust(uint16_t chan) - { - return vert_angles_[chan]; - } - - void narrow() - { - for (uint16_t chan = 0; chan < chan_num_; chan++) - { - vert_angles_[chan] = std::round(vert_angles_[chan] * 0.1f); - horiz_angles_[chan] = std::round(horiz_angles_[chan] * 0.1f); - } - } - - void print() - { - std::cout << "---------------------" << std::endl - << "chan_num:" << chan_num_ << std::endl; - - std::cout << "vert_angle\thoriz_angle\tuser_chan" << std::endl; - - for (uint16_t chan = 0; chan < chan_num_; chan++) - { - std::cout << vert_angles_[chan] << "\t" - << horiz_angles_[chan] << "\t" - << user_chans_[chan] << std::endl; - } - } - -#ifndef UNIT_TEST -private: -#endif - - static - void genUserChan(const std::vector& vert_angles, std::vector& user_chans) - { - user_chans.resize(vert_angles.size()); - - for (size_t i = 0; i < vert_angles.size(); i++) - { - int32_t angle = vert_angles[i]; - uint16_t chan = 0; - - for (size_t j = 0; j < vert_angles.size(); j++) - { - if (vert_angles[j] < angle) - { - chan++; - } - } - - user_chans[i] = chan; - } - } - - static int loadFromFile(const std::string& angle_path, - std::vector& vert_angles, std::vector& horiz_angles) - { - vert_angles.clear(); - horiz_angles.clear(); - - std::ifstream fd(angle_path.c_str(), std::ios::in); - if (!fd.is_open()) - { - std::cout << "fail to open angle file:" << angle_path << std::endl; - return -1; - } - - std::string line; - while (std::getline(fd, line)) - { - size_t pos_comma = 0; - float vert = std::stof(line, &pos_comma); - float horiz = std::stof(line.substr(pos_comma+1)); - - vert_angles.emplace_back(static_cast(vert * 100)); - horiz_angles.emplace_back(static_cast(horiz * 100)); - } - - fd.close(); - return 0; - } - - static int loadFromDifop(const RSCalibrationAngle* vert_angle_arr, - const RSCalibrationAngle* horiz_angle_arr, size_t size, - std::vector& vert_angles, std::vector& horiz_angles) - { - vert_angles.clear(); - horiz_angles.clear(); - - for (size_t i = 0; i < size; i++) - { - const RSCalibrationAngle& vert = vert_angle_arr[i]; - const RSCalibrationAngle& horiz = horiz_angle_arr[i]; - int32_t v; - - if (vert.sign == 0xFF) - break; - - v = ntohs(vert.value); - if (vert.sign != 0) v = -v; - vert_angles.emplace_back(v); - - v = ntohs(horiz.value); - if (horiz.sign != 0) v = -v; - horiz_angles.emplace_back(v); - - } - - return ((vert_angles.size() > 0) ? 0 : -1); - } - - uint16_t chan_num_; - std::vector vert_angles_; - std::vector horiz_angles_; - std::vector user_chans_; -}; - class SplitAngle { public: diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index a2c90298..242e384f 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -16,6 +16,7 @@ add_executable(rs_driver_test single_return_block_diff_test.cpp dual_return_block_diff_test.cpp decoder_opt_test.cpp + chan_angles_test.cpp trigon_test.cpp decoder_test.cpp decoder_rs32_test.cpp) diff --git a/test/chan_angles_test.cpp b/test/chan_angles_test.cpp new file mode 100644 index 00000000..093cf2b3 --- /dev/null +++ b/test/chan_angles_test.cpp @@ -0,0 +1,189 @@ + +#include + +#include + +using namespace robosense::lidar; + +TEST(TestChanAngles, genUserChan) +{ + std::vector vert_angles; + std::vector user_chans; + + vert_angles.push_back(100); + vert_angles.push_back(0); + vert_angles.push_back(-100); + vert_angles.push_back(200); + + ChanAngles::genUserChan (vert_angles, user_chans); + ASSERT_EQ(user_chans.size(), 4); + ASSERT_EQ(user_chans[0], 2); + ASSERT_EQ(user_chans[1], 1); + ASSERT_EQ(user_chans[2], 0); + ASSERT_EQ(user_chans[3], 3); +} + +TEST(TestChanAngles, loadFromFile) +{ + std::vector vert_angles, horiz_angles; + + ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); + ASSERT_EQ(vert_angles[0], 500); + ASSERT_EQ(vert_angles[1], 250); + ASSERT_EQ(vert_angles[2], 0); + ASSERT_EQ(vert_angles[3], -250); + + ASSERT_EQ(horiz_angles[0], 10); + ASSERT_EQ(horiz_angles[1], -20); + ASSERT_EQ(horiz_angles[2], 0); + ASSERT_EQ(horiz_angles[3], -100); + + ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); + + ASSERT_LT(ChanAngles::loadFromFile ("../rs_driver/test/res/non_exist.csv", vert_angles, horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 0); + ASSERT_EQ(horiz_angles.size(), 0); + +} + +TEST(TestChanAngles, loadFromDifop) +{ + uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, + 0x01, 0x03, 0x04, + 0x01, 0x05, 0x06, + 0x00, 0x07, 0x08}; + uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, + 0x01, 0x33, 0x44, + 0x00, 0x55, 0x66, + 0x01, 0x77, 0x88}; + + std::vector vert_angles, horiz_angles; + + ASSERT_EQ(ChanAngles::loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4, + vert_angles, + horiz_angles), 0); + + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); + ASSERT_EQ(vert_angles[0], 258); + ASSERT_EQ(vert_angles[1], -772); + ASSERT_EQ(vert_angles[2], -1286); + ASSERT_EQ(vert_angles[3], 1800); + + ASSERT_EQ(horiz_angles[0], 4386); + ASSERT_EQ(horiz_angles[1], -13124); + ASSERT_EQ(horiz_angles[2], 21862); + ASSERT_EQ(horiz_angles[3], -30600); + + ASSERT_EQ(ChanAngles::loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4, + vert_angles, + horiz_angles), 0); + ASSERT_EQ(vert_angles.size(), 4); + ASSERT_EQ(horiz_angles.size(), 4); +} + +TEST(TestChanAngles, memberLoadFromFile) +{ + ChanAngles angles(4); + ASSERT_EQ(angles.chan_num_, 4); + ASSERT_EQ(angles.vert_angles_.size(), 4); + ASSERT_EQ(angles.horiz_angles_.size(), 4); + ASSERT_EQ(angles.user_chans_.size(), 4); + + ASSERT_EQ(angles.loadFromFile ("../rs_driver/test/res/angle.csv"), 0); + ASSERT_EQ(angles.user_chans_.size(), 4); + ASSERT_EQ(angles.toUserChan(0), 3); + ASSERT_EQ(angles.toUserChan(1), 2); + ASSERT_EQ(angles.toUserChan(2), 1); + ASSERT_EQ(angles.toUserChan(3), 0); +} + +TEST(TestChanAngles, memberLoadFromFile_fail) +{ + ChanAngles angles(4); + ASSERT_EQ(angles.chan_num_, 4); + + ASSERT_LT(angles.loadFromFile ("../rs_driver/test/res/non_exist.csv"), 0); + ASSERT_EQ(angles.vert_angles_.size(), 4); + ASSERT_EQ(angles.vert_angles_[0], 0); +} + +TEST(TestChanAngles, memberLoadFromDifop) +{ + uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, + 0x01, 0x03, 0x04, + 0x01, 0x05, 0x06, + 0x00, 0x07, 0x08}; + uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, + 0x01, 0x33, 0x44, + 0x00, 0x55, 0x66, + 0x01, 0x77, 0x88}; + + ChanAngles angles(4); + ASSERT_EQ(angles.chan_num_, 4); + ASSERT_EQ(angles.loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4), 0); + + ASSERT_EQ(angles.vert_angles_.size(), 4); + ASSERT_EQ(angles.vert_angles_[0], 258); + ASSERT_EQ(angles.vert_angles_[1], -772); + ASSERT_EQ(angles.vert_angles_[2], -1286); + ASSERT_EQ(angles.vert_angles_[3], 1800); + + ASSERT_EQ(angles.horiz_angles_[0], 4386); + ASSERT_EQ(angles.horiz_angles_[1], -13124); + ASSERT_EQ(angles.horiz_angles_[2], 21862); + ASSERT_EQ(angles.horiz_angles_[3], -30600); + + angles.narrow(); + + ASSERT_EQ(angles.vert_angles_.size(), 4); + ASSERT_EQ(angles.vert_angles_[0], 26); + ASSERT_EQ(angles.vert_angles_[1], -77); + ASSERT_EQ(angles.vert_angles_[2], -129); + ASSERT_EQ(angles.vert_angles_[3], 180); + + ASSERT_EQ(angles.horiz_angles_[0], 439); + ASSERT_EQ(angles.horiz_angles_[1], -1312); + ASSERT_EQ(angles.horiz_angles_[2], 2186); + ASSERT_EQ(angles.horiz_angles_[3], -3060); + + ASSERT_EQ(angles.user_chans_.size(), 4); + ASSERT_EQ(angles.toUserChan(0), 2); + ASSERT_EQ(angles.toUserChan(1), 1); + ASSERT_EQ(angles.toUserChan(2), 0); + ASSERT_EQ(angles.toUserChan(3), 3); +} + +TEST(TestChanAngles, memberLoadFromDifop_fail) +{ + uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, + 0x01, 0x03, 0x04, + 0xFF, 0x05, 0x06, + 0xFF, 0x07, 0x08}; + uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, + 0x01, 0x33, 0x44, + 0xFF, 0x55, 0x66, + 0xFF, 0x77, 0x88}; + + ChanAngles angles(4); + ASSERT_EQ(angles.chan_num_, 4); + + ASSERT_LT(angles.loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4), 0); +} + diff --git a/test/decoder_opt_test.cpp b/test/decoder_opt_test.cpp index 352974f9..319e0dc4 100644 --- a/test/decoder_opt_test.cpp +++ b/test/decoder_opt_test.cpp @@ -93,188 +93,6 @@ TEST(TestDistanceBlock, ctorNoUseBlock) ASSERT_EQ(blk.max_, 200); } -TEST(TestChanAngles, genUserChan) -{ - std::vector vert_angles; - std::vector user_chans; - - vert_angles.push_back(100); - vert_angles.push_back(0); - vert_angles.push_back(-100); - vert_angles.push_back(200); - - ChanAngles::genUserChan (vert_angles, user_chans); - ASSERT_EQ(user_chans.size(), 4); - ASSERT_EQ(user_chans[0], 2); - ASSERT_EQ(user_chans[1], 1); - ASSERT_EQ(user_chans[2], 0); - ASSERT_EQ(user_chans[3], 3); -} - -TEST(TestChanAngles, loadFromFile) -{ - std::vector vert_angles, horiz_angles; - - ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); - ASSERT_EQ(vert_angles.size(), 4); - ASSERT_EQ(horiz_angles.size(), 4); - ASSERT_EQ(vert_angles[0], 500); - ASSERT_EQ(vert_angles[1], 250); - ASSERT_EQ(vert_angles[2], 0); - ASSERT_EQ(vert_angles[3], -250); - - ASSERT_EQ(horiz_angles[0], 10); - ASSERT_EQ(horiz_angles[1], -20); - ASSERT_EQ(horiz_angles[2], 0); - ASSERT_EQ(horiz_angles[3], -100); - - ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); - ASSERT_EQ(vert_angles.size(), 4); - ASSERT_EQ(horiz_angles.size(), 4); - - ASSERT_LT(ChanAngles::loadFromFile ("../rs_driver/test/res/non_exist.csv", vert_angles, horiz_angles), 0); - ASSERT_EQ(vert_angles.size(), 0); - ASSERT_EQ(horiz_angles.size(), 0); - -} - -TEST(TestChanAngles, loadFromDifop) -{ - uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, - 0x01, 0x03, 0x04, - 0x01, 0x05, 0x06, - 0x00, 0x07, 0x08}; - uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, - 0x01, 0x33, 0x44, - 0x00, 0x55, 0x66, - 0x01, 0x77, 0x88}; - - std::vector vert_angles, horiz_angles; - - ASSERT_EQ(ChanAngles::loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4, - vert_angles, - horiz_angles), 0); - - ASSERT_EQ(vert_angles.size(), 4); - ASSERT_EQ(horiz_angles.size(), 4); - ASSERT_EQ(vert_angles[0], 258); - ASSERT_EQ(vert_angles[1], -772); - ASSERT_EQ(vert_angles[2], -1286); - ASSERT_EQ(vert_angles[3], 1800); - - ASSERT_EQ(horiz_angles[0], 4386); - ASSERT_EQ(horiz_angles[1], -13124); - ASSERT_EQ(horiz_angles[2], 21862); - ASSERT_EQ(horiz_angles[3], -30600); - - ASSERT_EQ(ChanAngles::loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4, - vert_angles, - horiz_angles), 0); - ASSERT_EQ(vert_angles.size(), 4); - ASSERT_EQ(horiz_angles.size(), 4); -} - -TEST(TestChanAngles, memberLoadFromFile) -{ - ChanAngles angles(4); - ASSERT_EQ(angles.chan_num_, 4); - ASSERT_EQ(angles.vert_angles_.size(), 4); - ASSERT_EQ(angles.horiz_angles_.size(), 4); - ASSERT_EQ(angles.user_chans_.size(), 4); - - ASSERT_EQ(angles.loadFromFile ("../rs_driver/test/res/angle.csv"), 0); - ASSERT_EQ(angles.user_chans_.size(), 4); - ASSERT_EQ(angles.toUserChan(0), 3); - ASSERT_EQ(angles.toUserChan(1), 2); - ASSERT_EQ(angles.toUserChan(2), 1); - ASSERT_EQ(angles.toUserChan(3), 0); -} - -TEST(TestChanAngles, memberLoadFromFile_fail) -{ - ChanAngles angles(4); - ASSERT_EQ(angles.chan_num_, 4); - - ASSERT_LT(angles.loadFromFile ("../rs_driver/test/res/non_exist.csv"), 0); - ASSERT_EQ(angles.vert_angles_.size(), 4); - ASSERT_EQ(angles.vert_angles_[0], 0); -} - -TEST(TestChanAngles, memberLoadFromDifop) -{ - uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, - 0x01, 0x03, 0x04, - 0x01, 0x05, 0x06, - 0x00, 0x07, 0x08}; - uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, - 0x01, 0x33, 0x44, - 0x00, 0x55, 0x66, - 0x01, 0x77, 0x88}; - - ChanAngles angles(4); - ASSERT_EQ(angles.chan_num_, 4); - ASSERT_EQ(angles.loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4), 0); - - ASSERT_EQ(angles.vert_angles_.size(), 4); - ASSERT_EQ(angles.vert_angles_[0], 258); - ASSERT_EQ(angles.vert_angles_[1], -772); - ASSERT_EQ(angles.vert_angles_[2], -1286); - ASSERT_EQ(angles.vert_angles_[3], 1800); - - ASSERT_EQ(angles.horiz_angles_[0], 4386); - ASSERT_EQ(angles.horiz_angles_[1], -13124); - ASSERT_EQ(angles.horiz_angles_[2], 21862); - ASSERT_EQ(angles.horiz_angles_[3], -30600); - - angles.narrow(); - - ASSERT_EQ(angles.vert_angles_.size(), 4); - ASSERT_EQ(angles.vert_angles_[0], 26); - ASSERT_EQ(angles.vert_angles_[1], -77); - ASSERT_EQ(angles.vert_angles_[2], -129); - ASSERT_EQ(angles.vert_angles_[3], 180); - - ASSERT_EQ(angles.horiz_angles_[0], 439); - ASSERT_EQ(angles.horiz_angles_[1], -1312); - ASSERT_EQ(angles.horiz_angles_[2], 2186); - ASSERT_EQ(angles.horiz_angles_[3], -3060); - - ASSERT_EQ(angles.user_chans_.size(), 4); - ASSERT_EQ(angles.toUserChan(0), 2); - ASSERT_EQ(angles.toUserChan(1), 1); - ASSERT_EQ(angles.toUserChan(2), 0); - ASSERT_EQ(angles.toUserChan(3), 3); -} - -TEST(TestChanAngles, memberLoadFromDifop_fail) -{ - uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, - 0x01, 0x03, 0x04, - 0xFF, 0x05, 0x06, - 0xFF, 0x07, 0x08}; - uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, - 0x01, 0x33, 0x44, - 0xFF, 0x55, 0x66, - 0xFF, 0x77, 0x88}; - - ChanAngles angles(4); - ASSERT_EQ(angles.chan_num_, 4); - - ASSERT_LT(angles.loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4), 0); -} - TEST(TestSplitAngle, toSplit) { { From 3b56d37c290bed8ee76be65c7883b21e70a3972e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 17:28:47 +0800 Subject: [PATCH 083/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 2 +- src/rs_driver/driver/decoder/decoder_base_opt.hpp | 4 ---- .../driver/decoder/{set_member.hpp => member_checker.hpp} | 0 3 files changed, 1 insertion(+), 5 deletions(-) rename src/rs_driver/driver/decoder/{set_member.hpp => member_checker.hpp} (100%) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 7f843431..a9e5ece2 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -67,7 +67,7 @@ typedef struct } RSDecoderConstParam; -#include +#include #include #include #include diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 9f84ecf5..b0a58206 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -32,10 +32,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#include -#include -#include - #include #include #include diff --git a/src/rs_driver/driver/decoder/set_member.hpp b/src/rs_driver/driver/decoder/member_checker.hpp similarity index 100% rename from src/rs_driver/driver/decoder/set_member.hpp rename to src/rs_driver/driver/decoder/member_checker.hpp From 9487a447fdc004c4d398a6f9f73c7faf47cdbede Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 19:02:28 +0800 Subject: [PATCH 084/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 27 ++--- src/rs_driver/driver/decoder/decoder_RS32.hpp | 11 +- .../driver/decoder/decoder_base_opt.hpp | 79 ++++++------ src/rs_driver/driver/decoder/trigon.hpp | 4 + src/rs_driver/utility/thread_pool.hpp | 112 ------------------ src/rs_driver/utility/time.h | 46 ------- test/decoder_opt_test.cpp | 4 +- 7 files changed, 67 insertions(+), 216 deletions(-) delete mode 100644 src/rs_driver/utility/thread_pool.hpp delete mode 100644 src/rs_driver/utility/time.h diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index a9e5ece2..3b88b42e 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -70,11 +70,10 @@ typedef struct #include #include #include -#include #include +#include #include #include -#include #include @@ -83,17 +82,24 @@ typedef struct #include #include #include -#include #ifndef _USE_MATH_DEFINES #define _USE_MATH_DEFINES // for VC++, required to use const M_IP in #endif +#include namespace robosense { namespace lidar { +// Echo mode +enum RSEchoMode +{ + ECHO_SINGLE = 0, + ECHO_DUAL +}; + #if 0 const size_t MECH_PKT_LEN = 1248; const size_t MEMS_MSOP_LEN = 1210; @@ -104,13 +110,6 @@ const size_t ROCK_MSOP_LEN = 1236; constexpr int RS_ONE_ROUND = 36000; constexpr uint16_t PROTOCOL_VER_0 = 0x00; -/* Echo mode definition */ -enum RSEchoMode -{ - ECHO_SINGLE = 0, - ECHO_DUAL -}; - template class Decoder { @@ -160,12 +159,12 @@ class Decoder protected: #endif - void toSplit(int32_t azimuth); - void setPointCloudHeader(std::shared_ptr msg, double chan_ts); - template void decodeDifopCommon(const T_Difop& pkt); + void toSplit(int32_t azimuth); + void setPointCloudHeader(std::shared_ptr msg, double chan_ts); + RSDecoderConstParam const_param_; RSDecoderParam param_; std::function excb_; @@ -229,7 +228,7 @@ inline Decoder::Decoder(const RSDecoderParam& param, , num_blks_(0) , point_cloud_seq_(0) { - /* Calulate the lidar_alph0 and lidar_Rxy */ + // calulate lidar_alph0 and lidar_Rxy lidar_alph0_ = std::atan2(const_param_.RY, const_param_.RX) * 180 / M_PI * 100; lidar_Rxy_ = std::sqrt(const_param_.RX * const_param_.RX + const_param_.RY * const_param_.RY); diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 571ecae5..267e0f5a 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -59,27 +59,26 @@ typedef struct { uint8_t id[8]; uint16_t rpm; - RSEthNet eth; + RSEthNetV1 eth; RSFOV fov; uint16_t reserved0; uint16_t phase_lock_angle; - RSVersion version; + RSVersionV1 version; uint8_t reserved_1[242]; - RSSn sn; + RSSN sn; uint16_t zero_cali; uint8_t return_mode; uint16_t sw_ver; RSTimestampYMD timestamp; - RSStatus status; + RSStatusV1 status; uint8_t reserved_2[5]; - RSDiagno diagno; + RSDiagnoV1 diagno; uint8_t gprmc[86]; RSCalibrationAngle ver_angle_cali[32]; RSCalibrationAngle hori_angle_cali[32]; uint8_t reserved_3[586]; uint16_t tail; } RS32DifopPkt; - #pragma pack(pop) template diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index b0a58206..478eece5 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -47,6 +47,9 @@ namespace lidar #pragma pack(push, 1) +// +// msop +// typedef struct { uint8_t year; @@ -59,29 +62,22 @@ typedef struct uint16_t us; } RSTimestampYMD; -typedef struct -{ - uint8_t sec[6]; - uint8_t ss[4]; -} RSTimestampUTC2; - typedef struct { uint8_t sec[6]; uint32_t us; } RSTimestampUTC; -typedef struct +typedef struct { - uint8_t sync_mode; - uint8_t sync_sts; - RSTimestampUTC timestamp; -} RSTimeInfo; + uint8_t sec[6]; + uint8_t ss[4]; +} RSTimestampUTC2; typedef struct { uint8_t tt[2]; -} RsTemprature; +} RSTemprature; typedef struct { @@ -90,7 +86,7 @@ typedef struct RSTimestampYMD timestamp; uint8_t lidar_type; uint8_t reserved_2[7]; - RsTemprature temp; + RSTemprature temp; //uint16_t temp_raw; uint8_t reserved_3[2]; } RSMsopHeaderV1; @@ -101,7 +97,7 @@ typedef struct uint16_t protocol_version; uint8_t reserved_1; uint8_t wave_mode; - RsTemprature temp; + RSTemprature temp; #if 0 uint8_t temp_low; uint8_t temp_high; @@ -112,6 +108,16 @@ typedef struct uint8_t reserved_3[49]; } RSMsopHeaderV2; +typedef struct +{ + uint16_t distance; + uint8_t intensity; +} RSChannel; + +// +// difop +// + typedef struct { uint8_t lidar_ip[4]; @@ -121,7 +127,7 @@ typedef struct uint16_t dest_port; uint16_t port3; uint16_t port4; -} RSEthNet; +} RSEthNetV1; typedef struct { @@ -132,7 +138,7 @@ typedef struct uint16_t reserve_1; uint16_t difop_port; uint16_t reserve_2; -} RSEthNetNew; +} RSEthNetV2; typedef struct { @@ -140,23 +146,11 @@ typedef struct uint16_t end_angle; } RSFOV; -typedef struct -{ - uint8_t sign; - uint16_t value; -} RSCalibrationAngle; - -typedef struct -{ - uint16_t distance; - uint8_t intensity; -} RSChannel; - typedef struct { uint8_t top_ver[5]; uint8_t bottom_ver[5]; -} RSVersion; +} RSVersionV1; typedef struct { @@ -165,12 +159,12 @@ typedef struct uint8_t bot_soft_ver[5]; uint8_t motor_firmware_ver[5]; uint8_t hw_ver[3]; -} RSVersionNew; +} RSVersionV2; typedef struct { uint8_t num[6]; -} RSSn; +} RSSN; typedef struct { @@ -185,7 +179,7 @@ typedef struct uint16_t vol_ejc_5v; uint16_t vol_recv_5v; uint16_t vol_apd; -} RSStatus; +} RSStatusV1; typedef struct { @@ -196,7 +190,7 @@ typedef struct uint16_t vol_sim_5v; uint16_t vol_apd; uint8_t reserved[12]; -} RSStatusNew; +} RSStatusV2; typedef struct { @@ -213,7 +207,7 @@ typedef struct uint8_t reserved_2[5]; uint16_t cur_rpm; uint8_t reserved_3[7]; -} RSDiagno; +} RSDiagnoV1; typedef struct { @@ -228,7 +222,20 @@ typedef struct uint16_t main_status; uint8_t gps_status; uint8_t reserved[22]; -} RSDiagnoNew; +} RSDiagnoV2; + +typedef struct +{ + uint8_t sign; + uint16_t value; +} RSCalibrationAngle; + +typedef struct +{ + uint8_t sync_mode; + uint8_t sync_sts; + RSTimestampUTC timestamp; +} RSTimeInfo; #pragma pack(pop) @@ -335,7 +342,7 @@ inline uint64_t calcTimeHost(void) return t_us.count(); } -inline int16_t calcTemp(const RsTemprature* tmp) +inline int16_t calcTemp(const RSTemprature* tmp) { // | lsb | padding | neg | msb | // | 5 | 3 | 1 | 7 | (in bits) diff --git a/src/rs_driver/driver/decoder/trigon.hpp b/src/rs_driver/driver/decoder/trigon.hpp index 8c3ed54d..9d7617c8 100644 --- a/src/rs_driver/driver/decoder/trigon.hpp +++ b/src/rs_driver/driver/decoder/trigon.hpp @@ -32,6 +32,10 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once +#ifndef _USE_MATH_DEFINES +#define _USE_MATH_DEFINES // for VC++, required to use const M_IP in +#endif + #include namespace robosense diff --git a/src/rs_driver/utility/thread_pool.hpp b/src/rs_driver/utility/thread_pool.hpp deleted file mode 100644 index 00264a9d..00000000 --- a/src/rs_driver/utility/thread_pool.hpp +++ /dev/null @@ -1,112 +0,0 @@ -/********************************************************************************************************************* -Copyright (c) 2020 RoboSense -All rights reserved - -By downloading, copying, installing or using the software you agree to this license. If you do not agree to this -license, do not download, install, copy or use the software. - -License Agreement -For RoboSense LiDAR SDK Library -(3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials provided with the distribution. - -3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used -to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*********************************************************************************************************************/ - -#pragma once -#include -namespace robosense -{ -namespace lidar -{ -constexpr uint16_t MAX_THREAD_NUM = 2; -struct Thread -{ - Thread() : start_(false) - { - } - std::shared_ptr thread_; - std::atomic start_; -}; -class ThreadPool -{ -public: - typedef std::shared_ptr Ptr; - inline ThreadPool() : stop_flag_(false), idl_thr_num_(MAX_THREAD_NUM) - { - for (int i = 0; i < idl_thr_num_; ++i) - { - pool_.emplace_back([this] { - while (!this->stop_flag_) - { - std::function task; - { - std::unique_lock lock{ this->mutex_ }; - this->cv_task_.wait(lock, [this] { return this->stop_flag_.load() || !this->tasks_.empty(); }); - if (this->stop_flag_ && this->tasks_.empty()) - return; - task = std::move(this->tasks_.front()); - this->tasks_.pop(); - } - idl_thr_num_--; - task(); - idl_thr_num_++; - } - }); - } - } - - inline ~ThreadPool() - { - stop_flag_.store(true); - cv_task_.notify_all(); - for (std::thread& thread : pool_) - { - thread.join(); - } - } - -public: - template - inline void commit(F&& f, Args&&... args) - { - if (stop_flag_.load()) - throw std::runtime_error("Commit on LiDAR threadpool is stopped."); - using RetType = decltype(f(args...)); - auto task = - std::make_shared>(std::bind(std::forward(f), std::forward(args)...)); - { - std::lock_guard lock{ mutex_ }; - tasks_.emplace([task]() { (*task)(); }); - } - cv_task_.notify_one(); - } - -private: - using Task = std::function; - std::vector pool_; - std::queue tasks_; - std::mutex mutex_; - std::condition_variable cv_task_; - std::atomic stop_flag_; - std::atomic idl_thr_num_; -}; -} // namespace lidar -} // namespace robosense \ No newline at end of file diff --git a/src/rs_driver/utility/time.h b/src/rs_driver/utility/time.h deleted file mode 100644 index 116c00bc..00000000 --- a/src/rs_driver/utility/time.h +++ /dev/null @@ -1,46 +0,0 @@ -/********************************************************************************************************************* -Copyright (c) 2020 RoboSense -All rights reserved - -By downloading, copying, installing or using the software you agree to this license. If you do not agree to this -license, do not download, install, copy or use the software. - -License Agreement -For RoboSense LiDAR SDK Library -(3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials provided with the distribution. - -3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used -to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*********************************************************************************************************************/ - -#pragma once -#include -namespace robosense -{ -namespace lidar -{ -inline double getTime(void) -{ - const auto t = std::chrono::system_clock::now(); - const auto t_sec = std::chrono::duration_cast>(t.time_since_epoch()); - return (double)t_sec.count(); -} -} // namespace lidar -} // namespace robosense \ No newline at end of file diff --git a/test/decoder_opt_test.cpp b/test/decoder_opt_test.cpp index 319e0dc4..1e1e6410 100644 --- a/test/decoder_opt_test.cpp +++ b/test/decoder_opt_test.cpp @@ -31,12 +31,12 @@ TEST(TestParseTemp, calcTemp) { { uint8_t temp[] = {0x18, 0x01}; - ASSERT_EQ(calcTemp((RsTemprature*)&temp), 35); + ASSERT_EQ(calcTemp((RSTemprature*)&temp), 35); } { uint8_t temp[] = {0x18, 0x81}; - ASSERT_EQ(calcTemp((RsTemprature*)&temp), -35); + ASSERT_EQ(calcTemp((RSTemprature*)&temp), -35); } } From c452c17ebbdf9531c1c94b3fcf30452717a1523a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 20:23:06 +0800 Subject: [PATCH 085/379] refac: refactory decoder --- src/rs_driver/driver/decoder/block_diff.hpp | 35 ++++ src/rs_driver/driver/decoder/chan_angles.hpp | 14 +- src/rs_driver/driver/decoder/decoder.hpp | 178 +++++++----------- src/rs_driver/driver/decoder/decoder_RS32.hpp | 3 +- .../driver/decoder/decoder_base_opt.hpp | 52 ----- src/rs_driver/driver/decoder/section.hpp | 88 +++++++++ test/CMakeLists.txt | 1 + test/decoder_opt_test.cpp | 53 ------ test/section_test.cpp | 60 ++++++ 9 files changed, 266 insertions(+), 218 deletions(-) create mode 100644 src/rs_driver/driver/decoder/section.hpp create mode 100644 test/section_test.cpp diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index 029ca261..59e4c559 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -36,6 +36,41 @@ namespace robosense namespace lidar { +typedef struct +{ + uint16_t MSOP_LEN; + uint16_t DIFOP_LEN; + + // identity + uint8_t MSOP_ID_LEN; + uint8_t DIFOP_ID_LEN; + uint8_t MSOP_ID[8]; + uint8_t DIFOP_ID[8]; + uint8_t BLOCK_ID[2]; + + // duration + uint16_t BLOCKS_PER_PKT; + uint16_t CHANNELS_PER_BLOCK; + //uint16_t LASER_NUM; // diff from CHANNELS_PER_BLOCK ? + + // distance resolution + float DISTANCE_MIN; + float DISTANCE_MAX; + float DISTANCE_RES; + float TEMPERATURE_RES; + + // lens center + float RX; + float RY; + float RZ; + + // firing_ts / block_ts, chan_ts + double BLOCK_DURATION; + double CHAN_TSS[128]; + float CHAN_AZIS[128]; + +} RSDecoderConstParam; + template class SingleReturnBlockDiff { diff --git a/src/rs_driver/driver/decoder/chan_angles.hpp b/src/rs_driver/driver/decoder/chan_angles.hpp index c496f9d3..c3757bed 100644 --- a/src/rs_driver/driver/decoder/chan_angles.hpp +++ b/src/rs_driver/driver/decoder/chan_angles.hpp @@ -32,21 +32,23 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#include - #include #include #include -#include -#include -#include -#include namespace robosense { namespace lidar { +#pragma pack(push, 1) +typedef struct +{ + uint8_t sign; + uint16_t value; +} RSCalibrationAngle; +#pragma pack(pop) + class ChanAngles { public: diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 3b88b42e..5c263959 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -32,61 +32,22 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -typedef struct -{ - uint16_t MSOP_LEN; - uint16_t DIFOP_LEN; - - // identity - uint8_t MSOP_ID_LEN; - uint8_t DIFOP_ID_LEN; - uint8_t MSOP_ID[8]; - uint8_t DIFOP_ID[8]; - uint8_t BLOCK_ID[2]; - - // duration - uint16_t BLOCKS_PER_PKT; - uint16_t CHANNELS_PER_BLOCK; - //uint16_t LASER_NUM; // diff from CHANNELS_PER_BLOCK ? - - // distance resolution - float DISTANCE_MIN; - float DISTANCE_MAX; - float DISTANCE_RES; - float TEMPERATURE_RES; - - // lens center - float RX; - float RY; - float RZ; - - // firing_ts / block_ts, chan_ts - double BLOCK_DURATION; - double CHAN_TSS[128]; - float CHAN_AZIS[128]; - -} RSDecoderConstParam; - +#include +#include #include #include #include -#include +#include #include -#include -#include - -#include - -#include -#include -#include -#include -#include +#include #ifndef _USE_MATH_DEFINES #define _USE_MATH_DEFINES // for VC++, required to use const M_IP in #endif #include +#include +#include +#include namespace robosense { @@ -107,54 +68,32 @@ const size_t MEMS_DIFOP_LEN = 256; const size_t ROCK_MSOP_LEN = 1236; #endif -constexpr int RS_ONE_ROUND = 36000; -constexpr uint16_t PROTOCOL_VER_0 = 0x00; - template class Decoder { public: - void processDifopPkt(const uint8_t* pkt, size_t size); - virtual void decodeDifopPkt(const uint8_t* pkt, size_t size) = 0; + constexpr static int32_t RS_ONE_ROUND = 36000; + constexpr static uint16_t PROTOCOL_VER_0 = 0x00; - void processMsopPkt(const uint8_t* pkt, size_t size); + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size) = 0; virtual void decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; - virtual ~Decoder() = default; - void regRecvCallback(const std::function(void)>& cb_get, - const std::function)>& cb_put); - - float getTemperature() - { - return temperature_; - } - - double getPacketDiff() - { - return this->const_param_.BLOCK_DURATION * const_param_.BLOCKS_PER_PKT; - } - - void print () - { - std::cout << "-----------------------------------------" << std::endl - << "rps:\t\t\t" << this->rps_ << std::endl - << "echo_mode:\t\t" << this->echo_mode_ << std::endl - << "blks_per_frame:\t\t" << this->blks_per_frame_ << std::endl - << "split_blks_per_frame:\t" << this->split_blks_per_frame_ << std::endl - << "block_azi_diff:\t\t" << this->block_azi_diff_ << std::endl - << "fov_blind_ts_diff:\t" << this->fov_blind_ts_diff_ << std::endl - << "angle_from_file:\t" << this->param_.config_from_file << std::endl - << "angles_ready:\t\t" << this->angles_ready_ << std::endl; - - this->chan_angles_.print(); - } - explicit Decoder(const RSDecoderParam& param, const std::function& excb, const RSDecoderConstParam& const_param); + void processDifopPkt(const uint8_t* pkt, size_t size); + void processMsopPkt(const uint8_t* pkt, size_t size); + + void regRecvCallback(const std::function(void)>& cb_get, + const std::function)>& cb_put); + + float getTemperature(); + double getPacketDiff(); + void print(); + #ifndef UNIT_TEST protected: #endif @@ -165,41 +104,42 @@ class Decoder void toSplit(int32_t azimuth); void setPointCloudHeader(std::shared_ptr msg, double chan_ts); - RSDecoderConstParam const_param_; - RSDecoderParam param_; + RSDecoderConstParam const_param_; // const param of lidar/decoder + RSDecoderParam param_; // user param of lidar/decoder std::function excb_; - uint16_t height_; + uint16_t height_; Trigon trigon_; #define SIN(angle) this->trigon_.sin(angle) #define COS(angle) this->trigon_.cos(angle) - ChanAngles chan_angles_; - DistanceBlock distance_block_; - ScanBlock scan_block_; - SplitAngle split_angle_; + ChanAngles chan_angles_; // vert_angles/horiz_angles adjustment + DistanceSection distance_section_; // valid distance section + AzimuthSection scan_section_; // valid azimuth section + SplitAngle split_angle_; // angle to split frame - uint16_t blks_per_frame_; - uint16_t split_blks_per_frame_; - uint16_t block_azi_diff_; - float fov_blind_ts_diff_; + uint16_t blks_per_frame_; // blocks per frame/round + uint16_t split_blks_per_frame_; // blocks in msop pkt per frame/round. + // dependent on return mode. + uint16_t block_azi_diff_; // azimuth difference between adjacent blocks. + float fov_blind_ts_diff_; // timestamp difference across blind section(defined by fov) - unsigned int protocol_ver_; - uint16_t rps_; - RSEchoMode echo_mode_; - float temperature_; + unsigned int protocol_ver_; // protocol version of MSOP/DIFOP + uint16_t rps_; // rounds per second + RSEchoMode echo_mode_; // echo mode (defined by return mode) + float temperature_; // lidar temperature - bool angles_ready_; - double prev_chan_ts_; - uint16_t num_blks_; + bool angles_ready_; // is vert_angles/horiz_angles ready from csv file/difop packet? + double prev_chan_ts_; // previous channel/point timestamp + uint16_t num_blks_; // number of blocks in current point cloud - int lidar_alph0_; // atan2(Ry, Rx) * 180 / M_PI * 100 - float lidar_Rxy_; // sqrt(Rx*Rx + Ry*Ry) + int lidar_alph0_; // lens center related + float lidar_Rxy_; // lens center related std::function(void)> point_cloud_cb_get_; std::function)> point_cloud_cb_put_; - std::shared_ptr point_cloud_; - uint32_t point_cloud_seq_; + std::shared_ptr point_cloud_; // curernt point cloud + uint32_t point_cloud_seq_; // sequence of point cloud }; template @@ -211,9 +151,9 @@ inline Decoder::Decoder(const RSDecoderParam& param, , excb_(excb) , height_(const_param.CHANNELS_PER_BLOCK) , chan_angles_(const_param.CHANNELS_PER_BLOCK) - , distance_block_(const_param.DISTANCE_MIN, const_param.DISTANCE_MAX, + , distance_section_(const_param.DISTANCE_MIN, const_param.DISTANCE_MAX, param.min_distance, param.max_distance) - , scan_block_(param.start_angle * 100, param.end_angle * 100) + , scan_section_(param.start_angle * 100, param.end_angle * 100) , split_angle_(param.split_angle * 100) , blks_per_frame_(1/(10*const_param.BLOCK_DURATION)) , split_blks_per_frame_(blks_per_frame_) @@ -239,6 +179,34 @@ inline Decoder::Decoder(const RSDecoderParam& param, } } +template +void Decoder::print() +{ + std::cout << "-----------------------------------------" << std::endl + << "rps:\t\t\t" << this->rps_ << std::endl + << "echo_mode:\t\t" << this->echo_mode_ << std::endl + << "blks_per_frame:\t\t" << this->blks_per_frame_ << std::endl + << "split_blks_per_frame:\t" << this->split_blks_per_frame_ << std::endl + << "block_azi_diff:\t\t" << this->block_azi_diff_ << std::endl + << "fov_blind_ts_diff:\t" << this->fov_blind_ts_diff_ << std::endl + << "angle_from_file:\t" << this->param_.config_from_file << std::endl + << "angles_ready:\t\t" << this->angles_ready_ << std::endl; + + this->chan_angles_.print(); +} + +template +float Decoder::getTemperature() +{ + return temperature_; +} + +template +double Decoder::getPacketDiff() +{ + return this->const_param_.BLOCK_DURATION * const_param_.BLOCKS_PER_PKT; +} + template void Decoder::regRecvCallback( const std::function(void)>& cb_get, diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 267e0f5a..a5ea9a46 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -189,7 +189,6 @@ inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, siz template inline void DecoderRS32::decodeMsopPkt(const uint8_t* pkt, size_t size) { - //return; if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { internDecodeMsopPkt>(pkt, size); @@ -252,7 +251,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; uint8_t intensity = channel.intensity; - if (this->distance_block_.in(distance) && this->scan_block_.in(angle_horiz_final)) + if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 478eece5..0f6e9b49 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -224,11 +224,6 @@ typedef struct uint8_t reserved[22]; } RSDiagnoV2; -typedef struct -{ - uint8_t sign; - uint16_t value; -} RSCalibrationAngle; typedef struct { @@ -356,53 +351,6 @@ inline int16_t calcTemp(const RSTemprature* tmp) return t; } -class ScanBlock -{ -public: - ScanBlock(int32_t start, int32_t end) - { - start_ = start % 36000; - end_ = (end <= 36000) ? end : (end % 36000); - cross_zero_ = (start_ > end_); - } - - bool in(int32_t angle) - { - if (cross_zero_) - return (angle >= start_) || (angle < end_); - else - return (angle >= start_) && (angle < end_); - } - -#ifndef UNIT_TEST -private: -#endif - int32_t start_; - int32_t end_; - bool cross_zero_; -}; - -class DistanceBlock -{ -public: - DistanceBlock (float min, float max, float usr_min, float usr_max) - : min_((usr_min > min) ? usr_min : min), max_((usr_max < max) ? usr_max : max) - { - } - - bool in(float distance) - { - return ((min_ <= distance) && (distance <= max_)); - } - -#ifndef UNIT_TEST -private: -#endif - - float min_; - float max_; -}; - class SplitAngle { public: diff --git a/src/rs_driver/driver/decoder/section.hpp b/src/rs_driver/driver/decoder/section.hpp new file mode 100644 index 00000000..f35a3184 --- /dev/null +++ b/src/rs_driver/driver/decoder/section.hpp @@ -0,0 +1,88 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +namespace robosense +{ +namespace lidar +{ + +class AzimuthSection +{ +public: + AzimuthSection(int32_t start, int32_t end) + { + start_ = start % 36000; + end_ = (end <= 36000) ? end : (end % 36000); + cross_zero_ = (start_ > end_); + } + + bool in(int32_t angle) + { + if (cross_zero_) + return (angle >= start_) || (angle < end_); + else + return (angle >= start_) && (angle < end_); + } + +#ifndef UNIT_TEST +private: +#endif + int32_t start_; + int32_t end_; + bool cross_zero_; +}; + +class DistanceSection +{ +public: + DistanceSection (float min, float max, float usr_min, float usr_max) + : min_((usr_min > min) ? usr_min : min), max_((usr_max < max) ? usr_max : max) + { + } + + bool in(float distance) + { + return ((min_ <= distance) && (distance <= max_)); + } + +#ifndef UNIT_TEST +private: +#endif + + float min_; + float max_; +}; + +} // namespace lidar +} // namespace robosense diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 242e384f..c93d73ef 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -16,6 +16,7 @@ add_executable(rs_driver_test single_return_block_diff_test.cpp dual_return_block_diff_test.cpp decoder_opt_test.cpp + section_test.cpp chan_angles_test.cpp trigon_test.cpp decoder_test.cpp diff --git a/test/decoder_opt_test.cpp b/test/decoder_opt_test.cpp index 1e1e6410..f900c7c5 100644 --- a/test/decoder_opt_test.cpp +++ b/test/decoder_opt_test.cpp @@ -40,59 +40,6 @@ TEST(TestParseTemp, calcTemp) } } -TEST(TestScanBlock, ctor) -{ - ScanBlock blk(10, 20); - ASSERT_EQ(blk.start_, 10); - ASSERT_EQ(blk.end_, 20); - - ASSERT_FALSE(blk.in(5)); - ASSERT_TRUE(blk.in(10)); - ASSERT_TRUE(blk.in(15)); - ASSERT_FALSE(blk.in(20)); - ASSERT_FALSE(blk.in(25)); -} - -TEST(TestScanBlock, ctorCrossZero) -{ - ScanBlock blk(35000, 10); - ASSERT_EQ(blk.start_, 35000); - ASSERT_EQ(blk.end_, 10); - - ASSERT_FALSE(blk.in(34999)); - ASSERT_TRUE(blk.in(35000)); - ASSERT_TRUE(blk.in(0)); - ASSERT_FALSE(blk.in(10)); - ASSERT_FALSE(blk.in(15)); -} - -TEST(TestScanBlock, ctorBeyondRound) -{ - ScanBlock blk(36100, 36200); - ASSERT_EQ(blk.start_, 100); - ASSERT_EQ(blk.end_, 200); -} - -TEST(TestDistanceBlock, ctor) -{ - DistanceBlock blk(0.5, 200, 0.75, 150); - ASSERT_EQ(blk.min_, 0.75); - ASSERT_EQ(blk.max_, 150); - - ASSERT_FALSE(blk.in(0.45)); - ASSERT_TRUE(blk.in(0.75)); - ASSERT_TRUE(blk.in(0.8)); - ASSERT_TRUE(blk.in(150)); - ASSERT_FALSE(blk.in(150.5)); -} - -TEST(TestDistanceBlock, ctorNoUseBlock) -{ - DistanceBlock blk(0.5, 200, 0.0, 200.5); - ASSERT_EQ(blk.min_, 0.5); - ASSERT_EQ(blk.max_, 200); -} - TEST(TestSplitAngle, toSplit) { { diff --git a/test/section_test.cpp b/test/section_test.cpp new file mode 100644 index 00000000..d446fb16 --- /dev/null +++ b/test/section_test.cpp @@ -0,0 +1,60 @@ + +#include + +#include + +using namespace robosense::lidar; + +TEST(TestAzimuthSection, ctor) +{ + AzimuthSection sec(10, 20); + ASSERT_EQ(sec.start_, 10); + ASSERT_EQ(sec.end_, 20); + + ASSERT_FALSE(sec.in(5)); + ASSERT_TRUE(sec.in(10)); + ASSERT_TRUE(sec.in(15)); + ASSERT_FALSE(sec.in(20)); + ASSERT_FALSE(sec.in(25)); +} + +TEST(TestAzimuthSection, ctorCrossZero) +{ + AzimuthSection sec(35000, 10); + ASSERT_EQ(sec.start_, 35000); + ASSERT_EQ(sec.end_, 10); + + ASSERT_FALSE(sec.in(34999)); + ASSERT_TRUE(sec.in(35000)); + ASSERT_TRUE(sec.in(0)); + ASSERT_FALSE(sec.in(10)); + ASSERT_FALSE(sec.in(15)); +} + +TEST(TestAzimuthSection, ctorBeyondRound) +{ + AzimuthSection sec(36100, 36200); + ASSERT_EQ(sec.start_, 100); + ASSERT_EQ(sec.end_, 200); +} + +TEST(TestDistanceSection, ctor) +{ + DistanceSection sec(0.5, 200, 0.75, 150); + ASSERT_EQ(sec.min_, 0.75); + ASSERT_EQ(sec.max_, 150); + + ASSERT_FALSE(sec.in(0.45)); + ASSERT_TRUE(sec.in(0.75)); + ASSERT_TRUE(sec.in(0.8)); + ASSERT_TRUE(sec.in(150)); + ASSERT_FALSE(sec.in(150.5)); +} + +TEST(TestDistanceSection, ctorNoUseBlock) +{ + DistanceSection sec(0.5, 200, 0.0, 200.5); + ASSERT_EQ(sec.min_, 0.5); + ASSERT_EQ(sec.max_, 200); +} + From a630fe408d6fc36fca8d9b0770e267d9abd8bdce Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 20:46:25 +0800 Subject: [PATCH 086/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder_base_opt.hpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/decoder_base_opt.hpp index 0f6e9b49..38b92a3f 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/decoder_base_opt.hpp @@ -366,6 +366,12 @@ class SplitAngle prev_angle_ -= 36000; bool v = ((prev_angle_ < split_angle_) && (split_angle_ <= angle)); +#if 0 + if (v) + { + std::cout << prev_angle_ << "\t" << angle << std::endl; + } +#endif prev_angle_ = angle; return v; } From c57fa42863a956bafa6e429b1e051cf6483bb9ad Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Dec 2021 20:58:29 +0800 Subject: [PATCH 087/379] refac: refactory decoder --- src/rs_driver/driver/decoder/block_diff.hpp | 57 ++++--------------- src/rs_driver/driver/decoder/decoder.hpp | 36 ++++++++++++ src/rs_driver/driver/decoder/decoder_RS32.hpp | 2 +- test/dual_return_block_diff_test.cpp | 3 +- test/single_return_block_diff_test.cpp | 3 +- 5 files changed, 53 insertions(+), 48 deletions(-) diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index 59e4c559..f0418ffe 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -36,41 +36,6 @@ namespace robosense namespace lidar { -typedef struct -{ - uint16_t MSOP_LEN; - uint16_t DIFOP_LEN; - - // identity - uint8_t MSOP_ID_LEN; - uint8_t DIFOP_ID_LEN; - uint8_t MSOP_ID[8]; - uint8_t DIFOP_ID[8]; - uint8_t BLOCK_ID[2]; - - // duration - uint16_t BLOCKS_PER_PKT; - uint16_t CHANNELS_PER_BLOCK; - //uint16_t LASER_NUM; // diff from CHANNELS_PER_BLOCK ? - - // distance resolution - float DISTANCE_MIN; - float DISTANCE_MAX; - float DISTANCE_RES; - float TEMPERATURE_RES; - - // lens center - float RX; - float RY; - float RZ; - - // firing_ts / block_ts, chan_ts - double BLOCK_DURATION; - double CHAN_TSS[128]; - float CHAN_AZIS[128]; - -} RSDecoderConstParam; - template class SingleReturnBlockDiff { @@ -81,7 +46,7 @@ class SingleReturnBlockDiff float ret = 0.0f; if (blk > 0) { - ret = this->const_param_.BLOCK_DURATION; + ret = BLOCK_DURATION; } return ret; @@ -91,7 +56,7 @@ class SingleReturnBlockDiff { int32_t azi= 0; - if (blk < (this->const_param_.BLOCKS_PER_PKT - 1)) + if (blk < (BLOCKS_PER_PKT - 1)) azi = this->pkt_.blocks[blk+1].azimuth - this->pkt_.blocks[blk].azimuth; else azi = this->pkt_.blocks[blk].azimuth - this->pkt_.blocks[blk-1].azimuth; @@ -99,14 +64,15 @@ class SingleReturnBlockDiff return azi; } - SingleReturnBlockDiff(const RSDecoderConstParam const_param, const T_Packet& pkt) - : const_param_(const_param), pkt_(pkt) + SingleReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration) + : pkt_(pkt), BLOCKS_PER_PKT(blocks_per_pkt), BLOCK_DURATION(block_duration) { } protected: - const RSDecoderConstParam const_param_; const T_Packet& pkt_; + const uint16_t BLOCKS_PER_PKT; + const double BLOCK_DURATION; }; template @@ -121,7 +87,7 @@ class DualReturnBlockDiff if ((blk % 2 == 0) && (blk != 0)) { - ret = this->const_param_.BLOCK_DURATION; + ret = BLOCK_DURATION; } return ret; @@ -131,7 +97,7 @@ class DualReturnBlockDiff { int32_t azi = 0; - if (blk >= (this->const_param_.BLOCKS_PER_PKT - 2)) + if (blk >= (BLOCKS_PER_PKT - 2)) { azi = this->pkt_.blocks[blk].azimuth - this->pkt_.blocks[blk-2].azimuth; } @@ -143,14 +109,15 @@ class DualReturnBlockDiff return azi; } - DualReturnBlockDiff(const RSDecoderConstParam const_param, const T_Packet& pkt) - : const_param_(const_param), pkt_(pkt) + DualReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration) + : pkt_(pkt), BLOCKS_PER_PKT(blocks_per_pkt), BLOCK_DURATION(block_duration) { } protected: - const RSDecoderConstParam const_param_; const T_Packet& pkt_; + const uint16_t BLOCKS_PER_PKT; + const double BLOCK_DURATION; }; } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 5c263959..66dbebe0 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -61,6 +61,42 @@ enum RSEchoMode ECHO_DUAL }; +typedef struct +{ + uint16_t MSOP_LEN; + uint16_t DIFOP_LEN; + + // identity + uint8_t MSOP_ID_LEN; + uint8_t DIFOP_ID_LEN; + uint8_t MSOP_ID[8]; + uint8_t DIFOP_ID[8]; + uint8_t BLOCK_ID[2]; + + // duration + uint16_t BLOCKS_PER_PKT; + uint16_t CHANNELS_PER_BLOCK; + //uint16_t LASER_NUM; // diff from CHANNELS_PER_BLOCK ? + + // distance resolution + float DISTANCE_MIN; + float DISTANCE_MAX; + float DISTANCE_RES; + float TEMPERATURE_RES; + + // lens center + float RX; + float RY; + float RZ; + + // firing_ts / block_ts, chan_ts + double BLOCK_DURATION; + double CHAN_TSS[128]; + float CHAN_AZIS[128]; + +} RSDecoderConstParam; + + #if 0 const size_t MECH_PKT_LEN = 1248; const size_t MEMS_MSOP_LEN = 1210; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index a5ea9a46..2bce3655 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -217,7 +217,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet pkt_ts = calcTimeHost(); } - T_BlockDiff diff(this->const_param_, pkt); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_diff_test.cpp index af16059b..df01e0a6 100644 --- a/test/dual_return_block_diff_test.cpp +++ b/test/dual_return_block_diff_test.cpp @@ -62,7 +62,8 @@ TEST(TestDualPacketTraverser, toNext) , 51, 0x00, 0x00, 0x00, 0x00 }; - DualReturnBlockDiff diff(const_param, pkt); + DualReturnBlockDiff diff(pkt, + const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); ASSERT_EQ(diff.ts(0), 0.0f); ASSERT_EQ(diff.ts(1), 0.0f); diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_diff_test.cpp index 8c4af05b..52a5eb98 100644 --- a/test/single_return_block_diff_test.cpp +++ b/test/single_return_block_diff_test.cpp @@ -59,7 +59,8 @@ TEST(TestSingleReturnBlockDiff, ctor) , 51, 0x00, 0x00, 0x00, 0x00 }; - SingleReturnBlockDiff diff(const_param, pkt); + SingleReturnBlockDiff diff(pkt, + const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); ASSERT_EQ(diff.ts(0), 0.0f); ASSERT_EQ(diff.ts(1), 0.5f); From 6a8dab8af30db5519e154b6d6ad4867294fafe73 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 17 Dec 2021 09:23:44 +0800 Subject: [PATCH 088/379] refac: refactory decoder --- src/rs_driver/common/common_header.h | 5 +- .../{decoder_base_opt.hpp => basic_attr.hpp} | 32 --------- src/rs_driver/driver/decoder/decoder.hpp | 6 +- .../decoder/split_strategy.hpp} | 72 ++++++------------- test/CMakeLists.txt | 3 +- ...coder_opt_test.cpp => basic_attr_test.cpp} | 47 +----------- test/split_strategy_test.cpp | 52 ++++++++++++++ 7 files changed, 83 insertions(+), 134 deletions(-) rename src/rs_driver/driver/decoder/{decoder_base_opt.hpp => basic_attr.hpp} (93%) rename src/rs_driver/{utility/lock_queue.h => driver/decoder/split_strategy.hpp} (67%) rename test/{decoder_opt_test.cpp => basic_attr_test.cpp} (52%) create mode 100644 test/split_strategy_test.cpp diff --git a/src/rs_driver/common/common_header.h b/src/rs_driver/common/common_header.h index c384d385..c8e08f09 100644 --- a/src/rs_driver/common/common_header.h +++ b/src/rs_driver/common/common_header.h @@ -35,6 +35,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #if defined(_WIN32) + #include #include inline void setConsoleColor(WORD c) @@ -42,10 +43,8 @@ inline void setConsoleColor(WORD c) HANDLE hConsole = GetStdHandle(STD_OUTPUT_HANDLE); SetConsoleTextAttribute(hConsole, c); } -#endif -/*Camera*/ -typedef std::pair CameraTrigger; +#endif /*Output style*/ #ifndef RS_INFOL diff --git a/src/rs_driver/driver/decoder/decoder_base_opt.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp similarity index 93% rename from src/rs_driver/driver/decoder/decoder_base_opt.hpp rename to src/rs_driver/driver/decoder/basic_attr.hpp index 38b92a3f..2d73c8a2 100644 --- a/src/rs_driver/driver/decoder/decoder_base_opt.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -351,37 +351,5 @@ inline int16_t calcTemp(const RSTemprature* tmp) return t; } -class SplitAngle -{ -public: - SplitAngle (int32_t split_angle) - : split_angle_(split_angle), - prev_angle_(split_angle) - { - } - - bool toSplit(int32_t angle) - { - if (angle < prev_angle_) - prev_angle_ -= 36000; - - bool v = ((prev_angle_ < split_angle_) && (split_angle_ <= angle)); -#if 0 - if (v) - { - std::cout << prev_angle_ << "\t" << angle << std::endl; - } -#endif - prev_angle_ = angle; - return v; - } - -#ifndef UNIT_TEST -private: -#endif - int32_t split_angle_; - int32_t prev_angle_; -}; - } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 66dbebe0..0786e71f 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -36,9 +36,11 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include #include -#include +#include +#include +#include +#include #include #ifndef _USE_MATH_DEFINES diff --git a/src/rs_driver/utility/lock_queue.h b/src/rs_driver/driver/decoder/split_strategy.hpp similarity index 67% rename from src/rs_driver/utility/lock_queue.h rename to src/rs_driver/driver/decoder/split_strategy.hpp index 56e19d12..bfc0840e 100644 --- a/src/rs_driver/utility/lock_queue.h +++ b/src/rs_driver/driver/decoder/split_strategy.hpp @@ -31,71 +31,43 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include + namespace robosense { namespace lidar { -template -class Queue + +class SplitAngle { public: - inline Queue() : is_task_finished_(true) - { - } - - inline T front() + SplitAngle (int32_t split_angle) + : split_angle_(split_angle), + prev_angle_(split_angle) { - std::lock_guard lock(mutex_); - return queue_.front(); } - inline void push(const T& value) + bool toSplit(int32_t angle) { - std::lock_guard lock(mutex_); - queue_.push(value); - } + if (angle < prev_angle_) + prev_angle_ -= 36000; - inline void pop() - { - std::lock_guard lock(mutex_); - if (!queue_.empty()) + bool v = ((prev_angle_ < split_angle_) && (split_angle_ <= angle)); +#if 0 + if (v) { - queue_.pop(); + std::cout << prev_angle_ << "\t" << angle << std::endl; } +#endif + prev_angle_ = angle; + return v; } - inline T popFront() - { - T value; - std::lock_guard lock(mutex_); - if (!queue_.empty()) - { - value = std::move(queue_.front()); - queue_.pop(); - } - return value; - } - - inline void clear() - { - std::queue empty; - std::lock_guard lock(mutex_); - swap(empty, queue_); - } - - inline size_t size() - { - std::lock_guard lock(mutex_); - return queue_.size(); - } - -public: - std::queue queue_; - std::atomic is_task_finished_; - +#ifndef UNIT_TEST private: - mutable std::mutex mutex_; +#endif + int32_t split_angle_; + int32_t prev_angle_; }; + } // namespace lidar -} // namespace robosense \ No newline at end of file +} // namespace robosense diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index c93d73ef..2ee76586 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -15,7 +15,8 @@ add_executable(rs_driver_test sync_queue_test.cpp single_return_block_diff_test.cpp dual_return_block_diff_test.cpp - decoder_opt_test.cpp + basic_attr_test.cpp + split_strategy_test.cpp section_test.cpp chan_angles_test.cpp trigon_test.cpp diff --git a/test/decoder_opt_test.cpp b/test/basic_attr_test.cpp similarity index 52% rename from test/decoder_opt_test.cpp rename to test/basic_attr_test.cpp index f900c7c5..9f34a127 100644 --- a/test/decoder_opt_test.cpp +++ b/test/basic_attr_test.cpp @@ -1,7 +1,7 @@ #include -#include +#include using namespace robosense::lidar; @@ -40,48 +40,3 @@ TEST(TestParseTemp, calcTemp) } } -TEST(TestSplitAngle, toSplit) -{ - { - SplitAngle sa(10); - ASSERT_FALSE(sa.toSplit(5)); - ASSERT_TRUE(sa.toSplit(15)); - } - - { - SplitAngle sa(10); - ASSERT_FALSE(sa.toSplit(5)); - ASSERT_TRUE(sa.toSplit(10)); - ASSERT_FALSE(sa.toSplit(15)); - } - - { - SplitAngle sa(10); - ASSERT_FALSE(sa.toSplit(10)); - ASSERT_FALSE(sa.toSplit(15)); - } -} - -TEST(TestSplitAngle, toSplit_Zero) -{ - { - SplitAngle sa(0); - ASSERT_FALSE(sa.toSplit(35999)); - ASSERT_TRUE(sa.toSplit(1)); - ASSERT_FALSE(sa.toSplit(2)); - } - - { - SplitAngle sa(0); - ASSERT_FALSE(sa.toSplit(35999)); - ASSERT_TRUE(sa.toSplit(0)); - ASSERT_FALSE(sa.toSplit(2)); - } - - { - SplitAngle sa(0); - ASSERT_FALSE(sa.toSplit(0)); - ASSERT_FALSE(sa.toSplit(2)); - } -} - diff --git a/test/split_strategy_test.cpp b/test/split_strategy_test.cpp new file mode 100644 index 00000000..6033c029 --- /dev/null +++ b/test/split_strategy_test.cpp @@ -0,0 +1,52 @@ + +#include + +#include + +using namespace robosense::lidar; + +TEST(TestSplitAngle, toSplit) +{ + { + SplitAngle sa(10); + ASSERT_FALSE(sa.toSplit(5)); + ASSERT_TRUE(sa.toSplit(15)); + } + + { + SplitAngle sa(10); + ASSERT_FALSE(sa.toSplit(5)); + ASSERT_TRUE(sa.toSplit(10)); + ASSERT_FALSE(sa.toSplit(15)); + } + + { + SplitAngle sa(10); + ASSERT_FALSE(sa.toSplit(10)); + ASSERT_FALSE(sa.toSplit(15)); + } +} + +TEST(TestSplitAngle, toSplit_Zero) +{ + { + SplitAngle sa(0); + ASSERT_FALSE(sa.toSplit(35999)); + ASSERT_TRUE(sa.toSplit(1)); + ASSERT_FALSE(sa.toSplit(2)); + } + + { + SplitAngle sa(0); + ASSERT_FALSE(sa.toSplit(35999)); + ASSERT_TRUE(sa.toSplit(0)); + ASSERT_FALSE(sa.toSplit(2)); + } + + { + SplitAngle sa(0); + ASSERT_FALSE(sa.toSplit(0)); + ASSERT_FALSE(sa.toSplit(2)); + } +} + From 78e5cd03be4f3a425884071661a0ab1fa8ee2a9e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 17 Dec 2021 10:39:51 +0800 Subject: [PATCH 089/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 55 ++++++---------- .../driver/decoder/split_strategy.hpp | 50 +++++++++++++-- src/rs_driver/driver/driver_param.h | 2 +- test/decoder_test.cpp | 4 -- test/split_strategy_test.cpp | 62 ++++++++++++------- 5 files changed, 103 insertions(+), 70 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 0786e71f..125d433c 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -154,7 +154,7 @@ class Decoder ChanAngles chan_angles_; // vert_angles/horiz_angles adjustment DistanceSection distance_section_; // valid distance section AzimuthSection scan_section_; // valid azimuth section - SplitAngle split_angle_; // angle to split frame + std::shared_ptr split_strategy_; // split strategy uint16_t blks_per_frame_; // blocks per frame/round uint16_t split_blks_per_frame_; // blocks in msop pkt per frame/round. @@ -169,7 +169,6 @@ class Decoder bool angles_ready_; // is vert_angles/horiz_angles ready from csv file/difop packet? double prev_chan_ts_; // previous channel/point timestamp - uint16_t num_blks_; // number of blocks in current point cloud int lidar_alph0_; // lens center related float lidar_Rxy_; // lens center related @@ -192,7 +191,6 @@ inline Decoder::Decoder(const RSDecoderParam& param, , distance_section_(const_param.DISTANCE_MIN, const_param.DISTANCE_MAX, param.min_distance, param.max_distance) , scan_section_(param.start_angle * 100, param.end_angle * 100) - , split_angle_(param.split_angle * 100) , blks_per_frame_(1/(10*const_param.BLOCK_DURATION)) , split_blks_per_frame_(blks_per_frame_) , block_azi_diff_(20) @@ -203,9 +201,25 @@ inline Decoder::Decoder(const RSDecoderParam& param, , temperature_(0.0) , angles_ready_(false) , prev_chan_ts_(0.0) - , num_blks_(0) , point_cloud_seq_(0) { + switch (param_.split_frame_mode) + { + case SplitFrameMode::SPLIT_BY_FIXED_BLKS: + split_strategy_ = std::make_shared(&split_blks_per_frame_); + break; + + case SplitFrameMode::SPLIT_BY_CUSTOM_BLKS: + split_strategy_ = std::make_shared(¶m_.num_blks_split); + break; + + case SplitFrameMode::SPLIT_BY_ANGLE: + default: + uint16_t angle = (uint16_t)(param_.split_angle * 100); + split_strategy_ = std::make_shared(angle); + break; + } + // calulate lidar_alph0 and lidar_Rxy lidar_alph0_ = std::atan2(const_param_.RY, const_param_.RX) * 180 / M_PI * 100; lidar_Rxy_ = std::sqrt(const_param_.RX * const_param_.RX + const_param_.RY * const_param_.RY); @@ -259,38 +273,7 @@ void Decoder::regRecvCallback( template inline void Decoder::toSplit(int32_t azimuth) { - bool split = false; - - switch (param_.split_frame_mode) - { - case SplitFrameMode::SPLIT_BY_ANGLE: - split = split_angle_.toSplit(azimuth); - break; - - case SplitFrameMode::SPLIT_BY_FIXED_BLKS: - - this->num_blks_++; - if (this->num_blks_ >= this->split_blks_per_frame_) - { - this->num_blks_ = 0; - split = true; - } - break; - - case SplitFrameMode::SPLIT_BY_CUSTOM_BLKS: - - this->num_blks_++; - if (this->num_blks_ >= this->param_.num_blks_split) - { - this->num_blks_ = 0; - split = true; - } - break; - - default: - break; - } - + bool split = this->split_strategy_->newBlock(azimuth); if (split) { if (point_cloud_->points.size() > 0) diff --git a/src/rs_driver/driver/decoder/split_strategy.hpp b/src/rs_driver/driver/decoder/split_strategy.hpp index bfc0840e..90dacbba 100644 --- a/src/rs_driver/driver/decoder/split_strategy.hpp +++ b/src/rs_driver/driver/decoder/split_strategy.hpp @@ -37,16 +37,24 @@ namespace robosense namespace lidar { -class SplitAngle +class SplitStrategy { public: - SplitAngle (int32_t split_angle) - : split_angle_(split_angle), - prev_angle_(split_angle) + virtual bool newBlock(int32_t angle) = 0; + virtual ~SplitStrategy() = default; +}; + +class SplitStrategyByAngle : public SplitStrategy +{ +public: + SplitStrategyByAngle (int32_t split_angle) + : split_angle_(split_angle), prev_angle_(split_angle) { } - bool toSplit(int32_t angle) + virtual ~SplitStrategyByAngle() = default; + + virtual bool newBlock(int32_t angle) { if (angle < prev_angle_) prev_angle_ -= 36000; @@ -62,12 +70,42 @@ class SplitAngle return v; } + #ifndef UNIT_TEST private: #endif - int32_t split_angle_; + const int32_t split_angle_; int32_t prev_angle_; }; +class SplitStrategyByNum : public SplitStrategy +{ +public: + SplitStrategyByNum (uint16_t* max_blks) + : max_blks_(max_blks), blks_(0) + { + } + + virtual ~SplitStrategyByNum() = default; + + virtual bool newBlock(int32_t) + { + blks_++; + if (blks_ >= *max_blks_) + { + blks_ = 0; + return true; + } + + return false; + } + +#ifndef UNIT_TEST +private: +#endif + uint16_t* max_blks_; + uint16_t blks_; +}; + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index 902ece8b..ae30cf0c 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -214,7 +214,7 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter ///< 2: Split frames by fixed number of packets; ///< 3: Split frames by custom number of packets (num_pkts_split) float split_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 - uint32_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 + uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 1ef5ad2b..02fa9ddc 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -323,7 +323,6 @@ TEST(TestDecoder, split_by_angle) param.split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; param.split_angle = 0.0f; MyDecoder decoder(param, errCallback, const_param); - ASSERT_EQ(decoder.split_angle_.split_angle_, 0); point_cloud_to_get = std::make_shared(); decoder.regRecvCallback (getCallback, putCallback); @@ -364,7 +363,6 @@ TEST(TestDecoder, split_by_fixed_pkts) param.split_frame_mode = SplitFrameMode::SPLIT_BY_FIXED_BLKS; MyDecoder decoder(param, errCallback, const_param); decoder.split_blks_per_frame_ = 2; - ASSERT_EQ(decoder.num_blks_, 0); point_cloud_to_get = std::make_shared(); decoder.regRecvCallback (getCallback, putCallback); @@ -402,8 +400,6 @@ TEST(TestDecoder, split_by_custom_blks) param.split_frame_mode = SplitFrameMode::SPLIT_BY_CUSTOM_BLKS; param.num_blks_split = 2; MyDecoder decoder(param, errCallback, const_param); - decoder.blks_per_frame_ = 2; - ASSERT_EQ(decoder.num_blks_, 0); point_cloud_to_get = std::make_shared(); decoder.regRecvCallback (getCallback, putCallback); diff --git a/test/split_strategy_test.cpp b/test/split_strategy_test.cpp index 6033c029..a23d3e18 100644 --- a/test/split_strategy_test.cpp +++ b/test/split_strategy_test.cpp @@ -5,48 +5,64 @@ using namespace robosense::lidar; -TEST(TestSplitAngle, toSplit) +TEST(TestSplitStrategyByAngle, newBlock) { { - SplitAngle sa(10); - ASSERT_FALSE(sa.toSplit(5)); - ASSERT_TRUE(sa.toSplit(15)); + SplitStrategyByAngle sa(10); + ASSERT_FALSE(sa.newBlock(5)); + ASSERT_TRUE(sa.newBlock(15)); } { - SplitAngle sa(10); - ASSERT_FALSE(sa.toSplit(5)); - ASSERT_TRUE(sa.toSplit(10)); - ASSERT_FALSE(sa.toSplit(15)); + SplitStrategyByAngle sa(10); + ASSERT_FALSE(sa.newBlock(5)); + ASSERT_TRUE(sa.newBlock(10)); + ASSERT_FALSE(sa.newBlock(15)); } { - SplitAngle sa(10); - ASSERT_FALSE(sa.toSplit(10)); - ASSERT_FALSE(sa.toSplit(15)); + SplitStrategyByAngle sa(10); + ASSERT_FALSE(sa.newBlock(10)); + ASSERT_FALSE(sa.newBlock(15)); } } -TEST(TestSplitAngle, toSplit_Zero) +TEST(TestSplitStrategyByAngle, newBlock_Zero) { { - SplitAngle sa(0); - ASSERT_FALSE(sa.toSplit(35999)); - ASSERT_TRUE(sa.toSplit(1)); - ASSERT_FALSE(sa.toSplit(2)); + SplitStrategyByAngle sa(0); + ASSERT_FALSE(sa.newBlock(35999)); + ASSERT_TRUE(sa.newBlock(1)); + ASSERT_FALSE(sa.newBlock(2)); } { - SplitAngle sa(0); - ASSERT_FALSE(sa.toSplit(35999)); - ASSERT_TRUE(sa.toSplit(0)); - ASSERT_FALSE(sa.toSplit(2)); + SplitStrategyByAngle sa(0); + ASSERT_FALSE(sa.newBlock(35999)); + ASSERT_TRUE(sa.newBlock(0)); + ASSERT_FALSE(sa.newBlock(2)); } { - SplitAngle sa(0); - ASSERT_FALSE(sa.toSplit(0)); - ASSERT_FALSE(sa.toSplit(2)); + SplitStrategyByAngle sa(0); + ASSERT_FALSE(sa.newBlock(0)); + ASSERT_FALSE(sa.newBlock(2)); } } +TEST(TestSplitStrategyByNum, newBlock) +{ + uint16_t max_blks = 2; + SplitStrategyByNum sn(&max_blks); + ASSERT_FALSE(sn.newBlock(0)); + ASSERT_TRUE(sn.newBlock(0)); + ASSERT_FALSE(sn.newBlock(0)); + ASSERT_TRUE(sn.newBlock(0)); + + max_blks = 3; + ASSERT_FALSE(sn.newBlock(0)); + ASSERT_FALSE(sn.newBlock(0)); + ASSERT_TRUE(sn.newBlock(0)); +} + + From 71c564fa2c1380a8123cd585ce8e4f332eee048a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 17 Dec 2021 10:59:48 +0800 Subject: [PATCH 090/379] refac: refactory decoder --- src/rs_driver/common/error_code.h | 3 ++ src/rs_driver/driver/decoder/decoder.hpp | 8 ++-- src/rs_driver/driver/decoder/decoder_RS32.hpp | 2 +- src/rs_driver/driver/input/input.hpp | 18 ++++----- src/rs_driver/driver/input/input_factory.hpp | 6 +-- src/rs_driver/driver/input/input_pcap.hpp | 8 ++-- src/rs_driver/driver/input/input_raw.hpp | 2 +- src/rs_driver/driver/input/input_sock.hpp | 4 +- src/rs_driver/driver/lidar_driver_impl.hpp | 38 +++++++++---------- .../{msg/packet.h => utility/buffer.h} | 4 +- test/CMakeLists.txt | 2 +- test/{packet_test.cpp => buffer_test.cpp} | 6 +-- test/decoder_test.cpp | 16 ++++---- 13 files changed, 60 insertions(+), 57 deletions(-) rename src/rs_driver/{msg/packet.h => utility/buffer.h} (98%) rename test/{packet_test.cpp => buffer_test.cpp} (78%) diff --git a/src/rs_driver/common/error_code.h b/src/rs_driver/common/error_code.h index 9f6d74e4..1506ec9b 100644 --- a/src/rs_driver/common/error_code.h +++ b/src/rs_driver/common/error_code.h @@ -31,6 +31,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once + +#include + namespace robosense { namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 125d433c..68334a39 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -129,7 +129,7 @@ class Decoder const std::function)>& cb_put); float getTemperature(); - double getPacketDiff(); + double getPacketDuration(); void print(); #ifndef UNIT_TEST @@ -139,7 +139,7 @@ class Decoder template void decodeDifopCommon(const T_Difop& pkt); - void toSplit(int32_t azimuth); + void newBlock(int32_t azimuth); void setPointCloudHeader(std::shared_ptr msg, double chan_ts); RSDecoderConstParam const_param_; // const param of lidar/decoder @@ -254,7 +254,7 @@ float Decoder::getTemperature() } template -double Decoder::getPacketDiff() +double Decoder::getPacketDuration() { return this->const_param_.BLOCK_DURATION * const_param_.BLOCKS_PER_PKT; } @@ -271,7 +271,7 @@ void Decoder::regRecvCallback( } template -inline void Decoder::toSplit(int32_t azimuth) +inline void Decoder::newBlock(int32_t azimuth) { bool split = this->split_strategy_->newBlock(azimuth); if (split) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 2bce3655..7ca56948 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -233,7 +233,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet block_ts += diff.ts(blk); int32_t block_az = ntohs(block.azimuth); - this->toSplit(block_az); + this->newBlock(block_az); int32_t block_azi_diff = diff.azimuth(blk); diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index f2425c3d..cf0870e8 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -33,7 +33,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include -#include +#include #include #include @@ -52,8 +52,8 @@ class Input public: Input(const RSInputParam& input_param, const std::function& excb); - inline void regRecvCallback(const std::function(size_t)>& cb_get, - const std::function)>& cb_put); + inline void regRecvCallback(const std::function(size_t)>& cb_get, + const std::function)>& cb_put); virtual bool init() = 0; virtual bool start() = 0; @@ -63,11 +63,11 @@ class Input } protected: - inline void pushPacket(std::shared_ptr pkt); + inline void pushPacket(std::shared_ptr pkt); RSInputParam input_param_; - std::function(size_t size)> cb_get_; - std::function)> cb_put_; + std::function(size_t size)> cb_get_; + std::function)> cb_put_; std::function excb_; std::thread recv_thread_; bool to_exit_recv_; @@ -82,8 +82,8 @@ inline Input::Input(const RSInputParam& input_param, { } -inline void Input::regRecvCallback(const std::function(size_t)>& cb_get, - const std::function)>& cb_put) +inline void Input::regRecvCallback(const std::function(size_t)>& cb_get, + const std::function)>& cb_put) { cb_get_ = cb_get; cb_put_ = cb_put; @@ -100,7 +100,7 @@ inline void Input::stop() } } -inline void Input::pushPacket(std::shared_ptr pkt) +inline void Input::pushPacket(std::shared_ptr pkt) { cb_put_(pkt); } diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 50944d1b..72b74034 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -45,12 +45,12 @@ class InputFactory public: static std::shared_ptr createInput(InputType type, const RSInputParam& param, const std::function& excb, - double msec_to_delay); + double sec_to_delay); }; inline std::shared_ptr InputFactory::createInput(InputType type, const RSInputParam& param, const std::function& excb, - double msec_to_delay) + double sec_to_delay) { std::shared_ptr input; @@ -64,7 +64,7 @@ inline std::shared_ptr InputFactory::createInput(InputType type, case InputType::PCAP_FILE: { - input = std::make_shared(param, excb, msec_to_delay); + input = std::make_shared(param, excb, sec_to_delay); } break; diff --git a/src/rs_driver/driver/input/input_pcap.hpp b/src/rs_driver/driver/input/input_pcap.hpp index 790864be..4b9f6633 100644 --- a/src/rs_driver/driver/input/input_pcap.hpp +++ b/src/rs_driver/driver/input/input_pcap.hpp @@ -45,9 +45,9 @@ class InputPcap : public Input { public: InputPcap(const RSInputParam& input_param, - const std::function& excb, double msec_to_delay) + const std::function& excb, double sec_to_delay) : Input(input_param, excb), pcap_offset_(ETH_HDR_LEN), - difop_filter_valid_(false), msec_to_delay_(msec_to_delay*1000) + difop_filter_valid_(false), msec_to_delay_(sec_to_delay*1000000) { if (input_param.use_vlan) pcap_offset_ += VLAN_LEN; @@ -163,14 +163,14 @@ inline void InputPcap::recvPacket() if (pcap_offline_filter(&msop_filter_, header, pkt_data) != 0) { - std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_); pkt->setData(0, header->len - pcap_offset_); pushPacket(pkt); } else if (difop_filter_valid_ && (pcap_offline_filter(&difop_filter_, header, pkt_data) != 0)) { - std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_); pkt->setData(0, header->len - pcap_offset_); pushPacket(pkt); diff --git a/src/rs_driver/driver/input/input_raw.hpp b/src/rs_driver/driver/input/input_raw.hpp index 02f1f6dd..a02d8125 100644 --- a/src/rs_driver/driver/input/input_raw.hpp +++ b/src/rs_driver/driver/input/input_raw.hpp @@ -67,7 +67,7 @@ class InputRaw : public Input inline void InputRaw::feedPacket(const uint8_t* data, size_t size) { - std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); memcpy(pkt->data(), data, size); pkt->setData(0, size); pushPacket(pkt); diff --git a/src/rs_driver/driver/input/input_sock.hpp b/src/rs_driver/driver/input/input_sock.hpp index f8ccd2a3..64d4dd89 100644 --- a/src/rs_driver/driver/input/input_sock.hpp +++ b/src/rs_driver/driver/input/input_sock.hpp @@ -244,7 +244,7 @@ inline void InputSock::recvPacket() if (FD_ISSET(fds_[0], &rfds)) { - std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); ssize_t ret = recvfrom(fds_[0], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret <= 0) { @@ -257,7 +257,7 @@ inline void InputSock::recvPacket() } else if (FD_ISSET(fds_[1], &rfds)) { - std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); ssize_t ret = recvfrom(fds_[1], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret <= 0) break; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index df35d69c..a28a6269 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -32,11 +32,11 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include -#include +#include +#include +#include #include #include -#include -#include #include #include #include @@ -82,11 +82,11 @@ class LidarDriverImpl std::shared_ptr getPointCloud(); void putPointCloud(std::shared_ptr pc); - void runCallBack(std::shared_ptr pkt); + void runCallBack(std::shared_ptr pkt); void reportError(const Error& error); - std::shared_ptr packetGet(size_t size); - void packetPut(std::shared_ptr pkt); + std::shared_ptr packetGet(size_t size); + void packetPut(std::shared_ptr pkt); void processMsop(); void processDifop(); @@ -98,9 +98,9 @@ class LidarDriverImpl std::function err_cb_; std::shared_ptr> lidar_decoder_ptr_; std::shared_ptr input_ptr_; - SyncQueue> free_pkt_queue_; - SyncQueue> msop_pkt_queue_; - SyncQueue> difop_pkt_queue_; + SyncQueue> free_pkt_queue_; + SyncQueue> msop_pkt_queue_; + SyncQueue> difop_pkt_queue_; std::thread msop_handle_thread_; std::thread difop_handle_thread_; bool to_exit_handle_; @@ -148,11 +148,11 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) std::bind(&LidarDriverImpl::getPointCloud, this), std::bind(&LidarDriverImpl::putPointCloud, this, std::placeholders::_1)); - uint64_t packet_diff = lidar_decoder_ptr_->getPacketDiff(); + double packet_duration = lidar_decoder_ptr_->getPacketDuration(); input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1), - packet_diff); + packet_duration); input_ptr_->regRecvCallback(std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), std::bind(&LidarDriverImpl::packetPut, this, std::placeholders::_1)); @@ -266,7 +266,7 @@ inline bool LidarDriverImpl::getTemperature(float& temp) } template -inline void LidarDriverImpl::runCallBack(std::shared_ptr pkt) +inline void LidarDriverImpl::runCallBack(std::shared_ptr pkt) { if (pkt_cb_) { @@ -284,21 +284,21 @@ inline void LidarDriverImpl::reportError(const Error& error) } template -inline std::shared_ptr LidarDriverImpl::packetGet(size_t size) +inline std::shared_ptr LidarDriverImpl::packetGet(size_t size) { - std::shared_ptr pkt = free_pkt_queue_.pop(); + std::shared_ptr pkt = free_pkt_queue_.pop(); if (pkt.get() != NULL) { return pkt; } - return std::make_shared(size); + return std::make_shared(size); } template -inline void LidarDriverImpl::packetPut(std::shared_ptr pkt) +inline void LidarDriverImpl::packetPut(std::shared_ptr pkt) { - SyncQueue>* queue; + SyncQueue>* queue; uint8_t* id = pkt->data(); @@ -326,7 +326,7 @@ inline void LidarDriverImpl::processMsop() { while (!to_exit_handle_) { - std::shared_ptr pkt = msop_pkt_queue_.popWait(1000); + std::shared_ptr pkt = msop_pkt_queue_.popWait(1000); if (pkt.get() == NULL) continue; @@ -342,7 +342,7 @@ inline void LidarDriverImpl::processDifop() { while (!to_exit_handle_) { - std::shared_ptr pkt = difop_pkt_queue_.popWait(500000); + std::shared_ptr pkt = difop_pkt_queue_.popWait(500000); if (pkt.get() == NULL) continue; diff --git a/src/rs_driver/msg/packet.h b/src/rs_driver/utility/buffer.h similarity index 98% rename from src/rs_driver/msg/packet.h rename to src/rs_driver/utility/buffer.h index 929e8239..12a5ebd8 100644 --- a/src/rs_driver/msg/packet.h +++ b/src/rs_driver/utility/buffer.h @@ -40,11 +40,11 @@ namespace robosense { namespace lidar { -class Packet +class Buffer { public: - Packet(size_t buf_size) + Buffer(size_t buf_size) : data_off_(0), data_size_(0) { buf_.resize(buf_size); diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 2ee76586..b9c42fb1 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -11,7 +11,7 @@ add_definitions("-DUNIT_TEST") add_executable(rs_driver_test rs_driver_test.cpp - packet_test.cpp + buffer_test.cpp sync_queue_test.cpp single_return_block_diff_test.cpp dual_return_block_diff_test.cpp diff --git a/test/packet_test.cpp b/test/buffer_test.cpp similarity index 78% rename from test/packet_test.cpp rename to test/buffer_test.cpp index 219d908b..3a776226 100644 --- a/test/packet_test.cpp +++ b/test/buffer_test.cpp @@ -1,13 +1,13 @@ #include -#include +#include using namespace robosense::lidar; -TEST(TestPacket, ctor) +TEST(TestBuffer, ctor) { - Packet pkt(100); + Buffer pkt(100); ASSERT_TRUE(pkt.buf() != NULL); ASSERT_EQ(pkt.bufSize(), 100); diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 02fa9ddc..8f278a70 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -156,7 +156,7 @@ TEST(TestDecoder, processDifopPkt) , 0x01, 0x00, 0x02 }; - ASSERT_LT(decoder.getPacketDiff() - 55.52/1000, 0.00001); + ASSERT_LT(decoder.getPacketDuration() - 55.52/1000, 0.00001); // // angles from angle.csv @@ -330,12 +330,12 @@ TEST(TestDecoder, split_by_angle) { errCode = ERRCODE_SUCCESS; flag_point_cloud = false; - decoder.toSplit (35999); + decoder.newBlock (35999); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_FALSE(flag_point_cloud); errCode = ERRCODE_SUCCESS; - decoder.toSplit (2); + decoder.newBlock (2); ASSERT_EQ(errCode, ERRCODE_ZEROPOINTS); } @@ -346,7 +346,7 @@ TEST(TestDecoder, split_by_angle) errCode = ERRCODE_SUCCESS; flag_point_cloud = false; - decoder.toSplit (1); + decoder.newBlock (1); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_TRUE(flag_point_cloud); ASSERT_TRUE(point_cloud_to_put.get() != NULL); @@ -374,7 +374,7 @@ TEST(TestDecoder, split_by_fixed_pkts) { errCode = ERRCODE_SUCCESS; flag_point_cloud = false; - decoder.toSplit (0); + decoder.newBlock (0); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_FALSE(flag_point_cloud); } @@ -382,7 +382,7 @@ TEST(TestDecoder, split_by_fixed_pkts) { errCode = ERRCODE_SUCCESS; flag_point_cloud = false; - decoder.toSplit (0); + decoder.newBlock (0); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_TRUE(flag_point_cloud); @@ -411,7 +411,7 @@ TEST(TestDecoder, split_by_custom_blks) { errCode = ERRCODE_SUCCESS; flag_point_cloud = false; - decoder.toSplit (0); + decoder.newBlock (0); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_FALSE(flag_point_cloud); } @@ -419,7 +419,7 @@ TEST(TestDecoder, split_by_custom_blks) { errCode = ERRCODE_SUCCESS; flag_point_cloud = false; - decoder.toSplit (0); + decoder.newBlock (0); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_TRUE(flag_point_cloud); From a3e89b93d0c583ca3d9374cc3ba67b294d40a9e6 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 17 Dec 2021 11:18:20 +0800 Subject: [PATCH 091/379] refac: refactory decoder --- src/rs_driver/driver/decoder/basic_attr.hpp | 156 -------------------- src/rs_driver/driver/decoder/decoder.hpp | 155 ++++++++++++++++++- src/rs_driver/driver/decoder/scan_block.hpp | 100 ------------- 3 files changed, 154 insertions(+), 257 deletions(-) delete mode 100644 src/rs_driver/driver/decoder/scan_block.hpp diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index 2d73c8a2..52a23e1e 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -47,9 +47,6 @@ namespace lidar #pragma pack(push, 1) -// -// msop -// typedef struct { uint8_t year; @@ -79,159 +76,6 @@ typedef struct uint8_t tt[2]; } RSTemprature; -typedef struct -{ - uint8_t id[8]; - uint8_t reserved_1[12]; - RSTimestampYMD timestamp; - uint8_t lidar_type; - uint8_t reserved_2[7]; - RSTemprature temp; - //uint16_t temp_raw; - uint8_t reserved_3[2]; -} RSMsopHeaderV1; - -typedef struct -{ - uint8_t id[4]; - uint16_t protocol_version; - uint8_t reserved_1; - uint8_t wave_mode; - RSTemprature temp; -#if 0 - uint8_t temp_low; - uint8_t temp_high; -#endif - RSTimestampUTC timestamp; - uint8_t reserved_2[10]; - uint8_t lidar_type; - uint8_t reserved_3[49]; -} RSMsopHeaderV2; - -typedef struct -{ - uint16_t distance; - uint8_t intensity; -} RSChannel; - -// -// difop -// - -typedef struct -{ - uint8_t lidar_ip[4]; - uint8_t host_ip[4]; - uint8_t mac_addr[6]; - uint16_t local_port; - uint16_t dest_port; - uint16_t port3; - uint16_t port4; -} RSEthNetV1; - -typedef struct -{ - uint8_t lidar_ip[4]; - uint8_t dest_ip[4]; - uint8_t mac_addr[6]; - uint16_t msop_port; - uint16_t reserve_1; - uint16_t difop_port; - uint16_t reserve_2; -} RSEthNetV2; - -typedef struct -{ - uint16_t start_angle; - uint16_t end_angle; -} RSFOV; - -typedef struct -{ - uint8_t top_ver[5]; - uint8_t bottom_ver[5]; -} RSVersionV1; - -typedef struct -{ - uint8_t top_firmware_ver[5]; - uint8_t bot_firmware_ver[5]; - uint8_t bot_soft_ver[5]; - uint8_t motor_firmware_ver[5]; - uint8_t hw_ver[3]; -} RSVersionV2; - -typedef struct -{ - uint8_t num[6]; -} RSSN; - -typedef struct -{ - uint8_t device_current[3]; - uint8_t main_current[3]; - uint16_t vol_12v; - uint16_t vol_sim_1v8; - uint16_t vol_dig_3v3; - uint16_t vol_sim_3v3; - uint16_t vol_dig_5v4; - uint16_t vol_sim_5v; - uint16_t vol_ejc_5v; - uint16_t vol_recv_5v; - uint16_t vol_apd; -} RSStatusV1; - -typedef struct -{ - uint16_t device_current; - uint16_t vol_fpga; - uint16_t vol_12v; - uint16_t vol_dig_5v4; - uint16_t vol_sim_5v; - uint16_t vol_apd; - uint8_t reserved[12]; -} RSStatusV2; - -typedef struct -{ - uint8_t reserved_1[9]; - uint16_t checksum; - uint16_t manc_err1; - uint16_t manc_err2; - uint8_t gps_status; - uint16_t temperature1; - uint16_t temperature2; - uint16_t temperature3; - uint16_t temperature4; - uint16_t temperature5; - uint8_t reserved_2[5]; - uint16_t cur_rpm; - uint8_t reserved_3[7]; -} RSDiagnoV1; - -typedef struct -{ - uint16_t bot_fpga_temperature; - uint16_t recv_A_temperature; - uint16_t recv_B_temperature; - uint16_t main_fpga_temperature; - uint16_t main_fpga_core_temperature; - uint16_t real_rpm; - uint8_t lane_up; - uint16_t lane_up_cnt; - uint16_t main_status; - uint8_t gps_status; - uint8_t reserved[22]; -} RSDiagnoV2; - - -typedef struct -{ - uint8_t sync_mode; - uint8_t sync_sts; - RSTimestampUTC timestamp; -} RSTimeInfo; - #pragma pack(pop) inline uint64_t calcTimeUTCWithNs(const RSTimestampUTC2* tsUtc) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 68334a39..67712d08 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -56,6 +56,159 @@ namespace robosense namespace lidar { +// +// msop & difop +// +#pragma pack(push, 1) +typedef struct +{ + uint8_t id[8]; + uint8_t reserved_1[12]; + RSTimestampYMD timestamp; + uint8_t lidar_type; + uint8_t reserved_2[7]; + RSTemprature temp; + //uint16_t temp_raw; + uint8_t reserved_3[2]; +} RSMsopHeaderV1; + +typedef struct +{ + uint8_t id[4]; + uint16_t protocol_version; + uint8_t reserved_1; + uint8_t wave_mode; + RSTemprature temp; +#if 0 + uint8_t temp_low; + uint8_t temp_high; +#endif + RSTimestampUTC timestamp; + uint8_t reserved_2[10]; + uint8_t lidar_type; + uint8_t reserved_3[49]; +} RSMsopHeaderV2; + +typedef struct +{ + uint16_t distance; + uint8_t intensity; +} RSChannel; + +typedef struct +{ + uint8_t lidar_ip[4]; + uint8_t host_ip[4]; + uint8_t mac_addr[6]; + uint16_t local_port; + uint16_t dest_port; + uint16_t port3; + uint16_t port4; +} RSEthNetV1; + +typedef struct +{ + uint8_t lidar_ip[4]; + uint8_t dest_ip[4]; + uint8_t mac_addr[6]; + uint16_t msop_port; + uint16_t reserve_1; + uint16_t difop_port; + uint16_t reserve_2; +} RSEthNetV2; + +typedef struct +{ + uint16_t start_angle; + uint16_t end_angle; +} RSFOV; + +typedef struct +{ + uint8_t top_ver[5]; + uint8_t bottom_ver[5]; +} RSVersionV1; + +typedef struct +{ + uint8_t top_firmware_ver[5]; + uint8_t bot_firmware_ver[5]; + uint8_t bot_soft_ver[5]; + uint8_t motor_firmware_ver[5]; + uint8_t hw_ver[3]; +} RSVersionV2; + +typedef struct +{ + uint8_t num[6]; +} RSSN; + +typedef struct +{ + uint8_t device_current[3]; + uint8_t main_current[3]; + uint16_t vol_12v; + uint16_t vol_sim_1v8; + uint16_t vol_dig_3v3; + uint16_t vol_sim_3v3; + uint16_t vol_dig_5v4; + uint16_t vol_sim_5v; + uint16_t vol_ejc_5v; + uint16_t vol_recv_5v; + uint16_t vol_apd; +} RSStatusV1; + +typedef struct +{ + uint16_t device_current; + uint16_t vol_fpga; + uint16_t vol_12v; + uint16_t vol_dig_5v4; + uint16_t vol_sim_5v; + uint16_t vol_apd; + uint8_t reserved[12]; +} RSStatusV2; + +typedef struct +{ + uint8_t reserved_1[9]; + uint16_t checksum; + uint16_t manc_err1; + uint16_t manc_err2; + uint8_t gps_status; + uint16_t temperature1; + uint16_t temperature2; + uint16_t temperature3; + uint16_t temperature4; + uint16_t temperature5; + uint8_t reserved_2[5]; + uint16_t cur_rpm; + uint8_t reserved_3[7]; +} RSDiagnoV1; + +typedef struct +{ + uint16_t bot_fpga_temperature; + uint16_t recv_A_temperature; + uint16_t recv_B_temperature; + uint16_t main_fpga_temperature; + uint16_t main_fpga_core_temperature; + uint16_t real_rpm; + uint8_t lane_up; + uint16_t lane_up_cnt; + uint16_t main_status; + uint8_t gps_status; + uint8_t reserved[22]; +} RSDiagnoV2; + +typedef struct +{ + uint8_t sync_mode; + uint8_t sync_sts; + RSTimestampUTC timestamp; +} RSTimeInfo; +#pragma pack(pop) + // Echo mode enum RSEchoMode { @@ -63,6 +216,7 @@ enum RSEchoMode ECHO_DUAL }; +// decoder const param typedef struct { uint16_t MSOP_LEN; @@ -98,7 +252,6 @@ typedef struct } RSDecoderConstParam; - #if 0 const size_t MECH_PKT_LEN = 1248; const size_t MEMS_MSOP_LEN = 1210; diff --git a/src/rs_driver/driver/decoder/scan_block.hpp b/src/rs_driver/driver/decoder/scan_block.hpp deleted file mode 100644 index cfb0da97..00000000 --- a/src/rs_driver/driver/decoder/scan_block.hpp +++ /dev/null @@ -1,100 +0,0 @@ -/********************************************************************************************************************* -Copyright (c) 2020 RoboSense -All rights reserved - -By downloading, copying, installing or using the software you agree to this license. If you do not agree to this -license, do not download, install, copy or use the software. - -License Agreement -For RoboSense LiDAR SDK Library -(3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials provided with the distribution. - -3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used -to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*********************************************************************************************************************/ - -#pragma once - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -namespace robosense -{ -namespace lidar -{ - -class ScanBlock -{ -public: - ScanBlock(int32_t start, int32_t end) - { - start_ = start % 36000; - end_ = (end <= 36000) ? end : (end % 36000); - cross_zero_ = (start_ > end_); - } - - bool in(int32_t angle) - { - if (cross_zero_) - return (angle >= start_) || (angle < end_); - else - return (angle >= start_) && (angle < end_); - } - -#ifndef UNIT_TEST -private: -#endif - int32_t start_; - int32_t end_; - bool cross_zero_; -}; - -class DistanceBlock -{ -public: - DistanceBlock (float min, float max, float usr_min, float usr_max) - : min_((usr_min > min) ? usr_min : min), max_((usr_max < max) ? usr_max : max) - { - } - - bool in(float distance) - { - return ((min_ <= distance) && (distance <= max_)); - } - -#ifndef UNIT_TEST -private: -#endif - - float min_; - float max_; -}; - -} // namespace lidar -} // namespace robosense From 29327d17cf213647a76481a8f9df7ffa2cb72ad0 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 17 Dec 2021 18:30:28 +0800 Subject: [PATCH 092/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 6 + src/rs_driver/driver/decoder/decoder_RS32.hpp | 3 +- src/rs_driver/driver/driver_param.h | 2 +- test/CMakeLists.txt | 8 +- test/chan_angles_test.cpp | 29 +++- test/decoder_rs32_test.cpp | 23 ++- test/decoder_test.cpp | 136 +++++++++--------- 7 files changed, 113 insertions(+), 94 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 67712d08..6b1a408e 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -379,6 +379,12 @@ inline Decoder::Decoder(const RSDecoderParam& param, if (param.config_from_file) { + if (param_.wait_for_difop) + { + RS_WARNING << "When config_from_file is true, wait_for_difop cannot be true." + << " Reset it to be false." << RS_REND; + } + int ret = chan_angles_.loadFromFile(param.angle_path); this->angles_ready_ = (ret == 0); } diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 7ca56948..0ac3bad7 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -214,7 +214,8 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet } else { - pkt_ts = calcTimeHost(); + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = calcTimeHost() - this->getPacketDuration(); } T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index ae30cf0c..86d319f6 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -206,6 +206,7 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter { bool config_from_file = false; std::string angle_path = ""; ///< Path of angle calibration files(angle.csv). Only used for internal debugging. + bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet float min_distance = 0.2f; ///< Minimum distance of point cloud range float max_distance = 200.0f; ///< Max distance of point cloud range float start_angle = 0.0f; ///< Start angle of point cloud @@ -215,7 +216,6 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter ///< 3: Split frames by custom number of packets (num_pkts_split) float split_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 - bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points #if 0 diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index b9c42fb1..54c162ab 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -13,13 +13,13 @@ add_executable(rs_driver_test rs_driver_test.cpp buffer_test.cpp sync_queue_test.cpp - single_return_block_diff_test.cpp - dual_return_block_diff_test.cpp + trigon_test.cpp basic_attr_test.cpp - split_strategy_test.cpp section_test.cpp chan_angles_test.cpp - trigon_test.cpp + split_strategy_test.cpp + single_return_block_diff_test.cpp + dual_return_block_diff_test.cpp decoder_test.cpp decoder_rs32_test.cpp) diff --git a/test/chan_angles_test.cpp b/test/chan_angles_test.cpp index 093cf2b3..4cb40264 100644 --- a/test/chan_angles_test.cpp +++ b/test/chan_angles_test.cpp @@ -27,6 +27,7 @@ TEST(TestChanAngles, loadFromFile) { std::vector vert_angles, horiz_angles; + // load ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); ASSERT_EQ(vert_angles.size(), 4); ASSERT_EQ(horiz_angles.size(), 4); @@ -40,14 +41,15 @@ TEST(TestChanAngles, loadFromFile) ASSERT_EQ(horiz_angles[2], 0); ASSERT_EQ(horiz_angles[3], -100); + // load again ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); ASSERT_EQ(vert_angles.size(), 4); ASSERT_EQ(horiz_angles.size(), 4); + // load non-existing file ASSERT_LT(ChanAngles::loadFromFile ("../rs_driver/test/res/non_exist.csv", vert_angles, horiz_angles), 0); ASSERT_EQ(vert_angles.size(), 0); ASSERT_EQ(horiz_angles.size(), 0); - } TEST(TestChanAngles, loadFromDifop) @@ -63,6 +65,7 @@ TEST(TestChanAngles, loadFromDifop) std::vector vert_angles, horiz_angles; + // load ASSERT_EQ(ChanAngles::loadFromDifop( (const RSCalibrationAngle*)vert_angle_arr, (const RSCalibrationAngle*)horiz_angle_arr, @@ -82,6 +85,7 @@ TEST(TestChanAngles, loadFromDifop) ASSERT_EQ(horiz_angles[2], 21862); ASSERT_EQ(horiz_angles[3], -30600); + // load again ASSERT_EQ(ChanAngles::loadFromDifop( (const RSCalibrationAngle*)vert_angle_arr, (const RSCalibrationAngle*)horiz_angle_arr, @@ -94,12 +98,16 @@ TEST(TestChanAngles, loadFromDifop) TEST(TestChanAngles, memberLoadFromFile) { + ChanAngles angles(4); + + // not loading yet ASSERT_EQ(angles.chan_num_, 4); ASSERT_EQ(angles.vert_angles_.size(), 4); ASSERT_EQ(angles.horiz_angles_.size(), 4); ASSERT_EQ(angles.user_chans_.size(), 4); + // load ASSERT_EQ(angles.loadFromFile ("../rs_driver/test/res/angle.csv"), 0); ASSERT_EQ(angles.user_chans_.size(), 4); ASSERT_EQ(angles.toUserChan(0), 3); @@ -113,6 +121,7 @@ TEST(TestChanAngles, memberLoadFromFile_fail) ChanAngles angles(4); ASSERT_EQ(angles.chan_num_, 4); + // load non-existing file ASSERT_LT(angles.loadFromFile ("../rs_driver/test/res/non_exist.csv"), 0); ASSERT_EQ(angles.vert_angles_.size(), 4); ASSERT_EQ(angles.vert_angles_[0], 0); @@ -131,6 +140,8 @@ TEST(TestChanAngles, memberLoadFromDifop) ChanAngles angles(4); ASSERT_EQ(angles.chan_num_, 4); + + // load ASSERT_EQ(angles.loadFromDifop( (const RSCalibrationAngle*)vert_angle_arr, (const RSCalibrationAngle*)horiz_angle_arr, @@ -147,6 +158,13 @@ TEST(TestChanAngles, memberLoadFromDifop) ASSERT_EQ(angles.horiz_angles_[2], 21862); ASSERT_EQ(angles.horiz_angles_[3], -30600); + ASSERT_EQ(angles.user_chans_.size(), 4); + ASSERT_EQ(angles.toUserChan(0), 2); + ASSERT_EQ(angles.toUserChan(1), 1); + ASSERT_EQ(angles.toUserChan(2), 0); + ASSERT_EQ(angles.toUserChan(3), 3); + + // narrow after load. for RS32 angles.narrow(); ASSERT_EQ(angles.vert_angles_.size(), 4); @@ -159,12 +177,6 @@ TEST(TestChanAngles, memberLoadFromDifop) ASSERT_EQ(angles.horiz_angles_[1], -1312); ASSERT_EQ(angles.horiz_angles_[2], 2186); ASSERT_EQ(angles.horiz_angles_[3], -3060); - - ASSERT_EQ(angles.user_chans_.size(), 4); - ASSERT_EQ(angles.toUserChan(0), 2); - ASSERT_EQ(angles.toUserChan(1), 1); - ASSERT_EQ(angles.toUserChan(2), 0); - ASSERT_EQ(angles.toUserChan(3), 3); } TEST(TestChanAngles, memberLoadFromDifop_fail) @@ -181,9 +193,12 @@ TEST(TestChanAngles, memberLoadFromDifop_fail) ChanAngles angles(4); ASSERT_EQ(angles.chan_num_, 4); + // load invalid difop ASSERT_LT(angles.loadFromDifop( (const RSCalibrationAngle*)vert_angle_arr, (const RSCalibrationAngle*)horiz_angle_arr, 4), 0); + ASSERT_EQ(angles.vert_angles_.size(), 4); + ASSERT_EQ(angles.vert_angles_[0], 0); } diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index ae5adec8..616b4e0c 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -18,35 +18,32 @@ static void errCallback(const Error& err) TEST(TestDecoderRS32, getEchoMode) { - RSDecoderParam param; - DecoderRS32 decoder(param, errCallback); - - ASSERT_TRUE(decoder.getEchoMode(0) == RSEchoMode::ECHO_DUAL); - ASSERT_TRUE(decoder.getEchoMode(1) == RSEchoMode::ECHO_SINGLE); - ASSERT_TRUE(decoder.getEchoMode(2) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(DecoderRS32::getEchoMode(0) == RSEchoMode::ECHO_DUAL); + ASSERT_TRUE(DecoderRS32::getEchoMode(1) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(DecoderRS32::getEchoMode(2) == RSEchoMode::ECHO_SINGLE); } TEST(TestDecoderRS32, decodeDifopPkt) { + // const_param RSDecoderParam param; DecoderRS32 decoder(param, errCallback); ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.split_blks_per_frame_, 1801); + // rpm = 600, dual return RS32DifopPkt pkt; - - // rpm = 600 pkt.rpm = htons(600); - pkt.return_mode = 0; // dual return + pkt.return_mode = 0; decoder.decodeDifopPkt((uint8_t*)&pkt, sizeof(pkt)); ASSERT_EQ(decoder.rps_, 10); ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_DUAL); ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.split_blks_per_frame_, 3602); - // rpm = 1200 + // rpm = 1200, single return pkt.rpm = htons(1200); - pkt.return_mode = 1; // single return + pkt.return_mode = 1; decoder.decodeDifopPkt((uint8_t*)&pkt, sizeof(pkt)); ASSERT_EQ(decoder.rps_, 20); ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_SINGLE); @@ -145,6 +142,7 @@ TEST(TestDecoderRS32, decodeMsopPkt) 0x00, 0x00, // block id }; + // dense_points = false, use_lidar_clock = true RSDecoderParam param; DecoderRS32 decoder(param, errCallback); ASSERT_EQ(decoder.chan_angles_.user_chans_.size(), 32); @@ -161,6 +159,7 @@ TEST(TestDecoderRS32, decodeMsopPkt) PointT& point = decoder.point_cloud_->points[0]; ASSERT_EQ(point.intensity, 1); - ASSERT_EQ(point.ring, 2); ASSERT_NE(point.timestamp, 0); + ASSERT_EQ(point.ring, 2); } + diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 8f278a70..8150aa46 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -56,17 +56,30 @@ static void errCallback(const Error& err) errCode = err.error_code; } -TEST(TestDecoder, angles_from_angle_file) +TEST(TestDecoder, angles_from_file) { RSDecoderConstParam const_param; const_param.CHANNELS_PER_BLOCK = 4; RSDecoderParam param; param.config_from_file = true; param.angle_path = "../rs_driver/test/res/angle.csv"; + errCode = ERRCODE_SUCCESS; MyDecoder decoder(param, errCallback, const_param); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_TRUE(decoder.angles_ready_); } +TEST(TestDecoder, angles_from_file_fail) +{ + RSDecoderConstParam const_param; + const_param.CHANNELS_PER_BLOCK = 4; + RSDecoderParam param; + param.config_from_file = true; + param.angle_path = "../rs_driver/test/res/non_exist.csv"; + MyDecoder decoder(param, errCallback, const_param); + ASSERT_FALSE(decoder.angles_ready_); +} + TEST(TestDecoder, processDifopPkt_fail) { RSDecoderConstParam const_param = @@ -82,47 +95,18 @@ TEST(TestDecoder, processDifopPkt_fail) RSDecoderParam param; MyDecoder decoder(param, errCallback, const_param); + // wrong difop length MyDifopPkt pkt; errCode = ERRCODE_SUCCESS; decoder.processDifopPkt((const uint8_t*)&pkt, 10); ASSERT_EQ(errCode, ERRCODE_WRONGPKTLENGTH); + // wrong difop id errCode = ERRCODE_SUCCESS; decoder.processDifopPkt((const uint8_t*)&pkt, sizeof(pkt)); ASSERT_EQ(errCode, ERRCODE_WRONGPKTHEADER); } -TEST(TestDecoder, processDifopPkt_invalid_rpm) -{ - RSDecoderConstParam const_param = - { - sizeof(MyMsopPkt) // msop len - , sizeof(MyDifopPkt) // difop len - , 8 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id - , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0xFF, 0xEE} // block id - , 12 // blocks per packet - , 32 // channels per block - }; - - RSDecoderParam param; - MyDecoder decoder(param, errCallback, const_param); - - uint8_t pkt[] = - { - 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // difop len - , 0x00, 0x00 // rpm = 0 - }; - - errCode = ERRCODE_SUCCESS; - decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); - ASSERT_EQ(errCode, ERRCODE_SUCCESS); - - ASSERT_EQ(decoder.rps_, 10); -} - TEST(TestDecoder, processDifopPkt) { RSDecoderConstParam const_param = @@ -141,32 +125,29 @@ TEST(TestDecoder, processDifopPkt) const_param.BLOCK_DURATION = 55.52f / 1000000; RSDecoderParam param; + param.config_from_file = false; MyDecoder decoder(param, errCallback, const_param); ASSERT_FALSE(decoder.angles_ready_); - uint8_t pkt[] = + // + // angles from difop. no angles in difop + // + + uint8_t pkt_no_angles[] = { 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // difop id , 0x02, 0x58 // rpm , 0x23, 0x28 // start angle = 9000 , 0x46, 0x50 // end angle = 18000 - , 0x00, 0x00, 0x10 // vert angles - , 0x01, 0x00, 0x20 - , 0x00, 0x00, 0x01 // horiz angles - , 0x01, 0x00, 0x02 + , 0xFF, 0xFF, 0xFF // vert angles + , 0xFF, 0xFF, 0xFF + , 0xFF, 0xFF, 0xFF // horiz angles + , 0xFF, 0xFF, 0xFF }; - ASSERT_LT(decoder.getPacketDuration() - 55.52/1000, 0.00001); - - // - // angles from angle.csv - // - - decoder.param_.config_from_file = true; - decoder.param_.angle_path = "non_exist.csv"; errCode = ERRCODE_SUCCESS; - decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); - ASSERT_EQ(errCode, ERRCODE_SUCCESS); + decoder.processDifopPkt(pkt_no_angles, sizeof(MyDifopPkt)); + errCode = ERRCODE_SUCCESS; ASSERT_EQ(decoder.rps_, 10); ASSERT_EQ(decoder.blks_per_frame_, 1801); @@ -179,37 +160,25 @@ TEST(TestDecoder, processDifopPkt) ASSERT_EQ(decoder.chan_angles_.horiz_angles_[0], 0); // - //angles from difop. no angles in difop + // angles from difop. valid angels in difop. // - - uint8_t pkt_no_angles[] = + uint8_t pkt[] = { 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // difop id , 0x02, 0x58 // rpm , 0x23, 0x28 // start angle = 9000 , 0x46, 0x50 // end angle = 18000 - , 0xFF, 0xFF, 0xFF // vert angles - , 0xFF, 0xFF, 0xFF - , 0xFF, 0xFF, 0xFF // horiz angles - , 0xFF, 0xFF, 0xFF + , 0x00, 0x00, 0x10 // vert angles + , 0x01, 0x00, 0x20 + , 0x00, 0x00, 0x01 // horiz angles + , 0x01, 0x00, 0x02 }; - decoder.param_.config_from_file = false; - errCode = ERRCODE_SUCCESS; - decoder.processDifopPkt(pkt_no_angles, sizeof(MyDifopPkt)); - errCode = ERRCODE_SUCCESS; - - ASSERT_FALSE(decoder.angles_ready_); - ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); - ASSERT_EQ(decoder.chan_angles_.vert_angles_[0], 0); - ASSERT_EQ(decoder.chan_angles_.horiz_angles_.size(), 2); - ASSERT_EQ(decoder.chan_angles_.horiz_angles_[0], 0); + ASSERT_LT(decoder.getPacketDuration() - 55.52/1000, 0.00001); - // angles from difop. - decoder.param_.config_from_file = false; errCode = ERRCODE_SUCCESS; decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); - errCode = ERRCODE_SUCCESS; + ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_TRUE(decoder.angles_ready_); ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); @@ -218,6 +187,36 @@ TEST(TestDecoder, processDifopPkt) ASSERT_EQ(decoder.chan_angles_.horiz_angles_[0], 1); } +TEST(TestDecoder, processDifopPkt_invalid_rpm) +{ + RSDecoderConstParam const_param = + { + sizeof(MyMsopPkt) // msop len + , sizeof(MyDifopPkt) // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 12 // blocks per packet + , 32 // channels per block + }; + + RSDecoderParam param; + MyDecoder decoder(param, errCallback, const_param); + + uint8_t pkt[] = + { + 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // difop len + , 0x00, 0x00 // rpm = 0 + }; + + errCode = ERRCODE_SUCCESS; + decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); + ASSERT_EQ(decoder.rps_, 10); +} + TEST(TestDecoder, processMsopPkt) { RSDecoderConstParam const_param = @@ -231,11 +230,10 @@ TEST(TestDecoder, processMsopPkt) }; MyMsopPkt pkt; - RSDecoderParam param; MyDecoder decoder(param, errCallback, const_param); - // wrong msop len + // wait_for_difop = true, angles not ready decoder.param_.wait_for_difop = true; decoder.angles_ready_ = false; errCode = ERRCODE_SUCCESS; From 78dbc5938482e403a07e6c4f6651253e60430bfe Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 17 Dec 2021 18:49:54 +0800 Subject: [PATCH 093/379] refac: refactory decoder --- test/decoder_test.cpp | 11 ++++++++++- test/dual_return_block_diff_test.cpp | 7 +++++++ test/single_return_block_diff_test.cpp | 5 +++++ test/sync_queue_test.cpp | 12 +++++------- 4 files changed, 27 insertions(+), 8 deletions(-) diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 8150aa46..e1d1df05 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -265,6 +265,7 @@ TEST(TestDecoder, processMsopPkt) TEST(TestDecoder, setPointCloudHeader) { + // dense_points RSDecoderConstParam const_param = {}; const_param.CHANNELS_PER_BLOCK = 2; RSDecoderParam param; @@ -278,6 +279,7 @@ TEST(TestDecoder, setPointCloudHeader) pt->points.emplace_back(point); pt->points.emplace_back(point); + // dense_points = true { decoder.setPointCloudHeader(pt, 0.5f); ASSERT_EQ(pt->seq, 0); @@ -287,8 +289,8 @@ TEST(TestDecoder, setPointCloudHeader) ASSERT_EQ(pt->width, 2); } + // dense_points = false decoder.param_.dense_points = false; - { decoder.setPointCloudHeader(pt, 0.5f); ASSERT_EQ(pt->seq, 1); @@ -326,17 +328,20 @@ TEST(TestDecoder, split_by_angle) decoder.regRecvCallback (getCallback, putCallback); { + // not cross split angle yet. errCode = ERRCODE_SUCCESS; flag_point_cloud = false; decoder.newBlock (35999); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_FALSE(flag_point_cloud); + // cross split angle. no points in point cloud. errCode = ERRCODE_SUCCESS; decoder.newBlock (2); ASSERT_EQ(errCode, ERRCODE_ZEROPOINTS); } + // cross split angle. points in point cloud. { PointT point; point_cloud_to_get->points.emplace_back(point); @@ -370,6 +375,7 @@ TEST(TestDecoder, split_by_fixed_pkts) point_cloud_to_get->points.emplace_back(point); { + // blocks < split_blks_per_frame_ errCode = ERRCODE_SUCCESS; flag_point_cloud = false; decoder.newBlock (0); @@ -378,6 +384,7 @@ TEST(TestDecoder, split_by_fixed_pkts) } { + // blocks = split_blks_per_frame_ errCode = ERRCODE_SUCCESS; flag_point_cloud = false; decoder.newBlock (0); @@ -407,6 +414,7 @@ TEST(TestDecoder, split_by_custom_blks) point_cloud_to_get->points.emplace_back(point); { + // blocks < num_blks_split errCode = ERRCODE_SUCCESS; flag_point_cloud = false; decoder.newBlock (0); @@ -415,6 +423,7 @@ TEST(TestDecoder, split_by_custom_blks) } { + // blocks = num_blks_split errCode = ERRCODE_SUCCESS; flag_point_cloud = false; decoder.newBlock (0); diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_diff_test.cpp index df01e0a6..5342682d 100644 --- a/test/dual_return_block_diff_test.cpp +++ b/test/dual_return_block_diff_test.cpp @@ -65,13 +65,20 @@ TEST(TestDualPacketTraverser, toNext) DualReturnBlockDiff diff(pkt, const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); + // first block = 0 ASSERT_EQ(diff.ts(0), 0.0f); + // second block. calculate it. ASSERT_EQ(diff.ts(1), 0.0f); + // last block = prev block ASSERT_EQ(diff.ts(2), 0.5f); + // first block. calculate it. ASSERT_EQ(diff.azimuth(0), 20); + // second block. calculate it. ASSERT_EQ(diff.azimuth(1), 20); + // (last - 1) block = prev block ASSERT_EQ(diff.azimuth(4), 30); + // last block = prev block ASSERT_EQ(diff.azimuth(5), 30); } diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_diff_test.cpp index 52a5eb98..39297a43 100644 --- a/test/single_return_block_diff_test.cpp +++ b/test/single_return_block_diff_test.cpp @@ -62,11 +62,16 @@ TEST(TestSingleReturnBlockDiff, ctor) SingleReturnBlockDiff diff(pkt, const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); + // first block = 0 ASSERT_EQ(diff.ts(0), 0.0f); + // second block. calculate it. ASSERT_EQ(diff.ts(1), 0.5f); + // first block. calculate it. ASSERT_EQ(diff.azimuth(0), 20); + // second block. calculate it. ASSERT_EQ(diff.azimuth(1), 30); + // second block = prev block ASSERT_EQ(diff.azimuth(2), 30); } diff --git a/test/sync_queue_test.cpp b/test/sync_queue_test.cpp index af5931f3..dc8c1f82 100644 --- a/test/sync_queue_test.cpp +++ b/test/sync_queue_test.cpp @@ -51,11 +51,9 @@ TEST(TestSyncQueue, clear) { SyncQueue> queue; - { - std::shared_ptr v_ptr = std::make_shared(100); - ASSERT_EQ(queue.push(v_ptr), 1); - ASSERT_EQ(queue.push(v_ptr), 2); - queue.clear(); - ASSERT_EQ(queue.push(v_ptr), 1); - } + std::shared_ptr v_ptr = std::make_shared(100); + ASSERT_EQ(queue.push(v_ptr), 1); + ASSERT_EQ(queue.push(v_ptr), 2); + queue.clear(); + ASSERT_EQ(queue.push(v_ptr), 1); } From 17c87122c1e17e38b236b4f75b95140394cdf00e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 20 Dec 2021 14:48:22 +0800 Subject: [PATCH 094/379] fix: fix rs32 point cloud --- src/rs_driver/driver/decoder/block_diff.hpp | 8 +- src/rs_driver/driver/decoder/chan_angles.hpp | 33 +++-- src/rs_driver/driver/decoder/decoder.hpp | 6 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 10 +- src/rs_driver/driver/driver_param.h | 2 +- src/rs_driver/driver/lidar_driver_impl.hpp | 29 +++-- src/rs_driver/msg/pcl_point_cloud_msg.h | 2 +- src/rs_driver/msg/point_cloud_msg.h | 2 +- src/rs_driver/utility/lock_queue.h | 101 +++++++++++++++ src/rs_driver/utility/thread_pool.hpp | 120 ++++++++++++++++++ src/rs_driver/utility/time.h | 47 +++++++ test/chan_angles_test.cpp | 22 +++- test/dual_return_block_diff_test.cpp | 12 +- test/single_return_block_diff_test.cpp | 6 +- 14 files changed, 348 insertions(+), 52 deletions(-) create mode 100644 src/rs_driver/utility/lock_queue.h create mode 100644 src/rs_driver/utility/thread_pool.hpp create mode 100644 src/rs_driver/utility/time.h diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index f0418ffe..9a8c9b28 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -57,9 +57,9 @@ class SingleReturnBlockDiff int32_t azi= 0; if (blk < (BLOCKS_PER_PKT - 1)) - azi = this->pkt_.blocks[blk+1].azimuth - this->pkt_.blocks[blk].azimuth; + azi = ntohs(this->pkt_.blocks[blk+1].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); else - azi = this->pkt_.blocks[blk].azimuth - this->pkt_.blocks[blk-1].azimuth; + azi = ntohs(this->pkt_.blocks[blk].azimuth) - ntohs(this->pkt_.blocks[blk-1].azimuth); return azi; } @@ -99,11 +99,11 @@ class DualReturnBlockDiff if (blk >= (BLOCKS_PER_PKT - 2)) { - azi = this->pkt_.blocks[blk].azimuth - this->pkt_.blocks[blk-2].azimuth; + azi = ntohs(this->pkt_.blocks[blk].azimuth) - ntohs(this->pkt_.blocks[blk-2].azimuth); } else { - azi = this->pkt_.blocks[blk+2].azimuth - this->pkt_.blocks[blk].azimuth; + azi = ntohs(this->pkt_.blocks[blk+2].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); } return azi; diff --git a/src/rs_driver/driver/decoder/chan_angles.hpp b/src/rs_driver/driver/decoder/chan_angles.hpp index c3757bed..631e61bd 100644 --- a/src/rs_driver/driver/decoder/chan_angles.hpp +++ b/src/rs_driver/driver/decoder/chan_angles.hpp @@ -53,8 +53,8 @@ class ChanAngles { public: - ChanAngles(uint16_t chan_num) - : chan_num_(chan_num) + ChanAngles(uint16_t chan_num, bool narrow_angles = false) + : chan_num_(chan_num), narrow_angles_(narrow_angles) { vert_angles_.resize(chan_num_); horiz_angles_.resize(chan_num_); @@ -98,6 +98,16 @@ class ChanAngles vert_angles_.swap(vert_angles); horiz_angles_.swap(horiz_angles); genUserChan(vert_angles_, user_chans_); + + // + // some lidas, such as RS32, have higher resolution than the other lidars. + // fix them to the same resolution. + // + if (narrow_angles_) + { + narrow(); + } + return 0; } @@ -116,15 +126,6 @@ class ChanAngles return vert_angles_[chan]; } - void narrow() - { - for (uint16_t chan = 0; chan < chan_num_; chan++) - { - vert_angles_[chan] = std::round(vert_angles_[chan] * 0.1f); - horiz_angles_[chan] = std::round(horiz_angles_[chan] * 0.1f); - } - } - void print() { std::cout << "---------------------" << std::endl @@ -144,6 +145,15 @@ class ChanAngles private: #endif + void narrow() + { + for (uint16_t chan = 0; chan < chan_num_; chan++) + { + vert_angles_[chan] = std::round(vert_angles_[chan] * 0.1f); + horiz_angles_[chan] = std::round(horiz_angles_[chan] * 0.1f); + } + } + static void genUserChan(const std::vector& vert_angles, std::vector& user_chans) { @@ -224,6 +234,7 @@ class ChanAngles } uint16_t chan_num_; + bool narrow_angles_; std::vector vert_angles_; std::vector horiz_angles_; std::vector user_chans_; diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 6b1a408e..9285eda1 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -273,7 +273,7 @@ class Decoder explicit Decoder(const RSDecoderParam& param, const std::function& excb, - const RSDecoderConstParam& const_param); + const RSDecoderConstParam& const_param, bool narrow_angles = false); void processDifopPkt(const uint8_t* pkt, size_t size); void processMsopPkt(const uint8_t* pkt, size_t size); @@ -335,12 +335,12 @@ class Decoder template inline Decoder::Decoder(const RSDecoderParam& param, const std::function& excb, - const RSDecoderConstParam& const_param) + const RSDecoderConstParam& const_param, bool narrow_angles) : const_param_(const_param) , param_(param) , excb_(excb) , height_(const_param.CHANNELS_PER_BLOCK) - , chan_angles_(const_param.CHANNELS_PER_BLOCK) + , chan_angles_(const_param.CHANNELS_PER_BLOCK, narrow_angles) , distance_section_(const_param.DISTANCE_MIN, const_param.DISTANCE_MAX, param.min_distance, param.max_distance) , scan_section_(param.start_angle * 100, param.end_angle * 100) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 0ac3bad7..6ff57224 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -165,7 +165,7 @@ RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) template inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, getConstParam()) + : Decoder(param, excb, getConstParam(), true) { } @@ -178,12 +178,6 @@ inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, siz this->echo_mode_ = getEchoMode (pkt.return_mode); this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? (this->blks_per_frame_ << 1) : this->blks_per_frame_; - - // - // RS32's channel angles is of higher resolution than the other lidars. - // fix them to the same resolution. - // - this->chan_angles_.narrow(); } template @@ -208,6 +202,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet this->temperature_ = calcTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; double pkt_ts = 0; +#if 0 if (this->param_.use_lidar_clock) { pkt_ts = calcTimeYMD(&pkt.header.timestamp); @@ -217,6 +212,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet // roll back to first block to approach lidar ts as near as possible. pkt_ts = calcTimeHost() - this->getPacketDuration(); } +#endif T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index 86d319f6..41dad956 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -256,7 +256,7 @@ typedef struct RSInputParam ///< The LiDAR input parameter std::string multi_cast_address = "0.0.0.0"; ///< Address of multicast std::string pcap_path = "null"; ///< Absolute path of pcap file bool pcap_repeat = true; ///< true: The pcap bag will repeat play - double pcap_rate = 1; ///< Rate to read the pcap file + float pcap_rate = 1; ///< Rate to read the pcap file bool use_vlan = false; ///< Vlan on-off bool use_someip = false; ///< Someip on-off diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index a28a6269..f307ef9f 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -63,15 +63,7 @@ class LidarDriverImpl void stop(); void regRecvCallback(const std::function(void)>& cb_get, - const std::function)>& cb_put) - { - point_cloud_cb_get_ = cb_get; - point_cloud_cb_put_ = cb_put; - } - - std::function(void)> point_cloud_cb_get_; - std::function)> point_cloud_cb_put_; - + const std::function)>& cb_put); void regRecvCallback(const std::function& callback); void regExceptionCallback(const std::function& callback); void decodePacket(const uint8_t* pkt, size_t size); @@ -79,6 +71,9 @@ class LidarDriverImpl private: + std::function(void)> point_cloud_cb_get_; + std::function)> point_cloud_cb_put_; + std::shared_ptr getPointCloud(); void putPointCloud(std::shared_ptr pc); @@ -144,10 +139,6 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) param.lidar_type, param.decoder_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); - lidar_decoder_ptr_->regRecvCallback( - std::bind(&LidarDriverImpl::getPointCloud, this), - std::bind(&LidarDriverImpl::putPointCloud, this, std::placeholders::_1)); - double packet_duration = lidar_decoder_ptr_->getPacketDuration(); input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, @@ -213,6 +204,18 @@ inline void LidarDriverImpl::stop() } } +template +void LidarDriverImpl::regRecvCallback(const std::function(void)>& cb_get, + const std::function)>& cb_put) +{ + point_cloud_cb_get_ = cb_get; + point_cloud_cb_put_ = cb_put; + + lidar_decoder_ptr_->regRecvCallback( + std::bind(&LidarDriverImpl::getPointCloud, this), + std::bind(&LidarDriverImpl::putPointCloud, this, std::placeholders::_1)); +} + template inline void LidarDriverImpl::regRecvCallback(const std::function& callback) { diff --git a/src/rs_driver/msg/pcl_point_cloud_msg.h b/src/rs_driver/msg/pcl_point_cloud_msg.h index 6d4dcb62..4e52409f 100644 --- a/src/rs_driver/msg/pcl_point_cloud_msg.h +++ b/src/rs_driver/msg/pcl_point_cloud_msg.h @@ -57,6 +57,6 @@ class PointCloudT : public pcl::PointCloud typedef typename pcl::PointCloud::VectorType VectorT; double timestamp = 0.0; - std::string frame_id = ""; ///< Point cloud frame id + std::string frame_id = "rslidar"; ///< Point cloud frame id uint32_t seq = 0; ///< Sequence number of message }; diff --git a/src/rs_driver/msg/point_cloud_msg.h b/src/rs_driver/msg/point_cloud_msg.h index 52e8c1a3..fcbf0d9c 100644 --- a/src/rs_driver/msg/point_cloud_msg.h +++ b/src/rs_driver/msg/point_cloud_msg.h @@ -61,7 +61,7 @@ class PointCloudT uint32_t width = 0; ///< Width of point cloud bool is_dense = false; ///< If is_dense=true, the point cloud does not contain NAN points double timestamp = 0.0; - std::string frame_id = ""; ///< Point cloud frame id + std::string frame_id = "rslidar"; ///< Point cloud frame id uint32_t seq = 0; ///< Sequence number of message VectorT points; diff --git a/src/rs_driver/utility/lock_queue.h b/src/rs_driver/utility/lock_queue.h new file mode 100644 index 00000000..56e19d12 --- /dev/null +++ b/src/rs_driver/utility/lock_queue.h @@ -0,0 +1,101 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include +namespace robosense +{ +namespace lidar +{ +template +class Queue +{ +public: + inline Queue() : is_task_finished_(true) + { + } + + inline T front() + { + std::lock_guard lock(mutex_); + return queue_.front(); + } + + inline void push(const T& value) + { + std::lock_guard lock(mutex_); + queue_.push(value); + } + + inline void pop() + { + std::lock_guard lock(mutex_); + if (!queue_.empty()) + { + queue_.pop(); + } + } + + inline T popFront() + { + T value; + std::lock_guard lock(mutex_); + if (!queue_.empty()) + { + value = std::move(queue_.front()); + queue_.pop(); + } + return value; + } + + inline void clear() + { + std::queue empty; + std::lock_guard lock(mutex_); + swap(empty, queue_); + } + + inline size_t size() + { + std::lock_guard lock(mutex_); + return queue_.size(); + } + +public: + std::queue queue_; + std::atomic is_task_finished_; + +private: + mutable std::mutex mutex_; +}; +} // namespace lidar +} // namespace robosense \ No newline at end of file diff --git a/src/rs_driver/utility/thread_pool.hpp b/src/rs_driver/utility/thread_pool.hpp new file mode 100644 index 00000000..d97c85a2 --- /dev/null +++ b/src/rs_driver/utility/thread_pool.hpp @@ -0,0 +1,120 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include +#include +#include +#include +#include +#include +#include +#include +#include +namespace robosense +{ +namespace lidar +{ +constexpr uint16_t MAX_THREAD_NUM = 2; +struct Thread +{ + Thread() : start_(false) + { + } + std::shared_ptr thread_; + std::atomic start_; +}; +class ThreadPool +{ +public: + typedef std::shared_ptr Ptr; + inline ThreadPool() : stop_flag_(false), idl_thr_num_(MAX_THREAD_NUM) + { + for (int i = 0; i < idl_thr_num_; ++i) + { + pool_.emplace_back([this] { + while (!this->stop_flag_) + { + std::function task; + { + std::unique_lock lock{ this->mutex_ }; + this->cv_task_.wait(lock, [this] { return this->stop_flag_.load() || !this->tasks_.empty(); }); + if (this->stop_flag_ && this->tasks_.empty()) + return; + task = std::move(this->tasks_.front()); + this->tasks_.pop(); + } + idl_thr_num_--; + task(); + idl_thr_num_++; + } + }); + } + } + + inline ~ThreadPool() + { + stop_flag_.store(true); + cv_task_.notify_all(); + for (std::thread& thread : pool_) + { + thread.join(); + } + } + +public: + template + inline void commit(F&& f, Args&&... args) + { + if (stop_flag_.load()) + throw std::runtime_error("Commit on LiDAR threadpool is stopped."); + using RetType = decltype(f(args...)); + auto task = + std::make_shared>(std::bind(std::forward(f), std::forward(args)...)); + { + std::lock_guard lock{ mutex_ }; + tasks_.emplace([task]() { (*task)(); }); + } + cv_task_.notify_one(); + } + +private: + using Task = std::function; + std::vector pool_; + std::queue tasks_; + std::mutex mutex_; + std::condition_variable cv_task_; + std::atomic stop_flag_; + std::atomic idl_thr_num_; +}; +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/utility/time.h b/src/rs_driver/utility/time.h new file mode 100644 index 00000000..266106d8 --- /dev/null +++ b/src/rs_driver/utility/time.h @@ -0,0 +1,47 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include +#include +namespace robosense +{ +namespace lidar +{ +inline double getTime(void) +{ + const auto t = std::chrono::system_clock::now(); + const auto t_sec = std::chrono::duration_cast>(t.time_since_epoch()); + return (double)t_sec.count(); +} +} // namespace lidar +} // namespace robosense diff --git a/test/chan_angles_test.cpp b/test/chan_angles_test.cpp index 4cb40264..e6139e40 100644 --- a/test/chan_angles_test.cpp +++ b/test/chan_angles_test.cpp @@ -163,9 +163,27 @@ TEST(TestChanAngles, memberLoadFromDifop) ASSERT_EQ(angles.toUserChan(1), 1); ASSERT_EQ(angles.toUserChan(2), 0); ASSERT_EQ(angles.toUserChan(3), 3); +} + +TEST(TestChanAngles, memberLoadFromDifop_narrow) +{ + uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, + 0x01, 0x03, 0x04, + 0x01, 0x05, 0x06, + 0x00, 0x07, 0x08}; + uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, + 0x01, 0x33, 0x44, + 0x00, 0x55, 0x66, + 0x01, 0x77, 0x88}; - // narrow after load. for RS32 - angles.narrow(); + ChanAngles angles(4, true); + ASSERT_EQ(angles.chan_num_, 4); + + // load + ASSERT_EQ(angles.loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4), 0); ASSERT_EQ(angles.vert_angles_.size(), 4); ASSERT_EQ(angles.vert_angles_[0], 26); diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_diff_test.cpp index 5342682d..87bd0808 100644 --- a/test/dual_return_block_diff_test.cpp +++ b/test/dual_return_block_diff_test.cpp @@ -54,12 +54,12 @@ TEST(TestDualPacketTraverser, toNext) MyPacket pkt = { - 1, 0x00, 0x00, 0x00, 0x00 - , 1, 0x00, 0x00, 0x00, 0x00 - , 21, 0x00, 0x00, 0x00, 0x00 - , 21, 0x00, 0x00, 0x00, 0x00 - , 51, 0x00, 0x00, 0x00, 0x00 - , 51, 0x00, 0x00, 0x00, 0x00 + htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + , htons(51), 0x00, 0x00, 0x00, 0x00 + , htons(51), 0x00, 0x00, 0x00, 0x00 }; DualReturnBlockDiff diff(pkt, diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_diff_test.cpp index 39297a43..2485b7dd 100644 --- a/test/single_return_block_diff_test.cpp +++ b/test/single_return_block_diff_test.cpp @@ -54,9 +54,9 @@ TEST(TestSingleReturnBlockDiff, ctor) MyPacket pkt = { - 1, 0x00, 0x00, 0x00, 0x00 - , 21, 0x00, 0x00, 0x00, 0x00 - , 51, 0x00, 0x00, 0x00, 0x00 + htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + , htons(51), 0x00, 0x00, 0x00, 0x00 }; SingleReturnBlockDiff diff(pkt, From d28e2c0bb09f9dad97b7806e73136bea6d22ad55 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 20 Dec 2021 15:26:40 +0800 Subject: [PATCH 095/379] refac: refactory decoder --- src/rs_driver/driver/lidar_driver_impl.hpp | 13 ++- src/rs_driver/msg/packet_msg.h | 8 +- src/rs_driver/utility/lock_queue.h | 101 ----------------- src/rs_driver/utility/thread_pool.hpp | 120 --------------------- src/rs_driver/utility/time.h | 47 -------- 5 files changed, 12 insertions(+), 277 deletions(-) delete mode 100644 src/rs_driver/utility/lock_queue.h delete mode 100644 src/rs_driver/utility/thread_pool.hpp delete mode 100644 src/rs_driver/utility/time.h diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index f307ef9f..e9654239 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -138,6 +138,15 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) lidar_decoder_ptr_ = DecoderFactory::createDecoder( param.lidar_type, param.decoder_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); + if ((point_cloud_cb_get_ == nullptr) || (point_cloud_cb_put_ == nullptr)) + { + std::cout << "please set point cloud callback first." << std::endl; + return false; + } + + lidar_decoder_ptr_->regRecvCallback( + std::bind(&LidarDriverImpl::getPointCloud, this), + std::bind(&LidarDriverImpl::putPointCloud, this, std::placeholders::_1)); double packet_duration = lidar_decoder_ptr_->getPacketDuration(); @@ -210,10 +219,6 @@ void LidarDriverImpl::regRecvCallback(const std::functionregRecvCallback( - std::bind(&LidarDriverImpl::getPointCloud, this), - std::bind(&LidarDriverImpl::putPointCloud, this, std::placeholders::_1)); } template diff --git a/src/rs_driver/msg/packet_msg.h b/src/rs_driver/msg/packet_msg.h index 0a1a674d..b4548cc3 100644 --- a/src/rs_driver/msg/packet_msg.h +++ b/src/rs_driver/msg/packet_msg.h @@ -31,6 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once + #include namespace robosense @@ -42,11 +43,8 @@ enum PktType MSOP = 0, DIFOP }; -#ifdef _MSC_VER -struct __declspec(align(16)) PacketMsg -#elif __GNUC__ -struct __attribute__((aligned(16))) PacketMsg ///< LiDAR single packet message -#endif + +struct PacketMsg { std::vector packet; PacketMsg() diff --git a/src/rs_driver/utility/lock_queue.h b/src/rs_driver/utility/lock_queue.h deleted file mode 100644 index 56e19d12..00000000 --- a/src/rs_driver/utility/lock_queue.h +++ /dev/null @@ -1,101 +0,0 @@ -/********************************************************************************************************************* -Copyright (c) 2020 RoboSense -All rights reserved - -By downloading, copying, installing or using the software you agree to this license. If you do not agree to this -license, do not download, install, copy or use the software. - -License Agreement -For RoboSense LiDAR SDK Library -(3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials provided with the distribution. - -3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used -to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*********************************************************************************************************************/ - -#pragma once -#include -namespace robosense -{ -namespace lidar -{ -template -class Queue -{ -public: - inline Queue() : is_task_finished_(true) - { - } - - inline T front() - { - std::lock_guard lock(mutex_); - return queue_.front(); - } - - inline void push(const T& value) - { - std::lock_guard lock(mutex_); - queue_.push(value); - } - - inline void pop() - { - std::lock_guard lock(mutex_); - if (!queue_.empty()) - { - queue_.pop(); - } - } - - inline T popFront() - { - T value; - std::lock_guard lock(mutex_); - if (!queue_.empty()) - { - value = std::move(queue_.front()); - queue_.pop(); - } - return value; - } - - inline void clear() - { - std::queue empty; - std::lock_guard lock(mutex_); - swap(empty, queue_); - } - - inline size_t size() - { - std::lock_guard lock(mutex_); - return queue_.size(); - } - -public: - std::queue queue_; - std::atomic is_task_finished_; - -private: - mutable std::mutex mutex_; -}; -} // namespace lidar -} // namespace robosense \ No newline at end of file diff --git a/src/rs_driver/utility/thread_pool.hpp b/src/rs_driver/utility/thread_pool.hpp deleted file mode 100644 index d97c85a2..00000000 --- a/src/rs_driver/utility/thread_pool.hpp +++ /dev/null @@ -1,120 +0,0 @@ -/********************************************************************************************************************* -Copyright (c) 2020 RoboSense -All rights reserved - -By downloading, copying, installing or using the software you agree to this license. If you do not agree to this -license, do not download, install, copy or use the software. - -License Agreement -For RoboSense LiDAR SDK Library -(3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials provided with the distribution. - -3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used -to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*********************************************************************************************************************/ - -#pragma once -#include -#include -#include -#include -#include -#include -#include -#include -#include -namespace robosense -{ -namespace lidar -{ -constexpr uint16_t MAX_THREAD_NUM = 2; -struct Thread -{ - Thread() : start_(false) - { - } - std::shared_ptr thread_; - std::atomic start_; -}; -class ThreadPool -{ -public: - typedef std::shared_ptr Ptr; - inline ThreadPool() : stop_flag_(false), idl_thr_num_(MAX_THREAD_NUM) - { - for (int i = 0; i < idl_thr_num_; ++i) - { - pool_.emplace_back([this] { - while (!this->stop_flag_) - { - std::function task; - { - std::unique_lock lock{ this->mutex_ }; - this->cv_task_.wait(lock, [this] { return this->stop_flag_.load() || !this->tasks_.empty(); }); - if (this->stop_flag_ && this->tasks_.empty()) - return; - task = std::move(this->tasks_.front()); - this->tasks_.pop(); - } - idl_thr_num_--; - task(); - idl_thr_num_++; - } - }); - } - } - - inline ~ThreadPool() - { - stop_flag_.store(true); - cv_task_.notify_all(); - for (std::thread& thread : pool_) - { - thread.join(); - } - } - -public: - template - inline void commit(F&& f, Args&&... args) - { - if (stop_flag_.load()) - throw std::runtime_error("Commit on LiDAR threadpool is stopped."); - using RetType = decltype(f(args...)); - auto task = - std::make_shared>(std::bind(std::forward(f), std::forward(args)...)); - { - std::lock_guard lock{ mutex_ }; - tasks_.emplace([task]() { (*task)(); }); - } - cv_task_.notify_one(); - } - -private: - using Task = std::function; - std::vector pool_; - std::queue tasks_; - std::mutex mutex_; - std::condition_variable cv_task_; - std::atomic stop_flag_; - std::atomic idl_thr_num_; -}; -} // namespace lidar -} // namespace robosense diff --git a/src/rs_driver/utility/time.h b/src/rs_driver/utility/time.h deleted file mode 100644 index 266106d8..00000000 --- a/src/rs_driver/utility/time.h +++ /dev/null @@ -1,47 +0,0 @@ -/********************************************************************************************************************* -Copyright (c) 2020 RoboSense -All rights reserved - -By downloading, copying, installing or using the software you agree to this license. If you do not agree to this -license, do not download, install, copy or use the software. - -License Agreement -For RoboSense LiDAR SDK Library -(3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials provided with the distribution. - -3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used -to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*********************************************************************************************************************/ - -#pragma once -#include -#include -namespace robosense -{ -namespace lidar -{ -inline double getTime(void) -{ - const auto t = std::chrono::system_clock::now(); - const auto t_sec = std::chrono::duration_cast>(t.time_since_epoch()); - return (double)t_sec.count(); -} -} // namespace lidar -} // namespace robosense From fd07fad8542f336b5938cf316150929fe8e8c4ac Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 20 Dec 2021 16:34:04 +0800 Subject: [PATCH 096/379] format: format code --- src/rs_driver/driver/decoder/basic_attr.hpp | 12 +++++----- src/rs_driver/driver/decoder/decoder_RS32.hpp | 8 +++---- test/basic_attr_test.cpp | 22 +++++++++---------- 3 files changed, 20 insertions(+), 22 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index 52a23e1e..d0db67d7 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -78,7 +78,7 @@ typedef struct #pragma pack(pop) -inline uint64_t calcTimeUTCWithNs(const RSTimestampUTC2* tsUtc) +inline uint64_t parseTimeUTCWithNs(const RSTimestampUTC2* tsUtc) { // sec uint64_t sec = 0; @@ -98,7 +98,7 @@ inline uint64_t calcTimeUTCWithNs(const RSTimestampUTC2* tsUtc) return (sec * 1000000 + ns/1000); } -inline uint64_t calcTimeUTCWithUs(const RSTimestampUTC2* tsUtc) +inline uint64_t parseTimeUTCWithUs(const RSTimestampUTC2* tsUtc) { // sec uint64_t sec = 0; @@ -118,7 +118,7 @@ inline uint64_t calcTimeUTCWithUs(const RSTimestampUTC2* tsUtc) return (sec * 1000000 + us); } -inline uint64_t calcTimeUTCWithMs(const RSTimestampUTC2* tsUtc) +inline uint64_t parseTimeUTCWithMs(const RSTimestampUTC2* tsUtc) { // sec uint64_t sec = 0; @@ -141,7 +141,7 @@ inline uint64_t calcTimeUTCWithMs(const RSTimestampUTC2* tsUtc) return (sec * 1000000 + ms * 1000 + us); } -inline uint64_t calcTimeYMD(const RSTimestampYMD* tsYmd) +inline uint64_t parseTimeYMD(const RSTimestampYMD* tsYmd) { std::tm stm; memset(&stm, 0, sizeof(stm)); @@ -171,7 +171,7 @@ inline uint64_t calcTimeYMD(const RSTimestampYMD* tsYmd) return (sec * 1000000 + ms * 1000 + us); } -inline uint64_t calcTimeHost(void) +inline uint64_t getTimeHost(void) { std::chrono::system_clock::time_point t = std::chrono::system_clock::now(); std::chrono::system_clock::duration t_s = t.time_since_epoch(); @@ -181,7 +181,7 @@ inline uint64_t calcTimeHost(void) return t_us.count(); } -inline int16_t calcTemp(const RSTemprature* tmp) +inline int16_t parseTemp(const RSTemprature* tmp) { // | lsb | padding | neg | msb | // | 5 | 3 | 1 | 7 | (in bits) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 6ff57224..510adc29 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -199,20 +199,18 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet { const RS32MsopPkt& pkt = *(const RS32MsopPkt*)(packet); - this->temperature_ = calcTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; double pkt_ts = 0; -#if 0 if (this->param_.use_lidar_clock) { - pkt_ts = calcTimeYMD(&pkt.header.timestamp); + pkt_ts = parseTimeYMD(&pkt.header.timestamp); } else { // roll back to first block to approach lidar ts as near as possible. - pkt_ts = calcTimeHost() - this->getPacketDuration(); + pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); } -#endif T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); diff --git a/test/basic_attr_test.cpp b/test/basic_attr_test.cpp index 9f34a127..b0c7d087 100644 --- a/test/basic_attr_test.cpp +++ b/test/basic_attr_test.cpp @@ -5,38 +5,38 @@ using namespace robosense::lidar; -TEST(TestParseTime, calcTimeUTC) +TEST(TestParseTime, parseTimeUTC) { RSTimestampUTC2 ts = {{0x01, 0x02, 0x03, 0x04, 0x05, 0x06}, {0x11, 0x22, 0x33, 0x44}}; - ASSERT_EQ(calcTimeUTCWithNs(&ts), 0x010203040506 * 1000000 + 0x11223344/1000); - ASSERT_EQ(calcTimeUTCWithUs(&ts), 0x010203040506 * 1000000 + 0x11223344); - ASSERT_EQ(calcTimeUTCWithMs(&ts), 0x010203040506 * 1000000 + 0x1122 * 1000 + 0x3344); + ASSERT_EQ(parseTimeUTCWithNs(&ts), 0x010203040506 * 1000000 + 0x11223344/1000); + ASSERT_EQ(parseTimeUTCWithUs(&ts), 0x010203040506 * 1000000 + 0x11223344); + ASSERT_EQ(parseTimeUTCWithMs(&ts), 0x010203040506 * 1000000 + 0x1122 * 1000 + 0x3344); } -TEST(TestParseTime, calcTimeYMD) +TEST(TestParseTime, parseTimeYMD) { uint8_t ts[] = {0x15, 0x0a, 0x01, 0x01, 0x02, 0x03, 0x11, 0x22, 0x33, 0x44}; - ASSERT_EQ(calcTimeYMD((RSTimestampYMD*)&ts), 1633021327399124); + ASSERT_EQ(parseTimeYMD((RSTimestampYMD*)&ts), 1633021327399124); } -TEST(TestParseTime, calcTimeHost) +TEST(TestParseTime, getTimeHost) { - calcTimeHost(); + getTimeHost(); } -TEST(TestParseTemp, calcTemp) +TEST(TestParseTemp, parseTemp) { { uint8_t temp[] = {0x18, 0x01}; - ASSERT_EQ(calcTemp((RSTemprature*)&temp), 35); + ASSERT_EQ(parseTemp((RSTemprature*)&temp), 35); } { uint8_t temp[] = {0x18, 0x81}; - ASSERT_EQ(calcTemp((RSTemprature*)&temp), -35); + ASSERT_EQ(parseTemp((RSTemprature*)&temp), -35); } } From 3a8b54faee7e0cb46e8eb2d549bb092a0e3970f3 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 20 Dec 2021 17:54:20 +0800 Subject: [PATCH 097/379] format: format --- src/rs_driver/driver/decoder/block_diff.hpp | 4 ++++ src/rs_driver/driver/decoder/section.hpp | 4 ++++ src/rs_driver/driver/decoder/split_strategy.hpp | 2 ++ src/rs_driver/driver/decoder/trigon.hpp | 4 ++++ src/rs_driver/driver/lidar_driver_impl.hpp | 11 +++++++++++ 5 files changed, 25 insertions(+) diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index 9a8c9b28..db651fea 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -57,9 +57,13 @@ class SingleReturnBlockDiff int32_t azi= 0; if (blk < (BLOCKS_PER_PKT - 1)) + { azi = ntohs(this->pkt_.blocks[blk+1].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); + } else + { azi = ntohs(this->pkt_.blocks[blk].azimuth) - ntohs(this->pkt_.blocks[blk-1].azimuth); + } return azi; } diff --git a/src/rs_driver/driver/decoder/section.hpp b/src/rs_driver/driver/decoder/section.hpp index f35a3184..371355f2 100644 --- a/src/rs_driver/driver/decoder/section.hpp +++ b/src/rs_driver/driver/decoder/section.hpp @@ -50,9 +50,13 @@ class AzimuthSection bool in(int32_t angle) { if (cross_zero_) + { return (angle >= start_) || (angle < end_); + } else + { return (angle >= start_) && (angle < end_); + } } #ifndef UNIT_TEST diff --git a/src/rs_driver/driver/decoder/split_strategy.hpp b/src/rs_driver/driver/decoder/split_strategy.hpp index 90dacbba..dec6c7df 100644 --- a/src/rs_driver/driver/decoder/split_strategy.hpp +++ b/src/rs_driver/driver/decoder/split_strategy.hpp @@ -57,7 +57,9 @@ class SplitStrategyByAngle : public SplitStrategy virtual bool newBlock(int32_t angle) { if (angle < prev_angle_) + { prev_angle_ -= 36000; + } bool v = ((prev_angle_ < split_angle_) && (split_angle_ <= angle)); #if 0 diff --git a/src/rs_driver/driver/decoder/trigon.hpp b/src/rs_driver/driver/decoder/trigon.hpp index 9d7617c8..f55429d8 100644 --- a/src/rs_driver/driver/decoder/trigon.hpp +++ b/src/rs_driver/driver/decoder/trigon.hpp @@ -93,7 +93,9 @@ class Trigon { #ifdef DBG if (angle < MIN || angle >= MAX) + { return 0.0f; + } #endif return sins_[angle]; @@ -103,7 +105,9 @@ class Trigon { #ifdef DBG if (angle < MIN || angle >= MAX) + { return 0.0f; + } #endif return coss_[angle]; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index e9654239..d9cc3dfe 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -138,6 +138,7 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) lidar_decoder_ptr_ = DecoderFactory::createDecoder( param.lidar_type, param.decoder_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); + if ((point_cloud_cb_get_ == nullptr) || (point_cloud_cb_put_ == nullptr)) { std::cout << "please set point cloud callback first." << std::endl; @@ -182,10 +183,14 @@ template inline bool LidarDriverImpl::start() { if (start_flag_) + { return true; + } if (!init_flag_) + { return false; + } to_exit_handle_ = false; msop_handle_thread_ = std::thread(std::bind(&LidarDriverImpl::processMsop, this)); @@ -201,7 +206,9 @@ template inline void LidarDriverImpl::stop() { if (input_ptr_ != nullptr) + { input_ptr_->stop(); + } if (start_flag_) { @@ -336,7 +343,9 @@ inline void LidarDriverImpl::processMsop() { std::shared_ptr pkt = msop_pkt_queue_.popWait(1000); if (pkt.get() == NULL) + { continue; + } lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); runCallBack(pkt); @@ -352,7 +361,9 @@ inline void LidarDriverImpl::processDifop() { std::shared_ptr pkt = difop_pkt_queue_.popWait(500000); if (pkt.get() == NULL) + { continue; + } lidar_decoder_ptr_->processDifopPkt(pkt->data(), pkt->dataSize()); From ba4776b5bad94e97f0444fc87149348df5efa00b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 20 Dec 2021 20:33:35 +0800 Subject: [PATCH 098/379] refac: refactory decoder --- demo/demo_online.cpp | 8 +- src/rs_driver/driver/decoder/block_diff.hpp | 4 + src/rs_driver/driver/decoder/chan_angles.hpp | 10 + src/rs_driver/driver/decoder/decoder_RSBP.hpp | 298 ++++++++++-------- .../driver/decoder/decoder_factory.hpp | 10 +- src/rs_driver/driver/decoder/section.hpp | 6 + test/CMakeLists.txt | 1 + test/chan_angles_test.cpp | 91 ++++-- test/decoder_rsbp_test.cpp | 165 ++++++++++ 9 files changed, 432 insertions(+), 161 deletions(-) create mode 100644 test/decoder_rsbp_test.cpp diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 4c7f248f..b9470072 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -81,10 +81,10 @@ int main(int argc, char* argv[]) RSDriverParam param; ///< Create a parameter object param.input_type = InputType::ONLINE_LIDAR; - param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 - param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RS32; ///< Set the lidar type. Make sure this type is correct - param.decoder_param.wait_for_difop = false; ///< true: start sending point cloud until receive difop packet + param.input_param.msop_port = 2370; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 8310; ///< Set the lidar difop port number, the default is 7788 + param.lidar_type = LidarType::RSBP; ///< Set the lidar type. Make sure this type is correct + param.decoder_param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet param.print(); LidarDriver driver; diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index db651fea..f44bc051 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -64,6 +64,8 @@ class SingleReturnBlockDiff { azi = ntohs(this->pkt_.blocks[blk].azimuth) - ntohs(this->pkt_.blocks[blk-1].azimuth); } + + if (azi < 0) azi += 36000; return azi; } @@ -110,6 +112,8 @@ class DualReturnBlockDiff azi = ntohs(this->pkt_.blocks[blk+2].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); } + if (azi < 0) azi += 36000; + return azi; } diff --git a/src/rs_driver/driver/decoder/chan_angles.hpp b/src/rs_driver/driver/decoder/chan_angles.hpp index 631e61bd..cc944d1f 100644 --- a/src/rs_driver/driver/decoder/chan_angles.hpp +++ b/src/rs_driver/driver/decoder/chan_angles.hpp @@ -224,15 +224,25 @@ class ChanAngles if (vert.sign != 0) v = -v; vert_angles.emplace_back(v); + if (!angleCheck (v)) + return -1; + v = ntohs(horiz.value); if (horiz.sign != 0) v = -v; horiz_angles.emplace_back(v); + if (!angleCheck (v)) + return -1; } return ((vert_angles.size() > 0) ? 0 : -1); } + static bool angleCheck(int32_t v) + { + return ((-9000 <= v) && (v < 9000)); + } + uint16_t chan_num_; bool narrow_angles_; std::vector vert_angles_; diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index f710f1fc..c86e84e8 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -30,22 +30,24 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include +#include + namespace robosense { namespace lidar { + #pragma pack(push, 1) typedef struct { - uint16_t id; + uint8_t id[2]; uint16_t azimuth; RSChannel channels[32]; } RSBPMsopBlock; typedef struct { - RSMsopHeader header; + RSMsopHeaderV1 header; RSBPMsopBlock blocks[12]; unsigned int index; uint16_t tail; @@ -53,22 +55,22 @@ typedef struct typedef struct { - uint64_t id; + uint8_t id[8]; uint16_t rpm; - RSEthNet eth; + RSEthNetV1 eth; RSFOV fov; uint16_t reserved0; uint16_t phase_lock_angle; - RSVersion version; + RSVersionV1 version; uint8_t reserved_1[242]; - RSSn sn; + RSSN sn; uint16_t zero_cali; uint8_t return_mode; uint16_t sw_ver; RSTimestampYMD timestamp; - RSStatus status; + RSStatusV1 status; uint8_t reserved_2[5]; - RSDiagno diagno; + RSDiagnoV1 diagno; uint8_t gprmc[86]; RSCalibrationAngle ver_angle_cali[32]; RSCalibrationAngle hori_angle_cali[32]; @@ -79,164 +81,204 @@ typedef struct #pragma pack(pop) template -class DecoderRSBP : public DecoderBase +class DecoderRSBP : public Decoder { public: - explicit DecoderRSBP(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); - double getLidarTime(const uint8_t* pkt); + + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRSBP() = default; + + explicit DecoderRSBP(const RSDecoderParam& param, + const std::function& excb); + +#ifndef UNIT_TEST +protected: +#endif + + static RSDecoderConstParam getConstParam(); + static RSEchoMode getEchoMode(uint8_t mode); + + template + void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + }; template -inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) +RSDecoderConstParam DecoderRSBP::getConstParam() { - this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->beam_ring_table_.resize(this->lidar_const_param_.LASER_NUM); - if (this->param_.max_distance > 100.0f) + RSDecoderConstParam param = { - this->param_.max_distance = 100.0f; + 1248 // msop len + , 1248 // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 12 // blocks per packet + , 32 // channels per block + , 0.1f // distance min + , 100.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.01473f // RX + , 0.0085f // RY + , 0.09427f // RZ + }; + + float blk_ts = 55.52f; + float firing_tss[] = + { + 0.00f, 2.56f, 5.12f, 7.68f, 10.24f, 12.80f, 15.36f, 17.92f, + 25.68f, 28.24f, 30.80f, 33.36f, 35.92f, 38.48f, 41.04f, 43.60f, + 1.28f, 3.84f, 6.40f, 8.96f, 11.52f, 14.08f, 16.64f, 19.20f, + 26.96f, 29.52f, 32.08f, 34.64f, 37.20f, 39.76f, 42.32f, 44.88f + }; + + param.BLOCK_DURATION = blk_ts / 1000000; + for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) + { + param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; + param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; } - if (this->param_.min_distance < 0.1f || this->param_.min_distance > this->param_.max_distance) + + return param; +} + +template +RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) +{ + switch (mode) { - this->param_.min_distance = 0.1f; + case 0x00: // dual return + return RSEchoMode::ECHO_DUAL; + case 0x01: // strongest return + case 0x02: // last return + default: + return RSEchoMode::ECHO_SINGLE; } } template -inline double DecoderRSBP::getLidarTime(const uint8_t* pkt) +inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, + const std::function& excb) + : Decoder(param, excb, getConstParam()) +{ +} + +template +inline void DecoderRSBP::decodeDifopPkt(const uint8_t* packet, size_t size) +{ + const RSBPDifopPkt& pkt = *(const RSBPDifopPkt*)(packet); + this->template decodeDifopCommon(pkt); + + this->echo_mode_ = getEchoMode (pkt.return_mode); + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; +} + +template +inline void DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, size_t size) { - return this->template calculateTimeYMD(pkt); + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) + { + internDecodeMsopPkt>(pkt, size); + } + else + { + internDecodeMsopPkt>(pkt, size); + } } template -inline RSDecoderResult DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, - int& height, int& azimuth) +template +inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) { - height = this->lidar_const_param_.LASER_NUM; - const RSBPMsopPkt* mpkt_ptr = reinterpret_cast(pkt); - if (mpkt_ptr->header.id != this->lidar_const_param_.MSOP_ID) + const RSBPMsopPkt& pkt = *(const RSBPMsopPkt*)(packet); + + this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) { - return RSDecoderResult::WRONG_PKT_HEADER; + pkt_ts = parseTimeYMD(&pkt.header.timestamp); } - azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth); - this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_raw); - double block_timestamp = this->get_point_time_func_(pkt); - float azi_diff = 0; - for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) + else { - if (mpkt_ptr->blocks[blk_idx].id != this->lidar_const_param_.BLOCK_ID) + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); + } + + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); + + double block_ts = pkt_ts; + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + { + const RSBPMsopBlock& block = pkt.blocks[blk]; + + if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { + this->excb_(Error(ERRCODE_WRONGPKTHEADER)); break; } - int cur_azi = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].azimuth); - if (this->echo_mode_ == ECHO_DUAL) - { - if (blk_idx % 2 == 0) - { - if (blk_idx == 0) - { - azi_diff = static_cast( - (RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx + 2].azimuth) - cur_azi) % RS_ONE_ROUND); - } - else - { - azi_diff = static_cast( - (RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx - 2].azimuth)) % RS_ONE_ROUND); - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->time_duration_between_blocks_); - } - } - } - else - { - if (blk_idx == 0) // 12 - { - azi_diff = static_cast((RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx + 1].azimuth) - cur_azi) % - RS_ONE_ROUND); - } - else - { - azi_diff = static_cast((RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx - 1].azimuth)) % - RS_ONE_ROUND); - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->time_duration_between_blocks_); - } - } - azi_diff = (azi_diff > 100) ? this->azi_diff_between_block_theoretical_ : azi_diff; - for (int channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) + + block_ts += diff.ts(blk); + int32_t block_az = ntohs(block.azimuth); + + this->newBlock(block_az); + + int32_t block_azi_diff = diff.azimuth(blk); + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { - // charge + reserved = 5.2f - float azi_channel_ori = - cur_azi + - azi_diff * this->lidar_const_param_.FIRING_FREQUENCY * - (this->lidar_const_param_.DSR_TOFFSET * static_cast(2 * (channel_idx % 16) + (channel_idx / 16)) + - 5.2f * static_cast(channel_idx / 8 % 2)); - - int azi_channel_final = this->azimuthCalibration(azi_channel_ori, channel_idx); - float distance = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].channels[channel_idx].distance) * - this->lidar_const_param_.DIS_RESOLUTION; - int angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; - int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; - - // store to point cloud buffer - typename T_PointCloud::PointT point; - bool pointValid = false; - if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && - ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || - (!this->angle_flag_ && - ((azi_channel_final >= this->start_angle_) || (azi_channel_final <= this->end_angle_))))) + const RSChannel& channel = block.channels[chan]; + + double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + int32_t angle_horiz = block_az + + (int32_t)((float)block_azi_diff * this->const_param_.CHAN_AZIS[chan]); + + int32_t angle_vert = this->chan_angles_.vertAdjust(chan); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + uint8_t intensity = channel.intensity; + + if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * this->checkCosTable(angle_vert) * this->checkCosTable(azi_channel_final) + - this->lidar_const_param_.RX * this->checkCosTable(angle_horiz); - float y = -distance * this->checkCosTable(angle_vert) * this->checkSinTable(azi_channel_final) - - this->lidar_const_param_.RX * this->checkSinTable(angle_horiz); - float z = distance * this->checkSinTable(angle_vert) + this->lidar_const_param_.RZ; - uint8_t intensity = mpkt_ptr->blocks[blk_idx].channels[channel_idx].intensity; - this->transformPoint(x, y, z); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->const_param_.RZ; + typename T_PointCloud::PointT point; setX(point, x); setY(point, y); setZ(point, z); setIntensity(point, intensity); - pointValid = true; + + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } - else if (!this->param_.is_dense) + else if (!this->param_.dense_points) { + typename T_PointCloud::PointT point; setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); - pointValid = true; - } - - if (pointValid) - { - setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, block_timestamp); - vec.emplace_back(std::move(point)); + + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } - } - } - return RSDecoderResult::DECODE_OK; -} -template -inline RSDecoderResult DecoderRSBP::decodeDifopPkt(const uint8_t* pkt) -{ - const RSBPDifopPkt* dpkt_ptr = reinterpret_cast(pkt); - if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) - { - return RSDecoderResult::WRONG_PKT_HEADER; - } - this->template decodeDifopCommon(pkt, LidarType::RSBP); - if (!this->difop_flag_) - { - this->template decodeDifopCalibration(pkt, LidarType::RSBP); + this->prev_chan_ts_ = chan_ts; + } } - return RSDecoderResult::DECODE_OK; } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 97d32954..f8586ba6 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -31,11 +31,11 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #include +#include #if 0 #include #include #include -#include #include #include #include @@ -71,10 +71,10 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam case LidarType::RS32: ret_ptr = std::make_shared>(param, excb); break; -#if 0 case LidarType::RSBP: - ret_ptr = std::make_shared>(param.decoder_param); + ret_ptr = std::make_shared>(param, excb); break; +#if 0 case LidarType::RS128: ret_ptr = std::make_shared>(param.decoder_param); break; @@ -148,8 +148,8 @@ template inline const LidarConstantParameter DecoderFactory::getRSBPConstantParam() { LidarConstantParameter ret_param; - ret_param.MSOP_ID = 0xA050A55A0A05AA55; - ret_param.DIFOP_ID = 0x555511115A00FFA5; + ret_param.MSOP_ID = 0xA050 A55A 0A05 AA55; + ret_param.DIFOP_ID = 0x5555 1111 5A00 FFA5; ret_param.BLOCK_ID = 0xEEFF; ret_param.PKT_RATE = 1500; ret_param.BLOCKS_PER_PKT = 12; diff --git a/src/rs_driver/driver/decoder/section.hpp b/src/rs_driver/driver/decoder/section.hpp index 371355f2..cf1fb624 100644 --- a/src/rs_driver/driver/decoder/section.hpp +++ b/src/rs_driver/driver/decoder/section.hpp @@ -45,10 +45,15 @@ class AzimuthSection start_ = start % 36000; end_ = (end <= 36000) ? end : (end % 36000); cross_zero_ = (start_ > end_); + + full_round_ = ((start_ == 0) && (end_ == 36000)); } bool in(int32_t angle) { + if (full_round_) + return true; + if (cross_zero_) { return (angle >= start_) || (angle < end_); @@ -65,6 +70,7 @@ class AzimuthSection int32_t start_; int32_t end_; bool cross_zero_; + bool full_round_; }; class DistanceSection diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 54c162ab..ba648846 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -21,6 +21,7 @@ add_executable(rs_driver_test single_return_block_diff_test.cpp dual_return_block_diff_test.cpp decoder_test.cpp + decoder_rsbp_test.cpp decoder_rs32_test.cpp) diff --git a/test/chan_angles_test.cpp b/test/chan_angles_test.cpp index e6139e40..ed300a1f 100644 --- a/test/chan_angles_test.cpp +++ b/test/chan_angles_test.cpp @@ -58,10 +58,10 @@ TEST(TestChanAngles, loadFromDifop) 0x01, 0x03, 0x04, 0x01, 0x05, 0x06, 0x00, 0x07, 0x08}; - uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, - 0x01, 0x33, 0x44, - 0x00, 0x55, 0x66, - 0x01, 0x77, 0x88}; + uint8_t horiz_angle_arr[] = {0x00, 0x01, 0x11, + 0x01, 0x02, 0x22, + 0x00, 0x03, 0x33, + 0x01, 0x04, 0x44}; std::vector vert_angles, horiz_angles; @@ -80,10 +80,10 @@ TEST(TestChanAngles, loadFromDifop) ASSERT_EQ(vert_angles[2], -1286); ASSERT_EQ(vert_angles[3], 1800); - ASSERT_EQ(horiz_angles[0], 4386); - ASSERT_EQ(horiz_angles[1], -13124); - ASSERT_EQ(horiz_angles[2], 21862); - ASSERT_EQ(horiz_angles[3], -30600); + ASSERT_EQ(horiz_angles[0], 273); + ASSERT_EQ(horiz_angles[1], -546); + ASSERT_EQ(horiz_angles[2], 819); + ASSERT_EQ(horiz_angles[3], -1092); // load again ASSERT_EQ(ChanAngles::loadFromDifop( @@ -133,10 +133,10 @@ TEST(TestChanAngles, memberLoadFromDifop) 0x01, 0x03, 0x04, 0x01, 0x05, 0x06, 0x00, 0x07, 0x08}; - uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, - 0x01, 0x33, 0x44, - 0x00, 0x55, 0x66, - 0x01, 0x77, 0x88}; + uint8_t horiz_angle_arr[] = {0x00, 0x01, 0x11, + 0x01, 0x02, 0x22, + 0x00, 0x03, 0x33, + 0x01, 0x04, 0x44}; ChanAngles angles(4); ASSERT_EQ(angles.chan_num_, 4); @@ -153,10 +153,10 @@ TEST(TestChanAngles, memberLoadFromDifop) ASSERT_EQ(angles.vert_angles_[2], -1286); ASSERT_EQ(angles.vert_angles_[3], 1800); - ASSERT_EQ(angles.horiz_angles_[0], 4386); - ASSERT_EQ(angles.horiz_angles_[1], -13124); - ASSERT_EQ(angles.horiz_angles_[2], 21862); - ASSERT_EQ(angles.horiz_angles_[3], -30600); + ASSERT_EQ(angles.horiz_angles_[0], 273); + ASSERT_EQ(angles.horiz_angles_[1], -546); + ASSERT_EQ(angles.horiz_angles_[2], 819); + ASSERT_EQ(angles.horiz_angles_[3], -1092); ASSERT_EQ(angles.user_chans_.size(), 4); ASSERT_EQ(angles.toUserChan(0), 2); @@ -171,10 +171,10 @@ TEST(TestChanAngles, memberLoadFromDifop_narrow) 0x01, 0x03, 0x04, 0x01, 0x05, 0x06, 0x00, 0x07, 0x08}; - uint8_t horiz_angle_arr[] = {0x00, 0x11, 0x22, - 0x01, 0x33, 0x44, - 0x00, 0x55, 0x66, - 0x01, 0x77, 0x88}; + uint8_t horiz_angle_arr[] = {0x00, 0x01, 0x11, + 0x01, 0x02, 0x22, + 0x00, 0x03, 0x33, + 0x01, 0x04, 0x44}; ChanAngles angles(4, true); ASSERT_EQ(angles.chan_num_, 4); @@ -191,10 +191,10 @@ TEST(TestChanAngles, memberLoadFromDifop_narrow) ASSERT_EQ(angles.vert_angles_[2], -129); ASSERT_EQ(angles.vert_angles_[3], 180); - ASSERT_EQ(angles.horiz_angles_[0], 439); - ASSERT_EQ(angles.horiz_angles_[1], -1312); - ASSERT_EQ(angles.horiz_angles_[2], 2186); - ASSERT_EQ(angles.horiz_angles_[3], -3060); + ASSERT_EQ(angles.horiz_angles_[0], 27); + ASSERT_EQ(angles.horiz_angles_[1], -55); + ASSERT_EQ(angles.horiz_angles_[2], 82); + ASSERT_EQ(angles.horiz_angles_[3], -109); } TEST(TestChanAngles, memberLoadFromDifop_fail) @@ -220,3 +220,46 @@ TEST(TestChanAngles, memberLoadFromDifop_fail) ASSERT_EQ(angles.vert_angles_[0], 0); } +TEST(TestChanAngles, memberLoadFromDifop_fail_angle) +{ + uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, + 0x01, 0x03, 0x04, + 0x01, 0x05, 0x06, + 0x00, 0x07, 0x08}; + + ChanAngles angles(4, true); + ASSERT_EQ(angles.chan_num_, 4); + + { + uint8_t horiz_angle_arr[] = + { + 0x00, 0x01, 0x11, + 0x01, 0x02, 0x22, + 0x00, 0x03, 0x33, + 0x00, 0x23, 0x28 + }; + + // load + ASSERT_LT(angles.loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4), 0); + } + + { + uint8_t horiz_angle_arr[] = + { + 0x00, 0x01, 0x11, + 0x01, 0x02, 0x22, + 0x00, 0x03, 0x33, + 0x01, 0x23, 0x29 + }; + + // load + ASSERT_LT(angles.loadFromDifop( + (const RSCalibrationAngle*)vert_angle_arr, + (const RSCalibrationAngle*)horiz_angle_arr, + 4), 0); + } +} + diff --git a/test/decoder_rsbp_test.cpp b/test/decoder_rsbp_test.cpp new file mode 100644 index 00000000..96535d1c --- /dev/null +++ b/test/decoder_rsbp_test.cpp @@ -0,0 +1,165 @@ + +#include + +#include "rs_driver/msg/point_cloud_msg.h" +#include +#include + +using namespace robosense::lidar; + +typedef PointXYZIRT PointT; +typedef PointCloudT PointCloud; + +static ErrCode errCode = ERRCODE_SUCCESS; +static void errCallback(const Error& err) +{ + errCode = err.error_code; +} + +TEST(TestDecoderRSBP, getEchoMode) +{ + ASSERT_TRUE(DecoderRSBP::getEchoMode(0) == RSEchoMode::ECHO_DUAL); + ASSERT_TRUE(DecoderRSBP::getEchoMode(1) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(DecoderRSBP::getEchoMode(2) == RSEchoMode::ECHO_SINGLE); +} + +TEST(TestDecoderRSBP, decodeDifopPkt) +{ + // const_param + RSDecoderParam param; + DecoderRSBP decoder(param, errCallback); + ASSERT_EQ(decoder.blks_per_frame_, 1801); + ASSERT_EQ(decoder.split_blks_per_frame_, 1801); + + // rpm = 600, dual return + RSBPDifopPkt pkt; + pkt.rpm = htons(600); + pkt.return_mode = 0; + decoder.decodeDifopPkt((uint8_t*)&pkt, sizeof(pkt)); + ASSERT_EQ(decoder.rps_, 10); + ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_DUAL); + ASSERT_EQ(decoder.blks_per_frame_, 1801); + ASSERT_EQ(decoder.split_blks_per_frame_, 3602); + + // rpm = 1200, single return + pkt.rpm = htons(1200); + pkt.return_mode = 1; + decoder.decodeDifopPkt((uint8_t*)&pkt, sizeof(pkt)); + ASSERT_EQ(decoder.rps_, 20); + ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_SINGLE); + ASSERT_EQ(decoder.blks_per_frame_, 900); + ASSERT_EQ(decoder.split_blks_per_frame_, 900); +} + +TEST(TestDecoderRSBP, decodeMsopPkt) +{ + uint8_t pkt[] = + { + // + // header + // + 0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0, // msop id + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // reserved_1 + 0x15, 0x0a, 0x01, 0x01, 0x02, 0x03, 0x11, 0x22, 0x33, 0x44, // ts_YMD + 0x00, // lidar type + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // reserved_2 + 0x18, 0x01, // temprature + 0x00, 0x00, // reserved_3 + + // + // block_01 + // + 0xFF, 0xEE, // block id + 0x00, 0x00, // azimuth + 0x03, 0xE8, // chan_00, distance + 0x01, // chan_00, intensity + 0x00, 0x00, // chan_01, distance + 0x00, // chan_01, intensity + 0x00, 0x00, // chan_02, distance + 0x00, // chan_02, intensity + 0x00, 0x00, // chan_03, distance + 0x00, // chan_03, intensity + 0x00, 0x00, // chan_04, distance + 0x00, // chan_04, intensity + 0x00, 0x00, // chan_05, distance + 0x00, // chan_05, intensity + 0x00, 0x00, // chan_06, distance + 0x00, // chan_06, intensity + 0x00, 0x00, // chan_07, distance + 0x00, // chan_07, intensity + 0x00, 0x00, // chan_08, distance + 0x00, // chan_08, intensity + 0x00, 0x00, // chan_09, distance + 0x00, // chan_09, intensity + 0x00, 0x00, // chan_10, distance + 0x00, // chan_10, intensity + 0x00, 0x00, // chan_11, distance + 0x00, // chan_11, intensity + 0x00, 0x00, // chan_12, distance + 0x00, // chan_12, intensity + 0x00, 0x00, // chan_13, distance + 0x00, // chan_13, intensity + 0x00, 0x00, // chan_14, distance + 0x00, // chan_14, intensity + 0x00, 0x00, // chan_15, distance + 0x00, // chan_15, intensity + 0x00, 0x00, // chan_16, distance + 0x00, // chan_16, intensity + 0x00, 0x00, // chan_17, distance + 0x00, // chan_17, intensity + 0x00, 0x00, // chan_18, distance + 0x00, // chan_18, intensity + 0x00, 0x00, // chan_19, distance + 0x00, // chan_19, intensity + 0x00, 0x00, // chan_20, distance + 0x00, // chan_20, intensity + 0x00, 0x00, // chan_21, distance + 0x00, // chan_21, intensity + 0x00, 0x00, // chan_22, distance + 0x00, // chan_22, intensity + 0x00, 0x00, // chan_23, distance + 0x00, // chan_23, intensity + 0x00, 0x00, // chan_24, distance + 0x00, // chan_24, intensity + 0x00, 0x00, // chan_25, distance + 0x00, // chan_25, intensity + 0x00, 0x00, // chan_26, distance + 0x00, // chan_26, intensity + 0x00, 0x00, // chan_27, distance + 0x00, // chan_27, intensity + 0x00, 0x00, // chan_28, distance + 0x00, // chan_28, intensity + 0x00, 0x00, // chan_29, distance + 0x00, // chan_29, intensity + 0x00, 0x00, // chan_30, distance + 0x00, // chan_30, intensity + 0x00, 0x00, // chan_31, distance + 0x00, // chan_31, intensity + + // + // block_02 + // + 0x00, 0x00, // block id + }; + + // dense_points = false, use_lidar_clock = true + RSDecoderParam param; + DecoderRSBP decoder(param, errCallback); + ASSERT_EQ(decoder.chan_angles_.user_chans_.size(), 32); + decoder.chan_angles_.user_chans_[0] = 2; + decoder.chan_angles_.user_chans_[1] = 1; + decoder.param_.dense_points = false; + decoder.param_.use_lidar_clock = true; + + decoder.point_cloud_ = std::make_shared(); + + decoder.decodeMsopPkt(pkt, sizeof(pkt)); + ASSERT_EQ(decoder.getTemperature(), 2.1875); + ASSERT_EQ(decoder.point_cloud_->points.size(), 32); + + PointT& point = decoder.point_cloud_->points[0]; + ASSERT_EQ(point.intensity, 1); + ASSERT_NE(point.timestamp, 0); + ASSERT_EQ(point.ring, 2); +} + From e653a195e984895e89b4d1bc12fc560a63dcc0f1 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 20 Dec 2021 20:53:38 +0800 Subject: [PATCH 099/379] refac: refactory decoder --- src/rs_driver/driver/decoder/basic_attr.hpp | 4 +- src/rs_driver/driver/decoder/decoder.hpp | 9 +-- src/rs_driver/driver/decoder/decoder_RS32.hpp | 8 +-- .../driver/decoder/decoder_RSHELIOS.hpp | 64 +++++++++++-------- .../driver/decoder/decoder_factory.hpp | 6 +- 5 files changed, 51 insertions(+), 40 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index d0db67d7..793d2e35 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -74,7 +74,7 @@ typedef struct typedef struct { uint8_t tt[2]; -} RSTemprature; +} RSTemperature; #pragma pack(pop) @@ -181,7 +181,7 @@ inline uint64_t getTimeHost(void) return t_us.count(); } -inline int16_t parseTemp(const RSTemprature* tmp) +inline int16_t parseTemp(const RSTemperature* tmp) { // | lsb | padding | neg | msb | // | 5 | 3 | 1 | 7 | (in bits) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 9285eda1..57da9a63 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -67,8 +67,7 @@ typedef struct RSTimestampYMD timestamp; uint8_t lidar_type; uint8_t reserved_2[7]; - RSTemprature temp; - //uint16_t temp_raw; + RSTemperature temp; uint8_t reserved_3[2]; } RSMsopHeaderV1; @@ -78,11 +77,7 @@ typedef struct uint16_t protocol_version; uint8_t reserved_1; uint8_t wave_mode; - RSTemprature temp; -#if 0 - uint8_t temp_low; - uint8_t temp_high; -#endif + RSTemperature temp; RSTimestampUTC timestamp; uint8_t reserved_2[10]; uint8_t lidar_type; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 510adc29..1f875cd1 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -61,22 +61,22 @@ typedef struct uint16_t rpm; RSEthNetV1 eth; RSFOV fov; - uint16_t reserved0; + uint8_t reserved0[2]; uint16_t phase_lock_angle; RSVersionV1 version; - uint8_t reserved_1[242]; + uint8_t reserved1[242]; RSSN sn; uint16_t zero_cali; uint8_t return_mode; uint16_t sw_ver; RSTimestampYMD timestamp; RSStatusV1 status; - uint8_t reserved_2[5]; + uint8_t reserved2[5]; RSDiagnoV1 diagno; uint8_t gprmc[86]; RSCalibrationAngle ver_angle_cali[32]; RSCalibrationAngle hori_angle_cali[32]; - uint8_t reserved_3[586]; + uint8_t reserved3[586]; uint16_t tail; } RS32DifopPkt; #pragma pack(pop) diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index baa4c77c..75c3e22a 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -24,13 +24,13 @@ to endorse or promote products derived from this software without specific prior THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +PECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include +#include namespace robosense { namespace lidar @@ -38,26 +38,26 @@ namespace lidar #pragma pack(push, 1) typedef struct { - uint16_t id; + uint8_t id[2]; uint16_t azimuth; RSChannel channels[32]; } RSHELIOSMsopBlock; typedef struct { - uint32_t id; + uint8_t id[4]; uint16_t protocol_version; - uint8_t reserved_1[14]; + uint8_t reserved1[14]; RSTimestampUTC timestamp; uint8_t lidar_type; - uint8_t reserved_2[7]; - uint16_t temp_raw; - uint8_t reserved_3[2]; -} RSHeliosMsopHeader; + uint8_t reserved2[7]; + RSTemperature temp; + uint8_t reserved3[2]; +} RSHELIOSMsopHeader; typedef struct { - RSHeliosMsopHeader header; + RSHELIOSMsopHeader header; RSHELIOSMsopBlock blocks[12]; unsigned int index; uint16_t tail; @@ -65,40 +65,53 @@ typedef struct typedef struct { - uint64_t id; + uint8_t id[8]; uint16_t rpm; - RSEthNetNew eth; + RSEthNetV2 eth; RSFOV fov; - uint8_t reserved_1[2]; + uint8_t reserved1[2]; uint16_t phase_lock_angle; - RSVersionNew version; - uint8_t reserved_2[229]; - RSSn sn; + RSVersionV2 version; + uint8_t reserved2[229]; + RSSN sn; uint16_t zero_cali; uint8_t return_mode; RSTimeInfo time_info; - RSStatusNew status; - uint8_t reserved_3[5]; - RSDiagnoNew diagno; + RSStatusV2 status; + uint8_t reserved3[5]; + RSDiagnoV2 diagno; uint8_t gprmc[86]; RSCalibrationAngle ver_angle_cali[32]; RSCalibrationAngle hori_angle_cali[32]; - uint8_t reserved_4[586]; + uint8_t reserved4[586]; uint16_t tail; } RSHELIOSDifopPkt; #pragma pack(pop) template -class DecoderRSHELIOS : public DecoderBase +class DecoderRSHELIOS : public Decoder { public: - explicit DecoderRSHELIOS(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); - double getLidarTime(const uint8_t* pkt); + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRSHELIOS() = default; + + explicit DecoderRSHELIOS(const RSDecoderParam& param, + const std::function& excb); + +#ifndef UNIT_TEST +protected: +#endif + + static RSDecoderConstParam getConstParam(); + static RSEchoMode getEchoMode(uint8_t mode); + + template + void internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; +#if 0 template inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) @@ -248,6 +261,7 @@ inline RSDecoderResult DecoderRSHELIOS::decodeDifopPkt(const uint8 } return RSDecoderResult::DECODE_OK; } +#endif } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index f8586ba6..15de50be 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -32,12 +32,12 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include +#include #if 0 #include #include #include #include -#include #include #endif @@ -84,9 +84,11 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam case LidarType::RSM1: ret_ptr = std::make_shared>(param.decoder_param); break; +#endif case LidarType::RSHELIOS: - ret_ptr = std::make_shared>(param.decoder_param); + ret_ptr = std::make_shared>(param, excb); break; +#if 0 case LidarType::RSROCK: ret_ptr = std::make_shared>(param.decoder_param); break; From b24082ef0004ef012c736d03f2654945bc30ba53 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 21 Dec 2021 09:56:01 +0800 Subject: [PATCH 100/379] refac: refactory decoder --- src/rs_driver/driver/decoder/basic_attr.hpp | 10 +- .../driver/decoder/decoder_RSHELIOS.hpp | 255 ++++++++++-------- test/basic_attr_test.cpp | 6 +- 3 files changed, 150 insertions(+), 121 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index 793d2e35..51cfc21e 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -59,17 +59,19 @@ typedef struct uint16_t us; } RSTimestampYMD; +#if 0 typedef struct { uint8_t sec[6]; uint32_t us; } RSTimestampUTC; +#endif typedef struct { uint8_t sec[6]; uint8_t ss[4]; -} RSTimestampUTC2; +} RSTimestampUTC; typedef struct { @@ -78,7 +80,7 @@ typedef struct #pragma pack(pop) -inline uint64_t parseTimeUTCWithNs(const RSTimestampUTC2* tsUtc) +inline uint64_t parseTimeUTCWithNs(const RSTimestampUTC* tsUtc) { // sec uint64_t sec = 0; @@ -98,7 +100,7 @@ inline uint64_t parseTimeUTCWithNs(const RSTimestampUTC2* tsUtc) return (sec * 1000000 + ns/1000); } -inline uint64_t parseTimeUTCWithUs(const RSTimestampUTC2* tsUtc) +inline uint64_t parseTimeUTCWithUs(const RSTimestampUTC* tsUtc) { // sec uint64_t sec = 0; @@ -118,7 +120,7 @@ inline uint64_t parseTimeUTCWithUs(const RSTimestampUTC2* tsUtc) return (sec * 1000000 + us); } -inline uint64_t parseTimeUTCWithMs(const RSTimestampUTC2* tsUtc) +inline uint64_t parseTimeUTCWithMs(const RSTimestampUTC* tsUtc) { // sec uint64_t sec = 0; diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 75c3e22a..f7d9604c 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -111,157 +111,184 @@ class DecoderRSHELIOS : public Decoder void internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -#if 0 template -inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) +RSDecoderConstParam DecoderRSHELIOS::getConstParam() { - this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->beam_ring_table_.resize(this->lidar_const_param_.LASER_NUM); - if (this->param_.max_distance > 100.0f) + RSDecoderConstParam param = { - this->param_.max_distance = 100.0f; + 1248 // msop len + , 1248 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 12 // blocks per packet + , 32 // channels per block + , 0.4f // distance min + , 200.0f // distance max + , 0.0025f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.03498f // RX + , -0.015f // RY + , 0.0f // RZ + }; + + float blk_ts = 55.56f; + float firing_tss[] = + { + 0.00f, 1.57f, 3.15f, 4.72f, 6.30f, 7.87f, 9.45f, 11.36f, + 13.26f, 15.17f, 17.08f, 18.99f, 20.56f, 22.14f, 23.71f, 25.29f, + 26.53f, 29.01f, 27.77f, 30.25f, 31.49f, 33.98f, 32.73f, 35.22f, + 36.46f, 37.70f, 38.94f, 40.18f, 41.42f, 42.67f, 43.91f, 45.15f + }; + + param.BLOCK_DURATION = blk_ts / 1000000; + for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) + { + param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; + param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; } - if (this->param_.min_distance < 0.1f || this->param_.min_distance > this->param_.max_distance) + + return param; +} + +template +RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) +{ + switch (mode) { - this->param_.min_distance = 0.1f; + case 0x00: // dual return + return RSEchoMode::ECHO_DUAL; + case 0x04: // strongest return + case 0x05: // last return + case 0x06: // nearest return + default: + return RSEchoMode::ECHO_SINGLE; } } template -inline double DecoderRSHELIOS::getLidarTime(const uint8_t* pkt) +inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, + const std::function& excb) + : Decoder(param, excb, getConstParam()) +{ +} + +template +inline void DecoderRSHELIOS::decodeDifopPkt(const uint8_t* packet, size_t size) { - return this->template calculateTimeUTC(pkt, LidarType::RSHELIOS); + const RSHELIOSDifopPkt& pkt = *(const RSHELIOSDifopPkt*)(packet); + this->template decodeDifopCommon(pkt); + + this->echo_mode_ = getEchoMode (pkt.return_mode); + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; } template -inline RSDecoderResult DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, - int& azimuth) +inline void DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, size_t size) { - height = this->lidar_const_param_.LASER_NUM; - const RSHELIOSMsopPkt* mpkt_ptr = reinterpret_cast(pkt); - if (mpkt_ptr->header.id != this->lidar_const_param_.MSOP_ID) + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - return RSDecoderResult::WRONG_PKT_HEADER; + internDecodeMsopPkt>(pkt, size); } - this->protocol_ver_ = RS_SWAP_SHORT(mpkt_ptr->header.protocol_version); - azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth); - this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_raw); - double block_timestamp = this->get_point_time_func_(pkt); - float azi_diff = 0; - for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) + else { - if (mpkt_ptr->blocks[blk_idx].id != this->lidar_const_param_.BLOCK_ID) + internDecodeMsopPkt>(pkt, size); + } +} + +template +template +inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t size) +{ + const RSHELIOSMsopPkt& pkt = *(const RSHELIOSMsopPkt*)(packet); + + this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) + { + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp); + } + else + { + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); + } + + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); + + double block_ts = pkt_ts; + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + { + const RSHELIOSMsopBlock& block = pkt.blocks[blk]; + + if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { + this->excb_(Error(ERRCODE_WRONGPKTHEADER)); break; } - int cur_azi = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].azimuth); - if (this->echo_mode_ == ECHO_DUAL) - { - if (blk_idx % 2 == 0) - { - if (blk_idx == 0) - { - azi_diff = static_cast( - (RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx + 2].azimuth) - cur_azi) % RS_ONE_ROUND); - } - else - { - azi_diff = static_cast( - (RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx - 2].azimuth)) % RS_ONE_ROUND); - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->time_duration_between_blocks_); - } - } - } - else - { - if (blk_idx == 0) // 12 - { - azi_diff = static_cast((RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx + 1].azimuth) - cur_azi) % - RS_ONE_ROUND); - } - else - { - azi_diff = static_cast((RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx - 1].azimuth)) % - RS_ONE_ROUND); - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->time_duration_between_blocks_); - } - } - azi_diff = (azi_diff > 100) ? this->azi_diff_between_block_theoretical_ : azi_diff; - for (int channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) + + block_ts += diff.ts(blk); + int32_t block_az = ntohs(block.azimuth); + + this->newBlock(block_az); + + int32_t block_azi_diff = diff.azimuth(blk); + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { - float azi_channel_ori = - cur_azi + - azi_diff * this->lidar_const_param_.DSR_TOFFSET * this->lidar_const_param_.FIRING_FREQUENCY * - ((-0.014f * static_cast(channel_idx) + 1.8965f) * static_cast(channel_idx) - 0.6543f); - int azi_channel_final = this->azimuthCalibration(azi_channel_ori, channel_idx); - float distance = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].channels[channel_idx].distance) * - this->lidar_const_param_.DIS_RESOLUTION; - int angle_horiz = (int)(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; - int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; - - // store to point cloud buffer - typename T_PointCloud::PointT point; - bool pointValid = false; - if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && - ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || - (!this->angle_flag_ && - ((azi_channel_final >= this->start_angle_) || (azi_channel_final <= this->end_angle_))))) + const RSChannel& channel = block.channels[chan]; + + double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + int32_t angle_horiz = block_az + + (int32_t)((float)block_azi_diff * this->const_param_.CHAN_AZIS[chan]); + + int32_t angle_vert = this->chan_angles_.vertAdjust(chan); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + uint8_t intensity = channel.intensity; + + if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * this->checkCosTable(angle_vert) * this->checkCosTable(azi_channel_final) + - this->lidar_const_param_.RX * this->checkCosTable(angle_horiz); - float y = -distance * this->checkCosTable(angle_vert) * this->checkSinTable(azi_channel_final) - - this->lidar_const_param_.RX * this->checkSinTable(angle_horiz); - float z = distance * this->checkSinTable(angle_vert) + this->lidar_const_param_.RZ; - uint8_t intensity = mpkt_ptr->blocks[blk_idx].channels[channel_idx].intensity; - this->transformPoint(x, y, z); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->const_param_.RZ; + + typename T_PointCloud::PointT point; setX(point, x); setY(point, y); setZ(point, z); setIntensity(point, intensity); - pointValid = true; + + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } - else if (!this->param_.is_dense) + else if (!this->param_.dense_points) { + typename T_PointCloud::PointT point; setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); - pointValid = true; - } - if (pointValid) - { - setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, block_timestamp); - vec.emplace_back(std::move(point)); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } - } - } - return RSDecoderResult::DECODE_OK; -} -template -inline RSDecoderResult DecoderRSHELIOS::decodeDifopPkt(const uint8_t* pkt) -{ - RSHELIOSDifopPkt* dpkt_ptr = (RSHELIOSDifopPkt*)pkt; - if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) - { - return RSDecoderResult::WRONG_PKT_HEADER; - } - this->template decodeDifopCommon(pkt, LidarType::RSHELIOS); - if (!this->difop_flag_) - { - this->template decodeDifopCalibration(pkt, LidarType::RSHELIOS); + this->prev_chan_ts_ = chan_ts; + } } - return RSDecoderResult::DECODE_OK; } -#endif } // namespace lidar } // namespace robosense diff --git a/test/basic_attr_test.cpp b/test/basic_attr_test.cpp index b0c7d087..53b304c8 100644 --- a/test/basic_attr_test.cpp +++ b/test/basic_attr_test.cpp @@ -7,7 +7,7 @@ using namespace robosense::lidar; TEST(TestParseTime, parseTimeUTC) { - RSTimestampUTC2 ts = + RSTimestampUTC ts = {{0x01, 0x02, 0x03, 0x04, 0x05, 0x06}, {0x11, 0x22, 0x33, 0x44}}; ASSERT_EQ(parseTimeUTCWithNs(&ts), 0x010203040506 * 1000000 + 0x11223344/1000); @@ -31,12 +31,12 @@ TEST(TestParseTemp, parseTemp) { { uint8_t temp[] = {0x18, 0x01}; - ASSERT_EQ(parseTemp((RSTemprature*)&temp), 35); + ASSERT_EQ(parseTemp((RSTemperature*)&temp), 35); } { uint8_t temp[] = {0x18, 0x81}; - ASSERT_EQ(parseTemp((RSTemprature*)&temp), -35); + ASSERT_EQ(parseTemp((RSTemperature*)&temp), -35); } } From 220664012b99db260dc87f19bd74dd0672490b69 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 21 Dec 2021 10:32:16 +0800 Subject: [PATCH 101/379] refac: support rshelios --- src/rs_driver/driver/decoder/decoder.hpp | 2 -- src/rs_driver/driver/decoder/decoder_RS32.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp | 4 ++-- 4 files changed, 4 insertions(+), 6 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 57da9a63..de1e3c57 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -310,7 +310,6 @@ class Decoder uint16_t block_azi_diff_; // azimuth difference between adjacent blocks. float fov_blind_ts_diff_; // timestamp difference across blind section(defined by fov) - unsigned int protocol_ver_; // protocol version of MSOP/DIFOP uint16_t rps_; // rounds per second RSEchoMode echo_mode_; // echo mode (defined by return mode) float temperature_; // lidar temperature @@ -343,7 +342,6 @@ inline Decoder::Decoder(const RSDecoderParam& param, , split_blks_per_frame_(blks_per_frame_) , block_azi_diff_(20) , fov_blind_ts_diff_(0) - , protocol_ver_(0) , rps_(10) , echo_mode_(ECHO_SINGLE) , temperature_(0.0) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 1f875cd1..c2923565 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -204,7 +204,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeYMD(&pkt.header.timestamp); + pkt_ts = parseTimeYMD(&pkt.header.timestamp) * 0.000001; } else { diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index c86e84e8..1d18c438 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -204,7 +204,7 @@ inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeYMD(&pkt.header.timestamp); + pkt_ts = parseTimeYMD(&pkt.header.timestamp) * 0.000001; } else { diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index f7d9604c..6c62b721 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -120,7 +120,7 @@ RSDecoderConstParam DecoderRSHELIOS::getConstParam() , 1248 // difop len , 4 // msop id len , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x0A} // msop id + , {0x55, 0xAA, 0x05, 0x5A} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id , 12 // blocks per packet @@ -212,7 +212,7 @@ inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp); + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 0.000001; } else { From b22270603f2cb701ca758d868277d4c8e4b2b0e2 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 21 Dec 2021 11:35:59 +0800 Subject: [PATCH 102/379] refac: support rs80 --- src/rs_driver/driver/decoder/decoder_RS80.hpp | 308 ++++++++++-------- .../driver/decoder/decoder_factory.hpp | 8 +- 2 files changed, 183 insertions(+), 133 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 2f61858e..3a9af650 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -30,23 +30,24 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include +#include + namespace robosense { namespace lidar { + #pragma pack(push, 1) typedef struct { - uint8_t id; - uint8_t ret_id; + uint8_t id[2]; uint16_t azimuth; RSChannel channels[80]; } RS80MsopBlock; typedef struct { - RSMsopHeaderNew header; + RSMsopHeaderV2 header; RS80MsopBlock blocks[4]; uint8_t reserved[188]; unsigned int index; @@ -54,186 +55,235 @@ typedef struct typedef struct { - uint64_t id; + uint8_t id[8]; uint16_t rpm; - RSEthNetNew eth; + RSEthNetV2 eth; RSFOV fov; - uint16_t reserved_0; + uint8_t reserved1[2]; uint16_t phase_lock_angle; - RSVersionNew version; - uint8_t reserved_1[229]; - RSSn sn; + RSVersionV2 version; + uint8_t reserved2[229]; + RSSN sn; uint16_t zero_cali; uint8_t return_mode; RSTimeInfo time_info; - RSStatus status; - uint8_t reserved_2[5]; - RSDiagno diagno; + RSStatusV1 status; + uint8_t reserved3[5]; + RSDiagnoV1 diagno; uint8_t gprmc[86]; RSCalibrationAngle ver_angle_cali[128]; RSCalibrationAngle hori_angle_cali[128]; - uint8_t reserved_3[10]; + uint8_t reserved4[10]; uint16_t tail; } RS80DifopPkt; #pragma pack(pop) template -class DecoderRS80 : public DecoderBase +class DecoderRS80 : public Decoder { public: - explicit DecoderRS80(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); - double getLidarTime(const uint8_t* pkt); + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRS80() = default; + + explicit DecoderRS80(const RSDecoderParam& param, + const std::function& excb); + +#ifndef UNIT_TEST +protected: +#endif + + static RSDecoderConstParam getConstParam(); + static RSEchoMode getEchoMode(uint8_t mode); + + template + void internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; template -inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) +RSDecoderConstParam DecoderRS80::getConstParam() { - this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->beam_ring_table_.resize(this->lidar_const_param_.LASER_NUM); - if (this->param_.max_distance > 230.0f) + RSDecoderConstParam param = + { + 1248 // msop len + , 1248 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x5A} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 4 // blocks per packet + , 80 // channels per block + , 1.0f // distance min + , 230.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.03615f // RX + , -0.017f // RY + , 0.0f // RZ + }; + + float blk_ts = 55.552f; + float firing_tss[] = { - this->param_.max_distance = 230.0f; + 0.00f, 0.00f, 0.00f, 3.236f, 3.236f, 6.472f, 6.472f, 6.472f, + 6.472f, 9.708f, 9.708f, 9.708f, 12.944f, 12.944f, 12.944f, 16.18f, + 16.18f, 16.18f, 19.416f, 19.416f, 19.416f, 22.652f, 22.652f, 25.888f, + 25.888f, 29.124f, 29.124f, 32.36f, 32.36f, 35.596f, 35.596f, 38.832f, + 38.832f, 42.068f, 42.068f, 45.304f, 45.304f, 48.54f, 48.54f, 48.54f, + + 0.00f, 0.00f, 0.00f, 3.236f, 3.236f, 3.236f, 6.472f, 6.472f, + 6.472f, 9.708f, 9.708f, 12.944f, 12.944f, 12.944f, 12.944f, 16.18f, + 16.18f, 19.416f, 19.416f, 19.416f, 22.652f, 22.652f, 22.652f, 25.888f, + 25.888f, 29.124f, 29.124f, 32.36f, 32.36f, 35.596f, 35.596f, 35.596f, + 38.832f, 38.832f, 42.068f, 45.304f, 45.304f, 48.54f, 48.54f, 48.54f, + }; + + param.BLOCK_DURATION = blk_ts / 1000000; + for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) + { + param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; + param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; } - if (this->param_.min_distance < 1.0f || this->param_.min_distance > this->param_.max_distance) + + return param; +} + +template +RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) +{ + switch (mode) { - this->param_.min_distance = 1.0f; + case 0x03: // dual return + return RSEchoMode::ECHO_DUAL; + case 0x01: // strongest return + case 0x02: // last return + default: + return RSEchoMode::ECHO_SINGLE; } } template -inline double DecoderRS80::getLidarTime(const uint8_t* pkt) +inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, + const std::function& excb) + : Decoder(param, excb, getConstParam()) +{ +} + +template +inline void DecoderRS80::decodeDifopPkt(const uint8_t* packet, size_t size) +{ + const RS80DifopPkt& pkt = *(const RS80DifopPkt*)(packet); + this->template decodeDifopCommon(pkt); + + this->echo_mode_ = getEchoMode (pkt.return_mode); + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; +} + +template +inline void DecoderRS80::decodeMsopPkt(const uint8_t* pkt, size_t size) { - return this->template calculateTimeUTC(pkt, LidarType::RS80); + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) + { + internDecodeMsopPkt>(pkt, size); + } + else + { + internDecodeMsopPkt>(pkt, size); + } } template -inline RSDecoderResult DecoderRS80::decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, - int& height, int& azimuth) +template +inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) { - height = this->lidar_const_param_.LASER_NUM; - const RS80MsopPkt* mpkt_ptr = reinterpret_cast(pkt); - if (mpkt_ptr->header.id != this->lidar_const_param_.MSOP_ID) + const RS80MsopPkt& pkt = *(const RS80MsopPkt*)(packet); + + this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) + { + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 0.000001; + } + else { - return RSDecoderResult::WRONG_PKT_HEADER; + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); } - this->protocol_ver_ = RS_SWAP_SHORT(mpkt_ptr->header.protocol_version); - azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth); - this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_low, mpkt_ptr->header.temp_high); - double block_timestamp = this->get_point_time_func_(pkt); - float azi_diff = 0; - for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) + + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); + + double block_ts = pkt_ts; + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { - if (mpkt_ptr->blocks[blk_idx].id != this->lidar_const_param_.BLOCK_ID) + const RS80MsopBlock& block = pkt.blocks[blk]; + + if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { + this->excb_(Error(ERRCODE_WRONGPKTHEADER)); break; } - int cur_azi = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].azimuth); - if (this->echo_mode_ == ECHO_DUAL) - { - if (blk_idx % 2 == 0) - { - if (blk_idx == 0) - { - azi_diff = static_cast( - (RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx + 2].azimuth) - cur_azi) % RS_ONE_ROUND); - } - else - { - azi_diff = static_cast( - (RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx - 2].azimuth)) % RS_ONE_ROUND); - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->time_duration_between_blocks_); - } - } - } - else - { - if (blk_idx == 0) - { - azi_diff = static_cast((RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx + 1].azimuth) - cur_azi) % - RS_ONE_ROUND); - } - else - { - azi_diff = static_cast((RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx - 1].azimuth)) % - RS_ONE_ROUND); - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->time_duration_between_blocks_); - } - } - azi_diff = (azi_diff > 100) ? this->azi_diff_between_block_theoretical_ : azi_diff; - for (size_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) + + block_ts += diff.ts(blk); + int32_t block_az = ntohs(block.azimuth); + + this->newBlock(block_az); + + int32_t block_azi_diff = diff.azimuth(blk); + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { - int dsr_temp = (channel_idx / 4) % 16; - float azi_channel_ori = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].azimuth) + - (azi_diff * static_cast(dsr_temp) * this->lidar_const_param_.DSR_TOFFSET * - this->lidar_const_param_.FIRING_FREQUENCY); - int azi_channel_final = this->azimuthCalibration(azi_channel_ori, channel_idx); - float distance = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].channels[channel_idx].distance) * - this->lidar_const_param_.DIS_RESOLUTION; - int angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; - int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; - - typename T_PointCloud::PointT point; - bool pointValid = false; - if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && - ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || - (!this->angle_flag_ && - ((azi_channel_final >= this->start_angle_) || (azi_channel_final <= this->end_angle_))))) + const RSChannel& channel = block.channels[chan]; + + double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + int32_t angle_horiz = block_az + + (int32_t)((float)block_azi_diff * this->const_param_.CHAN_AZIS[chan]); + + int32_t angle_vert = this->chan_angles_.vertAdjust(chan); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + uint8_t intensity = channel.intensity; + + if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * this->checkCosTable(angle_vert) * this->checkCosTable(azi_channel_final) + - this->lidar_const_param_.RX * this->checkCosTable(angle_horiz); - float y = -distance * this->checkCosTable(angle_vert) * this->checkSinTable(azi_channel_final) - - this->lidar_const_param_.RX * this->checkSinTable(angle_horiz); - float z = distance * this->checkSinTable(angle_vert) + this->lidar_const_param_.RZ; - uint8_t intensity = mpkt_ptr->blocks[blk_idx].channels[channel_idx].intensity; - this->transformPoint(x, y, z); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->const_param_.RZ; + + typename T_PointCloud::PointT point; setX(point, x); setY(point, y); setZ(point, z); setIntensity(point, intensity); - pointValid = true; + + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } - else if (!this->param_.is_dense) + else if (!this->param_.dense_points) { + typename T_PointCloud::PointT point; setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); - pointValid = true; - } - if (pointValid) - { - setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, block_timestamp); - vec.emplace_back(std::move(point)); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } - } - } - return RSDecoderResult::DECODE_OK; -} -template -inline RSDecoderResult DecoderRS80::decodeDifopPkt(const uint8_t* pkt) -{ - const RS80DifopPkt* dpkt_ptr = reinterpret_cast(pkt); - if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) - { - return RSDecoderResult::WRONG_PKT_HEADER; - } - this->template decodeDifopCommon(pkt, LidarType::RS80); - if (!this->difop_flag_) - { - this->template decodeDifopCalibration(pkt, LidarType::RS80); + this->prev_chan_ts_ = chan_ts; + } } - return RSDecoderResult::DECODE_OK; } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 15de50be..1c687ede 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -33,9 +33,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #if 0 #include -#include #include #include #include @@ -74,13 +74,13 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam case LidarType::RSBP: ret_ptr = std::make_shared>(param, excb); break; + case LidarType::RS80: + ret_ptr = std::make_shared>(param, excb); + break; #if 0 case LidarType::RS128: ret_ptr = std::make_shared>(param.decoder_param); break; - case LidarType::RS80: - ret_ptr = std::make_shared>(param.decoder_param); - break; case LidarType::RSM1: ret_ptr = std::make_shared>(param.decoder_param); break; From 2918548cf6306d81bef729212c13819c4999c5e7 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 22 Dec 2021 09:52:50 +0800 Subject: [PATCH 103/379] feat: support rs80 --- demo/demo_online.cpp | 6 +++--- src/rs_driver/driver/decoder/decoder_RS32.hpp | 5 ++--- src/rs_driver/driver/decoder/decoder_RS80.hpp | 14 +++++++------- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 4 ++-- src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp | 5 ++--- 5 files changed, 16 insertions(+), 18 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index b9470072..5a5e0696 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -81,9 +81,9 @@ int main(int argc, char* argv[]) RSDriverParam param; ///< Create a parameter object param.input_type = InputType::ONLINE_LIDAR; - param.input_param.msop_port = 2370; ///< Set the lidar msop port number, the default is 6699 - param.input_param.difop_port = 8310; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RSBP; ///< Set the lidar type. Make sure this type is correct + param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 + param.lidar_type = LidarType::RS80; ///< Set the lidar type. Make sure this type is correct param.decoder_param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet param.print(); diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index c2923565..327cf169 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -225,13 +225,12 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet break; } - block_ts += diff.ts(blk); int32_t block_az = ntohs(block.azimuth); + block_ts += diff.ts(blk); + int32_t block_azi_diff = diff.azimuth(blk); this->newBlock(block_az); - int32_t block_azi_diff = diff.azimuth(blk); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 3a9af650..11148fd4 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -40,7 +40,8 @@ namespace lidar #pragma pack(push, 1) typedef struct { - uint8_t id[2]; + uint8_t id[1]; + uint8_t ret_id; uint16_t azimuth; RSChannel channels[80]; } RS80MsopBlock; @@ -112,7 +113,7 @@ RSDecoderConstParam DecoderRS80::getConstParam() , 8 // difop id len , {0x55, 0xAA, 0x05, 0x5A} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0xFF, 0xEE} // block id + , {0xFE} // block id , 4 // blocks per packet , 80 // channels per block , 1.0f // distance min @@ -208,7 +209,7 @@ inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 0.000001; + pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 0.000001; } else { @@ -223,19 +224,18 @@ inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet { const RS80MsopBlock& block = pkt.blocks[blk]; - if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) + if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { this->excb_(Error(ERRCODE_WRONGPKTHEADER)); break; } - block_ts += diff.ts(blk); int32_t block_az = ntohs(block.azimuth); + block_ts += diff.ts(blk); + int32_t block_azi_diff = diff.azimuth(blk); this->newBlock(block_az); - int32_t block_azi_diff = diff.azimuth(blk); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 1d18c438..104c444b 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -225,12 +225,12 @@ inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet break; } - block_ts += diff.ts(blk); int32_t block_az = ntohs(block.azimuth); + block_ts += diff.ts(blk); + int32_t block_azi_diff = diff.azimuth(blk); this->newBlock(block_az); - int32_t block_azi_diff = diff.azimuth(blk); for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 6c62b721..3bb0def1 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -233,13 +233,12 @@ inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa break; } - block_ts += diff.ts(blk); int32_t block_az = ntohs(block.azimuth); + block_ts += diff.ts(blk); + int32_t block_azi_diff = diff.azimuth(blk); this->newBlock(block_az); - int32_t block_azi_diff = diff.azimuth(blk); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; From 0843f52526fa2453240c95c2cd8ee9b00d76479a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 22 Dec 2021 17:25:29 +0800 Subject: [PATCH 104/379] feat: support rs128 --- src/rs_driver/driver/decoder/block_diff.hpp | 62 +++- src/rs_driver/driver/decoder/decoder.hpp | 2 +- .../driver/decoder/decoder_RS128.hpp | 314 ++++++++++-------- src/rs_driver/driver/decoder/decoder_RS32.hpp | 4 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 4 +- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 4 +- .../driver/decoder/decoder_RSHELIOS.hpp | 4 +- .../driver/decoder/decoder_factory.hpp | 6 +- test/ab_dual_return_block_diff_test.cpp | 110 ++++++ test/decoder_test.cpp | 4 +- test/dual_return_block_diff_test.cpp | 14 +- test/single_return_block_diff_test.cpp | 10 +- 12 files changed, 372 insertions(+), 166 deletions(-) create mode 100644 test/ab_dual_return_block_diff_test.cpp diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index f44bc051..d1e51a88 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -65,7 +65,10 @@ class SingleReturnBlockDiff azi = ntohs(this->pkt_.blocks[blk].azimuth) - ntohs(this->pkt_.blocks[blk-1].azimuth); } - if (azi < 0) azi += 36000; + if (azi < 0) + { + azi += 36000; + } return azi; } @@ -83,7 +86,6 @@ class SingleReturnBlockDiff template class DualReturnBlockDiff - { public: @@ -112,7 +114,10 @@ class DualReturnBlockDiff azi = ntohs(this->pkt_.blocks[blk+2].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); } - if (azi < 0) azi += 36000; + if (azi < 0) + { + azi += 36000; + } return azi; } @@ -128,5 +133,56 @@ class DualReturnBlockDiff const double BLOCK_DURATION; }; +template +class ABDualReturnBlockDiff +{ +public: + + float ts(uint16_t blk) + { + float ret = 0.0f; + + if (ntohs(pkt_.blocks[0].azimuth) == ntohs(pkt_.blocks[1].azimuth)) // AAB + { + if (blk == 2) + { + ret = BLOCK_DURATION; + } + } + else // ABB + { + if (blk == 1) + { + ret = BLOCK_DURATION; + } + } + + return ret; + } + + int32_t azimuth(uint16_t blk) + { + int32_t azi = + ntohs(pkt_.blocks[2].azimuth) - ntohs(pkt_.blocks[0].azimuth); + + if (azi < 0) + { + azi += 36000; + } + + return azi; + } + + ABDualReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration) + : pkt_(pkt), BLOCKS_PER_PKT(blocks_per_pkt), BLOCK_DURATION(block_duration) + { + } + +protected: + const T_Packet& pkt_; + const uint16_t BLOCKS_PER_PKT; + const double BLOCK_DURATION; +}; + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index de1e3c57..a2ca73a8 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -533,7 +533,7 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) if (!this->param_.config_from_file && !this->angles_ready_) { - int ret = this->chan_angles_.loadFromDifop(pkt.ver_angle_cali, pkt.hori_angle_cali, + int ret = this->chan_angles_.loadFromDifop(pkt.vert_angle_cali, pkt.horiz_angle_cali, this->const_param_.CHANNELS_PER_BLOCK); this->angles_ready_ = (ret == 0); } diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index c6cb24ea..08bb5e17 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -30,7 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include +#include namespace robosense { namespace lidar @@ -38,7 +38,7 @@ namespace lidar #pragma pack(push, 1) typedef struct { - uint8_t id; + uint8_t id[1]; uint8_t ret_id; uint16_t azimuth; RSChannel channels[128]; @@ -46,207 +46,247 @@ typedef struct typedef struct { - RSMsopHeaderNew header; + RSMsopHeaderV2 header; RS128MsopBlock blocks[3]; unsigned int index; } RS128MsopPkt; typedef struct { - uint64_t id; + uint8_t id[8]; uint16_t rpm; - RSEthNetNew eth; + RSEthNetV2 eth; RSFOV fov; - uint16_t reserved_0; + uint8_t reserved1[2]; uint16_t phase_lock_angle; - RSVersionNew version; - uint8_t reserved_1[229]; - RSSn sn; + RSVersionV2 version; + uint8_t reserved2[229]; + RSSN sn; uint16_t zero_cali; uint8_t return_mode; RSTimeInfo time_info; - RSStatus status; - uint8_t reserved_2[5]; - RSDiagno diagno; + RSStatusV1 status; + uint8_t reserved3[5]; + RSDiagnoV1 diagno; uint8_t gprmc[86]; - RSCalibrationAngle ver_angle_cali[128]; - RSCalibrationAngle hori_angle_cali[128]; - uint8_t reserved_3[10]; + RSCalibrationAngle vert_angle_cali[128]; + RSCalibrationAngle horiz_angle_cali[128]; + uint8_t reserved4[10]; uint16_t tail; } RS128DifopPkt; #pragma pack(pop) template -class DecoderRS128 : public DecoderBase +class DecoderRS128 : public Decoder { public: - explicit DecoderRS128(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); - double getLidarTime(const uint8_t* pkt); + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRS128() = default; + + explicit DecoderRS128(const RSDecoderParam& param, + const std::function& excb); + +#ifndef UNIT_TEST +protected: +#endif + + static RSDecoderConstParam getConstParam(); + static RSEchoMode getEchoMode(uint8_t mode); + + template + void internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; template -inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) +RSDecoderConstParam DecoderRS128::getConstParam() { - this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->beam_ring_table_.resize(this->lidar_const_param_.LASER_NUM); - if (this->param_.max_distance > 250.0f) + RSDecoderConstParam param = + { + 1248 // msop len + , 1248 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x5A} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFE} // block id + , 3 // blocks per packet + , 128 // channels per block + , 1.0f // distance min + , 250.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.03615f // RX + , -0.017f // RY + , 0.0f // RZ + }; + + float blk_ts = 55.55f; + float firing_tss[] = { - this->param_.max_distance = 250.0f; + 0.00f, 0.00f, 0.00f, 0.00f, 3.236f, 3.236f, 3.236f, 3.236f, + 6.472f, 6.472f, 6.472f, 6.472f, 9.708f, 9.708f, 9.708f, 9.708f, + 12.944f, 12.944f, 12.944f, 12.944f, 16.18f, 16.18f, 16.18f, 16.18f, + 19.416f, 19.416f, 19.416f, 19.416f, 22.652f, 22.652f, 22.652f, 22.652f, + 25.888f, 25.888f, 25.888f, 25.888f, 29.124f, 29.124f, 29.124f, 29.124f, + 332.36f, 32.36f, 32.36f, 32.36f, 35.596f, 35.596f, 35.596f, 35.596f, + 38.832f, 38.832f, 38.832f, 38.832f, 42.068f, 42.068f, 42.068f, 42.068f, + 45.304f, 45.304f, 45.304f, 45.304f, 48.54f, 48.54f, 48.54f, 48.54f, + + 00.00f, 0.00f, 0.00f, 0.00f, 3.236f, 3.236f, 3.236f, 3.236f, + 6.472f, 6.472f, 6.472f, 6.472f, 9.708f, 9.708f, 9.708f, 9.708f, + 12.944f, 12.944f, 12.944f, 12.944f, 16.18f, 16.18f, 16.18f, 16.18f, + 19.416f, 19.416f, 19.416f, 19.416f, 22.652f, 22.652f, 22.652f, 22.652f, + 25.888f, 25.888f, 25.888f, 25.888f, 29.124f, 29.124f, 29.124f, 29.124f, + 32.36f, 32.36f, 32.36f, 32.36f, 35.596f, 35.596f, 35.596f, 35.596f, + 38.832f, 38.832f, 38.832f, 38.832f, 42.068f, 42.068f, 42.068f, 42.068f, + 45.304f, 45.304f, 45.304f, 45.304f, 48.54f, 48.54f, 48.54f, 48.54f + }; + + param.BLOCK_DURATION = blk_ts / 1000000; + for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) + { + param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; + param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; } - if (this->param_.min_distance < 1.0f || this->param_.min_distance > this->param_.max_distance) + + return param; +} + +template +RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) +{ + switch (mode) { - this->param_.min_distance = 1.0f; + case 0x03: // dual return + return RSEchoMode::ECHO_DUAL; + case 0x01: // strongest return + case 0x02: // last return + default: + return RSEchoMode::ECHO_SINGLE; } } template -inline double DecoderRS128::getLidarTime(const uint8_t* pkt) +inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, + const std::function& excb) + : Decoder(param, excb, getConstParam()) +{ +} + +template +inline void DecoderRS128::decodeDifopPkt(const uint8_t* packet, size_t size) +{ + const RS128DifopPkt& pkt = *(const RS128DifopPkt*)(packet); + this->template decodeDifopCommon(pkt); + + this->echo_mode_ = getEchoMode (pkt.return_mode); + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; +} + +template +inline void DecoderRS128::decodeMsopPkt(const uint8_t* pkt, size_t size) { - return this->template calculateTimeUTC(pkt, LidarType::RS128); + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) + { + internDecodeMsopPkt>(pkt, size); + } + else + { + internDecodeMsopPkt>(pkt, size); + } } template -inline RSDecoderResult DecoderRS128::decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, - int& azimuth) +template +inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size) { - height = this->lidar_const_param_.LASER_NUM; - const RS128MsopPkt* mpkt_ptr = reinterpret_cast(pkt); - if (mpkt_ptr->header.id != this->lidar_const_param_.MSOP_ID) + const RS128MsopPkt& pkt = *(const RS128MsopPkt*)(packet); + + this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) { - return RSDecoderResult::WRONG_PKT_HEADER; + pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 0.000001; + } + else + { + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); } - this->protocol_ver_ = RS_SWAP_SHORT(mpkt_ptr->header.protocol_version); - azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth); - this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_low, mpkt_ptr->header.temp_high); - double block_timestamp = this->get_point_time_func_(pkt); - float azi_diff = 0; + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); - for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) + double block_ts = pkt_ts; + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { - if (mpkt_ptr->blocks[blk_idx].id != this->lidar_const_param_.BLOCK_ID) + const RS128MsopBlock& block = pkt.blocks[blk]; + + if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { + this->excb_(Error(ERRCODE_WRONGPKTHEADER)); break; } - int cur_azi = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].azimuth); + int32_t block_az = ntohs(block.azimuth); + block_ts += diff.ts(blk); + int32_t block_azi_diff = diff.azimuth(blk); -#if 0 - if (this->echo_mode_ == ECHO_DUAL) - { - azi_diff = static_cast( - (RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[2].azimuth) - RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth)) % - RS_ONE_ROUND); - if (RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth) == RS_SWAP_SHORT(mpkt_ptr->blocks[1].azimuth)) ///< AAB - { - if (blk_idx == 2) - { - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->time_duration_between_blocks_); - } - } - else ///< ABB - { - if (blk_idx == 1) - { - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->time_duration_between_blocks_); - } - } - } - else -#endif + this->newBlock(block_az); + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { - if (blk_idx == 0) - { - azi_diff = static_cast((RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx + 1].azimuth) - cur_azi) % RS_ONE_ROUND); - } - else - { - azi_diff = static_cast((RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx - 1].azimuth)) % RS_ONE_ROUND); + const RSChannel& channel = block.channels[chan]; - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->time_duration_between_blocks_); - } - } + double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + int32_t angle_horiz = block_az + + (int32_t)((float)block_azi_diff * this->const_param_.CHAN_AZIS[chan]); - azi_diff = (azi_diff > 100) ? this->azi_diff_between_block_theoretical_ : azi_diff; + int32_t angle_vert = this->chan_angles_.vertAdjust(chan); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); - for (size_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) - { - int dsr_temp = (channel_idx / 4) % 16; - float azi_channel_ori = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].azimuth) + - (azi_diff * static_cast(dsr_temp) * this->lidar_const_param_.DSR_TOFFSET * - this->lidar_const_param_.FIRING_FREQUENCY); - - int azi_channel_final = this->azimuthCalibration(azi_channel_ori, channel_idx); - - float distance = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].channels[channel_idx].distance) * - this->lidar_const_param_.DIS_RESOLUTION; - int angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; - int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; - - typename T_PointCloud::PointT point; - bool pointValid = false; - if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && - ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || - (!this->angle_flag_ && - ((azi_channel_final >= this->start_angle_) || (azi_channel_final <= this->end_angle_))))) + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + uint8_t intensity = channel.intensity; + + if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * this->checkCosTable(angle_vert) * this->checkCosTable(azi_channel_final) + - this->lidar_const_param_.RX * this->checkCosTable(angle_horiz); - float y = -distance * this->checkCosTable(angle_vert) * this->checkSinTable(azi_channel_final) - - this->lidar_const_param_.RX * this->checkSinTable(angle_horiz); - float z = distance * this->checkSinTable(angle_vert) + this->lidar_const_param_.RZ; - uint8_t intensity = mpkt_ptr->blocks[blk_idx].channels[channel_idx].intensity; - this->transformPoint(x, y, z); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->const_param_.RZ; + + typename T_PointCloud::PointT point; setX(point, x); setY(point, y); setZ(point, z); setIntensity(point, intensity); - pointValid = true; + + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } - else if (!this->param_.is_dense) + else if (!this->param_.dense_points) { + typename T_PointCloud::PointT point; setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); - pointValid = true; - } - if (pointValid) - { - setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, block_timestamp); - vec.emplace_back(std::move(point)); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } - } - } - return RSDecoderResult::DECODE_OK; -} -template -inline RSDecoderResult DecoderRS128::decodeDifopPkt(const uint8_t* pkt) -{ - const RS128DifopPkt* dpkt_ptr = reinterpret_cast(pkt); - if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) - { - return RSDecoderResult::WRONG_PKT_HEADER; - } - this->template decodeDifopCommon(pkt, LidarType::RS128); - if (!this->difop_flag_) - { - this->template decodeDifopCalibration(pkt, LidarType::RS128); + this->prev_chan_ts_ = chan_ts; + } } - return RSDecoderResult::DECODE_OK; } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 327cf169..2813575a 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -74,8 +74,8 @@ typedef struct uint8_t reserved2[5]; RSDiagnoV1 diagno; uint8_t gprmc[86]; - RSCalibrationAngle ver_angle_cali[32]; - RSCalibrationAngle hori_angle_cali[32]; + RSCalibrationAngle vert_angle_cali[32]; + RSCalibrationAngle horiz_angle_cali[32]; uint8_t reserved3[586]; uint16_t tail; } RS32DifopPkt; diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 11148fd4..6e70d6b4 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -72,8 +72,8 @@ typedef struct uint8_t reserved3[5]; RSDiagnoV1 diagno; uint8_t gprmc[86]; - RSCalibrationAngle ver_angle_cali[128]; - RSCalibrationAngle hori_angle_cali[128]; + RSCalibrationAngle vert_angle_cali[128]; + RSCalibrationAngle horiz_angle_cali[128]; uint8_t reserved4[10]; uint16_t tail; } RS80DifopPkt; diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 104c444b..9c0f33f5 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -72,8 +72,8 @@ typedef struct uint8_t reserved_2[5]; RSDiagnoV1 diagno; uint8_t gprmc[86]; - RSCalibrationAngle ver_angle_cali[32]; - RSCalibrationAngle hori_angle_cali[32]; + RSCalibrationAngle vert_angle_cali[32]; + RSCalibrationAngle horiz_angle_cali[32]; uint8_t reserved_3[586]; uint16_t tail; } RSBPDifopPkt; diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 3bb0def1..0bfa844e 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -81,8 +81,8 @@ typedef struct uint8_t reserved3[5]; RSDiagnoV2 diagno; uint8_t gprmc[86]; - RSCalibrationAngle ver_angle_cali[32]; - RSCalibrationAngle hori_angle_cali[32]; + RSCalibrationAngle vert_angle_cali[32]; + RSCalibrationAngle horiz_angle_cali[32]; uint8_t reserved4[586]; uint16_t tail; } RSHELIOSDifopPkt; diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 1c687ede..8a903f03 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -34,9 +34,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #if 0 #include -#include #include #include #endif @@ -77,10 +77,10 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam case LidarType::RS80: ret_ptr = std::make_shared>(param, excb); break; -#if 0 case LidarType::RS128: - ret_ptr = std::make_shared>(param.decoder_param); + ret_ptr = std::make_shared>(param, excb); break; +#if 0 case LidarType::RSM1: ret_ptr = std::make_shared>(param.decoder_param); break; diff --git a/test/ab_dual_return_block_diff_test.cpp b/test/ab_dual_return_block_diff_test.cpp new file mode 100644 index 00000000..b01afc53 --- /dev/null +++ b/test/ab_dual_return_block_diff_test.cpp @@ -0,0 +1,110 @@ + +#include + +#include +#include + +using namespace robosense::lidar; + +typedef struct +{ + uint16_t distance; + uint8_t intensity; +} MyChannel; + +typedef struct +{ + uint16_t azimuth; + MyChannel channels[2]; +} MyBlock; + +typedef struct +{ + MyBlock blocks[3]; +} MyPacket; + +TEST(TestDualPacketTraverser, toNext) +{ + RSDecoderConstParam const_param = + { + 0 + , 0 + , 0 + , 0 + , {0x00} // msop id + , {0x00} // difop id + , {0x00} // block id + , 3 // blocks per packet + , 2 // channels per block + , 0.0f // distance min + , 0.0f // distance max + , 0.0 // distance resolution + , 0.0 // temperature resolution + + // lens center + , 0 // RX + , 0 // RY + , 0 // RZ + + // firing_ts + , 0.50 // block_duration + , {0.0, 0.25} // chan_tss + , {0.0} // chan_azis + }; + + { + // AAB + MyPacket pkt = + { + htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + }; + + ABDualReturnBlockDiff diff(pkt, + const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); + + // first block + ASSERT_EQ(diff.ts(0), 0.0f); + // still first block + ASSERT_EQ(diff.ts(1), 0.0f); + // last block + ASSERT_EQ(diff.ts(2), 0.5f); + + // first block. + ASSERT_EQ(diff.azimuth(0), 20); + // last block + ASSERT_EQ(diff.azimuth(1), 20); + // still last block + ASSERT_EQ(diff.azimuth(2), 20); + } + + { + // ABB + MyPacket pkt = + { + htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + }; + + ABDualReturnBlockDiff diff(pkt, + const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); + + // first block + ASSERT_EQ(diff.ts(0), 0.0f); + // still first block + ASSERT_EQ(diff.ts(1), 0.5f); + // last block + ASSERT_EQ(diff.ts(2), 0.5f); + + // first block. + ASSERT_EQ(diff.azimuth(0), 20); + // second block = prev block + ASSERT_EQ(diff.azimuth(1), 20); + // (last - 1) block = + ASSERT_EQ(diff.azimuth(2), 20); + } + +} + diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index e1d1df05..45d20bfe 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -21,8 +21,8 @@ struct MyDifopPkt uint8_t id[8]; uint16_t rpm; RSFOV fov; - RSCalibrationAngle ver_angle_cali[2]; - RSCalibrationAngle hori_angle_cali[2]; + RSCalibrationAngle vert_angle_cali[2]; + RSCalibrationAngle horiz_angle_cali[2]; }; #pragma pack(pop) diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_diff_test.cpp index 87bd0808..289324b8 100644 --- a/test/dual_return_block_diff_test.cpp +++ b/test/dual_return_block_diff_test.cpp @@ -65,20 +65,20 @@ TEST(TestDualPacketTraverser, toNext) DualReturnBlockDiff diff(pkt, const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); - // first block = 0 + // first block ASSERT_EQ(diff.ts(0), 0.0f); - // second block. calculate it. + // still first block ASSERT_EQ(diff.ts(1), 0.0f); - // last block = prev block + // second block ASSERT_EQ(diff.ts(2), 0.5f); - // first block. calculate it. + // first block ASSERT_EQ(diff.azimuth(0), 20); - // second block. calculate it. + // still frist block ASSERT_EQ(diff.azimuth(1), 20); - // (last - 1) block = prev block + // last block ASSERT_EQ(diff.azimuth(4), 30); - // last block = prev block + // last block ASSERT_EQ(diff.azimuth(5), 30); } diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_diff_test.cpp index 2485b7dd..514c09ca 100644 --- a/test/single_return_block_diff_test.cpp +++ b/test/single_return_block_diff_test.cpp @@ -62,16 +62,16 @@ TEST(TestSingleReturnBlockDiff, ctor) SingleReturnBlockDiff diff(pkt, const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); - // first block = 0 + // first block ASSERT_EQ(diff.ts(0), 0.0f); - // second block. calculate it. + // second block ASSERT_EQ(diff.ts(1), 0.5f); - // first block. calculate it. + // first block ASSERT_EQ(diff.azimuth(0), 20); - // second block. calculate it. + // second block. ASSERT_EQ(diff.azimuth(1), 30); - // second block = prev block + // last block ASSERT_EQ(diff.azimuth(2), 30); } From a04767b9d84e3958a919af36328ecbe3c80ae332 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 23 Dec 2021 11:26:14 +0800 Subject: [PATCH 105/379] refac: support rs16 --- src/rs_driver/driver/decoder/chan_angles.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS16.hpp | 371 +++++++++++------- .../driver/decoder/decoder_factory.hpp | 6 +- 3 files changed, 225 insertions(+), 154 deletions(-) diff --git a/src/rs_driver/driver/decoder/chan_angles.hpp b/src/rs_driver/driver/decoder/chan_angles.hpp index cc944d1f..51e6118d 100644 --- a/src/rs_driver/driver/decoder/chan_angles.hpp +++ b/src/rs_driver/driver/decoder/chan_angles.hpp @@ -100,7 +100,7 @@ class ChanAngles genUserChan(vert_angles_, user_chans_); // - // some lidas, such as RS32, have higher resolution than the other lidars. + // some lidars, such as RS32, have higher resolution than the other lidars. // fix them to the same resolution. // if (narrow_angles_) diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 0cf5da3b..02785f42 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -30,7 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include +#include namespace robosense { namespace lidar @@ -38,14 +38,14 @@ namespace lidar #pragma pack(push, 1) typedef struct { - uint16_t id; + uint8_t id[2]; uint16_t azimuth; RSChannel channels[32]; } RS16MsopBlock; typedef struct { - RSMsopHeader header; + RSMsopHeaderV1 header; RS16MsopBlock blocks[12]; unsigned int index; uint16_t tail; @@ -53,207 +53,280 @@ typedef struct typedef struct { - uint64_t id; + uint8_t id[8]; uint16_t rpm; - RSEthNet eth; + RSEthNetV1 eth; RSFOV fov; - uint16_t static_base; + uint8_t reserved0[2]; uint16_t phase_lock_angle; - RSVersion version; - uint8_t reserved_1[242]; - RSSn sn; + RSVersionV1 version; + uint8_t reserved1[242]; + RSSN sn; uint16_t zero_cali; uint8_t return_mode; uint16_t sw_ver; RSTimestampYMD timestamp; - RSStatus status; - uint8_t reserved_2[5]; - RSDiagno diagno; + RSStatusV1 status; + uint8_t reserved2[5]; + RSDiagnoV1 diagno; uint8_t gprmc[86]; - uint8_t static_cali[697]; + uint8_t reserved3[697]; uint8_t pitch_cali[48]; - uint8_t reserved_3[33]; + uint8_t reserved4[33]; uint16_t tail; } RS16DifopPkt; +typedef struct +{ + uint8_t id[8]; + uint16_t rpm; + RSEthNetV1 eth; + RSFOV fov; + uint8_t reserved0[2]; + uint16_t phase_lock_angle; + RSVersionV1 version; + uint8_t reserved1[242]; + RSSN sn; + uint16_t zero_cali; + uint8_t return_mode; + uint16_t sw_ver; + RSTimestampYMD timestamp; + RSStatusV1 status; + uint8_t reserved2[5]; + RSDiagnoV1 diagno; + uint8_t gprmc[86]; + RSCalibrationAngle vert_angle_cali[32]; + RSCalibrationAngle horiz_angle_cali[32]; +} AdapterRS16DifopPkt; + #pragma pack(pop) +void RS16DifopPkt2Adapter (const uint8_t* difop) +{ + RS16DifopPkt& orig = *(RS16DifopPkt*)difop; + AdapterRS16DifopPkt& adapter = *(AdapterRS16DifopPkt*)difop; + + for (uint16_t i = 0, j = 16; i < 16; i++, j++) + { + uint32_t v = 0; + v += orig.pitch_cali[i*3]; + v = v << 8; + v += orig.pitch_cali[i*3 + 1]; + v = v << 8; + v += orig.pitch_cali[i*3 + 2]; + + uint16_t v2 = (uint16_t)(v * 0.01); + + adapter.vert_angle_cali[i].sign = (i < 8) ? 1 : 0; + adapter.vert_angle_cali[i].value = htons(v2); + adapter.horiz_angle_cali[i].sign = 0; + adapter.horiz_angle_cali[i].value = 0; + + adapter.vert_angle_cali[j].sign = adapter.vert_angle_cali[i].sign; + adapter.vert_angle_cali[j].value = adapter.vert_angle_cali[i].value; + adapter.horiz_angle_cali[j].sign = 0; + adapter.horiz_angle_cali[j].value = 0; + } +} + template -class DecoderRS16 : public DecoderBase +class DecoderRS16 : public Decoder { -public: - DecoderRS16(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - virtual RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - virtual RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); - virtual double getLidarTime(const uint8_t* pkt); +public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRS16() = default; + + explicit DecoderRS16(const RSDecoderParam& param, + const std::function& excb); + +#ifndef UNIT_TEST +protected: +#endif + + static RSDecoderConstParam getConstParam(); + static RSEchoMode getEchoMode(uint8_t mode); + + template + void internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; template -inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) +RSDecoderConstParam DecoderRS16::getConstParam() { - this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->beam_ring_table_.resize(this->lidar_const_param_.LASER_NUM); - if (this->param_.max_distance > 150.0f) + RSDecoderConstParam param = + { + 1248 // msop len + , 1248 // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 12 // blocks per packet + , 32 // channels per block. how many channels in the msop block. + , 0.2f // distance min + , 150.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.03825f // RX + , -0.01088f // RY + , 0.0f // RZ + }; + + float blk_ts = 55.5f * 2; + float firing_tss[] = { - this->param_.max_distance = 150.0f; + 0.00f, 2.80f, 5.60f, 8.40f, 11.20f, 14.00f, 16.80f, 19.60f, + 22.40f, 25.20f, 28.00f, 30.80f, 33.60f, 36.40f, 39.20f, 42.00f, + 55.50f, 58.30f, 61.10f, 63.90f, 66.70f, 69.50f, 72.30f, 75.10f, + 77.90f, 80.70f, 83.50f, 86.30f, 89.10f, 91.90f, 94.70f, 97.50f + }; + + param.BLOCK_DURATION = blk_ts / 1000000; + for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) + { + param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; + param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; } - if (this->param_.min_distance < 0.2f || this->param_.min_distance > this->param_.max_distance) + + return param; +} + +template +RSEchoMode DecoderRS16::getEchoMode(uint8_t mode) +{ + switch (mode) { - this->param_.min_distance = 0.2f; + case 0x00: // dual return + return RSEchoMode::ECHO_DUAL; + case 0x01: // strongest return + case 0x02: // last return + default: + return RSEchoMode::ECHO_SINGLE; } } template -inline double DecoderRS16::getLidarTime(const uint8_t* pkt) +inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, + const std::function& excb) + : Decoder(param, excb, getConstParam()) +{ +} + +template +inline void DecoderRS16::decodeDifopPkt(const uint8_t* packet, size_t size) +{ + RS16DifopPkt2Adapter (packet); + + const AdapterRS16DifopPkt& pkt = *(const AdapterRS16DifopPkt*)(packet); + this->template decodeDifopCommon(pkt); + + this->echo_mode_ = getEchoMode (pkt.return_mode); + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; +} + +template +inline void DecoderRS16::decodeMsopPkt(const uint8_t* pkt, size_t size) { - return this->template calculateTimeYMD(pkt); + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) + { + internDecodeMsopPkt>(pkt, size); + } + else + { + internDecodeMsopPkt>(pkt, size); + } } template -inline RSDecoderResult DecoderRS16::decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, - int& height, int& azimuth) +template +inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) { - height = this->lidar_const_param_.LASER_NUM; - const RS16MsopPkt* mpkt_ptr = reinterpret_cast(pkt); - if (mpkt_ptr->header.id != this->lidar_const_param_.MSOP_ID) + const RS16MsopPkt& pkt = *(const RS16MsopPkt*)(packet); + + this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) + { + pkt_ts = parseTimeYMD(&pkt.header.timestamp) * 0.000001; + } + else { - return RSDecoderResult::WRONG_PKT_HEADER; + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); } - azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].azimuth); - this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_raw); - double block_timestamp = this->get_point_time_func_(pkt); - float azi_diff = 0; - for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) + + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); + + double block_ts = pkt_ts; + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { - if (mpkt_ptr->blocks[blk_idx].id != this->lidar_const_param_.BLOCK_ID) + const RS16MsopBlock& block = pkt.blocks[blk]; + + if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { + this->excb_(Error(ERRCODE_WRONGPKTHEADER)); break; } - int cur_azi = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].azimuth); - if (blk_idx == 0) - { - azi_diff = static_cast((RS_ONE_ROUND + RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx + 1].azimuth) - cur_azi) % - RS_ONE_ROUND); - } - else - { - azi_diff = static_cast((RS_ONE_ROUND + cur_azi - RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx - 1].azimuth)) % - RS_ONE_ROUND); - block_timestamp = (azi_diff > 100) ? (block_timestamp + this->fov_time_jump_diff_) : - (block_timestamp + this->time_duration_between_blocks_); - } - azi_diff = (azi_diff > 100) ? this->azi_diff_between_block_theoretical_ : azi_diff; - for (size_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) + + int32_t block_az = ntohs(block.azimuth); + block_ts += diff.ts(blk); + int32_t block_azi_diff = diff.azimuth(blk); + + this->newBlock(block_az); + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { - float azi_channel_ori = 0; - if (this->echo_mode_ == ECHO_DUAL) - { - azi_channel_ori = cur_azi + - azi_diff * this->lidar_const_param_.DSR_TOFFSET * this->lidar_const_param_.FIRING_FREQUENCY * - 2.0f * static_cast(channel_idx % 16); - } - else - { - azi_channel_ori = - cur_azi + - azi_diff * ((this->lidar_const_param_.DSR_TOFFSET * this->lidar_const_param_.FIRING_FREQUENCY * - static_cast(channel_idx % 16)) + - static_cast(channel_idx / 16) * 0.5f); - } - int azi_channel_final = this->azimuthCalibration(azi_channel_ori, channel_idx % 16); - float distance = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].channels[channel_idx].distance) * - this->lidar_const_param_.DIS_RESOLUTION; - int angle_horiz_ori = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; - int angle_vert = ((this->vert_angle_list_[channel_idx % 16]) + RS_ONE_ROUND) % RS_ONE_ROUND; - - typename T_PointCloud::PointT point; - bool pointValid = false; - if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && - ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || - (!this->angle_flag_ && - ((azi_channel_final >= this->start_angle_) || (azi_channel_final <= this->end_angle_))))) + const RSChannel& channel = block.channels[chan]; + + double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + int32_t angle_horiz = block_az + + (int32_t)((float)block_azi_diff * this->const_param_.CHAN_AZIS[chan]); + + int32_t angle_vert = this->chan_angles_.vertAdjust(chan); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + uint8_t intensity = channel.intensity; + + if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * this->checkCosTable(angle_vert) * this->checkCosTable(azi_channel_final) + - this->lidar_const_param_.RX * this->checkCosTable(angle_horiz_ori); - float y = -distance * this->checkCosTable(angle_vert) * this->checkSinTable(azi_channel_final) - - this->lidar_const_param_.RX * this->checkSinTable(angle_horiz_ori); - float z = distance * this->checkSinTable(angle_vert) + this->lidar_const_param_.RZ; - uint8_t intensity = mpkt_ptr->blocks[blk_idx].channels[channel_idx].intensity; - this->transformPoint(x, y, z); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->const_param_.RZ; + + typename T_PointCloud::PointT point; setX(point, x); setY(point, y); setZ(point, z); setIntensity(point, intensity); - pointValid = true; + + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } - else if (!this->param_.is_dense) + else if (!this->param_.dense_points) { + typename T_PointCloud::PointT point; setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); - pointValid = true; - } - if (pointValid) - { - setRing(point, this->beam_ring_table_[channel_idx % 16]); - if (this->echo_mode_ != ECHO_DUAL && channel_idx > 15) - { - setTimestamp(point, block_timestamp + this->time_duration_between_blocks_ / 2); - } - else - { - setTimestamp(point, block_timestamp); - } - vec.emplace_back(std::move(point)); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } - } - } - return RSDecoderResult::DECODE_OK; -} -template -inline RSDecoderResult DecoderRS16::decodeDifopPkt(const uint8_t* pkt) -{ - const RS16DifopPkt* dpkt_ptr = reinterpret_cast(pkt); - if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) - { - return RSDecoderResult::WRONG_PKT_HEADER; - } - this->template decodeDifopCommon(pkt, LidarType::RS16); - if (!this->difop_flag_) - { - if ((dpkt_ptr->pitch_cali[0] == 0x00 || dpkt_ptr->pitch_cali[0] == 0xFF) && - (dpkt_ptr->pitch_cali[1] == 0x00 || dpkt_ptr->pitch_cali[1] == 0xFF) && - (dpkt_ptr->pitch_cali[2] == 0x00 || dpkt_ptr->pitch_cali[2] == 0xFF) && - (dpkt_ptr->pitch_cali[3] == 0x00 || dpkt_ptr->pitch_cali[3] == 0xFF)) - { - return RSDecoderResult::DECODE_OK; - } - for (size_t i = 0; i < this->lidar_const_param_.LASER_NUM; i++) - { - /* vert angle calibration data */ - union vertical_angle - { - uint8_t data[4]; - uint32_t vertical_angle; - } ver_angle; - ver_angle.data[0] = dpkt_ptr->pitch_cali[i * 3 + 2]; - ver_angle.data[1] = dpkt_ptr->pitch_cali[i * 3 + 1]; - ver_angle.data[2] = dpkt_ptr->pitch_cali[i * 3]; - ver_angle.data[3] = 0; - int neg = i < 8 ? -1 : 1; - this->vert_angle_list_[i] = static_cast(ver_angle.vertical_angle) * neg * 0.01f; - this->hori_angle_list_[i] = 0; + this->prev_chan_ts_ = chan_ts; } - this->sortBeamTable(); - this->difop_flag_ = true; } - return RSDecoderResult::DECODE_OK; } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 8a903f03..2ea746b7 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -35,8 +35,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#if 0 #include +#if 0 #include #include #endif @@ -63,11 +63,9 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam switch (type) { -#if 0 case LidarType::RS16: - ret_ptr = std::make_shared>(param.decoder_param); + ret_ptr = std::make_shared>(param, excb); break; -#endif case LidarType::RS32: ret_ptr = std::make_shared>(param, excb); break; From 438b41b73c546623325a6e9cd41bdfcd5aff8622 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 23 Dec 2021 12:18:47 +0800 Subject: [PATCH 106/379] refac: refactory decoder --- src/rs_driver/driver/decoder/chan_angles.hpp | 25 +------- src/rs_driver/driver/decoder/decoder.hpp | 6 +- src/rs_driver/driver/decoder/decoder_RS16.hpp | 4 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 59 ++++++++++++++++++- test/chan_angles_test.cpp | 37 ++---------- 5 files changed, 68 insertions(+), 63 deletions(-) diff --git a/src/rs_driver/driver/decoder/chan_angles.hpp b/src/rs_driver/driver/decoder/chan_angles.hpp index 51e6118d..141cf176 100644 --- a/src/rs_driver/driver/decoder/chan_angles.hpp +++ b/src/rs_driver/driver/decoder/chan_angles.hpp @@ -53,8 +53,8 @@ class ChanAngles { public: - ChanAngles(uint16_t chan_num, bool narrow_angles = false) - : chan_num_(chan_num), narrow_angles_(narrow_angles) + ChanAngles(uint16_t chan_num) + : chan_num_(chan_num) { vert_angles_.resize(chan_num_); horiz_angles_.resize(chan_num_); @@ -98,16 +98,6 @@ class ChanAngles vert_angles_.swap(vert_angles); horiz_angles_.swap(horiz_angles); genUserChan(vert_angles_, user_chans_); - - // - // some lidars, such as RS32, have higher resolution than the other lidars. - // fix them to the same resolution. - // - if (narrow_angles_) - { - narrow(); - } - return 0; } @@ -145,15 +135,6 @@ class ChanAngles private: #endif - void narrow() - { - for (uint16_t chan = 0; chan < chan_num_; chan++) - { - vert_angles_[chan] = std::round(vert_angles_[chan] * 0.1f); - horiz_angles_[chan] = std::round(horiz_angles_[chan] * 0.1f); - } - } - static void genUserChan(const std::vector& vert_angles, std::vector& user_chans) { @@ -233,6 +214,7 @@ class ChanAngles if (!angleCheck (v)) return -1; + } return ((vert_angles.size() > 0) ? 0 : -1); @@ -244,7 +226,6 @@ class ChanAngles } uint16_t chan_num_; - bool narrow_angles_; std::vector vert_angles_; std::vector horiz_angles_; std::vector user_chans_; diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index a2ca73a8..098922e5 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -268,7 +268,7 @@ class Decoder explicit Decoder(const RSDecoderParam& param, const std::function& excb, - const RSDecoderConstParam& const_param, bool narrow_angles = false); + const RSDecoderConstParam& const_param); void processDifopPkt(const uint8_t* pkt, size_t size); void processMsopPkt(const uint8_t* pkt, size_t size); @@ -329,12 +329,12 @@ class Decoder template inline Decoder::Decoder(const RSDecoderParam& param, const std::function& excb, - const RSDecoderConstParam& const_param, bool narrow_angles) + const RSDecoderConstParam& const_param) : const_param_(const_param) , param_(param) , excb_(excb) , height_(const_param.CHANNELS_PER_BLOCK) - , chan_angles_(const_param.CHANNELS_PER_BLOCK, narrow_angles) + , chan_angles_(const_param.CHANNELS_PER_BLOCK) , distance_section_(const_param.DISTANCE_MIN, const_param.DISTANCE_MAX, param.min_distance, param.max_distance) , scan_section_(param.start_angle * 100, param.end_angle * 100) diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 02785f42..c1513f7c 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -101,7 +101,7 @@ typedef struct #pragma pack(pop) -void RS16DifopPkt2Adapter (const uint8_t* difop) +inline void RS16DifopPkt2Adapter (const uint8_t* difop) { RS16DifopPkt& orig = *(RS16DifopPkt*)difop; AdapterRS16DifopPkt& adapter = *(AdapterRS16DifopPkt*)difop; @@ -115,7 +115,7 @@ void RS16DifopPkt2Adapter (const uint8_t* difop) v = v << 8; v += orig.pitch_cali[i*3 + 2]; - uint16_t v2 = (uint16_t)(v * 0.01); + uint16_t v2 = (uint16_t)(v * 0.01); // higher resolution to lower one. adapter.vert_angle_cali[i].sign = (i < 8) ? 1 : 0; adapter.vert_angle_cali[i].value = htons(v2); diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 2813575a..ab2a5920 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -79,8 +79,59 @@ typedef struct uint8_t reserved3[586]; uint16_t tail; } RS32DifopPkt; + +typedef struct +{ + uint8_t id[8]; + uint16_t rpm; + RSEthNetV1 eth; + RSFOV fov; + uint8_t reserved0[2]; + uint16_t phase_lock_angle; + RSVersionV1 version; + uint8_t reserved1[242]; + RSSN sn; + uint16_t zero_cali; + uint8_t return_mode; + uint16_t sw_ver; + RSTimestampYMD timestamp; + RSStatusV1 status; + uint8_t reserved2[5]; + RSDiagnoV1 diagno; + uint8_t gprmc[86]; + RSCalibrationAngle vert_angle_cali_orig[32]; + RSCalibrationAngle horiz_angle_cali_orig[32]; + RSCalibrationAngle vert_angle_cali[32]; + RSCalibrationAngle horiz_angle_cali[32]; +} AdapterRS32DifopPkt; + #pragma pack(pop) +inline void RS32DifopPkt2Adapter (const uint8_t* difop) +{ + RS32DifopPkt& orig = *(RS32DifopPkt*)difop; + AdapterRS32DifopPkt& adapter = *(AdapterRS32DifopPkt*)difop; + + for (uint16_t i = 0; i < 32; i++) + { + uint16_t v; + + // vert angles + adapter.vert_angle_cali[i].sign = orig.vert_angle_cali[i].sign; + + v = ntohs(orig.vert_angle_cali[i].value); + v = std::round(v * 0.1f); + adapter.vert_angle_cali[i].value = htons(v); + + // horiz_angles + adapter.horiz_angle_cali[i].sign = orig.horiz_angle_cali[i].sign; + + v = ntohs(orig.horiz_angle_cali[i].value); + v = std::round(v * 0.1f); + adapter.horiz_angle_cali[i].value = htons(v); + } +} + template class DecoderRS32 : public Decoder { @@ -165,15 +216,17 @@ RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) template inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, getConstParam(), true) + : Decoder(param, excb, getConstParam()) { } template inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, size_t size) { - const RS32DifopPkt& pkt = *(const RS32DifopPkt*)(packet); - this->template decodeDifopCommon(pkt); + RS32DifopPkt2Adapter (packet); + + const AdapterRS32DifopPkt& pkt = *(const AdapterRS32DifopPkt*)(packet); + this->template decodeDifopCommon(pkt); this->echo_mode_ = getEchoMode (pkt.return_mode); this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? diff --git a/test/chan_angles_test.cpp b/test/chan_angles_test.cpp index ed300a1f..f227d2dc 100644 --- a/test/chan_angles_test.cpp +++ b/test/chan_angles_test.cpp @@ -165,38 +165,6 @@ TEST(TestChanAngles, memberLoadFromDifop) ASSERT_EQ(angles.toUserChan(3), 3); } -TEST(TestChanAngles, memberLoadFromDifop_narrow) -{ - uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, - 0x01, 0x03, 0x04, - 0x01, 0x05, 0x06, - 0x00, 0x07, 0x08}; - uint8_t horiz_angle_arr[] = {0x00, 0x01, 0x11, - 0x01, 0x02, 0x22, - 0x00, 0x03, 0x33, - 0x01, 0x04, 0x44}; - - ChanAngles angles(4, true); - ASSERT_EQ(angles.chan_num_, 4); - - // load - ASSERT_EQ(angles.loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4), 0); - - ASSERT_EQ(angles.vert_angles_.size(), 4); - ASSERT_EQ(angles.vert_angles_[0], 26); - ASSERT_EQ(angles.vert_angles_[1], -77); - ASSERT_EQ(angles.vert_angles_[2], -129); - ASSERT_EQ(angles.vert_angles_[3], 180); - - ASSERT_EQ(angles.horiz_angles_[0], 27); - ASSERT_EQ(angles.horiz_angles_[1], -55); - ASSERT_EQ(angles.horiz_angles_[2], 82); - ASSERT_EQ(angles.horiz_angles_[3], -109); -} - TEST(TestChanAngles, memberLoadFromDifop_fail) { uint8_t vert_angle_arr[] = {0x00, 0x01, 0x02, @@ -227,10 +195,12 @@ TEST(TestChanAngles, memberLoadFromDifop_fail_angle) 0x01, 0x05, 0x06, 0x00, 0x07, 0x08}; - ChanAngles angles(4, true); + // -9000 <= angle < 9000 + ChanAngles angles(4); ASSERT_EQ(angles.chan_num_, 4); { + // 9000 uint8_t horiz_angle_arr[] = { 0x00, 0x01, 0x11, @@ -247,6 +217,7 @@ TEST(TestChanAngles, memberLoadFromDifop_fail_angle) } { + // -9001 uint8_t horiz_angle_arr[] = { 0x00, 0x01, 0x11, From 15bcae6bdaa4a0a01c8cb33d0cf670c937fcb0e0 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 23 Dec 2021 14:22:21 +0800 Subject: [PATCH 107/379] fix: fix rs16 ring --- src/rs_driver/driver/decoder/decoder_RS16.hpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index c1513f7c..65ba64fb 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -306,7 +306,7 @@ inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet setIntensity(point, intensity); setTimestamp(point, chan_ts); - setRing(point, this->chan_angles_.toUserChan(chan)); + setRing(point, (this->chan_angles_.toUserChan(chan) >> 1)); this->point_cloud_->points.emplace_back(point); } @@ -319,13 +319,14 @@ inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet setIntensity(point, 0); setTimestamp(point, chan_ts); - setRing(point, this->chan_angles_.toUserChan(chan)); + setRing(point, (this->chan_angles_.toUserChan(chan) >> 1)); this->point_cloud_->points.emplace_back(point); } this->prev_chan_ts_ = chan_ts; } + } } From 0396e56a7c4039ae202ce4e094a3dbfd951f4c1c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 23 Dec 2021 16:28:54 +0800 Subject: [PATCH 108/379] fix: minus 80 from temp to adapt to guide doc --- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index adbc858a..5576abdf 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -223,7 +223,7 @@ inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* p { return RSDecoderResult::WRONG_PKT_HEADER; } - this->current_temperature_ = static_cast(mpkt_ptr->header.temperature); + this->current_temperature_ = static_cast(mpkt_ptr->header.temperature - 80); this->protocol_ver_ = RS_SWAP_SHORT(mpkt_ptr->header.protocol_version); double pkt_timestamp = 0; switch (mpkt_ptr->blocks[0].return_seq) From 401b3fdcda5591daab3c3bd0a7ec08a043d04be9 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 23 Dec 2021 18:22:43 +0800 Subject: [PATCH 109/379] fix: fix msop copy --- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 5576abdf..feac8146 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -242,7 +242,7 @@ inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* p for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) { - RSM1Block blk = mpkt_ptr->blocks[blk_idx]; + const RSM1Block& blk = mpkt_ptr->blocks[blk_idx]; double point_time = pkt_timestamp + blk.time_offset * 1e-6; for (size_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) { From 193ace370bce0743cd3b599b895db52c4cc3da1e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 23 Dec 2021 19:24:01 +0800 Subject: [PATCH 110/379] refac: recover rsm1 --- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 295 +++++++++--------- .../driver/decoder/decoder_factory.hpp | 22 +- 2 files changed, 155 insertions(+), 162 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 6797fa2b..26e062bb 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -30,17 +30,27 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include +#include namespace robosense { namespace lidar { -const uint32_t SINGLE_PKT_NUM = 630; -const uint32_t DUAL_PKT_NUM = 1260; -const int ANGLE_OFFSET = 32768; #pragma pack(push, 1) +typedef struct +{ + uint32_t id; + uint16_t pkt_cnt; + uint16_t protocol_version; + uint8_t return_mode; + uint8_t time_mode; + RSTimestampUTC timestamp; + uint8_t reserved[10]; + uint8_t lidar_type; + int8_t temperature; +} RSM1MsopHeader; + typedef struct { uint16_t distance; @@ -58,19 +68,6 @@ typedef struct RSM1Channel channel[5]; } RSM1Block; -typedef struct -{ - uint32_t id; - uint16_t pkt_cnt; - uint16_t protocol_version; - uint8_t return_mode; - uint8_t time_mode; - RSTimestampUTC timestamp; - uint8_t reserved[10]; - uint8_t lidar_type; - int8_t temperature; -} RSM1MsopHeader; - typedef struct { RSM1MsopHeader header; @@ -118,198 +115,196 @@ typedef struct typedef struct { - uint64_t id; - uint8_t reserved_1; + uint8_t id[8]; + uint8_t reserved1[1]; uint8_t frame_rate; RSM1DifopEther ether; RSM1DifopFov fov_setting; RSM1DifopVerInfo ver_info; - RSSn sn; + RSSN sn; uint8_t return_mode; RSTimeInfo time_info; RSM1DifopRunSts status; - uint8_t diag_reserved[40]; + uint8_t reserved2[40]; RSM1DifopCalibration cali_param[20]; - uint8_t reserved_2[71]; + uint8_t reserved3[71]; } RSM1DifopPkt; + #pragma pack(pop) -template -class DecoderRSM1 : public DecoderBase +class Split { public: - DecoderRSM1(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); - double getLidarTime(const uint8_t* pkt); - RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size, typename T_PointCloud::VectorT& pointcloud_vec, - int& height); + + Split(uint16_t* max_seq) + : max_seq_(max_seq), prev_seq_(0) + { + } + + bool newPacket(uint16_t seq) + { + if ((seq == *max_seq_) || (seq < prev_seq_)) + { + prev_seq_ = 1; + return true; + } + else + { + return false; + } + } private: - uint32_t last_pkt_cnt_; - uint32_t max_pkt_num_; - double last_pkt_time_; + + uint16_t* max_seq_; + uint16_t prev_seq_; }; +const uint32_t SINGLE_PKT_NUM = 630; +const uint32_t DUAL_PKT_NUM = 1260; + template -inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) - , last_pkt_cnt_(1) - , max_pkt_num_(SINGLE_PKT_NUM) - , last_pkt_time_(0) +class DecoderRSM1 : public Decoder { - this->msop_pkt_len_ = MEMS_MSOP_LEN; - this->difop_pkt_len_ = MEMS_DIFOP_LEN; +public: - if (this->param_.max_distance > 200.0f) - { - this->param_.max_distance = 200.0f; - } - if (this->param_.min_distance < 0.2f || this->param_.min_distance > this->param_.max_distance) + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRSM1() = default; + + explicit DecoderRSM1(const RSDecoderParam& param, + const std::function& excb); + +private: + + RSDecoderConstParam getConstParam(); + RSEchoMode getEchoMode(uint8_t mode); + + uint16_t max_seq_; + Split split_; +}; + +template +RSDecoderConstParam DecoderRSM1::getConstParam() +{ + RSDecoderConstParam param = { - this->param_.min_distance = 0.2f; - } - this->time_duration_between_blocks_ = 5 * 1e-6; + 1210 // msop len + , 256 // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0x00, 0x00} + , 0 + , 0 + , 0.2f // distance min + , 200.0f // distance max + , 0.005f // distance resolution + }; + + return param; } template -inline double DecoderRSM1::getLidarTime(const uint8_t* pkt) +inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, + const std::function& excb) + : Decoder(param, excb, getConstParam()) + , max_seq_(SINGLE_PKT_NUM) + , split_(&max_seq_) { - return this->template calculateTimeUTC(pkt, LidarType::RSM1); +// this->time_duration_between_blocks_ = 5 * 1e-6; } template -inline RSDecoderResult DecoderRSM1::processMsopPkt(const uint8_t* pkt, size_t size, - typename T_PointCloud::VectorT& pointcloud_vec, - int& height) +RSEchoMode DecoderRSM1::getEchoMode(uint8_t mode) { - if (size != this->msop_pkt_len_) + switch (mode) { - return WRONG_PKT_LENGTH; - } - - int azimuth = 0; - RSDecoderResult ret = decodeMsopPkt(pkt, pointcloud_vec, height, azimuth); - this->pkt_count_++; - switch (this->param_.split_frame_mode) - { - case SplitFrameMode::SPLIT_BY_ANGLE: - case SplitFrameMode::SPLIT_BY_FIXED_PKTS: - return ret; - case SplitFrameMode::SPLIT_BY_CUSTOM_PKTS: - if (this->pkt_count_ >= this->param_.num_pkts_split) - { - this->pkt_count_ = 0; - this->trigger_index_ = 0; - this->prev_angle_diff_ = RS_ONE_ROUND; - return FRAME_SPLIT; - } - break; + case 0x00: // dual return + return RSEchoMode::ECHO_DUAL; + case 0x04: // strongest return + case 0x05: // last return + case 0x06: // first return default: - break; + return RSEchoMode::ECHO_SINGLE; } - return DECODE_OK; } template -inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, - int& height, int& azimuth) +void DecoderRSM1::decodeDifopPkt(const uint8_t* packet, size_t size) { - height = this->lidar_const_param_.LASER_NUM; - RSM1MsopPkt* mpkt_ptr = (RSM1MsopPkt*)pkt; - if (mpkt_ptr->header.id != this->lidar_const_param_.MSOP_ID) + const RSM1DifopPkt& pkt = *(RSM1DifopPkt*)packet; + this->echo_mode_ = this->getEchoMode(pkt.return_mode); + max_seq_ = (this->echo_mode_ == ECHO_SINGLE) ? 630 : 1260; +} + +template +void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) +{ + const RSM1MsopPkt& pkt = *(RSM1MsopPkt*)packet; + + this->temperature_ = static_cast(pkt.header.temperature - 80); + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) { - return RSDecoderResult::WRONG_PKT_HEADER; + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 0.000001; } - this->current_temperature_ = static_cast(mpkt_ptr->header.temperature); - this->protocol_ver_ = RS_SWAP_SHORT(mpkt_ptr->header.protocol_version); - double pkt_timestamp = 0; - switch (mpkt_ptr->blocks[0].return_seq) + else { - case 0: - pkt_timestamp = this->get_point_time_func_(pkt); - break; - case 1: - pkt_timestamp = this->get_point_time_func_(pkt); - last_pkt_time_ = pkt_timestamp; - break; - case 2: - pkt_timestamp = last_pkt_time_; - break; + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); } - for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) + for (size_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { - RSM1Block blk = mpkt_ptr->blocks[blk_idx]; - double point_time = pkt_timestamp + blk.time_offset * 1e-6; - for (size_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) + const RSM1Block& block = pkt.blocks[blk]; + + double point_time = pkt_ts + block.time_offset * 1e-6; + + for (size_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { - typename T_PointCloud::PointT point; - bool pointValid = false; - float distance = RS_SWAP_SHORT(blk.channel[channel_idx].distance) * this->lidar_const_param_.DIS_RESOLUTION; - if (distance <= this->param_.max_distance && distance >= this->param_.min_distance) + const RSM1Channel& channel = block.channel[chan]; + + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + + if (this->distance_section_.in(distance)) { - int pitch = RS_SWAP_SHORT(blk.channel[channel_idx].pitch) - ANGLE_OFFSET; - int yaw = RS_SWAP_SHORT(blk.channel[channel_idx].yaw) - ANGLE_OFFSET; - uint8_t intensity = blk.channel[channel_idx].intensity; - float x = distance * this->checkCosTable(pitch) * this->checkCosTable(yaw); - float y = distance * this->checkCosTable(pitch) * this->checkSinTable(yaw); - float z = distance * this->checkSinTable(pitch); - this->transformPoint(x, y, z); + static const int ANGLE_OFFSET = 32768; + int pitch = ntohs(channel.pitch) - ANGLE_OFFSET; + int yaw = ntohs(channel.yaw) - ANGLE_OFFSET; + + float x = distance * COS (pitch) * COS (yaw); + float y = distance * COS (pitch) * SIN (yaw); + float z = distance * SIN (pitch); + uint8_t intensity = channel.intensity; + + typename T_PointCloud::PointT point; setX(point, x); setY(point, y); setZ(point, z); setIntensity(point, intensity); - pointValid = true; + setRing(point, chan + 1); + setTimestamp(point, point_time); +// vec.emplace_back(std::move(point)); } - else if (!this->param_.is_dense) + else if (!this->param_.dense_points) { + typename T_PointCloud::PointT point; setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); - pointValid = true; - } - - if (pointValid) - { + setRing(point, chan + 1); setTimestamp(point, point_time); - setRing(point, channel_idx + 1); - vec.emplace_back(std::move(point)); + // vec.emplace_back(std::move(point)); } } } - unsigned int pkt_cnt = RS_SWAP_SHORT(mpkt_ptr->header.pkt_cnt); - - // TODO whatif packet loss or seq unorder - if (pkt_cnt == max_pkt_num_ || pkt_cnt < last_pkt_cnt_) - { - last_pkt_cnt_ = 1; - return RSDecoderResult::FRAME_SPLIT; - } - last_pkt_cnt_ = pkt_cnt; - return RSDecoderResult::DECODE_OK; -} -template -inline RSDecoderResult DecoderRSM1::decodeDifopPkt(const uint8_t* pkt) -{ - RSM1DifopPkt* dpkt_ptr = (RSM1DifopPkt*)pkt; - if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) - { - return RSDecoderResult::WRONG_PKT_HEADER; - } - if (!this->difop_flag_) - { - this->echo_mode_ = this->getEchoMode(LidarType::RSM1, dpkt_ptr->return_mode); - if (this->echo_mode_ == RSEchoMode::ECHO_DUAL) - { - max_pkt_num_ = DUAL_PKT_NUM; - } - this->difop_flag_ = true; - } - return RSDecoderResult::DECODE_OK; + unsigned int pkt_cnt = ntohs(pkt.header.pkt_cnt); + bool toSplit = split_.newPacket(pkt_cnt); } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 2ea746b7..c92802fb 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -36,8 +36,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#if 0 #include +#if 0 #include #endif @@ -63,6 +63,11 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam switch (type) { +#if 0 + case LidarType::RSROCK: + ret_ptr = std::make_shared>(param.decoder_param); + break; +#endif case LidarType::RS16: ret_ptr = std::make_shared>(param, excb); break; @@ -72,25 +77,18 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam case LidarType::RSBP: ret_ptr = std::make_shared>(param, excb); break; + case LidarType::RSHELIOS: + ret_ptr = std::make_shared>(param, excb); + break; case LidarType::RS80: ret_ptr = std::make_shared>(param, excb); break; case LidarType::RS128: ret_ptr = std::make_shared>(param, excb); break; -#if 0 case LidarType::RSM1: - ret_ptr = std::make_shared>(param.decoder_param); - break; -#endif - case LidarType::RSHELIOS: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared>(param, excb); break; -#if 0 - case LidarType::RSROCK: - ret_ptr = std::make_shared>(param.decoder_param); - break; -#endif default: RS_ERROR << "Wrong LiDAR Type. Please check your LiDAR Version! " << RS_REND; exit(-1); From 4a487faade00d4789e0f959879987407b1cd6b5a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 24 Dec 2021 09:09:51 +0800 Subject: [PATCH 111/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 26e062bb..701f6740 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -287,7 +287,7 @@ void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size setIntensity(point, intensity); setRing(point, chan + 1); setTimestamp(point, point_time); -// vec.emplace_back(std::move(point)); + this->point_cloud_->points.emplace_back(point); } else if (!this->param_.dense_points) { @@ -298,7 +298,7 @@ void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size setIntensity(point, 0); setRing(point, chan + 1); setTimestamp(point, point_time); - // vec.emplace_back(std::move(point)); + this->point_cloud_->points.emplace_back(point); } } } From 813edaca3b2a9255f02bcc09c1ec60b014f20bdd Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 24 Dec 2021 10:33:42 +0800 Subject: [PATCH 112/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 69 +++---------------- .../driver/decoder/decoder_RS128.hpp | 5 +- src/rs_driver/driver/decoder/decoder_RS16.hpp | 5 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 5 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 5 +- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 6 +- .../driver/decoder/decoder_RSHELIOS.hpp | 5 +- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 49 ++++--------- .../driver/decoder/split_strategy.hpp | 34 +++++++++ test/decoder_test.cpp | 4 ++ test/split_strategy_test.cpp | 24 +++++++ 11 files changed, 108 insertions(+), 103 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 098922e5..90d3d5fd 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -287,7 +287,7 @@ class Decoder template void decodeDifopCommon(const T_Difop& pkt); - void newBlock(int32_t azimuth); + void splitFrame(); void setPointCloudHeader(std::shared_ptr msg, double chan_ts); RSDecoderConstParam const_param_; // const param of lidar/decoder @@ -423,21 +423,17 @@ void Decoder::regRecvCallback( } template -inline void Decoder::newBlock(int32_t azimuth) +inline void Decoder::splitFrame() { - bool split = this->split_strategy_->newBlock(azimuth); - if (split) + if (point_cloud_->points.size() > 0) { - if (point_cloud_->points.size() > 0) - { - setPointCloudHeader(point_cloud_, prev_chan_ts_); - point_cloud_cb_put_(point_cloud_); - point_cloud_ = point_cloud_cb_get_(); - } - else - { - excb_(Error(ERRCODE_ZEROPOINTS)); - } + setPointCloudHeader(point_cloud_, prev_chan_ts_); + point_cloud_cb_put_(point_cloud_); + point_cloud_ = point_cloud_cb_get_(); + } + else + { + excb_(Error(ERRCODE_ZEROPOINTS)); } } @@ -539,50 +535,5 @@ inline void Decoder::decodeDifopCommon(const T_Difop& pkt) } } -#if 0 -template -inline RSEchoMode Decoder::getEchoMode(const LidarType& type, const uint8_t& return_mode) -{ - switch (type) - { - case LidarType::RS128: - case LidarType::RS80: - case LidarType::RSHELIOS: - switch (return_mode) - { - case 0x00: - case 0x03: - return RSEchoMode::ECHO_DUAL; - default: - return RSEchoMode::ECHO_SINGLE; - } - case LidarType::RS16: - case LidarType::RS32: - case LidarType::RSBP: - switch (return_mode) - { - case 0x00: - return RSEchoMode::ECHO_DUAL; - default: - return RSEchoMode::ECHO_SINGLE; - } - case LidarType::RSM1: - switch (return_mode) - { - case 0x00: - case 0x01: - case 0x02: - case 0x03: - return RSEchoMode::ECHO_DUAL; - default: - return RSEchoMode::ECHO_SINGLE; - } - case LidarType::RSROCK: // TODO - return RSEchoMode::ECHO_SINGLE; - } - return RSEchoMode::ECHO_SINGLE; -} -#endif - } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 08bb5e17..6bda0c55 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -237,7 +237,10 @@ inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packe block_ts += diff.ts(blk); int32_t block_azi_diff = diff.azimuth(blk); - this->newBlock(block_az); + if (this->split_strategy_->newBlock(block_az)) + { + this->splitFrame(); + } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 65ba64fb..1791e055 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -277,7 +277,10 @@ inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet block_ts += diff.ts(blk); int32_t block_azi_diff = diff.azimuth(blk); - this->newBlock(block_az); + if (this->split_strategy_->newBlock(block_az)) + { + this->splitFrame(); + } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index ab2a5920..f79e0341 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -282,7 +282,10 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet block_ts += diff.ts(blk); int32_t block_azi_diff = diff.azimuth(blk); - this->newBlock(block_az); + if (this->split_strategy_->newBlock(block_az)) + { + this->splitFrame(); + } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 6e70d6b4..98ecf9de 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -234,7 +234,10 @@ inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet block_ts += diff.ts(blk); int32_t block_azi_diff = diff.azimuth(blk); - this->newBlock(block_az); + if (this->split_strategy_->newBlock(block_az)) + { + this->splitFrame(); + } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 9c0f33f5..83748eb7 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -229,8 +229,10 @@ inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet block_ts += diff.ts(blk); int32_t block_azi_diff = diff.azimuth(blk); - this->newBlock(block_az); - + if (this->split_strategy_->newBlock(block_az)) + { + this->splitFrame(); + } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 0bfa844e..561a909b 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -237,7 +237,10 @@ inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa block_ts += diff.ts(blk); int32_t block_azi_diff = diff.azimuth(blk); - this->newBlock(block_az); + if (this->split_strategy_->newBlock(block_az)) + { + this->splitFrame(); + } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 701f6740..9bc11193 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -40,8 +40,8 @@ namespace lidar typedef struct { - uint32_t id; - uint16_t pkt_cnt; + uint8_t id[4]; + uint16_t pkt_seq; uint16_t protocol_version; uint8_t return_mode; uint8_t time_mode; @@ -119,7 +119,7 @@ typedef struct uint8_t reserved1[1]; uint8_t frame_rate; RSM1DifopEther ether; - RSM1DifopFov fov_setting; + RSM1DifopFov fov; RSM1DifopVerInfo ver_info; RSSN sn; uint8_t return_mode; @@ -132,34 +132,6 @@ typedef struct #pragma pack(pop) -class Split -{ -public: - - Split(uint16_t* max_seq) - : max_seq_(max_seq), prev_seq_(0) - { - } - - bool newPacket(uint16_t seq) - { - if ((seq == *max_seq_) || (seq < prev_seq_)) - { - prev_seq_ = 1; - return true; - } - else - { - return false; - } - } - -private: - - uint16_t* max_seq_; - uint16_t prev_seq_; -}; - const uint32_t SINGLE_PKT_NUM = 630; const uint32_t DUAL_PKT_NUM = 1260; @@ -181,7 +153,7 @@ class DecoderRSM1 : public Decoder RSEchoMode getEchoMode(uint8_t mode); uint16_t max_seq_; - Split split_; + SplitStrategyBySeq split_; }; template @@ -191,9 +163,9 @@ RSDecoderConstParam DecoderRSM1::getConstParam() { 1210 // msop len , 256 // difop len - , 8 // msop id len + , 4 // msop id len , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0x55, 0xAA, 0x5A, 0xA5} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0x00, 0x00} , 0 @@ -256,7 +228,7 @@ void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size // roll back to first block to approach lidar ts as near as possible. pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); } - + for (size_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSM1Block& block = pkt.blocks[blk]; @@ -303,8 +275,11 @@ void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size } } - unsigned int pkt_cnt = ntohs(pkt.header.pkt_cnt); - bool toSplit = split_.newPacket(pkt_cnt); + uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); + if (split_.newPacket(pkt_seq)) + { + this->splitFrame(); + } } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/split_strategy.hpp b/src/rs_driver/driver/decoder/split_strategy.hpp index dec6c7df..9679fc12 100644 --- a/src/rs_driver/driver/decoder/split_strategy.hpp +++ b/src/rs_driver/driver/decoder/split_strategy.hpp @@ -109,5 +109,39 @@ class SplitStrategyByNum : public SplitStrategy uint16_t blks_; }; +class SplitStrategyBySeq +{ +public: + + SplitStrategyBySeq(uint16_t* max_seq) + : max_seq_(max_seq), prev_seq_(0) + { + } + + bool newPacket(uint16_t seq) + { + if (seq == *max_seq_) + { + prev_seq_ = 0; + return true; + } + else if (seq < prev_seq_) + { + prev_seq_ = seq; + return true; + } + else + { + prev_seq_ = seq; + return false; + } + } + +private: + + uint16_t* max_seq_; + uint16_t prev_seq_; +}; + } // namespace lidar } // namespace robosense diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 45d20bfe..271c6724 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -302,6 +302,7 @@ TEST(TestDecoder, setPointCloudHeader) } std::shared_ptr point_cloud_to_get; + std::shared_ptr getCallback(void) { return point_cloud_to_get; @@ -309,12 +310,14 @@ std::shared_ptr getCallback(void) bool flag_point_cloud = false; std::shared_ptr point_cloud_to_put; + void putCallback(std::shared_ptr pt) { point_cloud_to_put = pt; flag_point_cloud = true; } +#if 0 TEST(TestDecoder, split_by_angle) { RSDecoderConstParam const_param; @@ -435,4 +438,5 @@ TEST(TestDecoder, split_by_custom_blks) ASSERT_EQ(point_cloud_to_put->width, 1); } } +#endif diff --git a/test/split_strategy_test.cpp b/test/split_strategy_test.cpp index a23d3e18..31f1bf4c 100644 --- a/test/split_strategy_test.cpp +++ b/test/split_strategy_test.cpp @@ -65,4 +65,28 @@ TEST(TestSplitStrategyByNum, newBlock) ASSERT_TRUE(sn.newBlock(0)); } +TEST(TestSplitStrategyBySeq, newPacket_max_seq) +{ + uint16_t max_seq = 2; + SplitStrategyBySeq sn(&max_seq); + + // reach max_seq + ASSERT_FALSE(sn.newPacket(1)); + ASSERT_TRUE(sn.newPacket(2)); + + // reach max_seq again + ASSERT_FALSE(sn.newPacket(1)); + ASSERT_TRUE(sn.newPacket(2)); +} + +TEST(TestSplitStrategyBySeq, newPacket_rewind) +{ + uint16_t max_seq = 3; + SplitStrategyBySeq sn(&max_seq); + + // rewind + ASSERT_FALSE(sn.newPacket(1)); + ASSERT_FALSE(sn.newPacket(2)); + ASSERT_TRUE(sn.newPacket(1)); +} From f3faccf202325c146f669a5388dd212cd5a78e1c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 24 Dec 2021 16:02:57 +0800 Subject: [PATCH 113/379] refac: use static const param --- .../driver/decoder/decoder_RS128.hpp | 23 +++++++++++-------- src/rs_driver/driver/decoder/decoder_RS16.hpp | 14 +++++++---- src/rs_driver/driver/decoder/decoder_RS32.hpp | 23 +++++++++++-------- src/rs_driver/driver/decoder/decoder_RS80.hpp | 13 +++++++---- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 12 ++++++---- .../driver/decoder/decoder_RSHELIOS.hpp | 13 +++++++---- 6 files changed, 59 insertions(+), 39 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 6bda0c55..f4824972 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -92,26 +92,26 @@ class DecoderRS128 : public Decoder protected: #endif - static RSDecoderConstParam getConstParam(); + static RSDecoderConstParam& initConstParam(RSDecoderConstParam& param); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + + static RSDecoderConstParam rs_const_param_; }; template -RSDecoderConstParam DecoderRS128::getConstParam() +RSDecoderConstParam DecoderRS128::rs_const_param_ = { - RSDecoderConstParam param = - { - 1248 // msop len + 1248 // msop len , 1248 // difop len , 4 // msop id len , 8 // difop id len , {0x55, 0xAA, 0x05, 0x5A} // msop id - , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0xFE} // block id - , 3 // blocks per packet + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFE} // block id + , 3 // blocks per packet , 128 // channels per block , 1.0f // distance min , 250.0f // distance max @@ -122,8 +122,11 @@ RSDecoderConstParam DecoderRS128::getConstParam() , 0.03615f // RX , -0.017f // RY , 0.0f // RZ - }; +}; +template +RSDecoderConstParam& DecoderRS128::initConstParam(RSDecoderConstParam& param) +{ float blk_ts = 55.55f; float firing_tss[] = { @@ -173,7 +176,7 @@ RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) template inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, getConstParam()) + : Decoder(param, excb, initConstParam(rs_const_param_)) { } diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 1791e055..6e050d7a 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -143,17 +143,18 @@ public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); protected: #endif - static RSDecoderConstParam getConstParam(); + static RSDecoderConstParam& initConstParam(RSDecoderConstParam& param); + //static RSDecoderConstParam getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + + static RSDecoderConstParam rs_const_param_; }; template -RSDecoderConstParam DecoderRS16::getConstParam() -{ - RSDecoderConstParam param = +RSDecoderConstParam DecoderRS16::rs_const_param_ = { 1248 // msop len , 1248 // difop len @@ -175,6 +176,9 @@ RSDecoderConstParam DecoderRS16::getConstParam() , 0.0f // RZ }; +template +RSDecoderConstParam& DecoderRS16::initConstParam(RSDecoderConstParam& param) +{ float blk_ts = 55.5f * 2; float firing_tss[] = { @@ -211,7 +215,7 @@ RSEchoMode DecoderRS16::getEchoMode(uint8_t mode) template inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, getConstParam()) + : Decoder(param, excb, initConstParam(rs_const_param_)) { } diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index f79e0341..aa820520 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -148,26 +148,26 @@ class DecoderRS32 : public Decoder protected: #endif - static RSDecoderConstParam getConstParam(); + static RSDecoderConstParam& initConstParam(RSDecoderConstParam& param); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + + static RSDecoderConstParam rs_const_param_; }; template -RSDecoderConstParam DecoderRS32::getConstParam() +RSDecoderConstParam DecoderRS32::rs_const_param_ = { - RSDecoderConstParam param = - { - 1248 // msop len + 1248 // msop len , 1248 // difop len , 8 // msop id len , 8 // difop id len , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id - , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0xFF, 0xEE} // block id - , 12 // blocks per packet + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 12 // blocks per packet , 32 // channels per block , 0.4f // distance min , 200.0f // distance max @@ -178,8 +178,11 @@ RSDecoderConstParam DecoderRS32::getConstParam() , 0.03997f // RX , -0.01087f // RY , 0.0f // RZ - }; +}; +template +RSDecoderConstParam& DecoderRS32::initConstParam(RSDecoderConstParam& param) +{ float blk_ts = 55.52f; float firing_tss[] = { @@ -216,7 +219,7 @@ RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) template inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, getConstParam()) + : Decoder(param, excb, initConstParam(rs_const_param_)) { } diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 98ecf9de..44a02a37 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -95,17 +95,18 @@ class DecoderRS80 : public Decoder protected: #endif + static RSDecoderConstParam& initConstParam(RSDecoderConstParam& param); static RSDecoderConstParam getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + + static RSDecoderConstParam rs_const_param_; }; template -RSDecoderConstParam DecoderRS80::getConstParam() -{ - RSDecoderConstParam param = +RSDecoderConstParam DecoderRS80::rs_const_param_ = { 1248 // msop len , 1248 // difop len @@ -127,6 +128,10 @@ RSDecoderConstParam DecoderRS80::getConstParam() , 0.0f // RZ }; +template +RSDecoderConstParam& DecoderRS80::initConstParam(RSDecoderConstParam& param) +{ + float blk_ts = 55.552f; float firing_tss[] = { @@ -170,7 +175,7 @@ RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) template inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, getConstParam()) + : Decoder(param, excb, initConstParam(rs_const_param_)) { } diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 83748eb7..132dc4e6 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -96,18 +96,17 @@ class DecoderRSBP : public Decoder protected: #endif - static RSDecoderConstParam getConstParam(); + static RSDecoderConstParam& initConstParam(RSDecoderConstParam& param); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + static RSDecoderConstParam rs_const_param_; }; template -RSDecoderConstParam DecoderRSBP::getConstParam() -{ - RSDecoderConstParam param = +RSDecoderConstParam DecoderRSBP::rs_const_param_ = { 1248 // msop len , 1248 // difop len @@ -129,6 +128,9 @@ RSDecoderConstParam DecoderRSBP::getConstParam() , 0.09427f // RZ }; +template +RSDecoderConstParam& DecoderRSBP::initConstParam(RSDecoderConstParam& param) +{ float blk_ts = 55.52f; float firing_tss[] = { @@ -165,7 +167,7 @@ RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) template inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, getConstParam()) + : Decoder(param, excb, initConstParam(rs_const_param_)) { } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 561a909b..cf6aaacc 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -104,17 +104,17 @@ class DecoderRSHELIOS : public Decoder protected: #endif - static RSDecoderConstParam getConstParam(); + static RSDecoderConstParam& initConstParam(RSDecoderConstParam& param); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + + static RSDecoderConstParam rs_const_param_; }; template -RSDecoderConstParam DecoderRSHELIOS::getConstParam() -{ - RSDecoderConstParam param = +RSDecoderConstParam DecoderRSHELIOS::rs_const_param_ = { 1248 // msop len , 1248 // difop len @@ -136,6 +136,9 @@ RSDecoderConstParam DecoderRSHELIOS::getConstParam() , 0.0f // RZ }; +template +RSDecoderConstParam& DecoderRSHELIOS::initConstParam(RSDecoderConstParam& param) +{ float blk_ts = 55.56f; float firing_tss[] = { @@ -173,7 +176,7 @@ RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) template inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, getConstParam()) + : Decoder(param, excb, initConstParam(rs_const_param_)) { } From 6482add740ed84ae59b65e4b451892f182e18989 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Dec 2021 11:18:00 +0800 Subject: [PATCH 114/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 143 +------------ .../driver/decoder/decoder_RS128.hpp | 24 +-- src/rs_driver/driver/decoder/decoder_RS16.hpp | 29 +-- src/rs_driver/driver/decoder/decoder_RS32.hpp | 26 +-- src/rs_driver/driver/decoder/decoder_RS80.hpp | 24 +-- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 27 +-- .../driver/decoder/decoder_RSHELIOS.hpp | 24 +-- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 27 +-- src/rs_driver/driver/decoder/decoder_mech.hpp | 199 ++++++++++++++++++ test/decoder_rsbp_test.cpp | 2 + test/decoder_test.cpp | 53 +++-- test/dual_return_block_diff_test.cpp | 6 +- test/single_return_block_diff_test.cpp | 6 +- 13 files changed, 334 insertions(+), 256 deletions(-) create mode 100644 src/rs_driver/driver/decoder/decoder_mech.hpp diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 90d3d5fd..e50a86df 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -56,9 +56,6 @@ namespace robosense namespace lidar { -// -// msop & difop -// #pragma pack(push, 1) typedef struct { @@ -202,6 +199,7 @@ typedef struct uint8_t sync_sts; RSTimestampUTC timestamp; } RSTimeInfo; + #pragma pack(pop) // Echo mode @@ -212,7 +210,7 @@ enum RSEchoMode }; // decoder const param -typedef struct +struct RSDecoderConstParam { uint16_t MSOP_LEN; uint16_t DIFOP_LEN; @@ -227,39 +225,19 @@ typedef struct // duration uint16_t BLOCKS_PER_PKT; uint16_t CHANNELS_PER_BLOCK; - //uint16_t LASER_NUM; // diff from CHANNELS_PER_BLOCK ? // distance resolution float DISTANCE_MIN; float DISTANCE_MAX; float DISTANCE_RES; float TEMPERATURE_RES; - - // lens center - float RX; - float RY; - float RZ; - - // firing_ts / block_ts, chan_ts - double BLOCK_DURATION; - double CHAN_TSS[128]; - float CHAN_AZIS[128]; - -} RSDecoderConstParam; - -#if 0 -const size_t MECH_PKT_LEN = 1248; -const size_t MEMS_MSOP_LEN = 1210; -const size_t MEMS_DIFOP_LEN = 256; -const size_t ROCK_MSOP_LEN = 1236; -#endif +}; template class Decoder { public: - constexpr static int32_t RS_ONE_ROUND = 36000; constexpr static uint16_t PROTOCOL_VER_0 = 0x00; virtual void decodeDifopPkt(const uint8_t* pkt, size_t size) = 0; @@ -278,15 +256,11 @@ class Decoder float getTemperature(); double getPacketDuration(); - void print(); #ifndef UNIT_TEST protected: #endif - template - void decodeDifopCommon(const T_Difop& pkt); - void splitFrame(); void setPointCloudHeader(std::shared_ptr msg, double chan_ts); @@ -299,27 +273,14 @@ class Decoder #define SIN(angle) this->trigon_.sin(angle) #define COS(angle) this->trigon_.cos(angle) - ChanAngles chan_angles_; // vert_angles/horiz_angles adjustment DistanceSection distance_section_; // valid distance section - AzimuthSection scan_section_; // valid azimuth section - std::shared_ptr split_strategy_; // split strategy - uint16_t blks_per_frame_; // blocks per frame/round - uint16_t split_blks_per_frame_; // blocks in msop pkt per frame/round. - // dependent on return mode. - uint16_t block_azi_diff_; // azimuth difference between adjacent blocks. - float fov_blind_ts_diff_; // timestamp difference across blind section(defined by fov) - - uint16_t rps_; // rounds per second RSEchoMode echo_mode_; // echo mode (defined by return mode) float temperature_; // lidar temperature bool angles_ready_; // is vert_angles/horiz_angles ready from csv file/difop packet? double prev_chan_ts_; // previous channel/point timestamp - int lidar_alph0_; // lens center related - float lidar_Rxy_; // lens center related - std::function(void)> point_cloud_cb_get_; std::function)> point_cloud_cb_put_; std::shared_ptr point_cloud_; // curernt point cloud @@ -333,70 +294,15 @@ inline Decoder::Decoder(const RSDecoderParam& param, : const_param_(const_param) , param_(param) , excb_(excb) - , height_(const_param.CHANNELS_PER_BLOCK) - , chan_angles_(const_param.CHANNELS_PER_BLOCK) + //, height_(const_param.CHANNELS_PER_BLOCK) , distance_section_(const_param.DISTANCE_MIN, const_param.DISTANCE_MAX, param.min_distance, param.max_distance) - , scan_section_(param.start_angle * 100, param.end_angle * 100) - , blks_per_frame_(1/(10*const_param.BLOCK_DURATION)) - , split_blks_per_frame_(blks_per_frame_) - , block_azi_diff_(20) - , fov_blind_ts_diff_(0) - , rps_(10) , echo_mode_(ECHO_SINGLE) , temperature_(0.0) , angles_ready_(false) , prev_chan_ts_(0.0) , point_cloud_seq_(0) { - switch (param_.split_frame_mode) - { - case SplitFrameMode::SPLIT_BY_FIXED_BLKS: - split_strategy_ = std::make_shared(&split_blks_per_frame_); - break; - - case SplitFrameMode::SPLIT_BY_CUSTOM_BLKS: - split_strategy_ = std::make_shared(¶m_.num_blks_split); - break; - - case SplitFrameMode::SPLIT_BY_ANGLE: - default: - uint16_t angle = (uint16_t)(param_.split_angle * 100); - split_strategy_ = std::make_shared(angle); - break; - } - - // calulate lidar_alph0 and lidar_Rxy - lidar_alph0_ = std::atan2(const_param_.RY, const_param_.RX) * 180 / M_PI * 100; - lidar_Rxy_ = std::sqrt(const_param_.RX * const_param_.RX + const_param_.RY * const_param_.RY); - - if (param.config_from_file) - { - if (param_.wait_for_difop) - { - RS_WARNING << "When config_from_file is true, wait_for_difop cannot be true." - << " Reset it to be false." << RS_REND; - } - - int ret = chan_angles_.loadFromFile(param.angle_path); - this->angles_ready_ = (ret == 0); - } -} - -template -void Decoder::print() -{ - std::cout << "-----------------------------------------" << std::endl - << "rps:\t\t\t" << this->rps_ << std::endl - << "echo_mode:\t\t" << this->echo_mode_ << std::endl - << "blks_per_frame:\t\t" << this->blks_per_frame_ << std::endl - << "split_blks_per_frame:\t" << this->split_blks_per_frame_ << std::endl - << "block_azi_diff:\t\t" << this->block_azi_diff_ << std::endl - << "fov_blind_ts_diff:\t" << this->fov_blind_ts_diff_ << std::endl - << "angle_from_file:\t" << this->param_.config_from_file << std::endl - << "angles_ready:\t\t" << this->angles_ready_ << std::endl; - - this->chan_angles_.print(); } template @@ -408,7 +314,8 @@ float Decoder::getTemperature() template double Decoder::getPacketDuration() { - return this->const_param_.BLOCK_DURATION * const_param_.BLOCKS_PER_PKT; + return 0; + //return this->const_param_.BLOCK_DURATION * const_param_.BLOCKS_PER_PKT; } template @@ -497,43 +404,5 @@ void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) decodeDifopPkt(pkt, size); } -template -template -inline void Decoder::decodeDifopCommon(const T_Difop& pkt) -{ - // rounds per second - this->rps_ = ntohs(pkt.rpm) / 60; - if (this->rps_ == 0) - { - RS_WARNING << "LiDAR RPM is 0. Use default value 600." << RS_REND; - this->rps_ = 10; - } - - // blocks per frame - this->blks_per_frame_ = 1 / (this->rps_ * this->const_param_.BLOCK_DURATION); - - // block diff of azimuth - this->block_azi_diff_ = - std::round(RS_ONE_ROUND * this->rps_ * this->const_param_.BLOCK_DURATION); - - // fov related - uint16_t fov_start_angle = ntohs(pkt.fov.start_angle); - uint16_t fov_end_angle = ntohs(pkt.fov.end_angle); - uint16_t fov_range = (fov_start_angle < fov_end_angle) ? - (fov_end_angle - fov_start_angle) : (fov_end_angle + RS_ONE_ROUND - fov_start_angle); - uint16_t fov_blind_range = RS_ONE_ROUND - fov_range; - - // fov blind diff of timestamp - this->fov_blind_ts_diff_ = - (float)fov_blind_range / ((float)RS_ONE_ROUND * (float)this->rps_); - - if (!this->param_.config_from_file && !this->angles_ready_) - { - int ret = this->chan_angles_.loadFromDifop(pkt.vert_angle_cali, pkt.horiz_angle_cali, - this->const_param_.CHANNELS_PER_BLOCK); - this->angles_ready_ = (ret == 0); - } -} - } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index f4824972..e0ded033 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -78,7 +78,7 @@ typedef struct #pragma pack(pop) template -class DecoderRS128 : public Decoder +class DecoderRS128 : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); @@ -92,17 +92,17 @@ class DecoderRS128 : public Decoder protected: #endif - static RSDecoderConstParam& initConstParam(RSDecoderConstParam& param); + static RSDecoderMechConstParam& initConstParam(RSDecoderMechConstParam& param); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - static RSDecoderConstParam rs_const_param_; + static RSDecoderMechConstParam rs_const_param_; }; template -RSDecoderConstParam DecoderRS128::rs_const_param_ = +RSDecoderMechConstParam DecoderRS128::rs_const_param_ = { 1248 // msop len , 1248 // difop len @@ -125,7 +125,7 @@ RSDecoderConstParam DecoderRS128::rs_const_param_ = }; template -RSDecoderConstParam& DecoderRS128::initConstParam(RSDecoderConstParam& param) +RSDecoderMechConstParam& DecoderRS128::initConstParam(RSDecoderMechConstParam& param) { float blk_ts = 55.55f; float firing_tss[] = @@ -176,7 +176,7 @@ RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) template inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, initConstParam(rs_const_param_)) + : DecoderMech(param, excb, initConstParam(rs_const_param_)) { } @@ -223,7 +223,7 @@ inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packe pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) @@ -249,9 +249,9 @@ inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packe { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + - (int32_t)((float)block_azi_diff * this->const_param_.CHAN_AZIS[chan]); + (int32_t)((float)block_azi_diff * this->mech_const_param_.CHAN_AZIS[chan]); int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -261,9 +261,9 @@ inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packe if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->const_param_.RZ; + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; typename T_PointCloud::PointT point; setX(point, x); diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 6e050d7a..ab96e2ef 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -30,11 +30,13 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include +#include + namespace robosense { namespace lidar { + #pragma pack(push, 1) typedef struct { @@ -130,7 +132,7 @@ inline void RS16DifopPkt2Adapter (const uint8_t* difop) } template -class DecoderRS16 : public Decoder +class DecoderRS16 : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); @@ -143,18 +145,17 @@ public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); protected: #endif - static RSDecoderConstParam& initConstParam(RSDecoderConstParam& param); - //static RSDecoderConstParam getConstParam(); + static RSDecoderMechConstParam& initConstParam(RSDecoderMechConstParam& param); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - static RSDecoderConstParam rs_const_param_; + static RSDecoderMechConstParam rs_const_param_; }; template -RSDecoderConstParam DecoderRS16::rs_const_param_ = +RSDecoderMechConstParam DecoderRS16::rs_const_param_ = { 1248 // msop len , 1248 // difop len @@ -177,7 +178,7 @@ RSDecoderConstParam DecoderRS16::rs_const_param_ = }; template -RSDecoderConstParam& DecoderRS16::initConstParam(RSDecoderConstParam& param) +RSDecoderMechConstParam& DecoderRS16::initConstParam(RSDecoderMechConstParam& param) { float blk_ts = 55.5f * 2; float firing_tss[] = @@ -215,7 +216,7 @@ RSEchoMode DecoderRS16::getEchoMode(uint8_t mode) template inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, initConstParam(rs_const_param_)) + : DecoderMech(param, excb, initConstParam(rs_const_param_)) { } @@ -264,7 +265,7 @@ inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) @@ -290,9 +291,9 @@ inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + - (int32_t)((float)block_azi_diff * this->const_param_.CHAN_AZIS[chan]); + (int32_t)((float)block_azi_diff * this->mech_const_param_.CHAN_AZIS[chan]); int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -302,9 +303,9 @@ inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->const_param_.RZ; + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; typename T_PointCloud::PointT point; setX(point, x); diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index aa820520..f759132b 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -31,7 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include +#include #include namespace robosense @@ -133,7 +133,7 @@ inline void RS32DifopPkt2Adapter (const uint8_t* difop) } template -class DecoderRS32 : public Decoder +class DecoderRS32 : public DecoderMech { public: @@ -148,17 +148,17 @@ class DecoderRS32 : public Decoder protected: #endif - static RSDecoderConstParam& initConstParam(RSDecoderConstParam& param); + static RSDecoderMechConstParam& initConstParam(RSDecoderMechConstParam& param); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - static RSDecoderConstParam rs_const_param_; + static RSDecoderMechConstParam rs_const_param_; }; template -RSDecoderConstParam DecoderRS32::rs_const_param_ = +RSDecoderMechConstParam DecoderRS32::rs_const_param_ = { 1248 // msop len , 1248 // difop len @@ -181,7 +181,7 @@ RSDecoderConstParam DecoderRS32::rs_const_param_ = }; template -RSDecoderConstParam& DecoderRS32::initConstParam(RSDecoderConstParam& param) +RSDecoderMechConstParam& DecoderRS32::initConstParam(RSDecoderMechConstParam& param) { float blk_ts = 55.52f; float firing_tss[] = @@ -219,7 +219,7 @@ RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) template inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, initConstParam(rs_const_param_)) + : DecoderMech(param, excb, initConstParam(rs_const_param_)) { } @@ -268,7 +268,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) @@ -294,9 +294,9 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + - (int32_t)((float)block_azi_diff * this->const_param_.CHAN_AZIS[chan]); + (int32_t)((float)block_azi_diff * this->mech_const_param_.CHAN_AZIS[chan]); int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -306,9 +306,9 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->const_param_.RZ; + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; typename T_PointCloud::PointT point; setX(point, x); diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 44a02a37..3c11fa34 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -81,7 +81,7 @@ typedef struct #pragma pack(pop) template -class DecoderRS80 : public Decoder +class DecoderRS80 : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); @@ -95,18 +95,18 @@ class DecoderRS80 : public Decoder protected: #endif - static RSDecoderConstParam& initConstParam(RSDecoderConstParam& param); + static RSDecoderMechConstParam& initConstParam(RSDecoderMechConstParam& param); static RSDecoderConstParam getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - static RSDecoderConstParam rs_const_param_; + static RSDecoderMechConstParam rs_const_param_; }; template -RSDecoderConstParam DecoderRS80::rs_const_param_ = +RSDecoderMechConstParam DecoderRS80::rs_const_param_ = { 1248 // msop len , 1248 // difop len @@ -129,7 +129,7 @@ RSDecoderConstParam DecoderRS80::rs_const_param_ = }; template -RSDecoderConstParam& DecoderRS80::initConstParam(RSDecoderConstParam& param) +RSDecoderMechConstParam& DecoderRS80::initConstParam(RSDecoderMechConstParam& param) { float blk_ts = 55.552f; @@ -175,7 +175,7 @@ RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) template inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, initConstParam(rs_const_param_)) + : DecoderMech(param, excb, initConstParam(rs_const_param_)) { } @@ -222,7 +222,7 @@ inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) @@ -248,9 +248,9 @@ inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + - (int32_t)((float)block_azi_diff * this->const_param_.CHAN_AZIS[chan]); + (int32_t)((float)block_azi_diff * this->mech_const_param_.CHAN_AZIS[chan]); int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -260,9 +260,9 @@ inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->const_param_.RZ; + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; typename T_PointCloud::PointT point; setX(point, x); diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 132dc4e6..b4253268 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -30,7 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include +#include namespace robosense { @@ -81,7 +81,7 @@ typedef struct #pragma pack(pop) template -class DecoderRSBP : public Decoder +class DecoderRSBP : public DecoderMech { public: @@ -96,17 +96,17 @@ class DecoderRSBP : public Decoder protected: #endif - static RSDecoderConstParam& initConstParam(RSDecoderConstParam& param); + static RSDecoderMechConstParam& initConstParam(RSDecoderMechConstParam& param); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - static RSDecoderConstParam rs_const_param_; + static RSDecoderMechConstParam rs_const_param_; }; template -RSDecoderConstParam DecoderRSBP::rs_const_param_ = +RSDecoderMechConstParam DecoderRSBP::rs_const_param_ = { 1248 // msop len , 1248 // difop len @@ -129,7 +129,7 @@ RSDecoderConstParam DecoderRSBP::rs_const_param_ = }; template -RSDecoderConstParam& DecoderRSBP::initConstParam(RSDecoderConstParam& param) +RSDecoderMechConstParam& DecoderRSBP::initConstParam(RSDecoderMechConstParam& param) { float blk_ts = 55.52f; float firing_tss[] = @@ -167,7 +167,7 @@ RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) template inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, initConstParam(rs_const_param_)) + : DecoderMech(param, excb, initConstParam(rs_const_param_)) { } @@ -214,7 +214,7 @@ inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) @@ -240,9 +240,9 @@ inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + - (int32_t)((float)block_azi_diff * this->const_param_.CHAN_AZIS[chan]); + (int32_t)((float)block_azi_diff * this->mech_const_param_.CHAN_AZIS[chan]); int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -252,9 +252,10 @@ inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->const_param_.RZ; + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + typename T_PointCloud::PointT point; setX(point, x); setY(point, y); diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index cf6aaacc..21ba4e87 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -90,7 +90,7 @@ typedef struct #pragma pack(pop) template -class DecoderRSHELIOS : public Decoder +class DecoderRSHELIOS : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); @@ -104,17 +104,17 @@ class DecoderRSHELIOS : public Decoder protected: #endif - static RSDecoderConstParam& initConstParam(RSDecoderConstParam& param); + static RSDecoderMechConstParam& initConstParam(RSDecoderMechConstParam& param); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - static RSDecoderConstParam rs_const_param_; + static RSDecoderMechConstParam rs_const_param_; }; template -RSDecoderConstParam DecoderRSHELIOS::rs_const_param_ = +RSDecoderMechConstParam DecoderRSHELIOS::rs_const_param_ = { 1248 // msop len , 1248 // difop len @@ -137,7 +137,7 @@ RSDecoderConstParam DecoderRSHELIOS::rs_const_param_ = }; template -RSDecoderConstParam& DecoderRSHELIOS::initConstParam(RSDecoderConstParam& param) +RSDecoderMechConstParam& DecoderRSHELIOS::initConstParam(RSDecoderMechConstParam& param) { float blk_ts = 55.56f; float firing_tss[] = @@ -176,7 +176,7 @@ RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) template inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, initConstParam(rs_const_param_)) + : DecoderMech(param, excb, initConstParam(rs_const_param_)) { } @@ -223,7 +223,7 @@ inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->const_param_.BLOCK_DURATION); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) @@ -249,9 +249,9 @@ inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + this->const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + - (int32_t)((float)block_azi_diff * this->const_param_.CHAN_AZIS[chan]); + (int32_t)((float)block_azi_diff * this->mech_const_param_.CHAN_AZIS[chan]); int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -261,9 +261,9 @@ inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->const_param_.RZ; + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; typename T_PointCloud::PointT point; setX(point, x); diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 9bc11193..99256f8a 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -149,43 +149,38 @@ class DecoderRSM1 : public Decoder private: - RSDecoderConstParam getConstParam(); RSEchoMode getEchoMode(uint8_t mode); + static RSDecoderConstParam rs_const_param_; + uint16_t max_seq_; SplitStrategyBySeq split_; }; template -RSDecoderConstParam DecoderRSM1::getConstParam() +RSDecoderConstParam DecoderRSM1::rs_const_param_ = { - RSDecoderConstParam param = - { - 1210 // msop len + 1210 // msop len , 256 // difop len , 4 // msop id len , 8 // difop id len , {0x55, 0xAA, 0x5A, 0xA5} // msop id - , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0x00, 0x00} - , 0 - , 0 - , 0.2f // distance min + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0x00, 0x00} + , 0 // blocks per packet + , 0 // channels per block + , 0.2f // distance min , 200.0f // distance max , 0.005f // distance resolution - }; - - return param; -} +}; template inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, getConstParam()) + : Decoder(param, excb, rs_const_param_) , max_seq_(SINGLE_PKT_NUM) , split_(&max_seq_) { -// this->time_duration_between_blocks_ = 5 * 1e-6; } template diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp new file mode 100644 index 00000000..75bffa16 --- /dev/null +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -0,0 +1,199 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include + +namespace robosense +{ +namespace lidar +{ + +struct RSDecoderMechConstParam +{ + RSDecoderConstParam base; + + // lens center + float RX; + float RY; + float RZ; + + // firing_ts / block_ts, chan_ts + double BLOCK_DURATION; + double CHAN_TSS[128]; + float CHAN_AZIS[128]; +}; + +template +class DecoderMech : public Decoder +{ +public: + + constexpr static int32_t RS_ONE_ROUND = 36000; + + virtual ~DecoderMech() = default; + + explicit DecoderMech(const RSDecoderParam& param, + const std::function& excb, + const RSDecoderMechConstParam& const_param); + + void print(); + +#ifndef UNIT_TEST +protected: +#endif + + template + void decodeDifopCommon(const T_Difop& pkt); + + RSDecoderMechConstParam mech_const_param_; // const param of lidar/decoder + ChanAngles chan_angles_; // vert_angles/horiz_angles adjustment + AzimuthSection scan_section_; // valid azimuth section + std::shared_ptr split_strategy_; // split strategy + + uint16_t rps_; // rounds per second + uint16_t blks_per_frame_; // blocks per frame/round + uint16_t split_blks_per_frame_; // blocks in msop pkt per frame/round. + uint16_t block_azi_diff_; // azimuth difference between adjacent blocks. + float fov_blind_ts_diff_; // timestamp difference across blind section(defined by fov) + + int lidar_alph0_; // lens center related + float lidar_Rxy_; // lens center related +}; + +template +inline DecoderMech::DecoderMech(const RSDecoderParam& param, + const std::function& excb, + const RSDecoderMechConstParam& const_param) + : Decoder(param, excb, const_param.base) + , mech_const_param_(const_param) + , chan_angles_(this->const_param_.CHANNELS_PER_BLOCK) + , scan_section_(this->param_.start_angle * 100, this->param_.end_angle * 100) + , rps_(10) + , blks_per_frame_(1/(10*this->mech_const_param_.BLOCK_DURATION)) + , split_blks_per_frame_(blks_per_frame_) + , block_azi_diff_(20) + , fov_blind_ts_diff_(0) +{ + switch (this->param_.split_frame_mode) + { + case SplitFrameMode::SPLIT_BY_FIXED_BLKS: + split_strategy_ = std::make_shared(&this->split_blks_per_frame_); + break; + + case SplitFrameMode::SPLIT_BY_CUSTOM_BLKS: + split_strategy_ = std::make_shared(&this->param_.num_blks_split); + break; + + case SplitFrameMode::SPLIT_BY_ANGLE: + default: + uint16_t angle = (uint16_t)(this->param_.split_angle * 100); + split_strategy_ = std::make_shared(angle); + break; + } + + // calulate lidar_alph0 and lidar_Rxy + lidar_alph0_ = std::atan2(mech_const_param_.RY, mech_const_param_.RX) * 180 / M_PI * 100; + lidar_Rxy_ = std::sqrt(mech_const_param_.RX * mech_const_param_.RX + + mech_const_param_.RY * mech_const_param_.RY); + + if (this->param_.config_from_file) + { + int ret = chan_angles_.loadFromFile(this->param_.angle_path); + this->angles_ready_ = (ret == 0); + + if (this->param_.wait_for_difop) + { + this->param_.wait_for_difop = false; + + RS_WARNING << "When config_from_file is true, wait_for_difop cannot be true." + << " Reset it to be false." << RS_REND; + } + } +} + +template +void DecoderMech::print() +{ + std::cout << "-----------------------------------------" << std::endl + << "rps:\t\t\t" << this->rps_ << std::endl + << "echo_mode:\t\t" << this->echo_mode_ << std::endl + << "blks_per_frame:\t\t" << this->blks_per_frame_ << std::endl + << "split_blks_per_frame:\t" << this->split_blks_per_frame_ << std::endl + << "block_azi_diff:\t\t" << this->block_azi_diff_ << std::endl + << "fov_blind_ts_diff:\t" << this->fov_blind_ts_diff_ << std::endl + << "angle_from_file:\t" << this->param_.config_from_file << std::endl + << "angles_ready:\t\t" << this->angles_ready_ << std::endl; + + this->chan_angles_.print(); +} + +template +template +inline void DecoderMech::decodeDifopCommon(const T_Difop& pkt) +{ + // rounds per second + this->rps_ = ntohs(pkt.rpm) / 60; + if (this->rps_ == 0) + { + RS_WARNING << "LiDAR RPM is 0. Use default value 600." << RS_REND; + this->rps_ = 10; + } + + // blocks per frame + this->blks_per_frame_ = 1 / (this->rps_ * this->mech_const_param_.BLOCK_DURATION); + + // block diff of azimuth + this->block_azi_diff_ = + std::round(RS_ONE_ROUND * this->rps_ * this->mech_const_param_.BLOCK_DURATION); + + // fov related + uint16_t fov_start_angle = ntohs(pkt.fov.start_angle); + uint16_t fov_end_angle = ntohs(pkt.fov.end_angle); + uint16_t fov_range = (fov_start_angle < fov_end_angle) ? + (fov_end_angle - fov_start_angle) : (fov_end_angle + RS_ONE_ROUND - fov_start_angle); + uint16_t fov_blind_range = RS_ONE_ROUND - fov_range; + + // fov blind diff of timestamp + this->fov_blind_ts_diff_ = + (float)fov_blind_range / ((float)RS_ONE_ROUND * (float)this->rps_); + + if (!this->param_.config_from_file && !this->angles_ready_) + { + int ret = this->chan_angles_.loadFromDifop(pkt.vert_angle_cali, pkt.horiz_angle_cali, + this->const_param_.CHANNELS_PER_BLOCK); + this->angles_ready_ = (ret == 0); + } +} + +} // namespace lidar +} // namespace robosense diff --git a/test/decoder_rsbp_test.cpp b/test/decoder_rsbp_test.cpp index 96535d1c..54b929fa 100644 --- a/test/decoder_rsbp_test.cpp +++ b/test/decoder_rsbp_test.cpp @@ -28,6 +28,7 @@ TEST(TestDecoderRSBP, decodeDifopPkt) // const_param RSDecoderParam param; DecoderRSBP decoder(param, errCallback); + ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.split_blks_per_frame_, 1801); @@ -145,6 +146,7 @@ TEST(TestDecoderRSBP, decodeMsopPkt) // dense_points = false, use_lidar_clock = true RSDecoderParam param; DecoderRSBP decoder(param, errCallback); + ASSERT_EQ(decoder.chan_angles_.user_chans_.size(), 32); decoder.chan_angles_.user_chans_[0] = 2; decoder.chan_angles_.user_chans_[1] = 1; diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 271c6724..c34d1dfa 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -2,7 +2,7 @@ #include #include "rs_driver/msg/point_cloud_msg.h" -#include +#include #include using namespace robosense::lidar; @@ -27,13 +27,13 @@ struct MyDifopPkt #pragma pack(pop) template -class MyDecoder : public Decoder +class MyDecoder : public DecoderMech { public: MyDecoder(const RSDecoderParam& param, const std::function& excb, - const RSDecoderConstParam& const_param) - : Decoder(param, excb, const_param) + const RSDecoderMechConstParam& const_param) + : DecoderMech(param, excb, const_param) { } @@ -58,31 +58,36 @@ static void errCallback(const Error& err) TEST(TestDecoder, angles_from_file) { - RSDecoderConstParam const_param; - const_param.CHANNELS_PER_BLOCK = 4; + RSDecoderMechConstParam const_param; + const_param.base.CHANNELS_PER_BLOCK = 4; + RSDecoderParam param; param.config_from_file = true; param.angle_path = "../rs_driver/test/res/angle.csv"; + errCode = ERRCODE_SUCCESS; MyDecoder decoder(param, errCallback, const_param); ASSERT_EQ(errCode, ERRCODE_SUCCESS); + ASSERT_TRUE(decoder.angles_ready_); } TEST(TestDecoder, angles_from_file_fail) { - RSDecoderConstParam const_param; - const_param.CHANNELS_PER_BLOCK = 4; + RSDecoderMechConstParam const_param; + const_param.base.CHANNELS_PER_BLOCK = 4; + RSDecoderParam param; param.config_from_file = true; param.angle_path = "../rs_driver/test/res/non_exist.csv"; + MyDecoder decoder(param, errCallback, const_param); ASSERT_FALSE(decoder.angles_ready_); } TEST(TestDecoder, processDifopPkt_fail) { - RSDecoderConstParam const_param = + RSDecoderMechConstParam const_param = { sizeof(MyMsopPkt) // msop len , sizeof(MyDifopPkt) // difop len @@ -109,7 +114,7 @@ TEST(TestDecoder, processDifopPkt_fail) TEST(TestDecoder, processDifopPkt) { - RSDecoderConstParam const_param = + RSDecoderMechConstParam const_param = { sizeof(MyMsopPkt) // msop len , sizeof(MyDifopPkt) // difop len @@ -189,7 +194,7 @@ TEST(TestDecoder, processDifopPkt) TEST(TestDecoder, processDifopPkt_invalid_rpm) { - RSDecoderConstParam const_param = + RSDecoderMechConstParam const_param = { sizeof(MyMsopPkt) // msop len , sizeof(MyDifopPkt) // difop len @@ -219,7 +224,7 @@ TEST(TestDecoder, processDifopPkt_invalid_rpm) TEST(TestDecoder, processMsopPkt) { - RSDecoderConstParam const_param = + RSDecoderMechConstParam const_param = { sizeof(MyMsopPkt) // msop len , sizeof(MyDifopPkt) // difop len @@ -266,8 +271,8 @@ TEST(TestDecoder, processMsopPkt) TEST(TestDecoder, setPointCloudHeader) { // dense_points - RSDecoderConstParam const_param = {}; - const_param.CHANNELS_PER_BLOCK = 2; + RSDecoderMechConstParam const_param = {}; + const_param.base.CHANNELS_PER_BLOCK = 2; RSDecoderParam param; param.dense_points = true; MyDecoder decoder(param, errCallback, const_param); @@ -301,6 +306,7 @@ TEST(TestDecoder, setPointCloudHeader) } } +#if 0 std::shared_ptr point_cloud_to_get; std::shared_ptr getCallback(void) @@ -317,14 +323,15 @@ void putCallback(std::shared_ptr pt) flag_point_cloud = true; } -#if 0 TEST(TestDecoder, split_by_angle) { - RSDecoderConstParam const_param; - const_param.CHANNELS_PER_BLOCK = 2; + RSDecoderMechConstParam const_param; + const_param.base.CHANNELS_PER_BLOCK = 2; + RSDecoderParam param; param.split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; param.split_angle = 0.0f; + MyDecoder decoder(param, errCallback, const_param); point_cloud_to_get = std::make_shared(); @@ -363,10 +370,12 @@ TEST(TestDecoder, split_by_angle) TEST(TestDecoder, split_by_fixed_pkts) { - RSDecoderConstParam const_param; - const_param.CHANNELS_PER_BLOCK = 2; + RSDecoderMechConstParam const_param; + const_param.base.CHANNELS_PER_BLOCK = 2; + RSDecoderParam param; param.split_frame_mode = SplitFrameMode::SPLIT_BY_FIXED_BLKS; + MyDecoder decoder(param, errCallback, const_param); decoder.split_blks_per_frame_ = 2; @@ -402,11 +411,13 @@ TEST(TestDecoder, split_by_fixed_pkts) TEST(TestDecoder, split_by_custom_blks) { - RSDecoderConstParam const_param; - const_param.CHANNELS_PER_BLOCK = 2; + RSDecoderMechConstParam const_param; + const_param.base.CHANNELS_PER_BLOCK = 2; + RSDecoderParam param; param.split_frame_mode = SplitFrameMode::SPLIT_BY_CUSTOM_BLKS; param.num_blks_split = 2; + MyDecoder decoder(param, errCallback, const_param); point_cloud_to_get = std::make_shared(); diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_diff_test.cpp index 289324b8..c6a6d9a0 100644 --- a/test/dual_return_block_diff_test.cpp +++ b/test/dual_return_block_diff_test.cpp @@ -1,7 +1,7 @@ #include -#include +#include #include using namespace robosense::lidar; @@ -25,7 +25,7 @@ typedef struct TEST(TestDualPacketTraverser, toNext) { - RSDecoderConstParam const_param = + RSDecoderMechConstParam const_param = { 0 , 0 @@ -63,7 +63,7 @@ TEST(TestDualPacketTraverser, toNext) }; DualReturnBlockDiff diff(pkt, - const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); + const_param.base.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); // first block ASSERT_EQ(diff.ts(0), 0.0f); diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_diff_test.cpp index 514c09ca..ba021d4b 100644 --- a/test/single_return_block_diff_test.cpp +++ b/test/single_return_block_diff_test.cpp @@ -1,7 +1,7 @@ #include -#include +#include #include using namespace robosense::lidar; @@ -25,7 +25,7 @@ typedef struct TEST(TestSingleReturnBlockDiff, ctor) { - RSDecoderConstParam const_param = + RSDecoderMechConstParam const_param = { 0 // msop len , 0 // difop len @@ -60,7 +60,7 @@ TEST(TestSingleReturnBlockDiff, ctor) }; SingleReturnBlockDiff diff(pkt, - const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); + const_param.base.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); // first block ASSERT_EQ(diff.ts(0), 0.0f); From de15e3f3bdb35bb98b455e2902a27122a1d017f4 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Dec 2021 14:37:01 +0800 Subject: [PATCH 115/379] add class DecoderMech --- src/rs_driver/driver/decoder/decoder.hpp | 32 ++++++++++--------- src/rs_driver/driver/decoder/decoder_RS16.hpp | 1 + src/rs_driver/driver/decoder/decoder_RS32.hpp | 2 +- .../driver/decoder/decoder_RSHELIOS.hpp | 5 ++- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 2 ++ src/rs_driver/driver/decoder/decoder_mech.hpp | 8 +++-- 6 files changed, 31 insertions(+), 19 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index e50a86df..8dbd3707 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -212,21 +212,22 @@ enum RSEchoMode // decoder const param struct RSDecoderConstParam { + // packet len uint16_t MSOP_LEN; uint16_t DIFOP_LEN; - // identity + // packet identity uint8_t MSOP_ID_LEN; uint8_t DIFOP_ID_LEN; uint8_t MSOP_ID[8]; uint8_t DIFOP_ID[8]; uint8_t BLOCK_ID[2]; - // duration + // packet structure uint16_t BLOCKS_PER_PKT; uint16_t CHANNELS_PER_BLOCK; - // distance resolution + // distance & temperature float DISTANCE_MIN; float DISTANCE_MAX; float DISTANCE_RES; @@ -244,13 +245,13 @@ class Decoder virtual void decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual ~Decoder() = default; + void processDifopPkt(const uint8_t* pkt, size_t size); + void processMsopPkt(const uint8_t* pkt, size_t size); + explicit Decoder(const RSDecoderParam& param, const std::function& excb, const RSDecoderConstParam& const_param); - void processDifopPkt(const uint8_t* pkt, size_t size); - void processMsopPkt(const uint8_t* pkt, size_t size); - void regRecvCallback(const std::function(void)>& cb_get, const std::function)>& cb_put); @@ -264,16 +265,19 @@ class Decoder void splitFrame(); void setPointCloudHeader(std::shared_ptr msg, double chan_ts); - RSDecoderConstParam const_param_; // const param of lidar/decoder - RSDecoderParam param_; // user param of lidar/decoder + RSDecoderConstParam const_param_; // const param + RSDecoderParam param_; // user param std::function excb_; - uint16_t height_; + std::function(void)> point_cloud_cb_get_; + std::function)> point_cloud_cb_put_; Trigon trigon_; #define SIN(angle) this->trigon_.sin(angle) #define COS(angle) this->trigon_.cos(angle) - DistanceSection distance_section_; // valid distance section + uint16_t height_; + double packet_duration_; + DistanceSection distance_section_; // invalid section of distance RSEchoMode echo_mode_; // echo mode (defined by return mode) float temperature_; // lidar temperature @@ -281,8 +285,6 @@ class Decoder bool angles_ready_; // is vert_angles/horiz_angles ready from csv file/difop packet? double prev_chan_ts_; // previous channel/point timestamp - std::function(void)> point_cloud_cb_get_; - std::function)> point_cloud_cb_put_; std::shared_ptr point_cloud_; // curernt point cloud uint32_t point_cloud_seq_; // sequence of point cloud }; @@ -294,7 +296,8 @@ inline Decoder::Decoder(const RSDecoderParam& param, : const_param_(const_param) , param_(param) , excb_(excb) - //, height_(const_param.CHANNELS_PER_BLOCK) + , height_(0) + , packet_duration_(0) , distance_section_(const_param.DISTANCE_MIN, const_param.DISTANCE_MAX, param.min_distance, param.max_distance) , echo_mode_(ECHO_SINGLE) @@ -314,8 +317,7 @@ float Decoder::getTemperature() template double Decoder::getPacketDuration() { - return 0; - //return this->const_param_.BLOCK_DURATION * const_param_.BLOCKS_PER_PKT; + return packet_duration_; } template diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index ab96e2ef..f6f355d1 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -218,6 +218,7 @@ inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, const std::function& excb) : DecoderMech(param, excb, initConstParam(rs_const_param_)) { + this->height_ = 16; } template diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index f759132b..1f885ad6 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -32,7 +32,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include -#include +//#include namespace robosense { diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 21ba4e87..8c46f0f1 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -30,12 +30,15 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include +#include + namespace robosense { namespace lidar { + #pragma pack(push, 1) + typedef struct { uint8_t id[2]; diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 99256f8a..3b927da8 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -181,6 +181,8 @@ inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, , max_seq_(SINGLE_PKT_NUM) , split_(&max_seq_) { + this->height_ = 1; // TODO + this->packet_duration_ = 1; // TODO } template diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index 75bffa16..5c53f829 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -75,7 +75,7 @@ class DecoderMech : public Decoder template void decodeDifopCommon(const T_Difop& pkt); - RSDecoderMechConstParam mech_const_param_; // const param of lidar/decoder + RSDecoderMechConstParam mech_const_param_; // const param ChanAngles chan_angles_; // vert_angles/horiz_angles adjustment AzimuthSection scan_section_; // valid azimuth section std::shared_ptr split_strategy_; // split strategy @@ -104,6 +104,10 @@ inline DecoderMech::DecoderMech(const RSDecoderParam& param, , block_azi_diff_(20) , fov_blind_ts_diff_(0) { + this->height_ = this->const_param_.CHANNELS_PER_BLOCK; + this->packet_duration_ = + this->mech_const_param_.BLOCK_DURATION * this->const_param_.BLOCKS_PER_PKT; + switch (this->param_.split_frame_mode) { case SplitFrameMode::SPLIT_BY_FIXED_BLKS: @@ -121,7 +125,7 @@ inline DecoderMech::DecoderMech(const RSDecoderParam& param, break; } - // calulate lidar_alph0 and lidar_Rxy + // lens center: (alph0, Rxy) lidar_alph0_ = std::atan2(mech_const_param_.RY, mech_const_param_.RX) * 180 / M_PI * 100; lidar_Rxy_ = std::sqrt(mech_const_param_.RX * mech_const_param_.RX + mech_const_param_.RY * mech_const_param_.RY); From 9f5b82356f28308821d576f663ede5e03b88db8a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Dec 2021 15:37:28 +0800 Subject: [PATCH 116/379] refac: format driver_param --- src/rs_driver/driver/driver_param.h | 20 +++++++++++--------- 1 file changed, 11 insertions(+), 9 deletions(-) diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index 41dad956..fca4343a 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -231,18 +231,18 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter #endif RS_INFO << "------------------------------------------------------" << RS_REND; RS_INFO << " RoboSense Decoder Parameters " << RS_REND; - RS_INFOL << "config_from_file: " << config_from_file << RS_REND; - RS_INFOL << "angle_path: " << angle_path << RS_REND; + RS_INFOL << "wait_for_difop: " << wait_for_difop << RS_REND; RS_INFOL << "max_distance: " << max_distance << RS_REND; RS_INFOL << "min_distance: " << min_distance << RS_REND; RS_INFOL << "start_angle: " << start_angle << RS_REND; RS_INFOL << "end_angle: " << end_angle << RS_REND; - RS_INFOL << "wait_for_difop: " << wait_for_difop << RS_REND; RS_INFOL << "use_lidar_clock: " << use_lidar_clock << RS_REND; + RS_INFOL << "dense_points: " << dense_points << RS_REND; + RS_INFOL << "config_from_file: " << config_from_file << RS_REND; + RS_INFOL << "angle_path: " << angle_path << RS_REND; RS_INFOL << "split_frame_mode: " << split_frame_mode << RS_REND; RS_INFOL << "split_angle: " << split_angle << RS_REND; RS_INFOL << "num_blks_split: " << num_blks_split << RS_REND; - RS_INFOL << "dense_points: " << dense_points << RS_REND; RS_INFO << "------------------------------------------------------" << RS_REND; } @@ -256,7 +256,7 @@ typedef struct RSInputParam ///< The LiDAR input parameter std::string multi_cast_address = "0.0.0.0"; ///< Address of multicast std::string pcap_path = "null"; ///< Absolute path of pcap file bool pcap_repeat = true; ///< true: The pcap bag will repeat play - float pcap_rate = 1; ///< Rate to read the pcap file + float pcap_rate = 1.0f; ///< Rate to read the pcap file bool use_vlan = false; ///< Vlan on-off bool use_someip = false; ///< Someip on-off @@ -268,8 +268,9 @@ typedef struct RSInputParam ///< The LiDAR input parameter RS_INFOL << "host_address: " << host_address << RS_REND; RS_INFOL << "msop_port: " << msop_port << RS_REND; RS_INFOL << "difop_port: " << difop_port << RS_REND; + RS_INFOL << "pcap_path: " << pcap_rate << RS_REND; + RS_INFOL << "pcap_rate: " << pcap_path << RS_REND; RS_INFOL << "pcap_repeat: " << pcap_repeat << RS_REND; - RS_INFOL << "pcap_path: " << pcap_path << RS_REND; RS_INFOL << "use_vlan: " << use_vlan << RS_REND; RS_INFOL << "use_someip: " << use_someip << RS_REND; RS_INFO << "------------------------------------------------------" << RS_REND; @@ -286,13 +287,14 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter void print() const { - input_param.print(); - decoder_param.print(); RS_INFO << "------------------------------------------------------" << RS_REND; RS_INFOL << " RoboSense Driver Parameters " << RS_REND; - RS_INFOL << "lidar_type: " << lidarTypeToStr(lidar_type) << RS_REND; RS_INFOL << "input type: " << inputTypeToStr(input_type) << RS_REND; + RS_INFOL << "lidar_type: " << lidarTypeToStr(lidar_type) << RS_REND; RS_INFOL << "------------------------------------------------------" << RS_REND; + + input_param.print(); + decoder_param.print(); } } RSDriverParam; From df46fa568ce8afaa3960114e5cf5d2ee225e717c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Dec 2021 17:25:45 +0800 Subject: [PATCH 117/379] refac: refactory decoder --- src/rs_driver/driver/decoder/decoder.hpp | 34 +++++++++---------- .../driver/decoder/decoder_RS128.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS16.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 2 +- .../driver/decoder/decoder_RSHELIOS.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 28 ++++++++------- src/rs_driver/driver/lidar_driver_impl.hpp | 7 ++-- 9 files changed, 44 insertions(+), 37 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 8dbd3707..5e085eea 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -283,7 +283,7 @@ class Decoder float temperature_; // lidar temperature bool angles_ready_; // is vert_angles/horiz_angles ready from csv file/difop packet? - double prev_chan_ts_; // previous channel/point timestamp + double prev_point_ts_; // last point's timestamp std::shared_ptr point_cloud_; // curernt point cloud uint32_t point_cloud_seq_; // sequence of point cloud @@ -303,7 +303,7 @@ inline Decoder::Decoder(const RSDecoderParam& param, , echo_mode_(ECHO_SINGLE) , temperature_(0.0) , angles_ready_(false) - , prev_chan_ts_(0.0) + , prev_point_ts_(0.0) , point_cloud_seq_(0) { } @@ -336,7 +336,7 @@ inline void Decoder::splitFrame() { if (point_cloud_->points.size() > 0) { - setPointCloudHeader(point_cloud_, prev_chan_ts_); + setPointCloudHeader(point_cloud_, prev_point_ts_); point_cloud_cb_put_(point_cloud_); point_cloud_ = point_cloud_cb_get_(); } @@ -365,45 +365,45 @@ void Decoder::setPointCloudHeader(std::shared_ptr ms } template -void Decoder::processMsopPkt(const uint8_t* pkt, size_t size) +void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) { - if (param_.wait_for_difop && !angles_ready_) - { - excb_(Error(ERRCODE_NODIFOPRECV)); - return; - } - - if (size != this->const_param_.MSOP_LEN) + if (size != this->const_param_.DIFOP_LEN) { this->excb_(Error(ERRCODE_WRONGPKTLENGTH)); return; } - if (memcmp(pkt, this->const_param_.MSOP_ID, const_param_.MSOP_ID_LEN) != 0) + if (memcmp(pkt, this->const_param_.DIFOP_ID, const_param_.DIFOP_ID_LEN) != 0) { this->excb_(Error(ERRCODE_WRONGPKTHEADER)); return; } - decodeMsopPkt(pkt, size); + decodeDifopPkt(pkt, size); } template -void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) +void Decoder::processMsopPkt(const uint8_t* pkt, size_t size) { - if (size != this->const_param_.DIFOP_LEN) + if (param_.wait_for_difop && !angles_ready_) + { + excb_(Error(ERRCODE_NODIFOPRECV)); + return; + } + + if (size != this->const_param_.MSOP_LEN) { this->excb_(Error(ERRCODE_WRONGPKTLENGTH)); return; } - if (memcmp(pkt, this->const_param_.DIFOP_ID, const_param_.DIFOP_ID_LEN) != 0) + if (memcmp(pkt, this->const_param_.MSOP_ID, const_param_.MSOP_ID_LEN) != 0) { this->excb_(Error(ERRCODE_WRONGPKTHEADER)); return; } - decodeDifopPkt(pkt, size); + decodeMsopPkt(pkt, size); } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index e0ded033..39c69b03 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -290,7 +290,7 @@ inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packe this->point_cloud_->points.emplace_back(point); } - this->prev_chan_ts_ = chan_ts; + this->prev_point_ts_ = chan_ts; } } } diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index f6f355d1..cc2691d7 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -333,7 +333,7 @@ inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet this->point_cloud_->points.emplace_back(point); } - this->prev_chan_ts_ = chan_ts; + this->prev_point_ts_ = chan_ts; } } diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 1f885ad6..8fe4ccff 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -335,7 +335,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet this->point_cloud_->points.emplace_back(point); } - this->prev_chan_ts_ = chan_ts; + this->prev_point_ts_ = chan_ts; } } } diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 3c11fa34..2536fe26 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -289,7 +289,7 @@ inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet this->point_cloud_->points.emplace_back(point); } - this->prev_chan_ts_ = chan_ts; + this->prev_point_ts_ = chan_ts; } } } diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index b4253268..8e0f7690 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -281,7 +281,7 @@ inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet this->point_cloud_->points.emplace_back(point); } - this->prev_chan_ts_ = chan_ts; + this->prev_point_ts_ = chan_ts; } } } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 8c46f0f1..35de5880 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -293,7 +293,7 @@ inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa this->point_cloud_->points.emplace_back(point); } - this->prev_chan_ts_ = chan_ts; + this->prev_point_ts_ = chan_ts; } } } diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 3b927da8..8d068cc6 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -132,14 +132,15 @@ typedef struct #pragma pack(pop) -const uint32_t SINGLE_PKT_NUM = 630; -const uint32_t DUAL_PKT_NUM = 1260; - template class DecoderRSM1 : public Decoder { public: + static const uint32_t SINGLE_PKT_NUM = 630; + static const uint32_t DUAL_PKT_NUM = 1260; + static const int ANGLE_OFFSET = 32768; + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRSM1() = default; @@ -167,8 +168,8 @@ RSDecoderConstParam DecoderRSM1::rs_const_param_ = , {0x55, 0xAA, 0x5A, 0xA5} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0x00, 0x00} - , 0 // blocks per packet - , 0 // channels per block + , 25 // blocks per packet + , 5 // channels per block , 0.2f // distance min , 200.0f // distance max , 0.005f // distance resolution @@ -181,8 +182,9 @@ inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, , max_seq_(SINGLE_PKT_NUM) , split_(&max_seq_) { - this->height_ = 1; // TODO + this->height_ = this->const_param_.CHANNELS_PER_BLOCK; this->packet_duration_ = 1; // TODO + this->angles_ready_ = true; } template @@ -200,12 +202,11 @@ RSEchoMode DecoderRSM1::getEchoMode(uint8_t mode) } } -template -void DecoderRSM1::decodeDifopPkt(const uint8_t* packet, size_t size) +template void DecoderRSM1::decodeDifopPkt(const uint8_t* packet, size_t size) { const RSM1DifopPkt& pkt = *(RSM1DifopPkt*)packet; this->echo_mode_ = this->getEchoMode(pkt.return_mode); - max_seq_ = (this->echo_mode_ == ECHO_SINGLE) ? 630 : 1260; + max_seq_ = (this->echo_mode_ == ECHO_SINGLE) ? SINGLE_PKT_NUM : DUAL_PKT_NUM; } template @@ -240,7 +241,6 @@ void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size if (this->distance_section_.in(distance)) { - static const int ANGLE_OFFSET = 32768; int pitch = ntohs(channel.pitch) - ANGLE_OFFSET; int yaw = ntohs(channel.yaw) - ANGLE_OFFSET; @@ -254,7 +254,8 @@ void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size setY(point, y); setZ(point, z); setIntensity(point, intensity); - setRing(point, chan + 1); + + setRing(point, chan); setTimestamp(point, point_time); this->point_cloud_->points.emplace_back(point); } @@ -265,11 +266,14 @@ void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); - setRing(point, chan + 1); + + setRing(point, chan); setTimestamp(point, point_time); this->point_cloud_->points.emplace_back(point); } } + + this->prev_point_ts_ = point_time; } uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index d9cc3dfe..f60fec5d 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -315,7 +315,6 @@ inline void LidarDriverImpl::packetPut(std::shared_ptr pkt { SyncQueue>* queue; - uint8_t* id = pkt->data(); if (*id == 0x55) { @@ -325,6 +324,11 @@ inline void LidarDriverImpl::packetPut(std::shared_ptr pkt { queue = &difop_pkt_queue_; } + else + { + free_pkt_queue_.push(pkt); + return; + } static const int PACKET_POOL_MAX = 1024; @@ -366,7 +370,6 @@ inline void LidarDriverImpl::processDifop() } lidar_decoder_ptr_->processDifopPkt(pkt->data(), pkt->dataSize()); - runCallBack(pkt); free_pkt_queue_.push(pkt); From f89a8b9a108e8b741ef8acde2a4f2e3e2a4693b0 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Dec 2021 17:54:14 +0800 Subject: [PATCH 118/379] feat: change version to 1.4.4 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 55368c24..99430fff 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.4.3) +project(rs_driver VERSION 1.4.4) #============================= # Compile Demos&Tools From be1578621906b2cbf39eb2e50cfe034e99cec48a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Dec 2021 19:29:31 +0800 Subject: [PATCH 119/379] refac: remove rsrock for now --- .../driver/decoder/decoder_RSROCK.hpp | 234 ------------------ .../driver/decoder/decoder_factory.hpp | 169 ------------- 2 files changed, 403 deletions(-) delete mode 100644 src/rs_driver/driver/decoder/decoder_RSROCK.hpp diff --git a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp b/src/rs_driver/driver/decoder/decoder_RSROCK.hpp deleted file mode 100644 index 662a667e..00000000 --- a/src/rs_driver/driver/decoder/decoder_RSROCK.hpp +++ /dev/null @@ -1,234 +0,0 @@ -/********************************************************************************************************************* -Copyright (c) 2020 RoboSense -All rights reserved - -By downloading, copying, installing or using the software you agree to this license. If you do not agree to this -license, do not download, install, copy or use the software. - -License Agreement -For RoboSense LiDAR SDK Library -(3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials provided with the distribution. - -3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used -to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*********************************************************************************************************************/ - -#include -namespace robosense -{ -namespace lidar -{ -#pragma pack(push, 1) - -typedef struct -{ - uint16_t azimuth; - RSChannel channels[4]; -} RSROCKChannel; - -typedef struct -{ - uint16_t id; - RSROCKChannel channels[14]; -} RSROCKMsopBlock; - -typedef struct -{ - RSMsopHeader header; - RSROCKMsopBlock blocks[6]; - unsigned int index; - uint16_t tail; -} RSROCKMsopPkt; - -// TODO -typedef struct -{ - uint64_t id; - uint16_t rpm; - RSEthNet eth; - RSFOV fov; - uint16_t reserved0; - uint16_t phase_lock_angle; - RSVersion version; - uint8_t reserved_1[242]; - RSSn sn; - uint16_t zero_cali; - uint8_t return_mode; - uint16_t sw_ver; - RSTimestampYMD timestamp; - RSStatus status; - uint8_t reserved_2[5]; - RSDiagno diagno; - uint8_t gprmc[86]; - RSCalibrationAngle ver_angle_cali[32]; - RSCalibrationAngle hori_angle_cali[32]; - uint8_t reserved_3[586]; - uint16_t tail; -} RSROCKDifopPkt; - -#pragma pack(pop) - -template -class DecoderRSROCK : public DecoderBase -{ -public: - explicit DecoderRSROCK(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); - double getLidarTime(const uint8_t* pkt); -}; - -template -inline DecoderRSROCK::DecoderRSROCK(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) -{ - this->msop_pkt_len_ = ROCK_MSOP_LEN; - - this->vert_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->hori_angle_list_.resize(this->lidar_const_param_.LASER_NUM); - this->beam_ring_table_.resize(this->lidar_const_param_.LASER_NUM); - - // TODO temp - this->vert_angle_list_[0] = 5 * 100; - this->vert_angle_list_[1] = 2.5 * 100; - this->vert_angle_list_[2] = 0 * 100; - this->vert_angle_list_[3] = -2.5 * 100; - - this->hori_angle_list_[0] = -0.2 * 100; - this->hori_angle_list_[1] = -0.2 * 100; - this->hori_angle_list_[2] = -0.2 * 100; - this->hori_angle_list_[3] = -0.2 * 100; - - if (this->param_.max_distance > 200.0f) - { - this->param_.max_distance = 200.0f; - } - if (this->param_.min_distance < 0.4f || this->param_.min_distance > this->param_.max_distance) - { - this->param_.min_distance = 0.4f; - } -} - -template -inline double DecoderRSROCK::getLidarTime(const uint8_t* pkt) -{ - return this->template calculateTimeYMD(pkt); -} - -template -inline RSDecoderResult DecoderRSROCK::decodeMsopPkt(const uint8_t* pkt, - typename T_PointCloud::VectorT& vec, int& height, - int& azimuth) -{ - height = this->lidar_const_param_.LASER_NUM; - const RSROCKMsopPkt* mpkt_ptr = reinterpret_cast(pkt); - if (mpkt_ptr->header.id != this->lidar_const_param_.MSOP_ID) - { - return RSDecoderResult::WRONG_PKT_HEADER; - } - - azimuth = RS_SWAP_SHORT(mpkt_ptr->blocks[0].channels[0].azimuth); - this->current_temperature_ = this->computeTemperature(mpkt_ptr->header.temp_raw); - double block_timestamp = this->get_point_time_func_(pkt); - float azi_diff = 0; - for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) - { - if (mpkt_ptr->blocks[blk_idx].id != this->lidar_const_param_.BLOCK_ID) - { - break; - } - - for (size_t firing_idx = 0; - firing_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK / this->lidar_const_param_.LASER_NUM; firing_idx++) - { - int cur_azi = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].channels[firing_idx].azimuth); - - azi_diff = 0.0; // TODO - for (int channel_idx = 0; channel_idx < this->lidar_const_param_.LASER_NUM; channel_idx++) - { - float azi_channel_ori = cur_azi + azi_diff * 1; // this->lidar_const_param_.FIRING_FREQUENCY * - // this->lidar_const_param_.DSR_TOFFSET * - // static_cast(2 * (channel_idx % 16) + (channel_idx / 16)); // TODO - int azi_channel_final = this->azimuthCalibration(azi_channel_ori, channel_idx); - float distance = RS_SWAP_SHORT(mpkt_ptr->blocks[blk_idx].channels[firing_idx].channels[channel_idx].distance) * - this->lidar_const_param_.DIS_RESOLUTION; - int angle_horiz = static_cast(azi_channel_ori + RS_ONE_ROUND) % RS_ONE_ROUND; - int angle_vert = ((this->vert_angle_list_[channel_idx]) + RS_ONE_ROUND) % RS_ONE_ROUND; - - typename T_PointCloud::PointT point; - bool pointValid = false; - if ((distance <= this->param_.max_distance && distance >= this->param_.min_distance) && - ((this->angle_flag_ && azi_channel_final >= this->start_angle_ && azi_channel_final <= this->end_angle_) || - (!this->angle_flag_ && - ((azi_channel_final >= this->start_angle_) || (azi_channel_final <= this->end_angle_))))) - { - float x = distance * this->checkCosTable(angle_vert) * this->checkCosTable(azi_channel_final) + - this->lidar_Rxy_ * this->checkCosTable(angle_horiz - this->lidar_alph0_); - float y = -distance * this->checkCosTable(angle_vert) * this->checkSinTable(azi_channel_final) - - this->lidar_Rxy_ * this->checkSinTable(angle_horiz - this->lidar_alph0_); - float z = distance * this->checkSinTable(angle_vert) + this->lidar_const_param_.RZ; - uint8_t intensity = mpkt_ptr->blocks[blk_idx].channels[firing_idx].channels[channel_idx].intensity; - this->transformPoint(x, y, z); - setX(point, x); - setY(point, y); - setZ(point, z); - setIntensity(point, intensity); - pointValid = true; - } - else if (!this->param_.is_dense) - { - setX(point, NAN); - setY(point, NAN); - setZ(point, NAN); - setIntensity(point, 0); - pointValid = true; - } - - if (pointValid) - { - setRing(point, this->beam_ring_table_[channel_idx]); - setTimestamp(point, block_timestamp); - vec.emplace_back(std::move(point)); - } - } - } - } - return RSDecoderResult::DECODE_OK; -} - -template -inline RSDecoderResult DecoderRSROCK::decodeDifopPkt(const uint8_t* pkt) -{ - const RSROCKDifopPkt* dpkt_ptr = reinterpret_cast(pkt); - if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) - { - return RSDecoderResult::WRONG_PKT_HEADER; - } - this->template decodeDifopCommon(pkt, LidarType::RSROCK); - if (!this->difop_flag_) - { - this->template decodeDifopCalibration(pkt, LidarType::RSROCK); - } - return RSDecoderResult::DECODE_OK; -} - -} // namespace lidar -} // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index c92802fb..ff530065 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -37,9 +37,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#if 0 -#include -#endif namespace robosense { @@ -63,11 +60,6 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam switch (type) { -#if 0 - case LidarType::RSROCK: - ret_ptr = std::make_shared>(param.decoder_param); - break; -#endif case LidarType::RS16: ret_ptr = std::make_shared>(param, excb); break; @@ -97,166 +89,5 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam return ret_ptr; } -#if 0 -template -inline const LidarConstantParameter DecoderFactory::getRS16ConstantParam() -{ - LidarConstantParameter ret_param; - ret_param.MSOP_ID = 0xA050A55A0A05AA55; - ret_param.DIFOP_ID = 0x555511115A00FFA5; - ret_param.BLOCK_ID = 0xEEFF; - ret_param.PKT_RATE = 750; - ret_param.BLOCKS_PER_PKT = 12; - ret_param.CHANNELS_PER_BLOCK = 32; - ret_param.LASER_NUM = 16; - ret_param.DSR_TOFFSET = 2.8; - ret_param.FIRING_FREQUENCY = 0.009; - ret_param.DIS_RESOLUTION = 0.005; - ret_param.RX = 0.03825; - ret_param.RY = -0.01088; - ret_param.RZ = 0; - return ret_param; -} - -template -inline const LidarConstantParameter DecoderFactory::getRS32ConstantParam() -{ - LidarConstantParameter ret_param; - ret_param.MSOP_ID = 0xA050A55A0A05AA55; - ret_param.DIFOP_ID = 0x555511115A00FFA5; - ret_param.BLOCK_ID = 0xEEFF; - ret_param.PKT_RATE = 1500; - ret_param.BLOCKS_PER_PKT = 12; - - ret_param.CHANNELS_PER_BLOCK = 32; - ret_param.LASER_NUM = 32; - - ret_param.DSR_TOFFSET = 1.44; - ret_param.FIRING_FREQUENCY = 0.018; - ret_param.DIS_RESOLUTION = 0.005; - - ret_param.RX = 0.03997; - ret_param.RY = -0.01087; - ret_param.RZ = 0; - - return ret_param; -} - -template -inline const LidarConstantParameter DecoderFactory::getRSBPConstantParam() -{ - LidarConstantParameter ret_param; - ret_param.MSOP_ID = 0xA050 A55A 0A05 AA55; - ret_param.DIFOP_ID = 0x5555 1111 5A00 FFA5; - ret_param.BLOCK_ID = 0xEEFF; - ret_param.PKT_RATE = 1500; - ret_param.BLOCKS_PER_PKT = 12; - ret_param.CHANNELS_PER_BLOCK = 32; - ret_param.LASER_NUM = 32; - ret_param.DSR_TOFFSET = 1.28; - ret_param.FIRING_FREQUENCY = 0.018; - ret_param.DIS_RESOLUTION = 0.005; - ret_param.RX = 0.01473; - ret_param.RY = 0.0085; - ret_param.RZ = 0.09427; - return ret_param; -} - -template -inline const LidarConstantParameter DecoderFactory::getRS80ConstantParam() -{ - LidarConstantParameter ret_param; - ret_param.MSOP_ID = 0x5A05AA55; - ret_param.DIFOP_ID = 0x555511115A00FFA5; - ret_param.BLOCK_ID = 0xFE; - ret_param.PKT_RATE = 4500; - ret_param.BLOCKS_PER_PKT = 4; - ret_param.CHANNELS_PER_BLOCK = 80; - ret_param.LASER_NUM = 80; - ret_param.DSR_TOFFSET = 3.236; - ret_param.FIRING_FREQUENCY = 0.018; - ret_param.DIS_RESOLUTION = 0.005; - ret_param.RX = 0.03615; - ret_param.RY = -0.017; - ret_param.RZ = 0; - return ret_param; -} - -template -inline const LidarConstantParameter DecoderFactory::getRS128ConstantParam() -{ - LidarConstantParameter ret_param; - ret_param.MSOP_ID = 0x5A05AA55; - ret_param.DIFOP_ID = 0x555511115A00FFA5; - ret_param.BLOCK_ID = 0xFE; - ret_param.PKT_RATE = 6000; - ret_param.BLOCKS_PER_PKT = 3; - ret_param.CHANNELS_PER_BLOCK = 128; - ret_param.LASER_NUM = 128; - ret_param.DSR_TOFFSET = 3.236; - ret_param.FIRING_FREQUENCY = 0.018; - ret_param.DIS_RESOLUTION = 0.005; - ret_param.RX = 0.03615; - ret_param.RY = -0.017; - ret_param.RZ = 0; - return ret_param; -} - -template -inline const LidarConstantParameter DecoderFactory::getRSM1ConstantParam() -{ - LidarConstantParameter ret_param; - ret_param.MSOP_ID = 0xA55AAA55; - ret_param.DIFOP_ID = 0x555511115A00FFA5; - ret_param.BLOCKS_PER_PKT = 25; - ret_param.CHANNELS_PER_BLOCK = 5; - ret_param.LASER_NUM = 5; - ret_param.DIS_RESOLUTION = 0.005; - return ret_param; -} - -template -inline const LidarConstantParameter DecoderFactory::getRSHELIOSConstantParam() -{ - LidarConstantParameter ret_param; - ret_param.MSOP_ID = 0x5A05AA55; - ret_param.DIFOP_ID = 0x555511115A00FFA5; - ret_param.BLOCK_ID = 0xEEFF; - ret_param.PKT_RATE = 1500; - ret_param.BLOCKS_PER_PKT = 12; - ret_param.BLOCKS_PER_FRAME = 1800; - ret_param.CHANNELS_PER_BLOCK = 32; - ret_param.LASER_NUM = 32; - ret_param.DSR_TOFFSET = 1.0; - ret_param.FIRING_FREQUENCY = 0.018; - ret_param.DIS_RESOLUTION = 0.0025; - ret_param.RX = 0.03498; - ret_param.RY = -0.015; - ret_param.RZ = 0.0; - return ret_param; -} - -// TODO -template -inline const LidarConstantParameter DecoderFactory::getRSROCKConstantParam() -{ - LidarConstantParameter ret_param; - ret_param.MSOP_ID = 0x000001005A05AA55; - ret_param.DIFOP_ID = 0x555511115A00FFA5; - ret_param.BLOCK_ID = 0xEEFF; - ret_param.PKT_RATE = 1071; // TODO - ret_param.BLOCKS_PER_PKT = 6; - ret_param.CHANNELS_PER_BLOCK = 14 * 4; // TODO - ret_param.LASER_NUM = 4; - ret_param.DSR_TOFFSET = 1.0; - ret_param.FIRING_FREQUENCY = 0.018; - ret_param.DIS_RESOLUTION = 0.0025; - ret_param.RX = 0.07526; - ret_param.RY = 0.00968; - ret_param.RZ = 0.0; - return ret_param; -} -#endif - } // namespace lidar } // namespace robosense From 2b0a47781e00c46a2fea77d3d2b16a7fe9c1609e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Dec 2021 20:03:31 +0800 Subject: [PATCH 120/379] refac: refactory decoder --- src/rs_driver/driver/decoder/basic_attr.hpp | 8 -------- src/rs_driver/driver/decoder/decoder_RS32.hpp | 1 - src/rs_driver/driver/decoder/decoder_RSM1.hpp | 6 +++--- src/rs_driver/driver/decoder/decoder_factory.hpp | 2 +- src/rs_driver/driver/decoder/decoder_mech.hpp | 2 +- src/rs_driver/driver/decoder/trigon.hpp | 4 ++-- src/rs_driver/driver/input/input_factory.hpp | 3 ++- src/rs_driver/driver/lidar_driver_impl.hpp | 3 +-- 8 files changed, 10 insertions(+), 19 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index 51cfc21e..509612ae 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -59,14 +59,6 @@ typedef struct uint16_t us; } RSTimestampYMD; -#if 0 -typedef struct -{ - uint8_t sec[6]; - uint32_t us; -} RSTimestampUTC; -#endif - typedef struct { uint8_t sec[6]; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 8fe4ccff..201e0255 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -32,7 +32,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include -//#include namespace robosense { diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 8d068cc6..c6cc8430 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -137,9 +137,9 @@ class DecoderRSM1 : public Decoder { public: - static const uint32_t SINGLE_PKT_NUM = 630; - static const uint32_t DUAL_PKT_NUM = 1260; - static const int ANGLE_OFFSET = 32768; + constexpr static uint32_t SINGLE_PKT_NUM = 630; + constexpr static uint32_t DUAL_PKT_NUM = 1260; + constexpr static int ANGLE_OFFSET = 32768; virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index ff530065..e083c030 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -30,12 +30,12 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#include #include #include #include #include #include -#include #include namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index 5c53f829..4f654c02 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -47,7 +47,7 @@ struct RSDecoderMechConstParam float RY; float RZ; - // firing_ts / block_ts, chan_ts + // firing_ts/chan_ts double BLOCK_DURATION; double CHAN_TSS[128]; float CHAN_AZIS[128]; diff --git a/src/rs_driver/driver/decoder/trigon.hpp b/src/rs_driver/driver/decoder/trigon.hpp index f55429d8..c79b12bb 100644 --- a/src/rs_driver/driver/decoder/trigon.hpp +++ b/src/rs_driver/driver/decoder/trigon.hpp @@ -49,8 +49,8 @@ class Trigon { public: - static const int32_t MIN = -9000; - static const int32_t MAX = 45000; + constexpr static int32_t MIN = -9000; + constexpr static int32_t MAX = 45000; Trigon() { diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 72b74034..fce36ab9 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -75,7 +75,8 @@ inline std::shared_ptr InputFactory::createInput(InputType type, break; default: - break; + RS_ERROR << "Wrong Input Type." << RS_REND; + exit(-1); } return input; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index f60fec5d..7c437859 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -34,7 +34,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include #include #include #include @@ -330,7 +329,7 @@ inline void LidarDriverImpl::packetPut(std::shared_ptr pkt return; } - static const int PACKET_POOL_MAX = 1024; + constexpr static int PACKET_POOL_MAX = 1024; size_t sz = queue->push(pkt); if (sz > PACKET_POOL_MAX) From ddbdde2da6f40e567b44e7927587f81347096296 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Dec 2021 21:05:53 +0800 Subject: [PATCH 121/379] fix: fix rsm1 split strategy --- .../driver/decoder/split_strategy.hpp | 43 +++++++++++--- test/split_strategy_test.cpp | 59 +++++++++++++++---- 2 files changed, 83 insertions(+), 19 deletions(-) diff --git a/src/rs_driver/driver/decoder/split_strategy.hpp b/src/rs_driver/driver/decoder/split_strategy.hpp index 9679fc12..47c8b1cd 100644 --- a/src/rs_driver/driver/decoder/split_strategy.hpp +++ b/src/rs_driver/driver/decoder/split_strategy.hpp @@ -116,31 +116,56 @@ class SplitStrategyBySeq SplitStrategyBySeq(uint16_t* max_seq) : max_seq_(max_seq), prev_seq_(0) { + setSafeRange(); } bool newPacket(uint16_t seq) { - if (seq == *max_seq_) + bool split = false; + + if (isSafe(seq)) { - prev_seq_ = 0; - return true; + if (seq == *max_seq_) + { + prev_seq_ = 0; + split = true; + } + else if (seq > prev_seq_) + { + prev_seq_ = seq; + } } else if (seq < prev_seq_) { prev_seq_ = seq; - return true; - } - else - { - prev_seq_ = seq; - return false; + split = true; } + + setSafeRange(); + return split; } +#ifndef UNIT_TEST private: +#endif + + constexpr static uint16_t RANGE = 10; + + void setSafeRange() + { + safe_seq_min_ = (prev_seq_ > RANGE) ? prev_seq_ - RANGE : 0; + safe_seq_max_ = prev_seq_ + RANGE; + } + + bool isSafe(uint16_t seq) + { + return ((safe_seq_min_ < seq) && (seq < safe_seq_max_)); + } uint16_t* max_seq_; uint16_t prev_seq_; + uint16_t safe_seq_min_; + uint16_t safe_seq_max_; }; } // namespace lidar diff --git a/test/split_strategy_test.cpp b/test/split_strategy_test.cpp index 31f1bf4c..a345c520 100644 --- a/test/split_strategy_test.cpp +++ b/test/split_strategy_test.cpp @@ -67,26 +67,65 @@ TEST(TestSplitStrategyByNum, newBlock) TEST(TestSplitStrategyBySeq, newPacket_max_seq) { - uint16_t max_seq = 2; + uint16_t max_seq = 15; SplitStrategyBySeq sn(&max_seq); + ASSERT_EQ(sn.prev_seq_, 0); + ASSERT_EQ(sn.safe_seq_min_, 0); + ASSERT_EQ(sn.safe_seq_max_, 10); - // reach max_seq + // init value ASSERT_FALSE(sn.newPacket(1)); - ASSERT_TRUE(sn.newPacket(2)); - - // reach max_seq again - ASSERT_FALSE(sn.newPacket(1)); - ASSERT_TRUE(sn.newPacket(2)); + ASSERT_EQ(sn.prev_seq_, 1); + ASSERT_EQ(sn.safe_seq_min_, 0); + ASSERT_EQ(sn.safe_seq_max_, 11); + + // too big value + ASSERT_FALSE(sn.newPacket(12)); + ASSERT_EQ(sn.prev_seq_, 1); + ASSERT_EQ(sn.safe_seq_min_, 0); + ASSERT_EQ(sn.safe_seq_max_, 11); + + ASSERT_FALSE(sn.newPacket(9)); + + ASSERT_FALSE(sn.newPacket(12)); + ASSERT_EQ(sn.prev_seq_, 12); + ASSERT_EQ(sn.safe_seq_min_, 2); + ASSERT_EQ(sn.safe_seq_max_, 22); + + ASSERT_FALSE(sn.newPacket(11)); + ASSERT_EQ(sn.prev_seq_, 12); + ASSERT_EQ(sn.safe_seq_min_, 2); + ASSERT_EQ(sn.safe_seq_max_, 22); + + ASSERT_TRUE(sn.newPacket(15)); + ASSERT_EQ(sn.prev_seq_, 0); + ASSERT_EQ(sn.safe_seq_min_, 0); + ASSERT_EQ(sn.safe_seq_max_, 10); } TEST(TestSplitStrategyBySeq, newPacket_rewind) { - uint16_t max_seq = 3; + uint16_t max_seq = 15; SplitStrategyBySeq sn(&max_seq); + ASSERT_EQ(sn.prev_seq_, 0); + ASSERT_EQ(sn.safe_seq_min_, 0); + ASSERT_EQ(sn.safe_seq_max_, 10); - // rewind - ASSERT_FALSE(sn.newPacket(1)); + // init value ASSERT_FALSE(sn.newPacket(2)); + ASSERT_EQ(sn.prev_seq_, 2); + ASSERT_EQ(sn.safe_seq_min_, 0); + ASSERT_EQ(sn.safe_seq_max_, 12); + + ASSERT_FALSE(sn.newPacket(10)); + ASSERT_FALSE(sn.newPacket(14)); + ASSERT_EQ(sn.prev_seq_, 14); + ASSERT_EQ(sn.safe_seq_min_, 4); + ASSERT_EQ(sn.safe_seq_max_, 24); + ASSERT_TRUE(sn.newPacket(1)); + ASSERT_EQ(sn.prev_seq_, 1); + ASSERT_EQ(sn.safe_seq_min_, 0); + ASSERT_EQ(sn.safe_seq_max_, 11); } From bf6f3c6fd95081bf3fe46ba0a2e130f655351621 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 28 Dec 2021 09:24:27 +0800 Subject: [PATCH 122/379] fix: fix rsm1 split strategy --- .../driver/decoder/split_strategy.hpp | 23 +++++++++++-------- 1 file changed, 13 insertions(+), 10 deletions(-) diff --git a/src/rs_driver/driver/decoder/split_strategy.hpp b/src/rs_driver/driver/decoder/split_strategy.hpp index 47c8b1cd..1bf36c07 100644 --- a/src/rs_driver/driver/decoder/split_strategy.hpp +++ b/src/rs_driver/driver/decoder/split_strategy.hpp @@ -123,19 +123,27 @@ class SplitStrategyBySeq { bool split = false; - if (isSafe(seq)) + if (seq > safe_seq_max_) { - if (seq == *max_seq_) + // do nothing. drop it. + } + else if (seq > prev_seq_) + { + if (seq == *max_seq_) // reach end { prev_seq_ = 0; split = true; } - else if (seq > prev_seq_) + else { prev_seq_ = seq; } } - else if (seq < prev_seq_) + else if (seq > safe_seq_min_) + { + // do nothing. save it. + } + else // rewind { prev_seq_ = seq; split = true; @@ -153,15 +161,10 @@ class SplitStrategyBySeq void setSafeRange() { - safe_seq_min_ = (prev_seq_ > RANGE) ? prev_seq_ - RANGE : 0; + safe_seq_min_ = (prev_seq_ > RANGE) ? (prev_seq_ - RANGE) : 0; safe_seq_max_ = prev_seq_ + RANGE; } - bool isSafe(uint16_t seq) - { - return ((safe_seq_min_ < seq) && (seq < safe_seq_max_)); - } - uint16_t* max_seq_; uint16_t prev_seq_; uint16_t safe_seq_min_; From 8f5dae8292c59ff58c41be69adf97c3d838570b9 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 28 Dec 2021 11:36:15 +0800 Subject: [PATCH 123/379] refac: format --- src/rs_driver/driver/decoder/decoder_mech.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index 4f654c02..34fb883d 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -139,8 +139,8 @@ inline DecoderMech::DecoderMech(const RSDecoderParam& param, { this->param_.wait_for_difop = false; - RS_WARNING << "When config_from_file is true, wait_for_difop cannot be true." - << " Reset it to be false." << RS_REND; + RS_WARNING << "wait_for_difop cannot be true when config_from_file is true." + << " reset it to be false." << RS_REND; } } } From 829f2160a393bddc3ee036df25895ad354e1db1b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 28 Dec 2021 12:10:31 +0800 Subject: [PATCH 124/379] refac: reformat --- src/rs_driver/driver/decoder/decoder.hpp | 12 +++++----- .../driver/decoder/decoder_RS128.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS16.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 2 +- .../driver/decoder/decoder_RSHELIOS.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 2 +- src/rs_driver/driver/decoder/decoder_mech.hpp | 14 ++++++------ test/decoder_test.cpp | 22 +++++++++---------- 10 files changed, 31 insertions(+), 31 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 5e085eea..a0f73b71 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -248,9 +248,9 @@ class Decoder void processDifopPkt(const uint8_t* pkt, size_t size); void processMsopPkt(const uint8_t* pkt, size_t size); - explicit Decoder(const RSDecoderParam& param, - const std::function& excb, - const RSDecoderConstParam& const_param); + explicit Decoder(const RSDecoderConstParam& const_param, + const RSDecoderParam& param, + const std::function& excb); void regRecvCallback(const std::function(void)>& cb_get, const std::function)>& cb_put); @@ -290,9 +290,9 @@ class Decoder }; template -inline Decoder::Decoder(const RSDecoderParam& param, - const std::function& excb, - const RSDecoderConstParam& const_param) +inline Decoder::Decoder(const RSDecoderConstParam& const_param, + const RSDecoderParam& param, + const std::function& excb) : const_param_(const_param) , param_(param) , excb_(excb) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 39c69b03..adc907e3 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -176,7 +176,7 @@ RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) template inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(param, excb, initConstParam(rs_const_param_)) + : DecoderMech(initConstParam(rs_const_param_), param, excb) { } diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index cc2691d7..fcbdc08b 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -216,7 +216,7 @@ RSEchoMode DecoderRS16::getEchoMode(uint8_t mode) template inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(param, excb, initConstParam(rs_const_param_)) + : DecoderMech(initConstParam(rs_const_param_), param, excb) { this->height_ = 16; } diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 201e0255..28598884 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -218,7 +218,7 @@ RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) template inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(param, excb, initConstParam(rs_const_param_)) + : DecoderMech(initConstParam(rs_const_param_), param, excb) { } diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 2536fe26..091feb48 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -175,7 +175,7 @@ RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) template inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(param, excb, initConstParam(rs_const_param_)) + : DecoderMech(initConstParam(rs_const_param_), param, excb) { } diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 8e0f7690..7cb510e7 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -167,7 +167,7 @@ RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) template inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(param, excb, initConstParam(rs_const_param_)) + : DecoderMech(initConstParam(rs_const_param_), param, excb) { } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 35de5880..9debdfaa 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -179,7 +179,7 @@ RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) template inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(param, excb, initConstParam(rs_const_param_)) + : DecoderMech(initConstParam(rs_const_param_), param, excb) { } diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index c6cc8430..91f57165 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -178,7 +178,7 @@ RSDecoderConstParam DecoderRSM1::rs_const_param_ = template inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, const std::function& excb) - : Decoder(param, excb, rs_const_param_) + : Decoder(rs_const_param_, param, excb) , max_seq_(SINGLE_PKT_NUM) , split_(&max_seq_) { diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index 34fb883d..251b345b 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -62,9 +62,9 @@ class DecoderMech : public Decoder virtual ~DecoderMech() = default; - explicit DecoderMech(const RSDecoderParam& param, - const std::function& excb, - const RSDecoderMechConstParam& const_param); + explicit DecoderMech(const RSDecoderMechConstParam& const_param, + const RSDecoderParam& param, + const std::function& excb); void print(); @@ -91,10 +91,10 @@ class DecoderMech : public Decoder }; template -inline DecoderMech::DecoderMech(const RSDecoderParam& param, - const std::function& excb, - const RSDecoderMechConstParam& const_param) - : Decoder(param, excb, const_param.base) +inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& const_param, + const RSDecoderParam& param, + const std::function& excb) + : Decoder(const_param.base, param, excb) , mech_const_param_(const_param) , chan_angles_(this->const_param_.CHANNELS_PER_BLOCK) , scan_section_(this->param_.start_angle * 100, this->param_.end_angle * 100) diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index c34d1dfa..7053b920 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -30,10 +30,10 @@ template class MyDecoder : public DecoderMech { public: - MyDecoder(const RSDecoderParam& param, - const std::function& excb, - const RSDecoderMechConstParam& const_param) - : DecoderMech(param, excb, const_param) + MyDecoder(const RSDecoderMechConstParam& const_param, + const RSDecoderParam& param, + const std::function& excb) + : DecoderMech(const_param, param, excb) { } @@ -66,7 +66,7 @@ TEST(TestDecoder, angles_from_file) param.angle_path = "../rs_driver/test/res/angle.csv"; errCode = ERRCODE_SUCCESS; - MyDecoder decoder(param, errCallback, const_param); + MyDecoder decoder(const_param, param, errCallback); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_TRUE(decoder.angles_ready_); @@ -81,7 +81,7 @@ TEST(TestDecoder, angles_from_file_fail) param.config_from_file = true; param.angle_path = "../rs_driver/test/res/non_exist.csv"; - MyDecoder decoder(param, errCallback, const_param); + MyDecoder decoder(const_param, param, errCallback); ASSERT_FALSE(decoder.angles_ready_); } @@ -98,7 +98,7 @@ TEST(TestDecoder, processDifopPkt_fail) }; RSDecoderParam param; - MyDecoder decoder(param, errCallback, const_param); + MyDecoder decoder(const_param, param, errCallback); // wrong difop length MyDifopPkt pkt; @@ -131,7 +131,7 @@ TEST(TestDecoder, processDifopPkt) RSDecoderParam param; param.config_from_file = false; - MyDecoder decoder(param, errCallback, const_param); + MyDecoder decoder(const_param, param, errCallback); ASSERT_FALSE(decoder.angles_ready_); // @@ -208,7 +208,7 @@ TEST(TestDecoder, processDifopPkt_invalid_rpm) }; RSDecoderParam param; - MyDecoder decoder(param, errCallback, const_param); + MyDecoder decoder(const_param, param, errCallback); uint8_t pkt[] = { @@ -236,7 +236,7 @@ TEST(TestDecoder, processMsopPkt) MyMsopPkt pkt; RSDecoderParam param; - MyDecoder decoder(param, errCallback, const_param); + MyDecoder decoder(const_param, param, errCallback); // wait_for_difop = true, angles not ready decoder.param_.wait_for_difop = true; @@ -275,7 +275,7 @@ TEST(TestDecoder, setPointCloudHeader) const_param.base.CHANNELS_PER_BLOCK = 2; RSDecoderParam param; param.dense_points = true; - MyDecoder decoder(param, errCallback, const_param); + MyDecoder decoder(const_param, param, errCallback); ASSERT_EQ(decoder.point_cloud_seq_, 0); ASSERT_TRUE(decoder.param_.dense_points); From bd9e0a8ea3ea6f9e5f8a2ff40c2f38bf6e28581e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 28 Dec 2021 20:30:49 +0800 Subject: [PATCH 125/379] refac: move point cloud to driver_impl --- src/rs_driver/api/lidar_driver.h | 66 ++--- src/rs_driver/driver/decoder/decoder.hpp | 100 +++----- .../driver/decoder/decoder_RS128.hpp | 1 + src/rs_driver/driver/decoder/decoder_RS16.hpp | 115 ++++----- src/rs_driver/driver/decoder/decoder_RS32.hpp | 118 ++++----- src/rs_driver/driver/decoder/decoder_RS80.hpp | 1 + src/rs_driver/driver/decoder/decoder_RSBP.hpp | 109 ++++---- .../driver/decoder/decoder_RSHELIOS.hpp | 1 + src/rs_driver/driver/decoder/decoder_RSM1.hpp | 1 + .../driver/decoder/decoder_factory.hpp | 21 +- src/rs_driver/driver/decoder/decoder_mech.hpp | 14 +- src/rs_driver/driver/input/input_factory.hpp | 1 + src/rs_driver/driver/lidar_driver_impl.hpp | 232 +++++++++++------- src/rs_driver/msg/point_cloud_msg.h | 2 +- test/decoder_rs32_test.cpp | 27 +- test/decoder_rsbp_test.cpp | 27 +- test/decoder_test.cpp | 23 +- 17 files changed, 428 insertions(+), 431 deletions(-) diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index c2bd439a..3b260ef0 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -57,63 +57,57 @@ class LidarDriver } /** - * @brief The initialization function, used to set up parameters and instance objects, - * used when get packets from online lidar or pcap - * @param param The custom struct RSDriverParam - * @return If successful, return true; else return false - */ - inline bool init(const RSDriverParam& param) - { - return driver_ptr_->init(param); - } - - /** - * @brief Start the thread to receive and decode packets - * @return If successful, return true; else return false + * @brief Register the lidar point cloud callback function to driver. When point cloud is ready, this function will be + * called + * @param callback The callback function */ - inline bool start() + inline void regRecvCallback(const std::function(void)>& cb_get_pc, + const std::function)>& cb_put_pc) { - return driver_ptr_->start(); + driver_ptr_->regRecvCallback(cb_get_pc, cb_put_pc); } /** - * @brief Stop all threads + * @brief Register the lidar difop packet message callback function to driver. When lidar difop packet message is + * ready, this function will be called + * @param callback The callback function */ - inline void stop() + inline void regRecvCallback(const std::function& cb_pkt) { - driver_ptr_->stop(); + driver_ptr_->regRecvCallback(cb_pkt); } /** - * @brief Register the lidar point cloud callback function to driver. When point cloud is ready, this function will be - * called + * @brief Register the exception message callback function to driver. When error occurs, this function will be called * @param callback The callback function */ - inline void regRecvCallback(const std::function(void)>& cb_get, - const std::function)>& cb_put) + inline void regExceptionCallback(const std::function& cb_excp) { - driver_ptr_->regRecvCallback(cb_get, cb_put); + driver_ptr_->regExceptionCallback(cb_excp); } /** - * @brief Register the exception message callback function to driver. When error occurs, this function will be called - * @param callback The callback function + * @brief The initialization function, used to set up parameters and instance objects, + * used when get packets from online lidar or pcap + * @param param The custom struct RSDriverParam + * @return If successful, return true; else return false */ - inline void regExceptionCallback(const std::function& callback) + inline bool init(const RSDriverParam& param) { - driver_ptr_->regExceptionCallback(callback); + return driver_ptr_->init(param); } /** - * @brief Register the lidar difop packet message callback function to driver. When lidar difop packet message is - * ready, this function will be called - * @param callback The callback function + * @brief Start the thread to receive and decode packets + * @return If successful, return true; else return false */ - inline void regRecvCallback(const std::function& callback) + inline bool start() { - driver_ptr_->regRecvCallback(callback); + return driver_ptr_->start(); } + + /** * @brief Decode lidar msop/difop messages * @param pkt_msg The lidar msop/difop packet @@ -133,6 +127,14 @@ class LidarDriver return driver_ptr_->getTemperature(temp); } + /** + * @brief Stop all threads + */ + inline void stop() + { + driver_ptr_->stop(); + } + private: std::shared_ptr> driver_ptr_; ///< The driver pointer }; diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index a0f73b71..f5acabfe 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -234,7 +234,21 @@ struct RSDecoderConstParam float TEMPERATURE_RES; }; -template +struct RSPoint +{ + float x; + float y; + float z; + uint8_t intensity; + uint16_t ring; + double timestamp; +}; + +#define INIT_ONLY_ONCE() \ + static bool init_flag = false; \ + if (init_flag) return param; \ + init_flag = true; + class Decoder { public: @@ -248,13 +262,13 @@ class Decoder void processDifopPkt(const uint8_t* pkt, size_t size); void processMsopPkt(const uint8_t* pkt, size_t size); + void regRecvCallback(const std::function& cb_new_point, + const std::function& cb_split); + explicit Decoder(const RSDecoderConstParam& const_param, const RSDecoderParam& param, const std::function& excb); - void regRecvCallback(const std::function(void)>& cb_get, - const std::function)>& cb_put); - float getTemperature(); double getPacketDuration(); @@ -262,14 +276,11 @@ class Decoder protected: #endif - void splitFrame(); - void setPointCloudHeader(std::shared_ptr msg, double chan_ts); - RSDecoderConstParam const_param_; // const param RSDecoderParam param_; // user param + std::function cb_new_point_; + std::function cb_split_; std::function excb_; - std::function(void)> point_cloud_cb_get_; - std::function)> point_cloud_cb_put_; Trigon trigon_; #define SIN(angle) this->trigon_.sin(angle) @@ -284,13 +295,17 @@ class Decoder bool angles_ready_; // is vert_angles/horiz_angles ready from csv file/difop packet? double prev_point_ts_; // last point's timestamp - - std::shared_ptr point_cloud_; // curernt point cloud - uint32_t point_cloud_seq_; // sequence of point cloud }; -template -inline Decoder::Decoder(const RSDecoderConstParam& const_param, +inline void Decoder::regRecvCallback( + const std::function& cb_new_point, + const std::function& cb_split) +{ + cb_new_point_ = cb_new_point; + cb_split_ = cb_split; +} + +inline Decoder::Decoder(const RSDecoderConstParam& const_param, const RSDecoderParam& param, const std::function& excb) : const_param_(const_param) @@ -304,68 +319,20 @@ inline Decoder::Decoder(const RSDecoderConstParam& const_param, , temperature_(0.0) , angles_ready_(false) , prev_point_ts_(0.0) - , point_cloud_seq_(0) { } -template -float Decoder::getTemperature() +inline float Decoder::getTemperature() { return temperature_; } -template -double Decoder::getPacketDuration() +inline double Decoder::getPacketDuration() { return packet_duration_; } -template -void Decoder::regRecvCallback( - const std::function(void)>& cb_get, - const std::function)>& cb_put) -{ - point_cloud_cb_get_ = cb_get; - point_cloud_cb_put_ = cb_put; - - point_cloud_ = point_cloud_cb_get_(); -} - -template -inline void Decoder::splitFrame() -{ - if (point_cloud_->points.size() > 0) - { - setPointCloudHeader(point_cloud_, prev_point_ts_); - point_cloud_cb_put_(point_cloud_); - point_cloud_ = point_cloud_cb_get_(); - } - else - { - excb_(Error(ERRCODE_ZEROPOINTS)); - } -} - -template -void Decoder::setPointCloudHeader(std::shared_ptr msg, double chan_ts) -{ - msg->seq = point_cloud_seq_++; - msg->timestamp = chan_ts; - msg->is_dense = param_.dense_points; - if (msg->is_dense) - { - msg->height = 1; - msg->width = msg->points.size(); - } - else - { - msg->height = height_; - msg->width = msg->points.size() / msg->height; - } -} - -template -void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) +inline void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) { if (size != this->const_param_.DIFOP_LEN) { @@ -382,8 +349,7 @@ void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) decodeDifopPkt(pkt, size); } -template -void Decoder::processMsopPkt(const uint8_t* pkt, size_t size) +inline void Decoder::processMsopPkt(const uint8_t* pkt, size_t size) { if (param_.wait_for_difop && !angles_ready_) { diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index adc907e3..af08754e 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense { diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index fcbdc08b..8a61822d 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense @@ -131,10 +132,11 @@ inline void RS16DifopPkt2Adapter (const uint8_t* difop) } } -template -class DecoderRS16 : public DecoderMech +class DecoderRS16 : public DecoderMech { -public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); +public: + + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRS16() = default; @@ -145,41 +147,39 @@ public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); protected: #endif - static RSDecoderMechConstParam& initConstParam(RSDecoderMechConstParam& param); + static RSDecoderMechConstParam& initConstParam(); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - - static RSDecoderMechConstParam rs_const_param_; }; -template -RSDecoderMechConstParam DecoderRS16::rs_const_param_ = +inline RSDecoderMechConstParam& DecoderRS16::initConstParam() +{ + static RSDecoderMechConstParam param = { - 1248 // msop len - , 1248 // difop len - , 8 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + 1248 // msop len + , 1248 // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id , 12 // blocks per packet - , 32 // channels per block. how many channels in the msop block. - , 0.2f // distance min - , 150.0f // distance max - , 0.005f // distance resolution - , 0.0625f // temperature resolution - - // lens center - , 0.03825f // RX - , -0.01088f // RY - , 0.0f // RZ + , 32 // channels per block. how many channels in the msop block. + , 0.2f // distance min + , 150.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.03825f // RX + , -0.01088f // RY + , 0.0f // RZ }; -template -RSDecoderMechConstParam& DecoderRS16::initConstParam(RSDecoderMechConstParam& param) -{ + INIT_ONLY_ONCE(); + float blk_ts = 55.5f * 2; float firing_tss[] = { @@ -199,8 +199,7 @@ RSDecoderMechConstParam& DecoderRS16::initConstParam(RSDecoderMech return param; } -template -RSEchoMode DecoderRS16::getEchoMode(uint8_t mode) +inline RSEchoMode DecoderRS16::getEchoMode(uint8_t mode) { switch (mode) { @@ -213,16 +212,14 @@ RSEchoMode DecoderRS16::getEchoMode(uint8_t mode) } } -template -inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, +inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(initConstParam(rs_const_param_), param, excb) + : DecoderMech(initConstParam(), param, excb) { this->height_ = 16; } -template -inline void DecoderRS16::decodeDifopPkt(const uint8_t* packet, size_t size) +inline void DecoderRS16::decodeDifopPkt(const uint8_t* packet, size_t size) { RS16DifopPkt2Adapter (packet); @@ -234,8 +231,7 @@ inline void DecoderRS16::decodeDifopPkt(const uint8_t* packet, siz (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -template -inline void DecoderRS16::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline void DecoderRS16::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { @@ -247,9 +243,8 @@ inline void DecoderRS16::decodeMsopPkt(const uint8_t* pkt, size_t } } -template template -inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS16MsopPkt& pkt = *(const RS16MsopPkt*)(packet); @@ -285,7 +280,7 @@ inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet if (this->split_strategy_->newBlock(block_az)) { - this->splitFrame(); + this->cb_split_(this->height_, this->prev_point_ts_); } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -298,39 +293,31 @@ inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); - float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; - uint8_t intensity = channel.intensity; if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; - - typename T_PointCloud::PointT point; - setX(point, x); - setY(point, y); - setZ(point, z); - setIntensity(point, intensity); - - setTimestamp(point, chan_ts); - setRing(point, (this->chan_angles_.toUserChan(chan) >> 1)); - - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + point.intensity = channel.intensity; + point.timestamp = chan_ts; + point.ring = (this->chan_angles_.toUserChan(chan) >> 1); + + this->cb_new_point_(point); } else if (!this->param_.dense_points) { - typename T_PointCloud::PointT point; - setX(point, NAN); - setY(point, NAN); - setZ(point, NAN); - setIntensity(point, 0); - - setTimestamp(point, chan_ts); - setRing(point, (this->chan_angles_.toUserChan(chan) >> 1)); - - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = NAN; + point.y = NAN; + point.z = NAN; + point.intensity = 0; + point.timestamp = chan_ts; + point.ring = (this->chan_angles_.toUserChan(chan) >> 1); + + this->cb_new_point_(point); } this->prev_point_ts_ = chan_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 28598884..94794d49 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -131,8 +131,7 @@ inline void RS32DifopPkt2Adapter (const uint8_t* difop) } } -template -class DecoderRS32 : public DecoderMech +class DecoderRS32 : public DecoderMech { public: @@ -147,41 +146,39 @@ class DecoderRS32 : public DecoderMech protected: #endif - static RSDecoderMechConstParam& initConstParam(RSDecoderMechConstParam& param); + static RSDecoderMechConstParam& initConstParam(); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - - static RSDecoderMechConstParam rs_const_param_; }; -template -RSDecoderMechConstParam DecoderRS32::rs_const_param_ = +inline RSDecoderMechConstParam& DecoderRS32::initConstParam() { - 1248 // msop len - , 1248 // difop len - , 8 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id - , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0xFF, 0xEE} // block id - , 12 // blocks per packet - , 32 // channels per block - , 0.4f // distance min - , 200.0f // distance max - , 0.005f // distance resolution - , 0.0625f // temperature resolution - - // lens center - , 0.03997f // RX - , -0.01087f // RY - , 0.0f // RZ -}; + static RSDecoderMechConstParam param = + { + 1248 // msop len + , 1248 // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 12 // blocks per packet + , 32 // channels per block + , 0.4f // distance min + , 200.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.03997f // RX + , -0.01087f // RY + , 0.0f // RZ + }; + + INIT_ONLY_ONCE(); -template -RSDecoderMechConstParam& DecoderRS32::initConstParam(RSDecoderMechConstParam& param) -{ float blk_ts = 55.52f; float firing_tss[] = { @@ -201,8 +198,7 @@ RSDecoderMechConstParam& DecoderRS32::initConstParam(RSDecoderMech return param; } -template -RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) +inline RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) { switch (mode) { @@ -215,15 +211,13 @@ RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) } } -template -inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, +inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(initConstParam(rs_const_param_), param, excb) + : DecoderMech(initConstParam(), param, excb) { } -template -inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, size_t size) +inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, size_t size) { RS32DifopPkt2Adapter (packet); @@ -235,8 +229,7 @@ inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, siz (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -template -inline void DecoderRS32::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline void DecoderRS32::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { @@ -248,9 +241,8 @@ inline void DecoderRS32::decodeMsopPkt(const uint8_t* pkt, size_t } } -template template -inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS32MsopPkt& pkt = *(const RS32MsopPkt*)(packet); @@ -286,7 +278,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet if (this->split_strategy_->newBlock(block_az)) { - this->splitFrame(); + this->cb_split_(this->height_, this->prev_point_ts_); } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -299,39 +291,31 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); - float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; - uint8_t intensity = channel.intensity; if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; - - typename T_PointCloud::PointT point; - setX(point, x); - setY(point, y); - setZ(point, z); - setIntensity(point, intensity); - - setTimestamp(point, chan_ts); - setRing(point, this->chan_angles_.toUserChan(chan)); - - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + point.intensity = channel.intensity; + point.timestamp = chan_ts; + point.ring = this->chan_angles_.toUserChan(chan); + + this->cb_new_point_(point); } else if (!this->param_.dense_points) { - typename T_PointCloud::PointT point; - setX(point, NAN); - setY(point, NAN); - setZ(point, NAN); - setIntensity(point, 0); - - setTimestamp(point, chan_ts); - setRing(point, this->chan_angles_.toUserChan(chan)); - - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = NAN; + point.y = NAN; + point.z = NAN; + point.intensity = 0; + point.timestamp = chan_ts; + point.ring = this->chan_angles_.toUserChan(chan); + + this->cb_new_point_(point); } this->prev_point_ts_ = chan_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 091feb48..9b57099c 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 7cb510e7..4147c524 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense @@ -80,8 +81,7 @@ typedef struct #pragma pack(pop) -template -class DecoderRSBP : public DecoderMech +class DecoderRSBP : public DecoderMech { public: @@ -96,41 +96,39 @@ class DecoderRSBP : public DecoderMech protected: #endif - static RSDecoderMechConstParam& initConstParam(RSDecoderMechConstParam& param); + static RSDecoderMechConstParam& initConstParam(); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - - static RSDecoderMechConstParam rs_const_param_; }; -template -RSDecoderMechConstParam DecoderRSBP::rs_const_param_ = +inline RSDecoderMechConstParam& DecoderRSBP::initConstParam() +{ + static RSDecoderMechConstParam param = { - 1248 // msop len - , 1248 // difop len - , 8 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + 1248 // msop len + , 1248 // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id , 12 // blocks per packet - , 32 // channels per block - , 0.1f // distance min - , 100.0f // distance max - , 0.005f // distance resolution - , 0.0625f // temperature resolution - - // lens center - , 0.01473f // RX - , 0.0085f // RY - , 0.09427f // RZ + , 32 // channels per block + , 0.1f // distance min + , 100.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.01473f // RX + , 0.0085f // RY + , 0.09427f // RZ }; -template -RSDecoderMechConstParam& DecoderRSBP::initConstParam(RSDecoderMechConstParam& param) -{ + INIT_ONLY_ONCE(); + float blk_ts = 55.52f; float firing_tss[] = { @@ -150,8 +148,7 @@ RSDecoderMechConstParam& DecoderRSBP::initConstParam(RSDecoderMech return param; } -template -RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) +inline RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) { switch (mode) { @@ -164,15 +161,13 @@ RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) } } -template -inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, +inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(initConstParam(rs_const_param_), param, excb) + : DecoderMech(initConstParam(), param, excb) { } -template -inline void DecoderRSBP::decodeDifopPkt(const uint8_t* packet, size_t size) +inline void DecoderRSBP::decodeDifopPkt(const uint8_t* packet, size_t size) { const RSBPDifopPkt& pkt = *(const RSBPDifopPkt*)(packet); this->template decodeDifopCommon(pkt); @@ -182,8 +177,7 @@ inline void DecoderRSBP::decodeDifopPkt(const uint8_t* packet, siz (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -template -inline void DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline void DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { @@ -195,9 +189,8 @@ inline void DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, size_t } } -template template -inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RSBPMsopPkt& pkt = *(const RSBPMsopPkt*)(packet); @@ -233,7 +226,7 @@ inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet if (this->split_strategy_->newBlock(block_az)) { - this->splitFrame(); + this->cb_split_(this->height_, this->prev_point_ts_); } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -248,37 +241,29 @@ inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; - uint8_t intensity = channel.intensity; if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; - - typename T_PointCloud::PointT point; - setX(point, x); - setY(point, y); - setZ(point, z); - setIntensity(point, intensity); - - setTimestamp(point, chan_ts); - setRing(point, this->chan_angles_.toUserChan(chan)); - - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + point.intensity = channel.intensity; + point.timestamp = chan_ts; + point.ring = this->chan_angles_.toUserChan(chan); + + this->cb_new_point_(point); } else if (!this->param_.dense_points) { - typename T_PointCloud::PointT point; - setX(point, NAN); - setY(point, NAN); - setZ(point, NAN); - setIntensity(point, 0); - - setTimestamp(point, chan_ts); - setRing(point, this->chan_angles_.toUserChan(chan)); - - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = NAN; + point.y = NAN; + point.z = NAN; + point.intensity = 0; + point.timestamp = chan_ts; + point.ring = this->chan_angles_.toUserChan(chan); + this->cb_new_point_(point); } this->prev_point_ts_ = chan_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 9debdfaa..4c0190a2 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 91f57165..c57c0ab7 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index e083c030..5483624c 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -30,45 +30,47 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include #include #include +#if 0 #include #include #include #include +#endif namespace robosense { namespace lidar { -template class DecoderFactory { public: - static std::shared_ptr> createDecoder(LidarType type, + static std::shared_ptr createDecoder(LidarType type, const RSDecoderParam& param, const std::function& excb); }; -template -inline std::shared_ptr> -DecoderFactory::createDecoder(LidarType type, const RSDecoderParam& param, +inline std::shared_ptr +DecoderFactory::createDecoder(LidarType type, const RSDecoderParam& param, const std::function& excb) { - std::shared_ptr> ret_ptr; + std::shared_ptr ret_ptr; switch (type) { case LidarType::RS16: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared(param, excb); break; case LidarType::RS32: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared(param, excb); break; case LidarType::RSBP: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared(param, excb); break; +#if 0 case LidarType::RSHELIOS: ret_ptr = std::make_shared>(param, excb); break; @@ -81,6 +83,7 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam case LidarType::RSM1: ret_ptr = std::make_shared>(param, excb); break; +#endif default: RS_ERROR << "Wrong LiDAR Type. Please check your LiDAR Version! " << RS_REND; exit(-1); diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index 251b345b..4f60a04c 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -53,8 +53,7 @@ struct RSDecoderMechConstParam float CHAN_AZIS[128]; }; -template -class DecoderMech : public Decoder +class DecoderMech : public Decoder { public: @@ -90,11 +89,10 @@ class DecoderMech : public Decoder float lidar_Rxy_; // lens center related }; -template -inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& const_param, +inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& const_param, const RSDecoderParam& param, const std::function& excb) - : Decoder(const_param.base, param, excb) + : Decoder(const_param.base, param, excb) , mech_const_param_(const_param) , chan_angles_(this->const_param_.CHANNELS_PER_BLOCK) , scan_section_(this->param_.start_angle * 100, this->param_.end_angle * 100) @@ -145,8 +143,7 @@ inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& con } } -template -void DecoderMech::print() +inline void DecoderMech::print() { std::cout << "-----------------------------------------" << std::endl << "rps:\t\t\t" << this->rps_ << std::endl @@ -161,9 +158,8 @@ void DecoderMech::print() this->chan_angles_.print(); } -template template -inline void DecoderMech::decodeDifopCommon(const T_Difop& pkt) +inline void DecoderMech::decodeDifopCommon(const T_Difop& pkt) { // rounds per second this->rps_ = ntohs(pkt.rpm) / 60; diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index fce36ab9..850023cd 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -30,6 +30,7 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#pragma once #include #include #include diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 7c437859..69adc9d3 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -47,35 +47,38 @@ namespace robosense namespace lidar { +inline std::string getDriverVersion() +{ + std::stringstream stream; + stream << RSLIDAR_VERSION_MAJOR << "." + << RSLIDAR_VERSION_MINOR << "." + << RSLIDAR_VERSION_PATCH; + + return stream.str(); +} + template class LidarDriverImpl { public: - static std::string getVersion(); - LidarDriverImpl(); ~LidarDriverImpl(); + void regRecvCallback(const std::function(void)>& cb_get_pc, + const std::function)>& cb_put_pc); + void regRecvCallback(const std::function& cb_pkt); + void regExceptionCallback(const std::function& cb_excp); + bool init(const RSDriverParam& param); bool start(); void stop(); - void regRecvCallback(const std::function(void)>& cb_get, - const std::function)>& cb_put); - void regRecvCallback(const std::function& callback); - void regExceptionCallback(const std::function& callback); - void decodePacket(const uint8_t* pkt, size_t size); + void decodePacket(const uint8_t* pkt, size_t size); bool getTemperature(float& temp); private: - std::function(void)> point_cloud_cb_get_; - std::function)> point_cloud_cb_put_; - - std::shared_ptr getPointCloud(); - void putPointCloud(std::shared_ptr pc); - void runCallBack(std::shared_ptr pkt); void reportError(const Error& error); @@ -85,13 +88,20 @@ class LidarDriverImpl void processMsop(); void processDifop(); -private: + std::shared_ptr getPointCloud(); + void newPoint(const RSPoint& point); + void splitFrame(uint16_t height, double ts); + void setPointCloudHeader(std::shared_ptr msg, uint16_t height, double chan_ts); + RSDriverParam driver_param_; - std::function pkt_cb_; - std::function feed_pkt_cb_; - std::function err_cb_; - std::shared_ptr> lidar_decoder_ptr_; + std::function(void)> cb_get_pc_; + std::function)> cb_put_pc_; + std::function cb_pkt_; + std::function cb_excp_; + std::function cb_feed_pkt_; + std::shared_ptr input_ptr_; + std::shared_ptr lidar_decoder_ptr_; SyncQueue> free_pkt_queue_; SyncQueue> msop_pkt_queue_; SyncQueue> difop_pkt_queue_; @@ -101,29 +111,63 @@ class LidarDriverImpl bool init_flag_; bool start_flag_; uint32_t pkt_seq_; - uint32_t ndifop_count_; + + std::shared_ptr point_cloud_; + uint32_t point_cloud_seq_; }; -inline std::string getDriverVersion() +template +inline LidarDriverImpl::LidarDriverImpl() + : init_flag_(false), start_flag_(false), pkt_seq_(0), point_cloud_seq_(0) { - std::stringstream stream; - stream << RSLIDAR_VERSION_MAJOR << "." - << RSLIDAR_VERSION_MINOR << "." - << RSLIDAR_VERSION_PATCH; +} - return stream.str(); +template +inline LidarDriverImpl::~LidarDriverImpl() +{ + stop(); } template -inline LidarDriverImpl::LidarDriverImpl() - : init_flag_(false), start_flag_(false), pkt_seq_(0), ndifop_count_(0) +std::shared_ptr LidarDriverImpl::getPointCloud() { + while (1) + { + std::shared_ptr pc = cb_get_pc_(); + if (pc) + { + pc->points.resize(0); + return pc; + } + + reportError(Error(ERRCODE_POINTCLOUDNULL)); + std::this_thread::sleep_for(std::chrono::milliseconds(300)); + } } template -inline LidarDriverImpl::~LidarDriverImpl() +void LidarDriverImpl::regRecvCallback( + const std::function(void)>& cb_get, + const std::function)>& cb_put) { - stop(); + cb_get_pc_ = cb_get; + cb_put_pc_ = cb_put; + + point_cloud_ = getPointCloud(); +} + +template +inline void LidarDriverImpl::regRecvCallback( + const std::function& cb_pkt) +{ + cb_pkt_ = cb_pkt; +} + +template +inline void LidarDriverImpl::regExceptionCallback( + const std::function& cb_excp) +{ + cb_excp_ = cb_excp; } template @@ -134,19 +178,13 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) return true; } - lidar_decoder_ptr_ = DecoderFactory::createDecoder( + lidar_decoder_ptr_ = DecoderFactory::createDecoder( param.lidar_type, param.decoder_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); - if ((point_cloud_cb_get_ == nullptr) || (point_cloud_cb_put_ == nullptr)) - { - std::cout << "please set point cloud callback first." << std::endl; - return false; - } - - lidar_decoder_ptr_->regRecvCallback( - std::bind(&LidarDriverImpl::getPointCloud, this), - std::bind(&LidarDriverImpl::putPointCloud, this, std::placeholders::_1)); + lidar_decoder_ptr_->regRecvCallback( + std::bind(&LidarDriverImpl::newPoint, this, std::placeholders::_1), + std::bind(&LidarDriverImpl::splitFrame, this, std::placeholders::_1, std::placeholders::_2)); double packet_duration = lidar_decoder_ptr_->getPacketDuration(); @@ -154,13 +192,15 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1), packet_duration); - input_ptr_->regRecvCallback(std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), - std::bind(&LidarDriverImpl::packetPut, this, std::placeholders::_1)); + input_ptr_->regRecvCallback( + std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), + std::bind(&LidarDriverImpl::packetPut, this, std::placeholders::_1)); if (param.input_type == InputType::RAW_PACKET) { InputRaw* inputRaw = dynamic_cast(input_ptr_.get()); - feed_pkt_cb_ = std::bind(&InputRaw::feedPacket, inputRaw, std::placeholders::_1, std::placeholders::_2); + cb_feed_pkt_ = + std::bind(&InputRaw::feedPacket, inputRaw, std::placeholders::_1, std::placeholders::_2); } if (!input_ptr_->init()) @@ -192,8 +232,10 @@ inline bool LidarDriverImpl::start() } to_exit_handle_ = false; - msop_handle_thread_ = std::thread(std::bind(&LidarDriverImpl::processMsop, this)); - difop_handle_thread_ = std::thread(std::bind(&LidarDriverImpl::processDifop, this)); + msop_handle_thread_ = + std::thread(std::bind(&LidarDriverImpl::processMsop, this)); + difop_handle_thread_ = + std::thread(std::bind(&LidarDriverImpl::processDifop, this)); input_ptr_->start(); @@ -219,53 +261,10 @@ inline void LidarDriverImpl::stop() } } -template -void LidarDriverImpl::regRecvCallback(const std::function(void)>& cb_get, - const std::function)>& cb_put) -{ - point_cloud_cb_get_ = cb_get; - point_cloud_cb_put_ = cb_put; -} - -template -inline void LidarDriverImpl::regRecvCallback(const std::function& callback) -{ - pkt_cb_ = callback; -} - -template -inline void LidarDriverImpl::regExceptionCallback(const std::function& callback) -{ - err_cb_ = callback; -} - -template -std::shared_ptr LidarDriverImpl::getPointCloud() -{ - while (1) - { - std::shared_ptr pc = point_cloud_cb_get_(); - if (pc) - { - pc->points.resize(0); - return pc; - } - - reportError(Error(ERRCODE_POINTCLOUDNULL)); - std::this_thread::sleep_for(std::chrono::milliseconds(300)); - } -} - -template -void LidarDriverImpl::putPointCloud(std::shared_ptr pc) -{ - point_cloud_cb_put_(pc); -} - template inline void LidarDriverImpl::decodePacket(const uint8_t* pkt, size_t size) { - feed_pkt_cb_(pkt, size); + cb_feed_pkt_(pkt, size); } template @@ -282,18 +281,18 @@ inline bool LidarDriverImpl::getTemperature(float& temp) template inline void LidarDriverImpl::runCallBack(std::shared_ptr pkt) { - if (pkt_cb_) + if (cb_pkt_) { - pkt_cb_(pkt->data(), pkt->dataSize()); + cb_pkt_(pkt->data(), pkt->dataSize()); } } template inline void LidarDriverImpl::reportError(const Error& error) { - if (err_cb_) + if (cb_excp_) { - err_cb_(error); + cb_excp_(error); } } @@ -375,5 +374,54 @@ inline void LidarDriverImpl::processDifop() } } +template +void LidarDriverImpl::newPoint(const RSPoint& pt) +{ + typename T_PointCloud::PointT point; + setX(point, pt.x); + setY(point, pt.y); + setZ(point, pt.z); + setIntensity(point, pt.intensity); + setRing(point, pt.ring); + setTimestamp(point, pt.timestamp); + + point_cloud_->points.emplace_back(point); +} + +template +void LidarDriverImpl::splitFrame(uint16_t height, double ts) +{ + if (point_cloud_->points.size() > 0) + { + setPointCloudHeader(point_cloud_, height, ts); + cb_put_pc_(point_cloud_); + + point_cloud_ = getPointCloud(); + } + else + { + reportError(Error(ERRCODE_ZEROPOINTS)); + } +} + +template +void LidarDriverImpl::setPointCloudHeader(std::shared_ptr msg, + uint16_t height, double ts) +{ + msg->seq = point_cloud_seq_++; + msg->timestamp = ts; + msg->is_dense = driver_param_.decoder_param.dense_points; + if (msg->is_dense) + { + msg->height = 1; + msg->width = msg->points.size(); + } + else + { + msg->height = height; + msg->width = msg->points.size() / msg->height; + } +} + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/msg/point_cloud_msg.h b/src/rs_driver/msg/point_cloud_msg.h index fcbf0d9c..bbab3942 100644 --- a/src/rs_driver/msg/point_cloud_msg.h +++ b/src/rs_driver/msg/point_cloud_msg.h @@ -59,7 +59,7 @@ class PointCloudT uint32_t height = 0; ///< Height of point cloud uint32_t width = 0; ///< Width of point cloud - bool is_dense = false; ///< If is_dense=true, the point cloud does not contain NAN points + bool is_dense = false; ///< If is_dense is true, the point cloud does not contain NAN points, double timestamp = 0.0; std::string frame_id = "rslidar"; ///< Point cloud frame id uint32_t seq = 0; ///< Sequence number of message diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index 616b4e0c..a1588c87 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -18,16 +18,16 @@ static void errCallback(const Error& err) TEST(TestDecoderRS32, getEchoMode) { - ASSERT_TRUE(DecoderRS32::getEchoMode(0) == RSEchoMode::ECHO_DUAL); - ASSERT_TRUE(DecoderRS32::getEchoMode(1) == RSEchoMode::ECHO_SINGLE); - ASSERT_TRUE(DecoderRS32::getEchoMode(2) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(DecoderRS32::getEchoMode(0) == RSEchoMode::ECHO_DUAL); + ASSERT_TRUE(DecoderRS32::getEchoMode(1) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(DecoderRS32::getEchoMode(2) == RSEchoMode::ECHO_SINGLE); } TEST(TestDecoderRS32, decodeDifopPkt) { // const_param RSDecoderParam param; - DecoderRS32 decoder(param, errCallback); + DecoderRS32 decoder(param, errCallback); ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.split_blks_per_frame_, 1801); @@ -51,6 +51,17 @@ TEST(TestDecoderRS32, decodeDifopPkt) ASSERT_EQ(decoder.split_blks_per_frame_, 900); } +static std::vector points; + +static void newPoint(const RSPoint& point) +{ + points.emplace_back(point); +} + +static void splitFrame(uint16_t height, double ts) +{ +} + TEST(TestDecoderRS32, decodeMsopPkt) { uint8_t pkt[] = @@ -144,20 +155,20 @@ TEST(TestDecoderRS32, decodeMsopPkt) // dense_points = false, use_lidar_clock = true RSDecoderParam param; - DecoderRS32 decoder(param, errCallback); + DecoderRS32 decoder(param, errCallback); ASSERT_EQ(decoder.chan_angles_.user_chans_.size(), 32); decoder.chan_angles_.user_chans_[0] = 2; decoder.chan_angles_.user_chans_[1] = 1; decoder.param_.dense_points = false; decoder.param_.use_lidar_clock = true; - decoder.point_cloud_ = std::make_shared(); + decoder.regRecvCallback(newPoint, splitFrame); decoder.decodeMsopPkt(pkt, sizeof(pkt)); ASSERT_EQ(decoder.getTemperature(), 2.1875); - ASSERT_EQ(decoder.point_cloud_->points.size(), 32); + ASSERT_EQ(points.size(), 32); - PointT& point = decoder.point_cloud_->points[0]; + RSPoint& point = points[0]; ASSERT_EQ(point.intensity, 1); ASSERT_NE(point.timestamp, 0); ASSERT_EQ(point.ring, 2); diff --git a/test/decoder_rsbp_test.cpp b/test/decoder_rsbp_test.cpp index 54b929fa..41f340b8 100644 --- a/test/decoder_rsbp_test.cpp +++ b/test/decoder_rsbp_test.cpp @@ -18,16 +18,16 @@ static void errCallback(const Error& err) TEST(TestDecoderRSBP, getEchoMode) { - ASSERT_TRUE(DecoderRSBP::getEchoMode(0) == RSEchoMode::ECHO_DUAL); - ASSERT_TRUE(DecoderRSBP::getEchoMode(1) == RSEchoMode::ECHO_SINGLE); - ASSERT_TRUE(DecoderRSBP::getEchoMode(2) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(DecoderRSBP::getEchoMode(0) == RSEchoMode::ECHO_DUAL); + ASSERT_TRUE(DecoderRSBP::getEchoMode(1) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(DecoderRSBP::getEchoMode(2) == RSEchoMode::ECHO_SINGLE); } TEST(TestDecoderRSBP, decodeDifopPkt) { // const_param RSDecoderParam param; - DecoderRSBP decoder(param, errCallback); + DecoderRSBP decoder(param, errCallback); ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.split_blks_per_frame_, 1801); @@ -52,6 +52,17 @@ TEST(TestDecoderRSBP, decodeDifopPkt) ASSERT_EQ(decoder.split_blks_per_frame_, 900); } +static std::vector points; + +static void newPoint(const RSPoint& point) +{ + points.emplace_back(point); +} + +static void splitFrame(uint16_t height, double ts) +{ +} + TEST(TestDecoderRSBP, decodeMsopPkt) { uint8_t pkt[] = @@ -145,7 +156,7 @@ TEST(TestDecoderRSBP, decodeMsopPkt) // dense_points = false, use_lidar_clock = true RSDecoderParam param; - DecoderRSBP decoder(param, errCallback); + DecoderRSBP decoder(param, errCallback); ASSERT_EQ(decoder.chan_angles_.user_chans_.size(), 32); decoder.chan_angles_.user_chans_[0] = 2; @@ -153,13 +164,13 @@ TEST(TestDecoderRSBP, decodeMsopPkt) decoder.param_.dense_points = false; decoder.param_.use_lidar_clock = true; - decoder.point_cloud_ = std::make_shared(); + decoder.regRecvCallback(newPoint, splitFrame); decoder.decodeMsopPkt(pkt, sizeof(pkt)); ASSERT_EQ(decoder.getTemperature(), 2.1875); - ASSERT_EQ(decoder.point_cloud_->points.size(), 32); + ASSERT_EQ(points.size(), 32); - PointT& point = decoder.point_cloud_->points[0]; + RSPoint& point = points[0]; ASSERT_EQ(point.intensity, 1); ASSERT_NE(point.timestamp, 0); ASSERT_EQ(point.ring, 2); diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 7053b920..5df80181 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -26,14 +26,13 @@ struct MyDifopPkt }; #pragma pack(pop) -template -class MyDecoder : public DecoderMech +class MyDecoder : public DecoderMech { public: MyDecoder(const RSDecoderMechConstParam& const_param, const RSDecoderParam& param, const std::function& excb) - : DecoderMech(const_param, param, excb) + : DecoderMech(const_param, param, excb) { } @@ -66,7 +65,7 @@ TEST(TestDecoder, angles_from_file) param.angle_path = "../rs_driver/test/res/angle.csv"; errCode = ERRCODE_SUCCESS; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param, errCallback); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_TRUE(decoder.angles_ready_); @@ -81,7 +80,7 @@ TEST(TestDecoder, angles_from_file_fail) param.config_from_file = true; param.angle_path = "../rs_driver/test/res/non_exist.csv"; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param, errCallback); ASSERT_FALSE(decoder.angles_ready_); } @@ -98,7 +97,7 @@ TEST(TestDecoder, processDifopPkt_fail) }; RSDecoderParam param; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param, errCallback); // wrong difop length MyDifopPkt pkt; @@ -131,7 +130,7 @@ TEST(TestDecoder, processDifopPkt) RSDecoderParam param; param.config_from_file = false; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param, errCallback); ASSERT_FALSE(decoder.angles_ready_); // @@ -208,7 +207,7 @@ TEST(TestDecoder, processDifopPkt_invalid_rpm) }; RSDecoderParam param; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param, errCallback); uint8_t pkt[] = { @@ -236,7 +235,7 @@ TEST(TestDecoder, processMsopPkt) MyMsopPkt pkt; RSDecoderParam param; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param, errCallback); // wait_for_difop = true, angles not ready decoder.param_.wait_for_difop = true; @@ -268,6 +267,7 @@ TEST(TestDecoder, processMsopPkt) ASSERT_EQ(errCode, ERRCODE_SUCCESS); } +#if 0 TEST(TestDecoder, setPointCloudHeader) { // dense_points @@ -275,7 +275,7 @@ TEST(TestDecoder, setPointCloudHeader) const_param.base.CHANNELS_PER_BLOCK = 2; RSDecoderParam param; param.dense_points = true; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param, errCallback); ASSERT_EQ(decoder.point_cloud_seq_, 0); ASSERT_TRUE(decoder.param_.dense_points); @@ -306,7 +306,6 @@ TEST(TestDecoder, setPointCloudHeader) } } -#if 0 std::shared_ptr point_cloud_to_get; std::shared_ptr getCallback(void) @@ -332,7 +331,7 @@ TEST(TestDecoder, split_by_angle) param.split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; param.split_angle = 0.0f; - MyDecoder decoder(param, errCallback, const_param); + MyDecoder decoder(param, errCallback, const_param); point_cloud_to_get = std::make_shared(); decoder.regRecvCallback (getCallback, putCallback); From a80847a9d4b007d3584eea27ca9492f702883b75 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 28 Dec 2021 20:32:10 +0800 Subject: [PATCH 126/379] refac --- demo/demo_online.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 5a5e0696..05d46511 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -83,7 +83,7 @@ int main(int argc, char* argv[]) param.input_type = InputType::ONLINE_LIDAR; param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RS80; ///< Set the lidar type. Make sure this type is correct + param.lidar_type = LidarType::RS32; ///< Set the lidar type. Make sure this type is correct param.decoder_param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet param.print(); From 9b6c6493962a895d2a689058a6992eb46ec70d63 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 29 Dec 2021 09:59:35 +0800 Subject: [PATCH 127/379] refac: move point cloud to driver_impl --- src/rs_driver/driver/decoder/decoder.hpp | 8 +- .../driver/decoder/decoder_RS128.hpp | 153 ++++++++---------- src/rs_driver/driver/decoder/decoder_RS16.hpp | 8 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 8 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 132 +++++++-------- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 8 +- .../driver/decoder/decoder_RSHELIOS.hpp | 112 ++++++------- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 60 +++---- .../driver/decoder/decoder_factory.hpp | 12 +- 9 files changed, 219 insertions(+), 282 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index f5acabfe..c1bd67a4 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -263,7 +263,7 @@ class Decoder void processMsopPkt(const uint8_t* pkt, size_t size); void regRecvCallback(const std::function& cb_new_point, - const std::function& cb_split); + const std::function& cb_split_frame); explicit Decoder(const RSDecoderConstParam& const_param, const RSDecoderParam& param, @@ -279,7 +279,7 @@ class Decoder RSDecoderConstParam const_param_; // const param RSDecoderParam param_; // user param std::function cb_new_point_; - std::function cb_split_; + std::function cb_split_frame_; std::function excb_; Trigon trigon_; @@ -299,10 +299,10 @@ class Decoder inline void Decoder::regRecvCallback( const std::function& cb_new_point, - const std::function& cb_split) + const std::function& cb_split_frame) { cb_new_point_ = cb_new_point; - cb_split_ = cb_split; + cb_split_frame_ = cb_split_frame; } inline Decoder::Decoder(const RSDecoderConstParam& const_param, diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index af08754e..69411b31 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -32,6 +32,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include + namespace robosense { namespace lidar @@ -78,8 +79,7 @@ typedef struct #pragma pack(pop) -template -class DecoderRS128 : public DecoderMech +class DecoderRS128 : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); @@ -93,61 +93,59 @@ class DecoderRS128 : public DecoderMech protected: #endif - static RSDecoderMechConstParam& initConstParam(RSDecoderMechConstParam& param); + static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - - static RSDecoderMechConstParam rs_const_param_; }; -template -RSDecoderMechConstParam DecoderRS128::rs_const_param_ = +RSDecoderMechConstParam& DecoderRS128::getConstParam() { - 1248 // msop len - , 1248 // difop len - , 4 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x5A} // msop id - , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0xFE} // block id - , 3 // blocks per packet - , 128 // channels per block - , 1.0f // distance min - , 250.0f // distance max - , 0.005f // distance resolution - , 0.0625f // temperature resolution - - // lens center - , 0.03615f // RX - , -0.017f // RY - , 0.0f // RZ -}; + static RSDecoderMechConstParam param = + { + 1248 // msop len + , 1248 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x5A} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFE} // block id + , 3 // blocks per packet + , 128 // channels per block + , 1.0f // distance min + , 250.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.03615f // RX + , -0.017f // RY + , 0.0f // RZ + }; + + INIT_ONLY_ONCE(); -template -RSDecoderMechConstParam& DecoderRS128::initConstParam(RSDecoderMechConstParam& param) -{ float blk_ts = 55.55f; float firing_tss[] = { - 0.00f, 0.00f, 0.00f, 0.00f, 3.236f, 3.236f, 3.236f, 3.236f, - 6.472f, 6.472f, 6.472f, 6.472f, 9.708f, 9.708f, 9.708f, 9.708f, - 12.944f, 12.944f, 12.944f, 12.944f, 16.18f, 16.18f, 16.18f, 16.18f, - 19.416f, 19.416f, 19.416f, 19.416f, 22.652f, 22.652f, 22.652f, 22.652f, - 25.888f, 25.888f, 25.888f, 25.888f, 29.124f, 29.124f, 29.124f, 29.124f, - 332.36f, 32.36f, 32.36f, 32.36f, 35.596f, 35.596f, 35.596f, 35.596f, - 38.832f, 38.832f, 38.832f, 38.832f, 42.068f, 42.068f, 42.068f, 42.068f, - 45.304f, 45.304f, 45.304f, 45.304f, 48.54f, 48.54f, 48.54f, 48.54f, - - 00.00f, 0.00f, 0.00f, 0.00f, 3.236f, 3.236f, 3.236f, 3.236f, - 6.472f, 6.472f, 6.472f, 6.472f, 9.708f, 9.708f, 9.708f, 9.708f, - 12.944f, 12.944f, 12.944f, 12.944f, 16.18f, 16.18f, 16.18f, 16.18f, - 19.416f, 19.416f, 19.416f, 19.416f, 22.652f, 22.652f, 22.652f, 22.652f, - 25.888f, 25.888f, 25.888f, 25.888f, 29.124f, 29.124f, 29.124f, 29.124f, - 32.36f, 32.36f, 32.36f, 32.36f, 35.596f, 35.596f, 35.596f, 35.596f, - 38.832f, 38.832f, 38.832f, 38.832f, 42.068f, 42.068f, 42.068f, 42.068f, - 45.304f, 45.304f, 45.304f, 45.304f, 48.54f, 48.54f, 48.54f, 48.54f + 0.00f, 0.00f, 0.00f, 0.00f, 3.236f, 3.236f, 3.236f, 3.236f, + 6.472f, 6.472f, 6.472f, 6.472f, 9.708f, 9.708f, 9.708f, 9.708f, + 12.944f, 12.944f, 12.944f, 12.944f, 16.18f, 16.18f, 16.18f, 16.18f, + 19.416f, 19.416f, 19.416f, 19.416f, 22.652f, 22.652f, 22.652f, 22.652f, + 25.888f, 25.888f, 25.888f, 25.888f, 29.124f, 29.124f, 29.124f, 29.124f, + 332.36f, 32.36f, 32.36f, 32.36f, 35.596f, 35.596f, 35.596f, 35.596f, + 38.832f, 38.832f, 38.832f, 38.832f, 42.068f, 42.068f, 42.068f, 42.068f, + 45.304f, 45.304f, 45.304f, 45.304f, 48.54f, 48.54f, 48.54f, 48.54f, + + 00.00f, 0.00f, 0.00f, 0.00f, 3.236f, 3.236f, 3.236f, 3.236f, + 6.472f, 6.472f, 6.472f, 6.472f, 9.708f, 9.708f, 9.708f, 9.708f, + 12.944f, 12.944f, 12.944f, 12.944f, 16.18f, 16.18f, 16.18f, 16.18f, + 19.416f, 19.416f, 19.416f, 19.416f, 22.652f, 22.652f, 22.652f, 22.652f, + 25.888f, 25.888f, 25.888f, 25.888f, 29.124f, 29.124f, 29.124f, 29.124f, + 32.36f, 32.36f, 32.36f, 32.36f, 35.596f, 35.596f, 35.596f, 35.596f, + 38.832f, 38.832f, 38.832f, 38.832f, 42.068f, 42.068f, 42.068f, 42.068f, + 45.304f, 45.304f, 45.304f, 45.304f, 48.54f, 48.54f, 48.54f, 48.54f }; param.BLOCK_DURATION = blk_ts / 1000000; @@ -160,8 +158,7 @@ RSDecoderMechConstParam& DecoderRS128::initConstParam(RSDecoderMec return param; } -template -RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) +RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) { switch (mode) { @@ -174,15 +171,13 @@ RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) } } -template -inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, +inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(initConstParam(rs_const_param_), param, excb) + : DecoderMech(getConstParam(), param, excb) { } -template -inline void DecoderRS128::decodeDifopPkt(const uint8_t* packet, size_t size) +inline void DecoderRS128::decodeDifopPkt(const uint8_t* packet, size_t size) { const RS128DifopPkt& pkt = *(const RS128DifopPkt*)(packet); this->template decodeDifopCommon(pkt); @@ -192,8 +187,7 @@ inline void DecoderRS128::decodeDifopPkt(const uint8_t* packet, si (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -template -inline void DecoderRS128::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline void DecoderRS128::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { @@ -205,9 +199,8 @@ inline void DecoderRS128::decodeMsopPkt(const uint8_t* pkt, size_t } } -template template -inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS128MsopPkt& pkt = *(const RS128MsopPkt*)(packet); @@ -243,7 +236,7 @@ inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packe if (this->split_strategy_->newBlock(block_az)) { - this->splitFrame(); + this->cb_split_frame_(this->height_, this->prev_point_ts_); } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -256,39 +249,31 @@ inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packe int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); - float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; - uint8_t intensity = channel.intensity; if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; - - typename T_PointCloud::PointT point; - setX(point, x); - setY(point, y); - setZ(point, z); - setIntensity(point, intensity); - - setTimestamp(point, chan_ts); - setRing(point, this->chan_angles_.toUserChan(chan)); - - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + point.intensity = channel.intensity; + point.timestamp = chan_ts; + point.ring = this->chan_angles_.toUserChan(chan); + + this->cb_new_point_(point); } else if (!this->param_.dense_points) { - typename T_PointCloud::PointT point; - setX(point, NAN); - setY(point, NAN); - setZ(point, NAN); - setIntensity(point, 0); - - setTimestamp(point, chan_ts); - setRing(point, this->chan_angles_.toUserChan(chan)); - - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = NAN; + point.y = NAN; + point.z = NAN; + point.intensity = 0; + point.timestamp = chan_ts; + point.ring = this->chan_angles_.toUserChan(chan); + + this->cb_new_point_(point); } this->prev_point_ts_ = chan_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 8a61822d..0be87a87 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -147,14 +147,14 @@ class DecoderRS16 : public DecoderMech protected: #endif - static RSDecoderMechConstParam& initConstParam(); + static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -inline RSDecoderMechConstParam& DecoderRS16::initConstParam() +inline RSDecoderMechConstParam& DecoderRS16::getConstParam() { static RSDecoderMechConstParam param = { @@ -214,7 +214,7 @@ inline RSEchoMode DecoderRS16::getEchoMode(uint8_t mode) inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(initConstParam(), param, excb) + : DecoderMech(getConstParam(), param, excb) { this->height_ = 16; } @@ -280,7 +280,7 @@ inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_(this->height_, this->prev_point_ts_); + this->cb_split_frame_(this->height_, this->prev_point_ts_); } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 94794d49..76cebf92 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -146,14 +146,14 @@ class DecoderRS32 : public DecoderMech protected: #endif - static RSDecoderMechConstParam& initConstParam(); + static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -inline RSDecoderMechConstParam& DecoderRS32::initConstParam() +inline RSDecoderMechConstParam& DecoderRS32::getConstParam() { static RSDecoderMechConstParam param = { @@ -213,7 +213,7 @@ inline RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(initConstParam(), param, excb) + : DecoderMech(getConstParam(), param, excb) { } @@ -278,7 +278,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_(this->height_, this->prev_point_ts_); + this->cb_split_frame_(this->height_, this->prev_point_ts_); } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 9b57099c..5f25ecf7 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -81,8 +81,7 @@ typedef struct #pragma pack(pop) -template -class DecoderRS80 : public DecoderMech +class DecoderRS80 : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); @@ -96,57 +95,53 @@ class DecoderRS80 : public DecoderMech protected: #endif - static RSDecoderMechConstParam& initConstParam(RSDecoderMechConstParam& param); - static RSDecoderConstParam getConstParam(); + static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - - static RSDecoderMechConstParam rs_const_param_; }; -template -RSDecoderMechConstParam DecoderRS80::rs_const_param_ = +RSDecoderMechConstParam& DecoderRS80::getConstParam() +{ + static RSDecoderMechConstParam param = { - 1248 // msop len - , 1248 // difop len - , 4 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x5A} // msop id + 1248 // msop len + , 1248 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x5A} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFE} // block id , 4 // blocks per packet - , 80 // channels per block - , 1.0f // distance min - , 230.0f // distance max - , 0.005f // distance resolution - , 0.0625f // temperature resolution - - // lens center - , 0.03615f // RX - , -0.017f // RY - , 0.0f // RZ + , 80 // channels per block + , 1.0f // distance min + , 230.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.03615f // RX + , -0.017f // RY + , 0.0f // RZ }; -template -RSDecoderMechConstParam& DecoderRS80::initConstParam(RSDecoderMechConstParam& param) -{ + INIT_ONLY_ONCE(); float blk_ts = 55.552f; float firing_tss[] = { - 0.00f, 0.00f, 0.00f, 3.236f, 3.236f, 6.472f, 6.472f, 6.472f, - 6.472f, 9.708f, 9.708f, 9.708f, 12.944f, 12.944f, 12.944f, 16.18f, - 16.18f, 16.18f, 19.416f, 19.416f, 19.416f, 22.652f, 22.652f, 25.888f, - 25.888f, 29.124f, 29.124f, 32.36f, 32.36f, 35.596f, 35.596f, 38.832f, - 38.832f, 42.068f, 42.068f, 45.304f, 45.304f, 48.54f, 48.54f, 48.54f, - - 0.00f, 0.00f, 0.00f, 3.236f, 3.236f, 3.236f, 6.472f, 6.472f, - 6.472f, 9.708f, 9.708f, 12.944f, 12.944f, 12.944f, 12.944f, 16.18f, - 16.18f, 19.416f, 19.416f, 19.416f, 22.652f, 22.652f, 22.652f, 25.888f, - 25.888f, 29.124f, 29.124f, 32.36f, 32.36f, 35.596f, 35.596f, 35.596f, - 38.832f, 38.832f, 42.068f, 45.304f, 45.304f, 48.54f, 48.54f, 48.54f, + 0.00f, 0.00f, 0.00f, 3.236f, 3.236f, 6.472f, 6.472f, 6.472f, + 6.472f, 9.708f, 9.708f, 9.708f, 12.944f, 12.944f, 12.944f, 16.18f, + 16.18f, 16.18f, 19.416f, 19.416f, 19.416f, 22.652f, 22.652f, 25.888f, + 25.888f, 29.124f, 29.124f, 32.36f, 32.36f, 35.596f, 35.596f, 38.832f, + 38.832f, 42.068f, 42.068f, 45.304f, 45.304f, 48.54f, 48.54f, 48.54f, + + 0.00f, 0.00f, 0.00f, 3.236f, 3.236f, 3.236f, 6.472f, 6.472f, + 6.472f, 9.708f, 9.708f, 12.944f, 12.944f, 12.944f, 12.944f, 16.18f, + 16.18f, 19.416f, 19.416f, 19.416f, 22.652f, 22.652f, 22.652f, 25.888f, + 25.888f, 29.124f, 29.124f, 32.36f, 32.36f, 35.596f, 35.596f, 35.596f, + 38.832f, 38.832f, 42.068f, 45.304f, 45.304f, 48.54f, 48.54f, 48.54f, }; param.BLOCK_DURATION = blk_ts / 1000000; @@ -159,8 +154,7 @@ RSDecoderMechConstParam& DecoderRS80::initConstParam(RSDecoderMech return param; } -template -RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) +RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) { switch (mode) { @@ -173,15 +167,13 @@ RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) } } -template -inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, +inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(initConstParam(rs_const_param_), param, excb) + : DecoderMech(getConstParam(), param, excb) { } -template -inline void DecoderRS80::decodeDifopPkt(const uint8_t* packet, size_t size) +inline void DecoderRS80::decodeDifopPkt(const uint8_t* packet, size_t size) { const RS80DifopPkt& pkt = *(const RS80DifopPkt*)(packet); this->template decodeDifopCommon(pkt); @@ -191,8 +183,7 @@ inline void DecoderRS80::decodeDifopPkt(const uint8_t* packet, siz (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -template -inline void DecoderRS80::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline void DecoderRS80::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { @@ -204,9 +195,8 @@ inline void DecoderRS80::decodeMsopPkt(const uint8_t* pkt, size_t } } -template template -inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS80MsopPkt& pkt = *(const RS80MsopPkt*)(packet); @@ -242,7 +232,7 @@ inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet if (this->split_strategy_->newBlock(block_az)) { - this->splitFrame(); + this->cb_split_frame_(this->height_, this->prev_point_ts_); } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -255,39 +245,31 @@ inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); - float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; - uint8_t intensity = channel.intensity; if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; - - typename T_PointCloud::PointT point; - setX(point, x); - setY(point, y); - setZ(point, z); - setIntensity(point, intensity); - - setTimestamp(point, chan_ts); - setRing(point, this->chan_angles_.toUserChan(chan)); - - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + point.intensity = channel.intensity; + point.timestamp = chan_ts; + point.ring = this->chan_angles_.toUserChan(chan); + + this->cb_new_point_(point); } else if (!this->param_.dense_points) { - typename T_PointCloud::PointT point; - setX(point, NAN); - setY(point, NAN); - setZ(point, NAN); - setIntensity(point, 0); - - setTimestamp(point, chan_ts); - setRing(point, this->chan_angles_.toUserChan(chan)); - - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = NAN; + point.y = NAN; + point.z = NAN; + point.intensity = 0; + point.timestamp = chan_ts; + point.ring = this->chan_angles_.toUserChan(chan); + + this->cb_new_point_(point); } this->prev_point_ts_ = chan_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 4147c524..8bff9aa2 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -96,14 +96,14 @@ class DecoderRSBP : public DecoderMech protected: #endif - static RSDecoderMechConstParam& initConstParam(); + static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -inline RSDecoderMechConstParam& DecoderRSBP::initConstParam() +inline RSDecoderMechConstParam& DecoderRSBP::getConstParam() { static RSDecoderMechConstParam param = { @@ -163,7 +163,7 @@ inline RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(initConstParam(), param, excb) + : DecoderMech(getConstParam(), param, excb) { } @@ -226,7 +226,7 @@ inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_(this->height_, this->prev_point_ts_); + this->cb_split_frame_(this->height_, this->prev_point_ts_); } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 4c0190a2..60ec9b49 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -93,8 +93,7 @@ typedef struct #pragma pack(pop) -template -class DecoderRSHELIOS : public DecoderMech +class DecoderRSHELIOS : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); @@ -108,45 +107,43 @@ class DecoderRSHELIOS : public DecoderMech protected: #endif - static RSDecoderMechConstParam& initConstParam(RSDecoderMechConstParam& param); + static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); template void internDecodeMsopPkt(const uint8_t* pkt, size_t size); - - static RSDecoderMechConstParam rs_const_param_; }; -template -RSDecoderMechConstParam DecoderRSHELIOS::rs_const_param_ = +RSDecoderMechConstParam& DecoderRSHELIOS::getConstParam() +{ + static RSDecoderMechConstParam param = { - 1248 // msop len - , 1248 // difop len - , 4 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x5A} // msop id + 1248 // msop len + , 1248 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x5A} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id , 12 // blocks per packet - , 32 // channels per block - , 0.4f // distance min - , 200.0f // distance max - , 0.0025f // distance resolution - , 0.0625f // temperature resolution - - // lens center - , 0.03498f // RX - , -0.015f // RY - , 0.0f // RZ + , 32 // channels per block + , 0.4f // distance min + , 200.0f // distance max + , 0.0025f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.03498f // RX + , -0.015f // RY + , 0.0f // RZ }; -template -RSDecoderMechConstParam& DecoderRSHELIOS::initConstParam(RSDecoderMechConstParam& param) -{ + INIT_ONLY_ONCE(); + float blk_ts = 55.56f; float firing_tss[] = { - 0.00f, 1.57f, 3.15f, 4.72f, 6.30f, 7.87f, 9.45f, 11.36f, + 0.00f, 1.57f, 3.15f, 4.72f, 6.30f, 7.87f, 9.45f, 11.36f, 13.26f, 15.17f, 17.08f, 18.99f, 20.56f, 22.14f, 23.71f, 25.29f, 26.53f, 29.01f, 27.77f, 30.25f, 31.49f, 33.98f, 32.73f, 35.22f, 36.46f, 37.70f, 38.94f, 40.18f, 41.42f, 42.67f, 43.91f, 45.15f @@ -162,8 +159,7 @@ RSDecoderMechConstParam& DecoderRSHELIOS::initConstParam(RSDecoder return param; } -template -RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) +RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) { switch (mode) { @@ -177,15 +173,13 @@ RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) } } -template -inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, +inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(initConstParam(rs_const_param_), param, excb) + : DecoderMech(getConstParam(), param, excb) { } -template -inline void DecoderRSHELIOS::decodeDifopPkt(const uint8_t* packet, size_t size) +inline void DecoderRSHELIOS::decodeDifopPkt(const uint8_t* packet, size_t size) { const RSHELIOSDifopPkt& pkt = *(const RSHELIOSDifopPkt*)(packet); this->template decodeDifopCommon(pkt); @@ -195,8 +189,7 @@ inline void DecoderRSHELIOS::decodeDifopPkt(const uint8_t* packet, (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -template -inline void DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline void DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { @@ -208,9 +201,8 @@ inline void DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, siz } } -template template -inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RSHELIOSMsopPkt& pkt = *(const RSHELIOSMsopPkt*)(packet); @@ -246,7 +238,7 @@ inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa if (this->split_strategy_->newBlock(block_az)) { - this->splitFrame(); + this->cb_split_frame_(this->height_, this->prev_point_ts_); } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -259,39 +251,31 @@ inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); - float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; - uint8_t intensity = channel.intensity; if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); - float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); - float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; - - typename T_PointCloud::PointT point; - setX(point, x); - setY(point, y); - setZ(point, z); - setIntensity(point, intensity); - - setTimestamp(point, chan_ts); - setRing(point, this->chan_angles_.toUserChan(chan)); - - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + point.intensity = channel.intensity; + point.timestamp = chan_ts; + point.ring = this->chan_angles_.toUserChan(chan); + + this->cb_new_point_(point); } else if (!this->param_.dense_points) { - typename T_PointCloud::PointT point; - setX(point, NAN); - setY(point, NAN); - setZ(point, NAN); - setIntensity(point, 0); - - setTimestamp(point, chan_ts); - setRing(point, this->chan_angles_.toUserChan(chan)); - - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = NAN; + point.y = NAN; + point.z = NAN; + point.intensity = 0; + point.timestamp = chan_ts; + point.ring = this->chan_angles_.toUserChan(chan); + + this->cb_new_point_(point); } this->prev_point_ts_ = chan_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index c57c0ab7..76dc8f7a 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -133,8 +133,7 @@ typedef struct #pragma pack(pop) -template -class DecoderRSM1 : public Decoder +class DecoderRSM1 : public Decoder { public: @@ -159,8 +158,7 @@ class DecoderRSM1 : public Decoder SplitStrategyBySeq split_; }; -template -RSDecoderConstParam DecoderRSM1::rs_const_param_ = +RSDecoderConstParam DecoderRSM1::rs_const_param_ = { 1210 // msop len , 256 // difop len @@ -176,10 +174,9 @@ RSDecoderConstParam DecoderRSM1::rs_const_param_ = , 0.005f // distance resolution }; -template -inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, +inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, const std::function& excb) - : Decoder(rs_const_param_, param, excb) + : Decoder(rs_const_param_, param, excb) , max_seq_(SINGLE_PKT_NUM) , split_(&max_seq_) { @@ -188,8 +185,7 @@ inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, this->angles_ready_ = true; } -template -RSEchoMode DecoderRSM1::getEchoMode(uint8_t mode) +RSEchoMode DecoderRSM1::getEchoMode(uint8_t mode) { switch (mode) { @@ -203,15 +199,14 @@ RSEchoMode DecoderRSM1::getEchoMode(uint8_t mode) } } -template void DecoderRSM1::decodeDifopPkt(const uint8_t* packet, size_t size) +void DecoderRSM1::decodeDifopPkt(const uint8_t* packet, size_t size) { const RSM1DifopPkt& pkt = *(RSM1DifopPkt*)packet; this->echo_mode_ = this->getEchoMode(pkt.return_mode); max_seq_ = (this->echo_mode_ == ECHO_SINGLE) ? SINGLE_PKT_NUM : DUAL_PKT_NUM; } -template -void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) +void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) { const RSM1MsopPkt& pkt = *(RSM1MsopPkt*)packet; @@ -245,32 +240,27 @@ void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size int pitch = ntohs(channel.pitch) - ANGLE_OFFSET; int yaw = ntohs(channel.yaw) - ANGLE_OFFSET; - float x = distance * COS (pitch) * COS (yaw); - float y = distance * COS (pitch) * SIN (yaw); - float z = distance * SIN (pitch); - uint8_t intensity = channel.intensity; + RSPoint point; + point.x = distance * COS (pitch) * COS (yaw); + point.y = distance * COS (pitch) * SIN (yaw); + point.z = distance * SIN (pitch); + point.intensity = channel.intensity; + point.timestamp = point_time; + point.ring = chan; - typename T_PointCloud::PointT point; - setX(point, x); - setY(point, y); - setZ(point, z); - setIntensity(point, intensity); - - setRing(point, chan); - setTimestamp(point, point_time); - this->point_cloud_->points.emplace_back(point); + this->cb_new_point_(point); } else if (!this->param_.dense_points) { - typename T_PointCloud::PointT point; - setX(point, NAN); - setY(point, NAN); - setZ(point, NAN); - setIntensity(point, 0); - - setRing(point, chan); - setTimestamp(point, point_time); - this->point_cloud_->points.emplace_back(point); + RSPoint point; + point.x = NAN; + point.y = NAN; + point.z = NAN; + point.intensity = 0; + point.timestamp = point_time; + point.ring = chan; + + this->cb_new_point_(point); } } @@ -280,7 +270,7 @@ void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); if (split_.newPacket(pkt_seq)) { - this->splitFrame(); + this->cb_split_frame_(this->height_, this->prev_point_ts_); } } diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 5483624c..2641b99a 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -34,12 +34,10 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#if 0 #include #include #include #include -#endif namespace robosense { @@ -70,20 +68,18 @@ DecoderFactory::createDecoder(LidarType type, const RSDecoderParam& param, case LidarType::RSBP: ret_ptr = std::make_shared(param, excb); break; -#if 0 case LidarType::RSHELIOS: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared(param, excb); break; case LidarType::RS80: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared(param, excb); break; case LidarType::RS128: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared(param, excb); break; case LidarType::RSM1: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared(param, excb); break; -#endif default: RS_ERROR << "Wrong LiDAR Type. Please check your LiDAR Version! " << RS_REND; exit(-1); From f1e9ddabbfda1b0b466e994b7e404f6ad8ca6748 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 29 Dec 2021 10:15:16 +0800 Subject: [PATCH 128/379] refac: move pointcloud to driver_impl --- .../driver/decoder/decoder_RS128.hpp | 4 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 4 +- .../driver/decoder/decoder_RSHELIOS.hpp | 4 +- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 44 ++++++++++--------- 4 files changed, 30 insertions(+), 26 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 69411b31..85cec229 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -100,7 +100,7 @@ class DecoderRS128 : public DecoderMech void internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -RSDecoderMechConstParam& DecoderRS128::getConstParam() +inline RSDecoderMechConstParam& DecoderRS128::getConstParam() { static RSDecoderMechConstParam param = { @@ -158,7 +158,7 @@ RSDecoderMechConstParam& DecoderRS128::getConstParam() return param; } -RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) +inline RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) { switch (mode) { diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 5f25ecf7..5ba4c78d 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -102,7 +102,7 @@ class DecoderRS80 : public DecoderMech void internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -RSDecoderMechConstParam& DecoderRS80::getConstParam() +inline RSDecoderMechConstParam& DecoderRS80::getConstParam() { static RSDecoderMechConstParam param = { @@ -154,7 +154,7 @@ RSDecoderMechConstParam& DecoderRS80::getConstParam() return param; } -RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) +inline RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) { switch (mode) { diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 60ec9b49..1fb2a319 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -114,7 +114,7 @@ class DecoderRSHELIOS : public DecoderMech void internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -RSDecoderMechConstParam& DecoderRSHELIOS::getConstParam() +inline RSDecoderMechConstParam& DecoderRSHELIOS::getConstParam() { static RSDecoderMechConstParam param = { @@ -159,7 +159,7 @@ RSDecoderMechConstParam& DecoderRSHELIOS::getConstParam() return param; } -RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) +inline RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) { switch (mode) { diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 76dc8f7a..cbee5d24 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -150,33 +150,37 @@ class DecoderRSM1 : public Decoder private: + static RSDecoderConstParam& getConstParam(); RSEchoMode getEchoMode(uint8_t mode); - static RSDecoderConstParam rs_const_param_; - uint16_t max_seq_; SplitStrategyBySeq split_; }; -RSDecoderConstParam DecoderRSM1::rs_const_param_ = +inline RSDecoderConstParam& DecoderRSM1::getConstParam() { - 1210 // msop len - , 256 // difop len - , 4 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x5A, 0xA5} // msop id - , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0x00, 0x00} - , 25 // blocks per packet - , 5 // channels per block - , 0.2f // distance min - , 200.0f // distance max - , 0.005f // distance resolution -}; + static RSDecoderConstParam param = + { + 1210 // msop len + , 256 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x5A, 0xA5} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0x00, 0x00} + , 25 // blocks per packet + , 5 // channels per block + , 0.2f // distance min + , 200.0f // distance max + , 0.005f // distance resolution + }; + + return param; +} inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, const std::function& excb) - : Decoder(rs_const_param_, param, excb) + : Decoder(getConstParam(), param, excb) , max_seq_(SINGLE_PKT_NUM) , split_(&max_seq_) { @@ -185,7 +189,7 @@ inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, this->angles_ready_ = true; } -RSEchoMode DecoderRSM1::getEchoMode(uint8_t mode) +inline RSEchoMode DecoderRSM1::getEchoMode(uint8_t mode) { switch (mode) { @@ -199,14 +203,14 @@ RSEchoMode DecoderRSM1::getEchoMode(uint8_t mode) } } -void DecoderRSM1::decodeDifopPkt(const uint8_t* packet, size_t size) +inline void DecoderRSM1::decodeDifopPkt(const uint8_t* packet, size_t size) { const RSM1DifopPkt& pkt = *(RSM1DifopPkt*)packet; this->echo_mode_ = this->getEchoMode(pkt.return_mode); max_seq_ = (this->echo_mode_ == ECHO_SINGLE) ? SINGLE_PKT_NUM : DUAL_PKT_NUM; } -void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) +inline void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) { const RSM1MsopPkt& pkt = *(RSM1MsopPkt*)packet; From 3a1ffa2c418468f1db922d2ba58bc43096d0d879 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 29 Dec 2021 10:32:53 +0800 Subject: [PATCH 129/379] refac: refactory decoder_factory --- src/rs_driver/driver/input/input_factory.hpp | 9 ++++++--- src/rs_driver/driver/lidar_driver_impl.hpp | 4 +++- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 850023cd..db5f71d9 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -46,12 +46,12 @@ class InputFactory public: static std::shared_ptr createInput(InputType type, const RSInputParam& param, const std::function& excb, - double sec_to_delay); + double sec_to_delay, std::function& cb_feed_pkt); }; inline std::shared_ptr InputFactory::createInput(InputType type, const RSInputParam& param, const std::function& excb, - double sec_to_delay) + double sec_to_delay, std::function& cb_feed_pkt) { std::shared_ptr input; @@ -71,7 +71,10 @@ inline std::shared_ptr InputFactory::createInput(InputType type, case InputType::RAW_PACKET: { - input = std::make_shared(param, excb); + std::shared_ptr inputRaw = std::make_shared(param, excb); + cb_feed_pkt = std::bind(&InputRaw::feedPacket, inputRaw, + std::placeholders::_1, std::placeholders::_2); + input = inputRaw; } break; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 69adc9d3..e1e03e77 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -190,18 +190,20 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1), - packet_duration); + packet_duration, cb_feed_pkt_); input_ptr_->regRecvCallback( std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), std::bind(&LidarDriverImpl::packetPut, this, std::placeholders::_1)); +#if 0 if (param.input_type == InputType::RAW_PACKET) { InputRaw* inputRaw = dynamic_cast(input_ptr_.get()); cb_feed_pkt_ = std::bind(&InputRaw::feedPacket, inputRaw, std::placeholders::_1, std::placeholders::_2); } +#endif if (!input_ptr_->init()) { From 74c83892e8b8a5bb0d959aa526ecbd518ebb6885 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 30 Dec 2021 16:03:01 +0800 Subject: [PATCH 130/379] feat: use option SO_REUSEADDR to resolve TIME_WAIT status --- src/rs_driver/driver/input/sock_input.hpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index eba449eb..1652defb 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -142,6 +142,7 @@ inline int SockInput::createSocket(uint16_t port, const std::string& hostIp, con int fd; int flags; int ret; + int reuse = 1; fd = socket(PF_INET, SOCK_DGRAM, 0); if (fd < 0) @@ -158,6 +159,13 @@ inline int SockInput::createSocket(uint16_t port, const std::string& hostIp, con if (hostIp != "0.0.0.0" && grpIp == "0.0.0.0") inet_pton(AF_INET, hostIp.c_str(), &(host_addr.sin_addr)); + ret = setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &reuse, sizeof(reuse)); + if (ret < 0) + { + std::cerr << "setsockopt: " << std::strerror(errno) << std::endl; + goto failOption; + } + ret = bind(fd, (struct sockaddr*)&host_addr, sizeof(host_addr)); if (ret < 0) { @@ -198,6 +206,7 @@ inline int SockInput::createSocket(uint16_t port, const std::string& hostIp, con failNonBlock: failGroup: failBind: +failOption: close(fd); failSocket: return -1; From 79631bf033f9de0251bdd61a708888bd9f01d084 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 31 Dec 2021 12:18:10 +0800 Subject: [PATCH 131/379] refac: recover packet msg --- src/rs_driver/api/lidar_driver.h | 10 ++-- src/rs_driver/driver/lidar_driver_impl.hpp | 26 +++++----- src/rs_driver/msg/{packet_msg.h => packet.h} | 27 +++++----- src/rs_driver/msg/scan_msg.h | 53 -------------------- 4 files changed, 31 insertions(+), 85 deletions(-) rename src/rs_driver/msg/{packet_msg.h => packet.h} (88%) delete mode 100644 src/rs_driver/msg/scan_msg.h diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index 3b260ef0..7ec8e539 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -72,9 +72,9 @@ class LidarDriver * ready, this function will be called * @param callback The callback function */ - inline void regRecvCallback(const std::function& cb_pkt) + inline void regRecvCallback(const std::function& cb_put_pkt) { - driver_ptr_->regRecvCallback(cb_pkt); + driver_ptr_->regRecvCallback(cb_put_pkt); } /** @@ -106,15 +106,13 @@ class LidarDriver return driver_ptr_->start(); } - - /** * @brief Decode lidar msop/difop messages * @param pkt_msg The lidar msop/difop packet */ - inline void decodePacket(const uint8_t* pkt, size_t size) + inline void decodePacket(const Packet& pkt) { - driver_ptr_->decodePacket(pkt, size); + driver_ptr_->decodePacket(pkt); } /** diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index e1e03e77..763cfcc8 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -34,8 +34,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include -#include +#include #include #include #include @@ -67,14 +66,14 @@ class LidarDriverImpl void regRecvCallback(const std::function(void)>& cb_get_pc, const std::function)>& cb_put_pc); - void regRecvCallback(const std::function& cb_pkt); + void regRecvCallback(const std::function& cb_put_pkt); void regExceptionCallback(const std::function& cb_excp); bool init(const RSDriverParam& param); bool start(); void stop(); - void decodePacket(const uint8_t* pkt, size_t size); + void decodePacket(const Packet& pkt); bool getTemperature(float& temp); private: @@ -96,7 +95,7 @@ class LidarDriverImpl RSDriverParam driver_param_; std::function(void)> cb_get_pc_; std::function)> cb_put_pc_; - std::function cb_pkt_; + std::function cb_put_pkt_; std::function cb_excp_; std::function cb_feed_pkt_; @@ -158,9 +157,9 @@ void LidarDriverImpl::regRecvCallback( template inline void LidarDriverImpl::regRecvCallback( - const std::function& cb_pkt) + const std::function& cb_put_pkt) { - cb_pkt_ = cb_pkt; + cb_put_pkt_ = cb_put_pkt; } template @@ -264,9 +263,9 @@ inline void LidarDriverImpl::stop() } template -inline void LidarDriverImpl::decodePacket(const uint8_t* pkt, size_t size) +inline void LidarDriverImpl::decodePacket(const Packet& pkt) { - cb_feed_pkt_(pkt, size); + cb_feed_pkt_(pkt.buf_.data(), pkt.buf_.size()); } template @@ -281,11 +280,14 @@ inline bool LidarDriverImpl::getTemperature(float& temp) } template -inline void LidarDriverImpl::runCallBack(std::shared_ptr pkt) +inline void LidarDriverImpl::runCallBack(std::shared_ptr buf) { - if (cb_pkt_) + if (cb_put_pkt_) { - cb_pkt_(pkt->data(), pkt->dataSize()); + Packet pkt; + pkt.buf_.resize(buf->dataSize()); + memcpy (pkt.buf_.data(), buf->data(), buf->dataSize()); + cb_put_pkt_(pkt); } } diff --git a/src/rs_driver/msg/packet_msg.h b/src/rs_driver/msg/packet.h similarity index 88% rename from src/rs_driver/msg/packet_msg.h rename to src/rs_driver/msg/packet.h index b4548cc3..af3d8265 100644 --- a/src/rs_driver/msg/packet_msg.h +++ b/src/rs_driver/msg/packet.h @@ -38,26 +38,25 @@ namespace robosense { namespace lidar { -enum PktType -{ - MSOP = 0, - DIFOP -}; -struct PacketMsg +struct Packet { - std::vector packet; - PacketMsg() - { - } - PacketMsg(const PacketMsg& msg) + double timestamp = 0.0; + uint32_t seq = 0; + uint8_t type = 0; /// 0 - msop, 1 - difop + + Packet(const Packet& msg) { - this->packet.assign(msg.packet.begin(), msg.packet.end()); + buf_.assign(msg.buf_.begin(), msg.buf_.end()); } - PacketMsg(const size_t& pkt_length) + + Packet(size_t size = 0) { - packet.resize(pkt_length); + buf_.resize(size); } + + std::vector buf_; }; + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/msg/scan_msg.h b/src/rs_driver/msg/scan_msg.h deleted file mode 100644 index 291fd3c0..00000000 --- a/src/rs_driver/msg/scan_msg.h +++ /dev/null @@ -1,53 +0,0 @@ -/********************************************************************************************************************* -Copyright (c) 2020 RoboSense -All rights reserved - -By downloading, copying, installing or using the software you agree to this license. If you do not agree to this -license, do not download, install, copy or use the software. - -License Agreement -For RoboSense LiDAR SDK Library -(3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials provided with the distribution. - -3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used -to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*********************************************************************************************************************/ - -#pragma once -#include -#include - -namespace robosense -{ -namespace lidar -{ -#ifdef _MSC_VER -struct __declspec(align(16)) ScanMsg -#elif __GNUC__ -struct __attribute__((aligned(16))) ScanMsg -#endif -{ - double timestamp = 0.0; - uint32_t seq = 0; - //std::string frame_id = ""; - std::vector packets; ///< A vector which store a scan of packets (the size of the vector is not fix) -}; -} // namespace lidar -} // namespace robosense From 73c6609d198f7bf6e620bf28af1cc591780c7f3b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 31 Dec 2021 12:19:39 +0800 Subject: [PATCH 132/379] refac: format --- src/rs_driver/driver/lidar_driver_impl.hpp | 9 --------- 1 file changed, 9 deletions(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 763cfcc8..9d58bf6e 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -195,15 +195,6 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), std::bind(&LidarDriverImpl::packetPut, this, std::placeholders::_1)); -#if 0 - if (param.input_type == InputType::RAW_PACKET) - { - InputRaw* inputRaw = dynamic_cast(input_ptr_.get()); - cb_feed_pkt_ = - std::bind(&InputRaw::feedPacket, inputRaw, std::placeholders::_1, std::placeholders::_2); - } -#endif - if (!input_ptr_->init()) { goto failInputInit; From 87234688a113555827e621c0c2fa4d0ab541ae14 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 31 Dec 2021 18:26:39 +0800 Subject: [PATCH 133/379] refac: format --- CMakeLists.txt | 2 +- src/rs_driver/api/lidar_driver.h | 1 + src/rs_driver/driver/driver_param.h | 2 ++ src/rs_driver/driver/lidar_driver_impl.hpp | 8 +++++--- src/rs_driver/msg/packet.h | 1 + 5 files changed, 10 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3f4e9c30..a6585db7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.4.1) +project(rs_driver VERSION 1.4.5) #============================= # Compile Demos&Tools diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index 7ec8e539..2f90537c 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -31,6 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once + #include namespace robosense diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index fca4343a..480ea807 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -31,9 +31,11 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once + #include #include #include + namespace robosense { namespace lidar diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 9d58bf6e..70af232f 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -31,11 +31,13 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include -#include -#include +#include #include +#include +#include #include + +#include #include #include diff --git a/src/rs_driver/msg/packet.h b/src/rs_driver/msg/packet.h index af3d8265..594d472c 100644 --- a/src/rs_driver/msg/packet.h +++ b/src/rs_driver/msg/packet.h @@ -44,6 +44,7 @@ struct Packet double timestamp = 0.0; uint32_t seq = 0; uint8_t type = 0; /// 0 - msop, 1 - difop + std::string frame_id = ""; Packet(const Packet& msg) { From 740430d64734a6dce40cf47cdf8cf37b1091632e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 10 Jan 2022 12:11:17 +0800 Subject: [PATCH 134/379] fix: fix headers --- src/rs_driver/api/lidar_driver.h | 1 + src/rs_driver/msg/packet.h | 2 ++ src/rs_driver/msg/pcl_point_cloud_msg.h | 1 + 3 files changed, 4 insertions(+) diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.h index 2f90537c..8349abec 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.h @@ -33,6 +33,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include +#include namespace robosense { diff --git a/src/rs_driver/msg/packet.h b/src/rs_driver/msg/packet.h index 594d472c..03e1409f 100644 --- a/src/rs_driver/msg/packet.h +++ b/src/rs_driver/msg/packet.h @@ -32,7 +32,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once +#include #include +#include namespace robosense { diff --git a/src/rs_driver/msg/pcl_point_cloud_msg.h b/src/rs_driver/msg/pcl_point_cloud_msg.h index 4e52409f..f9a51575 100644 --- a/src/rs_driver/msg/pcl_point_cloud_msg.h +++ b/src/rs_driver/msg/pcl_point_cloud_msg.h @@ -60,3 +60,4 @@ class PointCloudT : public pcl::PointCloud std::string frame_id = "rslidar"; ///< Point cloud frame id uint32_t seq = 0; ///< Sequence number of message }; + From 18d7ea4bec9c297f30f109ce5a5833924080d1d1 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 10 Jan 2022 14:31:26 +0800 Subject: [PATCH 135/379] refac: format --- CMakeLists.txt | 4 ++-- demo/demo_online.cpp | 6 +++--- demo/demo_pcap.cpp | 6 +++--- .../api/{lidar_driver.h => lidar_driver.hpp} | 2 +- .../{common_header.h => common_header.hpp} | 0 .../common/{error_code.h => error_code.hpp} | 0 src/rs_driver/driver/decoder/decoder.hpp | 4 ++-- .../{driver_param.h => driver_param.hpp} | 12 +++++------ src/rs_driver/driver/input/input.hpp | 4 ++-- src/rs_driver/driver/lidar_driver_impl.hpp | 12 +++++------ src/rs_driver/macro/version.hpp | 3 +++ .../macro/{version.h.in => version.hpp.in} | 0 src/rs_driver/msg/{packet.h => packet.hpp} | 0 ...nt_cloud_msg.h => pcl_point_cloud_msg.hpp} | 0 ...{point_cloud_msg.h => point_cloud_msg.hpp} | 0 .../utility/{buffer.h => buffer.hpp} | 0 src/rs_driver/utility/{dbg.h => dbg.hpp} | 0 .../utility/{sync_queue.h => sync_queue.hpp} | 0 test/buffer_test.cpp | 2 +- test/decoder_rs32_test.cpp | 4 ++-- test/decoder_rsbp_test.cpp | 4 ++-- test/decoder_test.cpp | 4 ++-- test/sync_queue_test.cpp | 2 +- tool/rs_driver_viewer.cpp | 20 ++++++++++++------- 24 files changed, 49 insertions(+), 40 deletions(-) rename src/rs_driver/api/{lidar_driver.h => lidar_driver.hpp} (99%) rename src/rs_driver/common/{common_header.h => common_header.hpp} (100%) rename src/rs_driver/common/{error_code.h => error_code.hpp} (100%) rename src/rs_driver/driver/{driver_param.h => driver_param.hpp} (96%) create mode 100644 src/rs_driver/macro/version.hpp rename src/rs_driver/macro/{version.h.in => version.hpp.in} (100%) rename src/rs_driver/msg/{packet.h => packet.hpp} (100%) rename src/rs_driver/msg/{pcl_point_cloud_msg.h => pcl_point_cloud_msg.hpp} (100%) rename src/rs_driver/msg/{point_cloud_msg.h => point_cloud_msg.hpp} (100%) rename src/rs_driver/utility/{buffer.h => buffer.hpp} (100%) rename src/rs_driver/utility/{dbg.h => dbg.hpp} (100%) rename src/rs_driver/utility/{sync_queue.h => sync_queue.hpp} (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index a6585db7..7c3bfddb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -143,8 +143,8 @@ configure_file( ) configure_file ( - ${CMAKE_CURRENT_LIST_DIR}/src/rs_driver/macro/version.h.in - ${CMAKE_CURRENT_LIST_DIR}/src/rs_driver/macro/version.h + ${CMAKE_CURRENT_LIST_DIR}/src/rs_driver/macro/version.hpp.in + ${CMAKE_CURRENT_LIST_DIR}/src/rs_driver/macro/version.hpp @ONLY ) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 05d46511..5a8621cb 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -30,14 +30,14 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include "rs_driver/api/lidar_driver.h" +#include #define PCL_POINTCLOUD #ifdef PCL_POINTCLOUD -#include "rs_driver/msg/pcl_point_cloud_msg.h" +#include #else -#include "rs_driver/msg/point_cloud_msg.h" +#include #endif typedef PointXYZI PointT; diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 05f3e8b9..f3f6d436 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -30,14 +30,14 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ -#include "rs_driver/api/lidar_driver.h" +#include #define PCL_POINTCLOUD #ifdef PCL_POINTCLOUD -#include "rs_driver/msg/pcl_point_cloud_msg.h" +#include #else -#include "rs_driver/msg/point_cloud_msg.h" +#include #endif typedef PointXYZI PointT; diff --git a/src/rs_driver/api/lidar_driver.h b/src/rs_driver/api/lidar_driver.hpp similarity index 99% rename from src/rs_driver/api/lidar_driver.h rename to src/rs_driver/api/lidar_driver.hpp index 8349abec..30386de8 100644 --- a/src/rs_driver/api/lidar_driver.h +++ b/src/rs_driver/api/lidar_driver.hpp @@ -33,7 +33,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include -#include +#include namespace robosense { diff --git a/src/rs_driver/common/common_header.h b/src/rs_driver/common/common_header.hpp similarity index 100% rename from src/rs_driver/common/common_header.h rename to src/rs_driver/common/common_header.hpp diff --git a/src/rs_driver/common/error_code.h b/src/rs_driver/common/error_code.hpp similarity index 100% rename from src/rs_driver/common/error_code.h rename to src/rs_driver/common/error_code.hpp diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index c1bd67a4..94e41081 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -32,8 +32,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#include -#include +#include +#include #include #include #include diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.hpp similarity index 96% rename from src/rs_driver/driver/driver_param.h rename to src/rs_driver/driver/driver_param.hpp index 480ea807..0dd358ae 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.hpp @@ -32,7 +32,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#include +#include #include #include @@ -256,11 +256,11 @@ typedef struct RSInputParam ///< The LiDAR input parameter uint16_t difop_port = 7788; ///< Difop packet port number std::string host_address = "0.0.0.0"; ///< Address of host std::string multi_cast_address = "0.0.0.0"; ///< Address of multicast - std::string pcap_path = "null"; ///< Absolute path of pcap file - bool pcap_repeat = true; ///< true: The pcap bag will repeat play - float pcap_rate = 1.0f; ///< Rate to read the pcap file - bool use_vlan = false; ///< Vlan on-off - bool use_someip = false; ///< Someip on-off + std::string pcap_path = ""; ///< Absolute path of pcap file + bool pcap_repeat = true; ///< true: The pcap bag will repeat play + float pcap_rate = 1.0f; ///< Rate to read the pcap file + bool use_vlan = false; ///< Vlan on-off + bool use_someip = false; ///< Someip on-off void print() const { diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index cf0870e8..29c0d746 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -32,8 +32,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#include -#include +#include +#include #include #include diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 70af232f..6bba9231 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -31,13 +31,13 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include #include #include diff --git a/src/rs_driver/macro/version.hpp b/src/rs_driver/macro/version.hpp new file mode 100644 index 00000000..22117eaf --- /dev/null +++ b/src/rs_driver/macro/version.hpp @@ -0,0 +1,3 @@ +#define RSLIDAR_VERSION_MAJOR 1 +#define RSLIDAR_VERSION_MINOR 4 +#define RSLIDAR_VERSION_PATCH 5 diff --git a/src/rs_driver/macro/version.h.in b/src/rs_driver/macro/version.hpp.in similarity index 100% rename from src/rs_driver/macro/version.h.in rename to src/rs_driver/macro/version.hpp.in diff --git a/src/rs_driver/msg/packet.h b/src/rs_driver/msg/packet.hpp similarity index 100% rename from src/rs_driver/msg/packet.h rename to src/rs_driver/msg/packet.hpp diff --git a/src/rs_driver/msg/pcl_point_cloud_msg.h b/src/rs_driver/msg/pcl_point_cloud_msg.hpp similarity index 100% rename from src/rs_driver/msg/pcl_point_cloud_msg.h rename to src/rs_driver/msg/pcl_point_cloud_msg.hpp diff --git a/src/rs_driver/msg/point_cloud_msg.h b/src/rs_driver/msg/point_cloud_msg.hpp similarity index 100% rename from src/rs_driver/msg/point_cloud_msg.h rename to src/rs_driver/msg/point_cloud_msg.hpp diff --git a/src/rs_driver/utility/buffer.h b/src/rs_driver/utility/buffer.hpp similarity index 100% rename from src/rs_driver/utility/buffer.h rename to src/rs_driver/utility/buffer.hpp diff --git a/src/rs_driver/utility/dbg.h b/src/rs_driver/utility/dbg.hpp similarity index 100% rename from src/rs_driver/utility/dbg.h rename to src/rs_driver/utility/dbg.hpp diff --git a/src/rs_driver/utility/sync_queue.h b/src/rs_driver/utility/sync_queue.hpp similarity index 100% rename from src/rs_driver/utility/sync_queue.h rename to src/rs_driver/utility/sync_queue.hpp diff --git a/test/buffer_test.cpp b/test/buffer_test.cpp index 3a776226..e69bdd1b 100644 --- a/test/buffer_test.cpp +++ b/test/buffer_test.cpp @@ -1,7 +1,7 @@ #include -#include +#include using namespace robosense::lidar; diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index a1588c87..af5eba9d 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -1,9 +1,9 @@ #include -#include "rs_driver/msg/point_cloud_msg.h" #include -#include +#include +#include using namespace robosense::lidar; diff --git a/test/decoder_rsbp_test.cpp b/test/decoder_rsbp_test.cpp index 41f340b8..d535e8c3 100644 --- a/test/decoder_rsbp_test.cpp +++ b/test/decoder_rsbp_test.cpp @@ -1,9 +1,9 @@ #include -#include "rs_driver/msg/point_cloud_msg.h" #include -#include +#include +#include using namespace robosense::lidar; diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 5df80181..bd926303 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -1,9 +1,9 @@ #include -#include "rs_driver/msg/point_cloud_msg.h" #include -#include +#include +#include using namespace robosense::lidar; diff --git a/test/sync_queue_test.cpp b/test/sync_queue_test.cpp index dc8c1f82..f31b8038 100644 --- a/test/sync_queue_test.cpp +++ b/test/sync_queue_test.cpp @@ -1,7 +1,7 @@ #include -#include +#include using namespace robosense::lidar; diff --git a/tool/rs_driver_viewer.cpp b/tool/rs_driver_viewer.cpp index 3052d457..094e085a 100644 --- a/tool/rs_driver_viewer.cpp +++ b/tool/rs_driver_viewer.cpp @@ -30,9 +30,10 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ +#include + #include #include -#include "rs_driver/api/lidar_driver.h" typedef pcl::PointXYZI PointT; @@ -88,11 +89,11 @@ bool parseArgument(int argc, const char* const* argv, const char* str, std::stri void parseParam(int argc, char* argv[], RSDriverParam& param) { - param.wait_for_difop = false; + param.decoder_param.wait_for_difop = false; std::string result_str; if (parseArgument(argc, argv, "-type", result_str)) { - param.lidar_type = param.strToLidarType(result_str); + param.lidar_type = strToLidarType(result_str); } if (parseArgument(argc, argv, "-msop", result_str)) { @@ -102,6 +103,7 @@ void parseParam(int argc, char* argv[], RSDriverParam& param) { param.input_param.difop_port = std::stoi(result_str); } +#if 0 if (parseArgument(argc, argv, "-x", result_str)) { param.decoder_param.transform_param.x = std::stof(result_str); @@ -126,9 +128,10 @@ void parseParam(int argc, char* argv[], RSDriverParam& param) { param.decoder_param.transform_param.yaw = std::stof(result_str); } +#endif if (parseArgument(argc, argv, "-pcap", param.input_param.pcap_path)) { - param.input_param.read_pcap = true; + //param.input_param.read_pcap = true; } } @@ -154,7 +157,7 @@ void printHelpMenu() void printParam(const RSDriverParam& param) { - if (param.input_param.read_pcap) + if (param.input_type == InputType::PCAP_FILE) { RS_INFOL << "Working mode: "; RS_INFO << "Offline Pcap " << RS_REND; @@ -166,12 +169,14 @@ void printParam(const RSDriverParam& param) RS_INFOL << "Working mode: "; RS_INFO << "Online LiDAR " << RS_REND; } + RS_INFOL << "MSOP Port: "; RS_INFO << param.input_param.msop_port << RS_REND; RS_INFOL << "DIFOP Port: "; RS_INFO << param.input_param.difop_port << RS_REND; RS_INFOL << "LiDAR Type: "; - RS_INFO << param.lidarTypeToStr(param.lidar_type) << RS_REND; + RS_INFO << lidarTypeToStr(param.lidar_type) << RS_REND; +#if 0 RS_INFOL << "Transformation Parameters (x, y, z, roll, pitch, yaw): " << RS_REND; RS_INFOL << "x: "; RS_INFO << std::fixed << param.decoder_param.transform_param.x << RS_REND; @@ -185,6 +190,7 @@ void printParam(const RSDriverParam& param) RS_INFO << std::fixed << param.decoder_param.transform_param.pitch << RS_REND; RS_INFOL << "yaw: "; RS_INFO << std::fixed << param.decoder_param.transform_param.yaw << RS_REND; +#endif } std::shared_ptr pointCloudGetCallback(void) @@ -259,7 +265,7 @@ int main(int argc, char* argv[]) LidarDriver driver; ///< Declare the driver object driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver - driver.regRecvCallback(pointCloudPutCallback, pointCloudGetCallback); ///< Register the point cloud callback function into the driver + driver.regRecvCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback function into the driver if (!driver.init(param)) ///< Call the init function and pass the parameter { RS_ERROR << "Driver Initialize Error..." << RS_REND; From 2f9ed0f8b871a014826f6fe5056356c16e0599b2 Mon Sep 17 00:00:00 2001 From: "rex.zheng" Date: Tue, 11 Jan 2022 08:42:22 +0800 Subject: [PATCH 136/379] feat: fixed the modification in accordance with EOL --- src/rs_driver/driver/input/input_factory.hpp | 4 ++-- src/rs_driver/driver/input/sock_input.hpp | 1 + 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 85fcd44d..0d7cfeea 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -33,7 +33,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include #include -#include +// #include namespace robosense { @@ -99,7 +99,7 @@ inline std::shared_ptr InputFactory::createInput(const RSDriverParam& dri if (input_param.read_pcap) { long long msec = msecToDelay(driver_param.lidar_type, input_param.pcap_rate); - input = std::make_shared(input_param, excb, msec); + // input = std::make_shared(input_param, excb, msec); } else { diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index 1652defb..92cd98c0 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -35,6 +35,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include "input.hpp" #include #include +#include namespace robosense { From c50fba26f96d21aea414b74216e9c334a0abe81d Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 11 Jan 2022 14:23:04 +0800 Subject: [PATCH 137/379] refac: change version --- CMakeLists.txt | 2 +- src/rs_driver/macro/version.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 7c3bfddb..b02c0e57 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.4.5) +project(rs_driver VERSION 1.4.3) #============================= # Compile Demos&Tools diff --git a/src/rs_driver/macro/version.hpp b/src/rs_driver/macro/version.hpp index 22117eaf..eb359fab 100644 --- a/src/rs_driver/macro/version.hpp +++ b/src/rs_driver/macro/version.hpp @@ -1,3 +1,3 @@ #define RSLIDAR_VERSION_MAJOR 1 #define RSLIDAR_VERSION_MINOR 4 -#define RSLIDAR_VERSION_PATCH 5 +#define RSLIDAR_VERSION_PATCH 3 From 351a2884aee95f04672f007a3efcea7145c22584 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 12 Jan 2022 10:27:29 +0800 Subject: [PATCH 138/379] refac: fix print info --- src/rs_driver/driver/driver_param.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 0dd358ae..04b49b35 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -270,8 +270,8 @@ typedef struct RSInputParam ///< The LiDAR input parameter RS_INFOL << "host_address: " << host_address << RS_REND; RS_INFOL << "msop_port: " << msop_port << RS_REND; RS_INFOL << "difop_port: " << difop_port << RS_REND; - RS_INFOL << "pcap_path: " << pcap_rate << RS_REND; - RS_INFOL << "pcap_rate: " << pcap_path << RS_REND; + RS_INFOL << "pcap_path: " << pcap_path << RS_REND; + RS_INFOL << "pcap_rate: " << pcap_rate << RS_REND; RS_INFOL << "pcap_repeat: " << pcap_repeat << RS_REND; RS_INFOL << "use_vlan: " << use_vlan << RS_REND; RS_INFOL << "use_someip: " << use_someip << RS_REND; From 0bdc40aa620dd5921f0e091ac86f95ab23609935 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 12 Jan 2022 16:09:46 +0800 Subject: [PATCH 139/379] refac: refactory packet --- src/rs_driver/driver/lidar_driver_impl.hpp | 13 +++++++++---- src/rs_driver/msg/packet.hpp | 5 +++-- 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 6bba9231..e289f57f 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -80,7 +80,7 @@ class LidarDriverImpl private: - void runCallBack(std::shared_ptr pkt); + void runCallBack(std::shared_ptr pkt, double timestamp, uint8_t is_difop = true, uint8_t is_frame_begin = false); void reportError(const Error& error); std::shared_ptr packetGet(size_t size); @@ -273,11 +273,16 @@ inline bool LidarDriverImpl::getTemperature(float& temp) } template -inline void LidarDriverImpl::runCallBack(std::shared_ptr buf) +inline void LidarDriverImpl::runCallBack(std::shared_ptr buf, + double timestamp, uint8_t is_difop, uint8_t is_frame_begin) { if (cb_put_pkt_) { Packet pkt; + pkt.is_difop = is_difop; + pkt.is_frame_begin = is_frame_begin; + pkt.seq = pkt_seq_++; + pkt.buf_.resize(buf->dataSize()); memcpy (pkt.buf_.data(), buf->data(), buf->dataSize()); cb_put_pkt_(pkt); @@ -347,7 +352,7 @@ inline void LidarDriverImpl::processMsop() } lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); - runCallBack(pkt); + runCallBack(pkt, 0, false, false); free_pkt_queue_.push(pkt); } @@ -365,7 +370,7 @@ inline void LidarDriverImpl::processDifop() } lidar_decoder_ptr_->processDifopPkt(pkt->data(), pkt->dataSize()); - runCallBack(pkt); + runCallBack(pkt, 0); free_pkt_queue_.push(pkt); } diff --git a/src/rs_driver/msg/packet.hpp b/src/rs_driver/msg/packet.hpp index 03e1409f..6c22dc36 100644 --- a/src/rs_driver/msg/packet.hpp +++ b/src/rs_driver/msg/packet.hpp @@ -45,8 +45,9 @@ struct Packet { double timestamp = 0.0; uint32_t seq = 0; - uint8_t type = 0; /// 0 - msop, 1 - difop - std::string frame_id = ""; +// std::string frame_id = ""; + uint8_t is_difop = 0; + uint8_t is_frame_begin = 0; Packet(const Packet& msg) { From 56cf0a0e3927fc3ff94900a4cc5d9f6ca550379a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 12 Jan 2022 17:29:44 +0800 Subject: [PATCH 140/379] refac: refactory decoder --- src/rs_driver/driver/lidar_driver_impl.hpp | 2 +- src/rs_driver/msg/packet.hpp | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index e289f57f..565854c7 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -75,7 +75,7 @@ class LidarDriverImpl bool start(); void stop(); - void decodePacket(const Packet& pkt); + void decodePacket(const Packet& pkt); bool getTemperature(float& temp); private: diff --git a/src/rs_driver/msg/packet.hpp b/src/rs_driver/msg/packet.hpp index 6c22dc36..4355bdde 100644 --- a/src/rs_driver/msg/packet.hpp +++ b/src/rs_driver/msg/packet.hpp @@ -45,7 +45,6 @@ struct Packet { double timestamp = 0.0; uint32_t seq = 0; -// std::string frame_id = ""; uint8_t is_difop = 0; uint8_t is_frame_begin = 0; From 121184534e1a106cc813845f3f3c73232fd25a08 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 13 Jan 2022 15:18:51 +0800 Subject: [PATCH 141/379] refac: format --- CMakeLists.txt | 2 +- demo/demo_online.cpp | 1 + src/rs_driver/driver/decoder/basic_attr.hpp | 8 ++++++-- src/rs_driver/driver/decoder/decoder_RS32.hpp | 4 ++-- src/rs_driver/utility/dbg.hpp | 2 +- 5 files changed, 11 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b02c0e57..3616f706 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -13,7 +13,7 @@ project(rs_driver VERSION 1.4.3) #============================= option(COMPILE_DEMOS "Build rs_driver demos" ON) option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) -option(COMPILE_TESTS "Build rs_driver unit tests" ON) +option(COMPILE_TESTS "Build rs_driver unit tests" OFF) #============================= # Compile Features diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 5a8621cb..f4ef5605 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -85,6 +85,7 @@ int main(int argc, char* argv[]) param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 param.lidar_type = LidarType::RS32; ///< Set the lidar type. Make sure this type is correct param.decoder_param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + param.decoder_param.use_lidar_clock = false; param.print(); LidarDriver driver; diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index 509612ae..40b66611 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -157,12 +157,16 @@ inline uint64_t parseTimeYMD(const RSTimestampYMD* tsYmd) #if 0 std::cout << "tm_year:" << stm.tm_year << ", tm_mon:" << stm.tm_mon + << ", tm_day:" << stm.tm_mday + << ", tm_hour:" << stm.tm_hour + << ", tm_min:" << stm.tm_min + << ", tm_sec:" << stm.tm_sec << ", ms:" << ms << ", us:" << us << std::endl; #endif - return (sec * 1000000 + ms * 1000 + us); + return (sec * 1e6 + ms * 1e3 + us); } inline uint64_t getTimeHost(void) @@ -171,7 +175,7 @@ inline uint64_t getTimeHost(void) std::chrono::system_clock::duration t_s = t.time_since_epoch(); std::chrono::duration> t_us = - std::chrono::duration_cast>>(t_s); + std::chrono::duration_cast>>(t_s); return t_us.count(); } diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 76cebf92..ce44868e 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -251,12 +251,12 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeYMD(&pkt.header.timestamp) * 0.000001; + pkt_ts = parseTimeYMD(&pkt.header.timestamp) * 1e-6; } else { // roll back to first block to approach lidar ts as near as possible. - pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); + pkt_ts = getTimeHost() * 1e-6 - this->getPacketDuration(); } T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); diff --git a/src/rs_driver/utility/dbg.hpp b/src/rs_driver/utility/dbg.hpp index 24f26ad7..4e6e3fbd 100644 --- a/src/rs_driver/utility/dbg.hpp +++ b/src/rs_driver/utility/dbg.hpp @@ -38,7 +38,7 @@ namespace robosense namespace lidar { -inline void hexdump(const unsigned char* data, size_t size, const char* desc = NULL) +inline void hexdump(const uint8_t* data, size_t size, const char* desc = NULL) { printf("\n---------------%s(size:%d)------------------", (desc ? desc : ""), (int)size); From bd5a3e5cba6e57a35fed103c5b335b240cbb6441 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 13 Jan 2022 16:22:48 +0800 Subject: [PATCH 142/379] refac: add packet split flag --- src/rs_driver/driver/decoder/decoder.hpp | 14 +++++++------- src/rs_driver/driver/decoder/decoder_RS128.hpp | 16 ++++++++++------ src/rs_driver/driver/decoder/decoder_RS16.hpp | 17 ++++++++++------- src/rs_driver/driver/decoder/decoder_RS32.hpp | 16 ++++++++++------ src/rs_driver/driver/decoder/decoder_RS80.hpp | 16 ++++++++++------ src/rs_driver/driver/decoder/decoder_RSBP.hpp | 16 ++++++++++------ .../driver/decoder/decoder_RSHELIOS.hpp | 16 ++++++++++------ src/rs_driver/driver/decoder/decoder_RSM1.hpp | 8 ++++++-- src/rs_driver/driver/lidar_driver_impl.hpp | 8 ++++---- 9 files changed, 77 insertions(+), 50 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 94e41081..a4b8b18e 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -256,11 +256,11 @@ class Decoder constexpr static uint16_t PROTOCOL_VER_0 = 0x00; virtual void decodeDifopPkt(const uint8_t* pkt, size_t size) = 0; - virtual void decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual ~Decoder() = default; void processDifopPkt(const uint8_t* pkt, size_t size); - void processMsopPkt(const uint8_t* pkt, size_t size); + bool processMsopPkt(const uint8_t* pkt, size_t size); void regRecvCallback(const std::function& cb_new_point, const std::function& cb_split_frame); @@ -349,27 +349,27 @@ inline void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) decodeDifopPkt(pkt, size); } -inline void Decoder::processMsopPkt(const uint8_t* pkt, size_t size) +inline bool Decoder::processMsopPkt(const uint8_t* pkt, size_t size) { if (param_.wait_for_difop && !angles_ready_) { excb_(Error(ERRCODE_NODIFOPRECV)); - return; + return false; } if (size != this->const_param_.MSOP_LEN) { this->excb_(Error(ERRCODE_WRONGPKTLENGTH)); - return; + return false; } if (memcmp(pkt, this->const_param_.MSOP_ID, const_param_.MSOP_ID_LEN) != 0) { this->excb_(Error(ERRCODE_WRONGPKTHEADER)); - return; + return false; } - decodeMsopPkt(pkt, size); + return decodeMsopPkt(pkt, size); } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 85cec229..5bd96966 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -83,7 +83,7 @@ class DecoderRS128 : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); - virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRS128() = default; explicit DecoderRS128(const RSDecoderParam& param, @@ -97,7 +97,7 @@ class DecoderRS128 : public DecoderMech static RSEchoMode getEchoMode(uint8_t mode); template - void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; inline RSDecoderMechConstParam& DecoderRS128::getConstParam() @@ -187,22 +187,23 @@ inline void DecoderRS128::decodeDifopPkt(const uint8_t* packet, size_t size) (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -inline void DecoderRS128::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline bool DecoderRS128::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template -inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS128MsopPkt& pkt = *(const RS128MsopPkt*)(packet); + bool ret = false; this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; @@ -237,6 +238,7 @@ inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); + ret = true; } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -279,6 +281,8 @@ inline void DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size this->prev_point_ts_ = chan_ts; } } + + return ret; } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 0be87a87..b4360bf1 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -137,7 +137,7 @@ class DecoderRS16 : public DecoderMech public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); - virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRS16() = default; explicit DecoderRS16(const RSDecoderParam& param, @@ -151,7 +151,7 @@ class DecoderRS16 : public DecoderMech static RSEchoMode getEchoMode(uint8_t mode); template - void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; inline RSDecoderMechConstParam& DecoderRS16::getConstParam() @@ -231,22 +231,23 @@ inline void DecoderRS16::decodeDifopPkt(const uint8_t* packet, size_t size) (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -inline void DecoderRS16::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline bool DecoderRS16::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template -inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS16MsopPkt& pkt = *(const RS16MsopPkt*)(packet); + bool ret = false; this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; @@ -281,6 +282,7 @@ inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); + ret = true; } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -322,8 +324,9 @@ inline void DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) this->prev_point_ts_ = chan_ts; } - } + + return ret; } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index ce44868e..bc6c1617 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -136,7 +136,7 @@ class DecoderRS32 : public DecoderMech public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); - virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRS32() = default; explicit DecoderRS32(const RSDecoderParam& param, @@ -150,7 +150,7 @@ class DecoderRS32 : public DecoderMech static RSEchoMode getEchoMode(uint8_t mode); template - void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; inline RSDecoderMechConstParam& DecoderRS32::getConstParam() @@ -229,22 +229,23 @@ inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, size_t size) (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -inline void DecoderRS32::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline bool DecoderRS32::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template -inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS32MsopPkt& pkt = *(const RS32MsopPkt*)(packet); + bool ret = false; this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; @@ -279,6 +280,7 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); + ret = true; } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -321,6 +323,8 @@ inline void DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) this->prev_point_ts_ = chan_ts; } } + + return ret; } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 5ba4c78d..799a5063 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -85,7 +85,7 @@ class DecoderRS80 : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); - virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRS80() = default; explicit DecoderRS80(const RSDecoderParam& param, @@ -99,7 +99,7 @@ class DecoderRS80 : public DecoderMech static RSEchoMode getEchoMode(uint8_t mode); template - void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; inline RSDecoderMechConstParam& DecoderRS80::getConstParam() @@ -183,22 +183,23 @@ inline void DecoderRS80::decodeDifopPkt(const uint8_t* packet, size_t size) (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -inline void DecoderRS80::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline bool DecoderRS80::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template -inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS80MsopPkt& pkt = *(const RS80MsopPkt*)(packet); + bool ret = false; this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; @@ -233,6 +234,7 @@ inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); + ret = true; } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -275,6 +277,8 @@ inline void DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) this->prev_point_ts_ = chan_ts; } } + + return ret; } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 8bff9aa2..a09b3b90 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -86,7 +86,7 @@ class DecoderRSBP : public DecoderMech public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); - virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRSBP() = default; explicit DecoderRSBP(const RSDecoderParam& param, @@ -100,7 +100,7 @@ class DecoderRSBP : public DecoderMech static RSEchoMode getEchoMode(uint8_t mode); template - void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; inline RSDecoderMechConstParam& DecoderRSBP::getConstParam() @@ -177,22 +177,23 @@ inline void DecoderRSBP::decodeDifopPkt(const uint8_t* packet, size_t size) (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -inline void DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline bool DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template -inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RSBPMsopPkt& pkt = *(const RSBPMsopPkt*)(packet); + bool ret = false; this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; @@ -227,6 +228,7 @@ inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); + ret = true; } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -269,6 +271,8 @@ inline void DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) this->prev_point_ts_ = chan_ts; } } + + return ret; } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 1fb2a319..decab5d7 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -97,7 +97,7 @@ class DecoderRSHELIOS : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); - virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRSHELIOS() = default; explicit DecoderRSHELIOS(const RSDecoderParam& param, @@ -111,7 +111,7 @@ class DecoderRSHELIOS : public DecoderMech static RSEchoMode getEchoMode(uint8_t mode); template - void internDecodeMsopPkt(const uint8_t* pkt, size_t size); + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; inline RSDecoderMechConstParam& DecoderRSHELIOS::getConstParam() @@ -189,22 +189,23 @@ inline void DecoderRSHELIOS::decodeDifopPkt(const uint8_t* packet, size_t size) (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -inline void DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline bool DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template -inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RSHELIOSMsopPkt& pkt = *(const RSHELIOSMsopPkt*)(packet); + bool ret = false; this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; @@ -239,6 +240,7 @@ inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t s if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); + ret = true; } for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -281,6 +283,8 @@ inline void DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t s this->prev_point_ts_ = chan_ts; } } + + return ret; } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index cbee5d24..f282ae6a 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -142,7 +142,7 @@ class DecoderRSM1 : public Decoder constexpr static int ANGLE_OFFSET = 32768; virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); - virtual void decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRSM1() = default; explicit DecoderRSM1(const RSDecoderParam& param, @@ -210,9 +210,10 @@ inline void DecoderRSM1::decodeDifopPkt(const uint8_t* packet, size_t size) max_seq_ = (this->echo_mode_ == ECHO_SINGLE) ? SINGLE_PKT_NUM : DUAL_PKT_NUM; } -inline void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) { const RSM1MsopPkt& pkt = *(RSM1MsopPkt*)packet; + bool ret = false; this->temperature_ = static_cast(pkt.header.temperature - 80); @@ -275,7 +276,10 @@ inline void DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) if (split_.newPacket(pkt_seq)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); + ret = true; } + + return ret; } } // namespace lidar diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 565854c7..c197a4d9 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -80,7 +80,7 @@ class LidarDriverImpl private: - void runCallBack(std::shared_ptr pkt, double timestamp, uint8_t is_difop = true, uint8_t is_frame_begin = false); + void runCallBack(std::shared_ptr pkt, double timestamp, uint8_t is_difop, uint8_t is_frame_begin); void reportError(const Error& error); std::shared_ptr packetGet(size_t size); @@ -351,8 +351,8 @@ inline void LidarDriverImpl::processMsop() continue; } - lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); - runCallBack(pkt, 0, false, false); + bool split = lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); + runCallBack(pkt, 0, false, split); // msop packet free_pkt_queue_.push(pkt); } @@ -370,7 +370,7 @@ inline void LidarDriverImpl::processDifop() } lidar_decoder_ptr_->processDifopPkt(pkt->data(), pkt->dataSize()); - runCallBack(pkt, 0); + runCallBack(pkt, 0, true, false); // difop packet free_pkt_queue_.push(pkt); } From 5af6d1353c35bb66a3fcade678fb1a1dbb9c4804 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 13 Jan 2022 16:49:30 +0800 Subject: [PATCH 143/379] refac: write pkt ts --- src/rs_driver/driver/decoder/decoder.hpp | 8 ++++++++ src/rs_driver/driver/lidar_driver_impl.hpp | 1 + 2 files changed, 9 insertions(+) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index a4b8b18e..03f60786 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -271,6 +271,7 @@ class Decoder float getTemperature(); double getPacketDuration(); + void enableWritePktTs(bool value); #ifndef UNIT_TEST protected: @@ -281,6 +282,7 @@ class Decoder std::function cb_new_point_; std::function cb_split_frame_; std::function excb_; + bool write_pkt_ts_; Trigon trigon_; #define SIN(angle) this->trigon_.sin(angle) @@ -311,6 +313,7 @@ inline Decoder::Decoder(const RSDecoderConstParam& const_param, : const_param_(const_param) , param_(param) , excb_(excb) + , write_pkt_ts_(false) , height_(0) , packet_duration_(0) , distance_section_(const_param.DISTANCE_MIN, const_param.DISTANCE_MAX, @@ -322,6 +325,11 @@ inline Decoder::Decoder(const RSDecoderConstParam& const_param, { } +void Decoder::enableWritePktTs(bool value) +{ + write_pkt_ts_ = value; +} + inline float Decoder::getTemperature() { return temperature_; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index c197a4d9..a87fd336 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -186,6 +186,7 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) lidar_decoder_ptr_->regRecvCallback( std::bind(&LidarDriverImpl::newPoint, this, std::placeholders::_1), std::bind(&LidarDriverImpl::splitFrame, this, std::placeholders::_1, std::placeholders::_2)); + lidar_decoder_ptr_->enableWritePktTs((cb_put_pkt_ == nullptr) ? false : true); double packet_duration = lidar_decoder_ptr_->getPacketDuration(); From 673b7a1a60f842043b2a9d6d99eeec6636ef4c63 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 13 Jan 2022 17:45:12 +0800 Subject: [PATCH 144/379] refac: fix rs32 timestamp --- src/rs_driver/driver/decoder/basic_attr.hpp | 40 ++++++++++++++++++- src/rs_driver/driver/decoder/decoder_RS32.hpp | 9 ++++- src/rs_driver/driver/lidar_driver_impl.hpp | 3 +- 3 files changed, 49 insertions(+), 3 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index 40b66611..d387fa8a 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -141,7 +141,7 @@ inline uint64_t parseTimeYMD(const RSTimestampYMD* tsYmd) memset(&stm, 0, sizeof(stm)); // since 2000 in robosense YMD, and since 1900 in struct tm - stm.tm_year = tsYmd->year + 2000 - 1900; + stm.tm_year = tsYmd->year + (2000 - 1900); // since 1 in robosense YMD, and since 0 in struct tm stm.tm_mon = tsYmd->month - 1; // since 1 in both robosense YMD and struct tm @@ -169,6 +169,44 @@ inline uint64_t parseTimeYMD(const RSTimestampYMD* tsYmd) return (sec * 1e6 + ms * 1e3 + us); } +inline void createTimeYMD(uint64_t usec, RSTimestampYMD* tsYmd) +{ + uint64_t us = usec % 1000; + uint64_t tot_ms = (usec - us) / 1000; + + uint64_t ms = tot_ms % 1000; + uint64_t sec = tot_ms / 1000; + + time_t t_sec = sec; + + std::tm* stm = localtime(&t_sec); + + // since 2000 in robosense YMD, and since 1900 in struct tm + tsYmd->year = stm->tm_year - (2000 - 1900); + // since 1 in robosense YMD, and since 0 in struct tm + tsYmd->month = stm->tm_mon + 1; + // since 1 in both robosense YMD and struct tm + tsYmd->day = stm->tm_mday; + tsYmd->hour = stm->tm_hour; + tsYmd->minute = stm->tm_min; + tsYmd->second = stm->tm_sec; + + tsYmd->ms = htons((uint16_t)ms); + tsYmd->us = htons((uint16_t)us); + +#if 0 + std::cout << "year:" << (int)tsYmd->year + << ", month:" << (int)tsYmd->month + << ", day:" << (int)tsYmd->day + << ", hour:" << (int)tsYmd->hour + << ", minute:" << (int)tsYmd->minute + << ", second:" << (int)tsYmd->second + << ", ms:" << tsYmd->ms + << ", us:" << tsYmd->us + << std::endl; +#endif +} + inline uint64_t getTimeHost(void) { std::chrono::system_clock::time_point t = std::chrono::system_clock::now(); diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index bc6c1617..fe21ee26 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -256,8 +256,15 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) } else { + uint64_t ts = getTimeHost(); + // roll back to first block to approach lidar ts as near as possible. - pkt_ts = getTimeHost() * 1e-6 - this->getPacketDuration(); + pkt_ts = ts * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeYMD (ts, (RSTimestampYMD*)&pkt.header.timestamp); + } } T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index a87fd336..61feb743 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -186,7 +186,8 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) lidar_decoder_ptr_->regRecvCallback( std::bind(&LidarDriverImpl::newPoint, this, std::placeholders::_1), std::bind(&LidarDriverImpl::splitFrame, this, std::placeholders::_1, std::placeholders::_2)); - lidar_decoder_ptr_->enableWritePktTs((cb_put_pkt_ == nullptr) ? false : true); + //lidar_decoder_ptr_->enableWritePktTs((cb_put_pkt_ == nullptr) ? false : true); + lidar_decoder_ptr_->enableWritePktTs(true); double packet_duration = lidar_decoder_ptr_->getPacketDuration(); From 5aa8941746902ad4c73ba2a072b64324ce2fa14d Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 13 Jan 2022 17:54:35 +0800 Subject: [PATCH 145/379] refac: write pkt ts --- src/rs_driver/driver/decoder/decoder.hpp | 8 ++++++++ src/rs_driver/driver/decoder/decoder_RS32.hpp | 1 + src/rs_driver/driver/lidar_driver_impl.hpp | 5 ++--- 3 files changed, 11 insertions(+), 3 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 03f60786..4f0cde06 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -272,6 +272,7 @@ class Decoder float getTemperature(); double getPacketDuration(); void enableWritePktTs(bool value); + double prevPktTs(); #ifndef UNIT_TEST protected: @@ -296,6 +297,7 @@ class Decoder float temperature_; // lidar temperature bool angles_ready_; // is vert_angles/horiz_angles ready from csv file/difop packet? + double prev_pkt_ts_; // last packet's timestamp double prev_point_ts_; // last point's timestamp }; @@ -321,6 +323,7 @@ inline Decoder::Decoder(const RSDecoderConstParam& const_param, , echo_mode_(ECHO_SINGLE) , temperature_(0.0) , angles_ready_(false) + , prev_pkt_ts_(0.0) , prev_point_ts_(0.0) { } @@ -340,6 +343,11 @@ inline double Decoder::getPacketDuration() return packet_duration_; } +inline double Decoder::prevPktTs() +{ + return prev_pkt_ts_; +} + inline void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) { if (size != this->const_param_.DIFOP_LEN) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index fe21ee26..5c0b8660 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -331,6 +331,7 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) } } + this->prev_pkt_ts_ = pkt_ts; return ret; } diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 61feb743..7f9f6624 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -186,8 +186,7 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) lidar_decoder_ptr_->regRecvCallback( std::bind(&LidarDriverImpl::newPoint, this, std::placeholders::_1), std::bind(&LidarDriverImpl::splitFrame, this, std::placeholders::_1, std::placeholders::_2)); - //lidar_decoder_ptr_->enableWritePktTs((cb_put_pkt_ == nullptr) ? false : true); - lidar_decoder_ptr_->enableWritePktTs(true); + lidar_decoder_ptr_->enableWritePktTs((cb_put_pkt_ == nullptr) ? false : true); double packet_duration = lidar_decoder_ptr_->getPacketDuration(); @@ -354,7 +353,7 @@ inline void LidarDriverImpl::processMsop() } bool split = lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); - runCallBack(pkt, 0, false, split); // msop packet + runCallBack(pkt, lidar_decoder_ptr_->prevPktTs(), false, split); // msop packet free_pkt_queue_.push(pkt); } From 062906c30286a79a150e1dae794015b0c8908dcd Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 13 Jan 2022 18:15:04 +0800 Subject: [PATCH 146/379] refac: fix compiling error --- src/rs_driver/driver/decoder/decoder.hpp | 2 +- test/decoder_test.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 4f0cde06..03657bb4 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -328,7 +328,7 @@ inline Decoder::Decoder(const RSDecoderConstParam& const_param, { } -void Decoder::enableWritePktTs(bool value) +inline void Decoder::enableWritePktTs(bool value) { write_pkt_ts_ = value; } diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index bd926303..4412d13a 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -42,8 +42,9 @@ class MyDecoder : public DecoderMech this->template decodeDifopCommon(pkt); } - virtual void decodeMsopPkt(const uint8_t* pkt, size_t size) + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size) { + return false; } }; From fd424354ac20eac3eed6f4865c5d6f39208c4a24 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 14 Jan 2022 16:34:02 +0800 Subject: [PATCH 147/379] refac: format --- src/rs_driver/driver/decoder/decoder.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 03657bb4..861d12ff 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -50,6 +50,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include namespace robosense { From 0b03631947ed484606c8c3cef6ebd811e18c6823 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 14 Jan 2022 16:53:48 +0800 Subject: [PATCH 148/379] refac: refac rs16 --- src/rs_driver/driver/decoder/decoder_RS128.hpp | 1 + src/rs_driver/driver/decoder/decoder_RS16.hpp | 12 ++++++++++-- src/rs_driver/driver/decoder/decoder_RS80.hpp | 1 + src/rs_driver/driver/decoder/decoder_RSBP.hpp | 1 + src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp | 1 + src/rs_driver/driver/decoder/decoder_RSM1.hpp | 1 + 6 files changed, 15 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 5bd96966..2f06ad91 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -282,6 +282,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size } } + this->prev_pkt_ts_ = pkt_ts; return ret; } diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index b4360bf1..fe394467 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -254,12 +254,19 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeYMD(&pkt.header.timestamp) * 0.000001; + pkt_ts = parseTimeYMD(&pkt.header.timestamp) * 1e-6; } else { + uint64_t ts = getTimeHost(); + // roll back to first block to approach lidar ts as near as possible. - pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); + pkt_ts = ts * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeYMD (ts, (RSTimestampYMD*)&pkt.header.timestamp); + } } T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); @@ -326,6 +333,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) } } + this->prev_pkt_ts_ = pkt_ts; return ret; } diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 799a5063..9461a8f2 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -278,6 +278,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) } } + this->prev_pkt_ts_ = pkt_ts; return ret; } diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index a09b3b90..ff42b526 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -272,6 +272,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) } } + this->prev_pkt_ts_ = pkt_ts; return ret; } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index decab5d7..d2423308 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -284,6 +284,7 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t s } } + this->prev_pkt_ts_ = pkt_ts; return ret; } diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index f282ae6a..7181946b 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -279,6 +279,7 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) ret = true; } + this->prev_pkt_ts_ = pkt_ts; return ret; } From eaad7b2ae41963f6c7f9b9a5846546cc74467f3e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 14 Jan 2022 18:47:22 +0800 Subject: [PATCH 149/379] refac: refactory rshelios --- src/rs_driver/driver/decoder/basic_attr.hpp | 48 +++++++++++++------ .../driver/decoder/decoder_RSHELIOS.hpp | 11 ++++- test/basic_attr_test.cpp | 32 +++++++++---- 3 files changed, 66 insertions(+), 25 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index d387fa8a..69a13dd1 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -82,6 +82,7 @@ inline uint64_t parseTimeUTCWithNs(const RSTimestampUTC* tsUtc) sec += tsUtc->sec[i]; } + // ns uint64_t ns = 0; for (int i = 0; i < 4; i++) { @@ -102,6 +103,7 @@ inline uint64_t parseTimeUTCWithUs(const RSTimestampUTC* tsUtc) sec += tsUtc->sec[i]; } + // us uint64_t us = 0; for (int i = 0; i < 4; i++) { @@ -112,6 +114,24 @@ inline uint64_t parseTimeUTCWithUs(const RSTimestampUTC* tsUtc) return (sec * 1000000 + us); } +inline void createTimeUTCWithUs(uint64_t us, RSTimestampUTC* tsUtc) +{ + uint64_t sec = us / 1000000; + uint64_t usec = us % 1000000; + + for (int i = 5; i >= 0; i--) + { + tsUtc->sec[i] = sec & 0xFF; + sec >>= 8; + } + + for (int i = 3; i >= 0; i--) + { + tsUtc->ss[i] = usec & 0xFF; + usec >>= 8; + } +} + inline uint64_t parseTimeUTCWithMs(const RSTimestampUTC* tsUtc) { // sec @@ -166,7 +186,7 @@ inline uint64_t parseTimeYMD(const RSTimestampYMD* tsYmd) << std::endl; #endif - return (sec * 1e6 + ms * 1e3 + us); + return (sec * 1000000 + ms * 1000 + us); } inline void createTimeYMD(uint64_t usec, RSTimestampYMD* tsYmd) @@ -179,7 +199,19 @@ inline void createTimeYMD(uint64_t usec, RSTimestampYMD* tsYmd) time_t t_sec = sec; - std::tm* stm = localtime(&t_sec); + std::tm* stm = localtime(&t_sec); + +#if 0 + std::cout << "+ tm_year:" << stm->tm_year + << ", tm_mon:" << stm->tm_mon + << ", tm_day:" << stm->tm_mday + << ", tm_hour:" << stm->tm_hour + << ", tm_min:" << stm->tm_min + << ", tm_sec:" << stm->tm_sec + << ", ms:" << ms + << ", us:" << us + << std::endl; +#endif // since 2000 in robosense YMD, and since 1900 in struct tm tsYmd->year = stm->tm_year - (2000 - 1900); @@ -193,18 +225,6 @@ inline void createTimeYMD(uint64_t usec, RSTimestampYMD* tsYmd) tsYmd->ms = htons((uint16_t)ms); tsYmd->us = htons((uint16_t)us); - -#if 0 - std::cout << "year:" << (int)tsYmd->year - << ", month:" << (int)tsYmd->month - << ", day:" << (int)tsYmd->day - << ", hour:" << (int)tsYmd->hour - << ", minute:" << (int)tsYmd->minute - << ", second:" << (int)tsYmd->second - << ", ms:" << tsYmd->ms - << ", us:" << tsYmd->us - << std::endl; -#endif } inline uint64_t getTimeHost(void) diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index d2423308..86d9093c 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -212,12 +212,19 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t s double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 0.000001; + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 1e-6; } else { + uint64_t ts = getTimeHost(); + // roll back to first block to approach lidar ts as near as possible. - pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); + pkt_ts = ts * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + } } T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); diff --git a/test/basic_attr_test.cpp b/test/basic_attr_test.cpp index 53b304c8..2603c24b 100644 --- a/test/basic_attr_test.cpp +++ b/test/basic_attr_test.cpp @@ -2,24 +2,38 @@ #include #include +#include using namespace robosense::lidar; -TEST(TestParseTime, parseTimeUTC) +TEST(TestParseTime, parseTimeYMD) { - RSTimestampUTC ts = - {{0x01, 0x02, 0x03, 0x04, 0x05, 0x06}, {0x11, 0x22, 0x33, 0x44}}; + uint8_t ts1[] = {0x15, 0x0a, 0x01, 0x01, 0x02, 0x03, 0x01, 0x11, 0x02, 0x22}; + uint8_t ts2[10]; + + ASSERT_EQ(parseTimeYMD((RSTimestampYMD*)ts1), 1633021323273546); - ASSERT_EQ(parseTimeUTCWithNs(&ts), 0x010203040506 * 1000000 + 0x11223344/1000); - ASSERT_EQ(parseTimeUTCWithUs(&ts), 0x010203040506 * 1000000 + 0x11223344); - ASSERT_EQ(parseTimeUTCWithMs(&ts), 0x010203040506 * 1000000 + 0x1122 * 1000 + 0x3344); + createTimeYMD(1633021323273546, (RSTimestampYMD*)ts2); + ASSERT_EQ(memcmp(ts2, ts1, 10), 0); } -TEST(TestParseTime, parseTimeYMD) +TEST(TestParseTime, parseTimeUTC) { - uint8_t ts[] = {0x15, 0x0a, 0x01, 0x01, 0x02, 0x03, 0x11, 0x22, 0x33, 0x44}; + RSTimestampUTC ts1 = + {{0x01, 0x02, 0x03, 0x04, 0x05, 0x06}, {0x00, 0x02, 0x33, 0x44}}; + RSTimestampUTC ts2; + + ASSERT_EQ(parseTimeUTCWithNs(&ts1), 0x010203040506 * 1000000 + 0x00023344/1000); + + { + ASSERT_EQ(parseTimeUTCWithUs(&ts1), 0x010203040506 * 1000000 + 0x00023344); + + createTimeUTCWithUs(0x010203040506 * 1000000 + 0x00023344, &ts2); + hexdump ((uint8_t*)&ts2, sizeof(ts2), "ts2"); + ASSERT_EQ(memcmp(&ts2, &ts1, sizeof(ts1)), 0); + } - ASSERT_EQ(parseTimeYMD((RSTimestampYMD*)&ts), 1633021327399124); + ASSERT_EQ(parseTimeUTCWithMs(&ts1), 0x010203040506 * 1000000 + 0x0002 * 1000 + 0x3344); } TEST(TestParseTime, getTimeHost) From 282701b1596ac4a60f410860daeece4b4190a00e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 14 Jan 2022 18:52:28 +0800 Subject: [PATCH 150/379] refac: refactory rsbp --- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index ff42b526..a8ff6cb4 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -200,12 +200,19 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeYMD(&pkt.header.timestamp) * 0.000001; + pkt_ts = parseTimeYMD(&pkt.header.timestamp) * 1e-6; } else { + uint64_t ts = getTimeHost(); + // roll back to first block to approach lidar ts as near as possible. - pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); + pkt_ts = ts * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeYMD (ts, (RSTimestampYMD*)&pkt.header.timestamp); + } } T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); From 4cca9b4f6cd423309865a103b10547e874862a52 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 14 Jan 2022 19:29:11 +0800 Subject: [PATCH 151/379] refac: refactory rs128 --- src/rs_driver/driver/decoder/basic_attr.hpp | 20 +++++++++++++++ .../driver/decoder/decoder_RS128.hpp | 11 ++++++-- test/basic_attr_test.cpp | 25 +++++++++++-------- 3 files changed, 44 insertions(+), 12 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index 69a13dd1..a991f720 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -93,6 +93,26 @@ inline uint64_t parseTimeUTCWithNs(const RSTimestampUTC* tsUtc) return (sec * 1000000 + ns/1000); } +inline void createTimeUTCWithNs(uint64_t us, RSTimestampUTC* tsUtc) +{ + uint64_t sec = us / 1000000; + uint64_t nsec = (us % 1000000) * 1000; + + std::cout << std::hex << "usec:" << nsec << std::endl; + + for (int i = 5; i >= 0; i--) + { + tsUtc->sec[i] = sec & 0xFF; + sec >>= 8; + } + + for (int i = 3; i >= 0; i--) + { + tsUtc->ss[i] = nsec & 0xFF; + nsec >>= 8; + } +} + inline uint64_t parseTimeUTCWithUs(const RSTimestampUTC* tsUtc) { // sec diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 2f06ad91..2734fd21 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -210,12 +210,19 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 0.000001; + pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 1e-6; } else { + uint64_t ts = getTimeHost(); + // roll back to first block to approach lidar ts as near as possible. - pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); + pkt_ts = ts * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeUTCWithNs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + } } T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); diff --git a/test/basic_attr_test.cpp b/test/basic_attr_test.cpp index 2603c24b..76beb180 100644 --- a/test/basic_attr_test.cpp +++ b/test/basic_attr_test.cpp @@ -17,23 +17,28 @@ TEST(TestParseTime, parseTimeYMD) ASSERT_EQ(memcmp(ts2, ts1, 10), 0); } -TEST(TestParseTime, parseTimeUTC) +TEST(TestParseTime, parseTimeUTCWithNs) { RSTimestampUTC ts1 = - {{0x01, 0x02, 0x03, 0x04, 0x05, 0x06}, {0x00, 0x02, 0x33, 0x44}}; + {{0x01, 0x02, 0x03, 0x04, 0x05, 0x06}, {0x06, 0xA1, 0x1C, 0xF0}}; RSTimestampUTC ts2; - ASSERT_EQ(parseTimeUTCWithNs(&ts1), 0x010203040506 * 1000000 + 0x00023344/1000); + ASSERT_EQ(parseTimeUTCWithNs(&ts1), 0x010203040506 * 1000000 + 0x06A11CF0/1000); - { - ASSERT_EQ(parseTimeUTCWithUs(&ts1), 0x010203040506 * 1000000 + 0x00023344); + createTimeUTCWithNs(0x010203040506 * 1000000 + 0x06A11CF0/1000, &ts2); + ASSERT_EQ(memcmp(&ts2, &ts1, sizeof(ts1)), 0); +} - createTimeUTCWithUs(0x010203040506 * 1000000 + 0x00023344, &ts2); - hexdump ((uint8_t*)&ts2, sizeof(ts2), "ts2"); - ASSERT_EQ(memcmp(&ts2, &ts1, sizeof(ts1)), 0); - } +TEST(TestParseTime, parseTimeUTCWithUs) +{ + RSTimestampUTC ts1 = + {{0x01, 0x02, 0x03, 0x04, 0x05, 0x06}, {0x00, 0x02, 0x33, 0x44}}; + RSTimestampUTC ts2; + + ASSERT_EQ(parseTimeUTCWithUs(&ts1), 0x010203040506 * 1000000 + 0x00023344); - ASSERT_EQ(parseTimeUTCWithMs(&ts1), 0x010203040506 * 1000000 + 0x0002 * 1000 + 0x3344); + createTimeUTCWithUs(0x010203040506 * 1000000 + 0x00023344, &ts2); + ASSERT_EQ(memcmp(&ts2, &ts1, sizeof(ts1)), 0); } TEST(TestParseTime, getTimeHost) From 2660ae3f18d4b67bcef04ab90b83b4260e90bc71 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 14 Jan 2022 19:31:29 +0800 Subject: [PATCH 152/379] refac: refactory rs80 --- src/rs_driver/driver/decoder/decoder_RS80.hpp | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 9461a8f2..696108a9 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -206,12 +206,19 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 0.000001; + pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 1e-6; } else { + uint64_t ts = getTimeHost(); + // roll back to first block to approach lidar ts as near as possible. - pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); + pkt_ts = ts * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeUTCWithNs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + } } T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); From 9f67ab704d728e0b55d49e2e2747d14cde198514 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 14 Jan 2022 19:34:26 +0800 Subject: [PATCH 153/379] refac: refactory rsm1 --- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 7181946b..ca7e9fc2 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -220,12 +220,19 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 0.000001; + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 1e-6; } else { + uint64_t ts = getTimeHost(); + // roll back to first block to approach lidar ts as near as possible. - pkt_ts = getTimeHost() * 0.000001 - this->getPacketDuration(); + pkt_ts = getTimeHost() * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + } } for (size_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) From 6d5d9b50323c89545cbca2e913cf4d5385afc6fb Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 17 Jan 2022 11:08:37 +0800 Subject: [PATCH 154/379] refac: tested temp parsing --- src/rs_driver/driver/decoder/basic_attr.hpp | 18 +++++++++++++-- .../driver/decoder/decoder_RS128.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS16.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 2 +- .../driver/decoder/decoder_RSHELIOS.hpp | 2 +- test/basic_attr_test.cpp | 23 +++++++++++++++---- 8 files changed, 40 insertions(+), 13 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index a991f720..2abd6a70 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -257,13 +257,13 @@ inline uint64_t getTimeHost(void) return t_us.count(); } -inline int16_t parseTemp(const RSTemperature* tmp) +inline int16_t parseTempInLe(const RSTemperature* tmp) // format of little endian { // | lsb | padding | neg | msb | // | 5 | 3 | 1 | 7 | (in bits) uint8_t lsb = tmp->tt[0] >> 3; - uint8_t msb = tmp->tt[1] & 0x7F; uint8_t neg = tmp->tt[1] & 0x80; + uint8_t msb = tmp->tt[1] & 0x7F; int16_t t = ((uint16_t)msb << 5) + lsb; if (neg) t = -t; @@ -271,5 +271,19 @@ inline int16_t parseTemp(const RSTemperature* tmp) return t; } +inline int16_t parseTempInBe(const RSTemperature* tmp) // format of big endian +{ + // | neg | msb | lsb | padding | + // | 1 | 7 | 4 | 4 | (in bits) + uint8_t neg = tmp->tt[0] & 0x80; + uint8_t msb = tmp->tt[0] & 0x7F; + uint8_t lsb = tmp->tt[1] >> 4; + + int16_t t = ((uint16_t)msb << 4) + lsb; + if (neg) t = -t; + + return t; +} + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 2734fd21..8c88782c 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -205,7 +205,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size const RS128MsopPkt& pkt = *(const RS128MsopPkt*)(packet); bool ret = false; - this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + this->temperature_ = parseTempInBe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; double pkt_ts = 0; if (this->param_.use_lidar_clock) diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index fe394467..999f244d 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -249,7 +249,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) const RS16MsopPkt& pkt = *(const RS16MsopPkt*)(packet); bool ret = false; - this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + this->temperature_ = parseTempInLe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; double pkt_ts = 0; if (this->param_.use_lidar_clock) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 5c0b8660..ba3f39da 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -247,7 +247,7 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) const RS32MsopPkt& pkt = *(const RS32MsopPkt*)(packet); bool ret = false; - this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + this->temperature_ = parseTempInLe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; double pkt_ts = 0; if (this->param_.use_lidar_clock) diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 696108a9..d10f7c5c 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -201,7 +201,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) const RS80MsopPkt& pkt = *(const RS80MsopPkt*)(packet); bool ret = false; - this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + this->temperature_ = parseTempInBe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; double pkt_ts = 0; if (this->param_.use_lidar_clock) diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index a8ff6cb4..fd93b4e2 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -195,7 +195,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) const RSBPMsopPkt& pkt = *(const RSBPMsopPkt*)(packet); bool ret = false; - this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + this->temperature_ = parseTempInLe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; double pkt_ts = 0; if (this->param_.use_lidar_clock) diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 86d9093c..21373a3c 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -207,7 +207,7 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t s const RSHELIOSMsopPkt& pkt = *(const RSHELIOSMsopPkt*)(packet); bool ret = false; - this->temperature_ = parseTemp(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + this->temperature_ = parseTempInLe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; double pkt_ts = 0; if (this->param_.use_lidar_clock) diff --git a/test/basic_attr_test.cpp b/test/basic_attr_test.cpp index 76beb180..fb65e971 100644 --- a/test/basic_attr_test.cpp +++ b/test/basic_attr_test.cpp @@ -46,16 +46,29 @@ TEST(TestParseTime, getTimeHost) getTimeHost(); } -TEST(TestParseTemp, parseTemp) +TEST(TestParseTemp, parseTempInLe) { { - uint8_t temp[] = {0x18, 0x01}; - ASSERT_EQ(parseTemp((RSTemperature*)&temp), 35); + uint8_t temp[] = {0x88, 0x11}; + ASSERT_EQ(parseTempInLe((RSTemperature*)&temp), 561); } { - uint8_t temp[] = {0x18, 0x81}; - ASSERT_EQ(parseTemp((RSTemperature*)&temp), -35); + uint8_t temp[] = {0x88, 0x91}; + ASSERT_EQ(parseTempInLe((RSTemperature*)&temp), -561); + } +} + +TEST(TestParseTemp, parseTempInBe) +{ + { + uint8_t temp[] = {0x23, 0x10}; + ASSERT_EQ(parseTempInBe((RSTemperature*)&temp), 561); + } + + { + uint8_t temp[] = {0xA3, 0x10}; + ASSERT_EQ(parseTempInBe((RSTemperature*)&temp), -561); } } From 2db4f660447d9382543cfc29c945011f96c14542 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 17 Jan 2022 11:47:53 +0800 Subject: [PATCH 155/379] refac: format --- tool/rs_driver_viewer.cpp | 25 +++++++------------------ 1 file changed, 7 insertions(+), 18 deletions(-) diff --git a/tool/rs_driver_viewer.cpp b/tool/rs_driver_viewer.cpp index 094e085a..eafd18dd 100644 --- a/tool/rs_driver_viewer.cpp +++ b/tool/rs_driver_viewer.cpp @@ -31,29 +31,17 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #include +#include #include #include -typedef pcl::PointXYZI PointT; - -template -class PointCloudT : public pcl::PointCloud -{ -public: - typedef T_Point PointT; - typedef typename pcl::PointCloud::VectorType VectorT; - - double timestamp = 0.0; - std::string frame_id = ""; ///< Point cloud frame id - uint32_t seq = 0; ///< Sequence number of message -}; +using namespace robosense::lidar; +using namespace pcl::visualization; -typedef PointCloudT PointCloudMsg; +typedef PointCloudT PointCloudMsg; std::shared_ptr g_pointcloud; -using namespace robosense::lidar; -using namespace pcl::visualization; std::shared_ptr pcl_viewer; std::mutex mex_viewer; @@ -91,6 +79,7 @@ void parseParam(int argc, char* argv[], RSDriverParam& param) { param.decoder_param.wait_for_difop = false; std::string result_str; + if (parseArgument(argc, argv, "-type", result_str)) { param.lidar_type = strToLidarType(result_str); @@ -235,14 +224,14 @@ void exceptionCallback(const Error& code) int main(int argc, char* argv[]) { RS_TITLE << "------------------------------------------------------" << RS_REND; - RS_TITLE << " RS_Driver Viewer Version: v" << RSLIDAR_VERSION_MAJOR << "." << RSLIDAR_VERSION_MINOR << "." - << RSLIDAR_VERSION_PATCH << RS_REND; + RS_TITLE << " RS_Driver Viewer Version: v" << getDriverVersion() << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; if (argc < 2) { RS_INFOL << "Use 'rs_driver_viewer -h/--help' to check the argument menu..." << RS_REND; } + if (checkKeywordExist(argc, argv, "-h") || checkKeywordExist(argc, argv, "--help")) { printHelpMenu(); From d41485914936e09802618d2d812a6e0c2241d5cf Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 17 Jan 2022 14:10:28 +0800 Subject: [PATCH 156/379] refac: refactory rs32/16 --- src/rs_driver/driver/decoder/decoder_RS16.hpp | 61 ++++++------------- src/rs_driver/driver/decoder/decoder_RS32.hpp | 53 +++++----------- src/rs_driver/driver/decoder/decoder_mech.hpp | 9 +++ 3 files changed, 44 insertions(+), 79 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 999f244d..c5d89142 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -79,56 +79,34 @@ typedef struct uint16_t tail; } RS16DifopPkt; -typedef struct -{ - uint8_t id[8]; - uint16_t rpm; - RSEthNetV1 eth; - RSFOV fov; - uint8_t reserved0[2]; - uint16_t phase_lock_angle; - RSVersionV1 version; - uint8_t reserved1[242]; - RSSN sn; - uint16_t zero_cali; - uint8_t return_mode; - uint16_t sw_ver; - RSTimestampYMD timestamp; - RSStatusV1 status; - uint8_t reserved2[5]; - RSDiagnoV1 diagno; - uint8_t gprmc[86]; - RSCalibrationAngle vert_angle_cali[32]; - RSCalibrationAngle horiz_angle_cali[32]; -} AdapterRS16DifopPkt; - #pragma pack(pop) -inline void RS16DifopPkt2Adapter (const uint8_t* difop) +inline void RS16DifopPkt2Adapter (const RS16DifopPkt& src, AdapterDifopPkt& dst) { - RS16DifopPkt& orig = *(RS16DifopPkt*)difop; - AdapterRS16DifopPkt& adapter = *(AdapterRS16DifopPkt*)difop; + dst.rpm = src.rpm; + dst.fov = src.fov; + dst.return_mode = src.return_mode; for (uint16_t i = 0, j = 16; i < 16; i++, j++) { uint32_t v = 0; - v += orig.pitch_cali[i*3]; + v += src.pitch_cali[i*3]; v = v << 8; - v += orig.pitch_cali[i*3 + 1]; + v += src.pitch_cali[i*3 + 1]; v = v << 8; - v += orig.pitch_cali[i*3 + 2]; + v += src.pitch_cali[i*3 + 2]; uint16_t v2 = (uint16_t)(v * 0.01); // higher resolution to lower one. - adapter.vert_angle_cali[i].sign = (i < 8) ? 1 : 0; - adapter.vert_angle_cali[i].value = htons(v2); - adapter.horiz_angle_cali[i].sign = 0; - adapter.horiz_angle_cali[i].value = 0; + dst.vert_angle_cali[i].sign = (i < 8) ? 1 : 0; + dst.vert_angle_cali[i].value = htons(v2); + dst.horiz_angle_cali[i].sign = 0; + dst.horiz_angle_cali[i].value = 0; - adapter.vert_angle_cali[j].sign = adapter.vert_angle_cali[i].sign; - adapter.vert_angle_cali[j].value = adapter.vert_angle_cali[i].value; - adapter.horiz_angle_cali[j].sign = 0; - adapter.horiz_angle_cali[j].value = 0; + dst.vert_angle_cali[j].sign = dst.vert_angle_cali[i].sign; + dst.vert_angle_cali[j].value = dst.vert_angle_cali[i].value; + dst.horiz_angle_cali[j].sign = 0; + dst.horiz_angle_cali[j].value = 0; } } @@ -221,12 +199,13 @@ inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, inline void DecoderRS16::decodeDifopPkt(const uint8_t* packet, size_t size) { - RS16DifopPkt2Adapter (packet); + const RS16DifopPkt& orig = *(const RS16DifopPkt*)packet; + AdapterDifopPkt adapter; + RS16DifopPkt2Adapter (orig, adapter); - const AdapterRS16DifopPkt& pkt = *(const AdapterRS16DifopPkt*)(packet); - this->template decodeDifopCommon(pkt); + this->template decodeDifopCommon(adapter); - this->echo_mode_ = getEchoMode (pkt.return_mode); + this->echo_mode_ = getEchoMode (adapter.return_mode); this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? (this->blks_per_frame_ << 1) : this->blks_per_frame_; } diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index ba3f39da..f77dff0d 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -79,55 +79,31 @@ typedef struct uint16_t tail; } RS32DifopPkt; -typedef struct -{ - uint8_t id[8]; - uint16_t rpm; - RSEthNetV1 eth; - RSFOV fov; - uint8_t reserved0[2]; - uint16_t phase_lock_angle; - RSVersionV1 version; - uint8_t reserved1[242]; - RSSN sn; - uint16_t zero_cali; - uint8_t return_mode; - uint16_t sw_ver; - RSTimestampYMD timestamp; - RSStatusV1 status; - uint8_t reserved2[5]; - RSDiagnoV1 diagno; - uint8_t gprmc[86]; - RSCalibrationAngle vert_angle_cali_orig[32]; - RSCalibrationAngle horiz_angle_cali_orig[32]; - RSCalibrationAngle vert_angle_cali[32]; - RSCalibrationAngle horiz_angle_cali[32]; -} AdapterRS32DifopPkt; - #pragma pack(pop) -inline void RS32DifopPkt2Adapter (const uint8_t* difop) +inline void RS32DifopPkt2Adapter (const RS32DifopPkt& src, AdapterDifopPkt& dst) { - RS32DifopPkt& orig = *(RS32DifopPkt*)difop; - AdapterRS32DifopPkt& adapter = *(AdapterRS32DifopPkt*)difop; + dst.rpm = src.rpm; + dst.fov = src.fov; + dst.return_mode = src.return_mode; for (uint16_t i = 0; i < 32; i++) { uint16_t v; // vert angles - adapter.vert_angle_cali[i].sign = orig.vert_angle_cali[i].sign; + dst.vert_angle_cali[i].sign = src.vert_angle_cali[i].sign; - v = ntohs(orig.vert_angle_cali[i].value); + v = ntohs(src.vert_angle_cali[i].value); v = std::round(v * 0.1f); - adapter.vert_angle_cali[i].value = htons(v); + dst.vert_angle_cali[i].value = htons(v); // horiz_angles - adapter.horiz_angle_cali[i].sign = orig.horiz_angle_cali[i].sign; + dst.horiz_angle_cali[i].sign = src.horiz_angle_cali[i].sign; - v = ntohs(orig.horiz_angle_cali[i].value); + v = ntohs(src.horiz_angle_cali[i].value); v = std::round(v * 0.1f); - adapter.horiz_angle_cali[i].value = htons(v); + dst.horiz_angle_cali[i].value = htons(v); } } @@ -219,12 +195,13 @@ inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, size_t size) { - RS32DifopPkt2Adapter (packet); + const RS32DifopPkt& orig = *(const RS32DifopPkt*)packet; + AdapterDifopPkt adapter; + RS32DifopPkt2Adapter (orig, adapter); - const AdapterRS32DifopPkt& pkt = *(const AdapterRS32DifopPkt*)(packet); - this->template decodeDifopCommon(pkt); + this->template decodeDifopCommon(adapter); - this->echo_mode_ = getEchoMode (pkt.return_mode); + this->echo_mode_ = getEchoMode (adapter.return_mode); this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? (this->blks_per_frame_ << 1) : this->blks_per_frame_; } diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index 4f60a04c..a634921d 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -53,6 +53,15 @@ struct RSDecoderMechConstParam float CHAN_AZIS[128]; }; +typedef struct +{ + uint16_t rpm; + RSFOV fov; + uint8_t return_mode; + RSCalibrationAngle vert_angle_cali[32]; + RSCalibrationAngle horiz_angle_cali[32]; +} AdapterDifopPkt; + class DecoderMech : public Decoder { public: From 0d30bb9cee7f9b455957e5f0a9fb3079f3dd6225 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 17 Jan 2022 14:40:03 +0800 Subject: [PATCH 157/379] refac: recover transform func --- CMakeLists.txt | 14 +++++----- src/rs_driver/driver/decoder/decoder.hpp | 24 +++++++++++++++++ .../driver/decoder/decoder_RS128.hpp | 2 ++ src/rs_driver/driver/decoder/decoder_RS16.hpp | 2 ++ src/rs_driver/driver/decoder/decoder_RS32.hpp | 2 ++ src/rs_driver/driver/decoder/decoder_RS80.hpp | 2 ++ src/rs_driver/driver/decoder/decoder_RSBP.hpp | 2 ++ .../driver/decoder/decoder_RSHELIOS.hpp | 2 ++ src/rs_driver/driver/decoder/decoder_RSM1.hpp | 2 ++ src/rs_driver/driver/driver_param.hpp | 26 ++----------------- 10 files changed, 48 insertions(+), 30 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3616f706..84762370 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,13 +12,14 @@ project(rs_driver VERSION 1.4.3) # Compile Demos&Tools #============================= option(COMPILE_DEMOS "Build rs_driver demos" ON) -option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) -option(COMPILE_TESTS "Build rs_driver unit tests" OFF) +option(COMPILE_TOOLS "Build point cloud visualization tool" ON) +option(COMPILE_TESTS "Build rs_driver unit tests" ON) #============================= # Compile Features #============================= option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) +option(ENABLE_TRANSFORM "Enable transform functions" OFF) #======================== # Project setup @@ -93,15 +94,16 @@ else() list(APPEND EXTERNAL_LIBS pcap) endif(WIN32) -#======================== -# Eigen -#======================== if(${ENABLE_TRANSFORM}) add_definitions("-DENABLE_TRANSFORM") + + #======================== + # Eigen + #======================== find_package(Eigen3 REQUIRED) include_directories(${EIGEN3_INCLUDE_DIR}) message(=============================================================) - message("-- Enable Transform Fcuntions") + message("-- Enable Transform Fucntions") message(=============================================================) endif(${ENABLE_TRANSFORM}) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 861d12ff..bb005c18 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -46,6 +46,12 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #ifndef _USE_MATH_DEFINES #define _USE_MATH_DEFINES // for VC++, required to use const M_IP in #endif + +#ifdef ENABLE_TRANSFORM +// Eigen lib +#include +#endif + #include #include #include @@ -274,6 +280,7 @@ class Decoder double getPacketDuration(); void enableWritePktTs(bool value); double prevPktTs(); + void transformPoint(float& x, float& y, float& z); #ifndef UNIT_TEST protected: @@ -349,6 +356,23 @@ inline double Decoder::prevPktTs() return prev_pkt_ts_; } +inline void Decoder::transformPoint(float& x, float& y, float& z) +{ +#ifdef ENABLE_TRANSFORM + Eigen::AngleAxisd current_rotation_x(param_.transform_param.roll, Eigen::Vector3d::UnitX()); + Eigen::AngleAxisd current_rotation_y(param_.transform_param.pitch, Eigen::Vector3d::UnitY()); + Eigen::AngleAxisd current_rotation_z(param_.transform_param.yaw, Eigen::Vector3d::UnitZ()); + Eigen::Translation3d current_translation(param_.transform_param.x, param_.transform_param.y, + param_.transform_param.z); + Eigen::Matrix4d trans = (current_translation * current_rotation_z * current_rotation_y * current_rotation_x).matrix(); + Eigen::Vector4d target_ori(x, y, z, 1); + Eigen::Vector4d target_rotate = trans * target_ori; + x = target_rotate(0); + y = target_rotate(1); + z = target_rotate(2); +#endif +} + inline void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) { if (size != this->const_param_.DIFOP_LEN) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 8c88782c..d32ae257 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -266,6 +266,8 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(point.x, point.y, point.z); + point.intensity = channel.intensity; point.timestamp = chan_ts; point.ring = this->chan_angles_.toUserChan(chan); diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index c5d89142..b9695469 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -289,6 +289,8 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(point.x, point.y, point.z); + point.intensity = channel.intensity; point.timestamp = chan_ts; point.ring = (this->chan_angles_.toUserChan(chan) >> 1); diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index f77dff0d..f46aaacd 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -285,6 +285,8 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(point.x, point.y, point.z); + point.intensity = channel.intensity; point.timestamp = chan_ts; point.ring = this->chan_angles_.toUserChan(chan); diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index d10f7c5c..5c685a1e 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -262,6 +262,8 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(point.x, point.y, point.z); + point.intensity = channel.intensity; point.timestamp = chan_ts; point.ring = this->chan_angles_.toUserChan(chan); diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index fd93b4e2..4caed4a6 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -257,6 +257,8 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(point.x, point.y, point.z); + point.intensity = channel.intensity; point.timestamp = chan_ts; point.ring = this->chan_angles_.toUserChan(chan); diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 21373a3c..478d1f04 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -268,6 +268,8 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t s point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(point.x, point.y, point.z); + point.intensity = channel.intensity; point.timestamp = chan_ts; point.ring = this->chan_angles_.toUserChan(chan); diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index ca7e9fc2..a44566af 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -256,6 +256,8 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) point.x = distance * COS (pitch) * COS (yaw); point.y = distance * COS (pitch) * SIN (yaw); point.z = distance * SIN (pitch); + this->transformPoint(point.x, point.y, point.z); + point.intensity = channel.intensity; point.timestamp = point_time; point.ring = chan; diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 04b49b35..c511d986 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -165,22 +165,6 @@ enum SplitFrameMode SPLIT_BY_CUSTOM_BLKS }; -#if 0 -typedef struct RSCameraTriggerParam ///< Camera trigger parameters -{ - std::map trigger_map; ///< Map stored the trigger angle and camera frame id - void print() const - { - RS_INFO << "------------------------------------------------------" << RS_REND; - RS_INFO << " RoboSense Camera Trigger Parameters " << RS_REND; - for (auto iter : trigger_map) - { - RS_INFOL << "camera_frame_id: " << iter.second << " trigger_angle : " << iter.first << RS_REND; - } - RS_INFO << "------------------------------------------------------" << RS_REND; - } -} RSCameraTriggerParam; - typedef struct RSTransformParam ///< The Point transform parameter { float x = 0.0f; ///< unit, m @@ -189,6 +173,7 @@ typedef struct RSTransformParam ///< The Point transform parameter float roll = 0.0f; ///< unit, radian float pitch = 0.0f; ///< unit, radian float yaw = 0.0f; ///< unit, radian + void print() const { RS_INFO << "------------------------------------------------------" << RS_REND; @@ -202,7 +187,6 @@ typedef struct RSTransformParam ///< The Point transform parameter RS_INFO << "------------------------------------------------------" << RS_REND; } } RSTransformParam; -#endif typedef struct RSDecoderParam ///< LiDAR decoder parameter { @@ -220,17 +204,10 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points -#if 0 RSTransformParam transform_param; ///< Used to transform points - RSCameraTriggerParam trigger_param; ///< Used to trigger camera -#endif void print() const { -#if 0 - transform_param.print(); - trigger_param.print(); -#endif RS_INFO << "------------------------------------------------------" << RS_REND; RS_INFO << " RoboSense Decoder Parameters " << RS_REND; RS_INFOL << "wait_for_difop: " << wait_for_difop << RS_REND; @@ -246,6 +223,7 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter RS_INFOL << "split_angle: " << split_angle << RS_REND; RS_INFOL << "num_blks_split: " << num_blks_split << RS_REND; RS_INFO << "------------------------------------------------------" << RS_REND; + transform_param.print(); } } RSDecoderParam; From 1830cec07237e81aa0b808eaf08b11b03c5d0181 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 17 Jan 2022 15:23:03 +0800 Subject: [PATCH 158/379] refac: refactory rs_viewer --- src/rs_driver/driver/driver_param.hpp | 29 ++++----- src/rs_driver/driver/input/input_sock.hpp | 4 +- tool/rs_driver_viewer.cpp | 71 +++++++++++++++-------- 3 files changed, 63 insertions(+), 41 deletions(-) diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index c511d986..6801a5b7 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -193,18 +193,19 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter bool config_from_file = false; std::string angle_path = ""; ///< Path of angle calibration files(angle.csv). Only used for internal debugging. bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet - float min_distance = 0.2f; ///< Minimum distance of point cloud range - float max_distance = 200.0f; ///< Max distance of point cloud range - float start_angle = 0.0f; ///< Start angle of point cloud - float end_angle = 360.0f; ///< End angle of point cloud - SplitFrameMode split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; ///< 1: Split frames by cut_angle; - ///< 2: Split frames by fixed number of packets; - ///< 3: Split frames by custom number of packets (num_pkts_split) - float split_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 - uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 - bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp - bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points - RSTransformParam transform_param; ///< Used to transform points + float min_distance = 0.2f; ///< Minimum distance of point cloud range + float max_distance = 200.0f; ///< Max distance of point cloud range + float start_angle = 0.0f; ///< Start angle of point cloud + float end_angle = 360.0f; ///< End angle of point cloud + SplitFrameMode split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; + ///< 1: Split frames by cut_angle; + ///< 2: Split frames by fixed number of packets; + ///< 3: Split frames by custom number of packets (num_pkts_split) + float split_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 + uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 + bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp + bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points + RSTransformParam transform_param; ///< Used to transform points void print() const { @@ -233,7 +234,7 @@ typedef struct RSInputParam ///< The LiDAR input parameter uint16_t msop_port = 6699; ///< Msop packet port number uint16_t difop_port = 7788; ///< Difop packet port number std::string host_address = "0.0.0.0"; ///< Address of host - std::string multi_cast_address = "0.0.0.0"; ///< Address of multicast + std::string multicast_address = "0.0.0.0"; ///< Address of multicast std::string pcap_path = ""; ///< Absolute path of pcap file bool pcap_repeat = true; ///< true: The pcap bag will repeat play float pcap_rate = 1.0f; ///< Rate to read the pcap file @@ -244,7 +245,7 @@ typedef struct RSInputParam ///< The LiDAR input parameter { RS_INFO << "------------------------------------------------------" << RS_REND; RS_INFO << " RoboSense Input Parameters " << RS_REND; - RS_INFOL << "multi_cast_address: " << multi_cast_address << RS_REND; + RS_INFOL << "multicast_address: " << multicast_address << RS_REND; RS_INFOL << "host_address: " << host_address << RS_REND; RS_INFOL << "msop_port: " << msop_port << RS_REND; RS_INFOL << "difop_port: " << difop_port << RS_REND; diff --git a/src/rs_driver/driver/input/input_sock.hpp b/src/rs_driver/driver/input/input_sock.hpp index 64d4dd89..c6611cce 100644 --- a/src/rs_driver/driver/input/input_sock.hpp +++ b/src/rs_driver/driver/input/input_sock.hpp @@ -102,13 +102,13 @@ inline bool InputSock::init() int msop_fd = -1, difop_fd = -1; - msop_fd = createSocket(input_param_.msop_port, input_param_.host_address, input_param_.multi_cast_address); + msop_fd = createSocket(input_param_.msop_port, input_param_.host_address, input_param_.multicast_address); if (msop_fd < 0) goto failMsop; if ((input_param_.difop_port != 0) && (input_param_.difop_port != input_param_.msop_port)) { - difop_fd = createSocket(input_param_.difop_port, input_param_.host_address, input_param_.multi_cast_address); + difop_fd = createSocket(input_param_.difop_port, input_param_.host_address, input_param_.multicast_address); if (difop_fd < 0) goto failDifop; } diff --git a/tool/rs_driver_viewer.cpp b/tool/rs_driver_viewer.cpp index eafd18dd..a61a9320 100644 --- a/tool/rs_driver_viewer.cpp +++ b/tool/rs_driver_viewer.cpp @@ -60,6 +60,7 @@ bool checkKeywordExist(int argc, const char* const* argv, const char* str) bool parseArgument(int argc, const char* const* argv, const char* str, std::string& val) { int index = -1; + for (int i = 1; i < argc; i++) { if (strcmp(argv[i], str) == 0) @@ -67,23 +68,36 @@ bool parseArgument(int argc, const char* const* argv, const char* str, std::stri index = i + 1; } } + if (index > 0 && index < argc) { val = argv[index]; return true; } + return false; } void parseParam(int argc, char* argv[], RSDriverParam& param) { param.decoder_param.wait_for_difop = false; + std::string result_str; - if (parseArgument(argc, argv, "-type", result_str)) + // input param + parseArgument(argc, argv, "-pcap", param.input_param.pcap_path); + if (param.input_param.pcap_path.empty()) { - param.lidar_type = strToLidarType(result_str); + param.input_type = InputType::ONLINE_LIDAR; + } + else + { + param.input_type = InputType::PCAP_FILE; } + + parseArgument(argc, argv, "-host", param.input_param.host_address); + parseArgument(argc, argv, "-multicast", param.input_param.host_address); + if (parseArgument(argc, argv, "-msop", result_str)) { param.input_param.msop_port = std::stoi(result_str); @@ -92,7 +106,12 @@ void parseParam(int argc, char* argv[], RSDriverParam& param) { param.input_param.difop_port = std::stoi(result_str); } -#if 0 + + // decoder param + if (parseArgument(argc, argv, "-type", result_str)) + { + param.lidar_type = strToLidarType(result_str); + } if (parseArgument(argc, argv, "-x", result_str)) { param.decoder_param.transform_param.x = std::stof(result_str); @@ -117,31 +136,26 @@ void parseParam(int argc, char* argv[], RSDriverParam& param) { param.decoder_param.transform_param.yaw = std::stof(result_str); } -#endif - if (parseArgument(argc, argv, "-pcap", param.input_param.pcap_path)) - { - //param.input_param.read_pcap = true; - } } void printHelpMenu() { - RS_MSG << "Arguments are: " << RS_REND; + RS_MSG << "Argument list: " << RS_REND; RS_MSG << " -msop = LiDAR msop port number,the default value is 6699" << RS_REND; RS_MSG << " -difop = LiDAR difop port number,the default value is 7788" << RS_REND; - RS_MSG << " -type = LiDAR type( RS16, RS32, RSBP, RS128, RS80, RSM1, RSHELIOS, RSROCK ), the " - "default " - "value is RS16" - << RS_REND; + RS_MSG << " -host = LiDAR destination address." << RS_REND; + RS_MSG << " -multicast = LiDAR destination group address." << RS_REND; + RS_MSG << " -pcap = The path of the pcap file, if this argument is set, the driver " + "will work in off-line mode and read the pcap file. Otherwise the driver work in online mode." << RS_REND; + + RS_MSG << " -type = LiDAR type(RS16, RS32, RSBP, RSHELIOS, RS128, RS80, RSM1), the default value is RS16" + << RS_REND; RS_MSG << " -x = Transformation parameter, unit: m " << RS_REND; RS_MSG << " -y = Transformation parameter, unit: m " << RS_REND; RS_MSG << " -z = Transformation parameter, unit: m " << RS_REND; RS_MSG << " -roll = Transformation parameter, unit: radian " << RS_REND; RS_MSG << " -pitch = Transformation parameter, unit: radian " << RS_REND; RS_MSG << " -yaw = Transformation parameter, unit: radian " << RS_REND; - RS_MSG << " -pcap = The path of the pcap file, if this argument is set, the driver " - "will work in off-line mode and read the pcap file. Otherwise the driver work in online mode." - << RS_REND; } void printParam(const RSDriverParam& param) @@ -163,9 +177,13 @@ void printParam(const RSDriverParam& param) RS_INFO << param.input_param.msop_port << RS_REND; RS_INFOL << "DIFOP Port: "; RS_INFO << param.input_param.difop_port << RS_REND; + RS_INFOL << "Host Adress: "; + RS_INFO << param.input_param.host_address << RS_REND; + RS_INFOL << "Multicast Adress: "; + RS_INFO << param.input_param.multicast_address << RS_REND; + RS_INFOL << "LiDAR Type: "; RS_INFO << lidarTypeToStr(param.lidar_type) << RS_REND; -#if 0 RS_INFOL << "Transformation Parameters (x, y, z, roll, pitch, yaw): " << RS_REND; RS_INFOL << "x: "; RS_INFO << std::fixed << param.decoder_param.transform_param.x << RS_REND; @@ -179,7 +197,6 @@ void printParam(const RSDriverParam& param) RS_INFO << std::fixed << param.decoder_param.transform_param.pitch << RS_REND; RS_INFOL << "yaw: "; RS_INFO << std::fixed << param.decoder_param.transform_param.yaw << RS_REND; -#endif } std::shared_ptr pointCloudGetCallback(void) @@ -238,6 +255,10 @@ int main(int argc, char* argv[]) return 0; } + RSDriverParam param; ///< Create a parameter object + parseParam(argc, argv, param); + printParam(param); + g_pointcloud = std::make_shared(); pcl_viewer = std::make_shared("RSPointCloudViewer"); @@ -248,19 +269,17 @@ int main(int argc, char* argv[]) pcl_viewer->addPointCloud(pcl_pointcloud, "rslidar"); pcl_viewer->setPointCloudRenderingProperties(PCL_VISUALIZER_POINT_SIZE, 2, "rslidar"); - RSDriverParam param; ///< Create a parameter object - parseParam(argc, argv, param); - printParam(param); - LidarDriver driver; ///< Declare the driver object - driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver - driver.regRecvCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback function into the driver - if (!driver.init(param)) ///< Call the init function and pass the parameter + driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback + driver.regRecvCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback + if (!driver.init(param)) ///< Call the init function { RS_ERROR << "Driver Initialize Error..." << RS_REND; return -1; } + driver.start(); ///< The driver thread will start + RS_INFO << "RoboSense Lidar-Driver Viewer start......" << RS_REND; while (!pcl_viewer->wasStopped()) @@ -271,5 +290,7 @@ int main(int argc, char* argv[]) } std::this_thread::sleep_for(std::chrono::milliseconds(100)); } + return 0; } + From 79a17b53f86cd0c37e78e2f664f167dbd0d6e717 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 17 Jan 2022 16:07:57 +0800 Subject: [PATCH 159/379] refac: calc rsm1's packet duration --- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index a44566af..d977b056 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -137,6 +137,7 @@ class DecoderRSM1 : public Decoder { public: + constexpr static double FRAME_DURATION = 0.1; constexpr static uint32_t SINGLE_PKT_NUM = 630; constexpr static uint32_t DUAL_PKT_NUM = 1260; constexpr static int ANGLE_OFFSET = 32768; @@ -185,7 +186,7 @@ inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, , split_(&max_seq_) { this->height_ = this->const_param_.CHANNELS_PER_BLOCK; - this->packet_duration_ = 1; // TODO + this->packet_duration_ = FRAME_DURATION / SINGLE_PKT_NUM; this->angles_ready_ = true; } From ee202cd5d76736b830894e0db3531de135c5dd68 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 17 Jan 2022 16:15:32 +0800 Subject: [PATCH 160/379] refac: format --- src/rs_driver/driver/driver_param.hpp | 6 +++--- src/rs_driver/driver/input/input_sock.hpp | 4 ++-- tool/rs_driver_viewer.cpp | 8 ++++---- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 6801a5b7..83968e48 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -234,7 +234,7 @@ typedef struct RSInputParam ///< The LiDAR input parameter uint16_t msop_port = 6699; ///< Msop packet port number uint16_t difop_port = 7788; ///< Difop packet port number std::string host_address = "0.0.0.0"; ///< Address of host - std::string multicast_address = "0.0.0.0"; ///< Address of multicast + std::string group_address = "0.0.0.0"; ///< Address of multicast group std::string pcap_path = ""; ///< Absolute path of pcap file bool pcap_repeat = true; ///< true: The pcap bag will repeat play float pcap_rate = 1.0f; ///< Rate to read the pcap file @@ -245,10 +245,10 @@ typedef struct RSInputParam ///< The LiDAR input parameter { RS_INFO << "------------------------------------------------------" << RS_REND; RS_INFO << " RoboSense Input Parameters " << RS_REND; - RS_INFOL << "multicast_address: " << multicast_address << RS_REND; - RS_INFOL << "host_address: " << host_address << RS_REND; RS_INFOL << "msop_port: " << msop_port << RS_REND; RS_INFOL << "difop_port: " << difop_port << RS_REND; + RS_INFOL << "host_address: " << host_address << RS_REND; + RS_INFOL << "group_address: " << group_address << RS_REND; RS_INFOL << "pcap_path: " << pcap_path << RS_REND; RS_INFOL << "pcap_rate: " << pcap_rate << RS_REND; RS_INFOL << "pcap_repeat: " << pcap_repeat << RS_REND; diff --git a/src/rs_driver/driver/input/input_sock.hpp b/src/rs_driver/driver/input/input_sock.hpp index c6611cce..47e0635a 100644 --- a/src/rs_driver/driver/input/input_sock.hpp +++ b/src/rs_driver/driver/input/input_sock.hpp @@ -102,13 +102,13 @@ inline bool InputSock::init() int msop_fd = -1, difop_fd = -1; - msop_fd = createSocket(input_param_.msop_port, input_param_.host_address, input_param_.multicast_address); + msop_fd = createSocket(input_param_.msop_port, input_param_.host_address, input_param_.group_address); if (msop_fd < 0) goto failMsop; if ((input_param_.difop_port != 0) && (input_param_.difop_port != input_param_.msop_port)) { - difop_fd = createSocket(input_param_.difop_port, input_param_.host_address, input_param_.multicast_address); + difop_fd = createSocket(input_param_.difop_port, input_param_.host_address, input_param_.group_address); if (difop_fd < 0) goto failDifop; } diff --git a/tool/rs_driver_viewer.cpp b/tool/rs_driver_viewer.cpp index a61a9320..ae5712ed 100644 --- a/tool/rs_driver_viewer.cpp +++ b/tool/rs_driver_viewer.cpp @@ -96,7 +96,7 @@ void parseParam(int argc, char* argv[], RSDriverParam& param) } parseArgument(argc, argv, "-host", param.input_param.host_address); - parseArgument(argc, argv, "-multicast", param.input_param.host_address); + parseArgument(argc, argv, "-group", param.input_param.group_address); if (parseArgument(argc, argv, "-msop", result_str)) { @@ -144,7 +144,7 @@ void printHelpMenu() RS_MSG << " -msop = LiDAR msop port number,the default value is 6699" << RS_REND; RS_MSG << " -difop = LiDAR difop port number,the default value is 7788" << RS_REND; RS_MSG << " -host = LiDAR destination address." << RS_REND; - RS_MSG << " -multicast = LiDAR destination group address." << RS_REND; + RS_MSG << " -group = LiDAR destination group address." << RS_REND; RS_MSG << " -pcap = The path of the pcap file, if this argument is set, the driver " "will work in off-line mode and read the pcap file. Otherwise the driver work in online mode." << RS_REND; @@ -179,8 +179,8 @@ void printParam(const RSDriverParam& param) RS_INFO << param.input_param.difop_port << RS_REND; RS_INFOL << "Host Adress: "; RS_INFO << param.input_param.host_address << RS_REND; - RS_INFOL << "Multicast Adress: "; - RS_INFO << param.input_param.multicast_address << RS_REND; + RS_INFOL << "Group Adress: "; + RS_INFO << param.input_param.group_address << RS_REND; RS_INFOL << "LiDAR Type: "; RS_INFO << lidarTypeToStr(param.lidar_type) << RS_REND; From 2a99d6ca50cb21cc2ab6c50126a15438724a4bbe Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 17 Jan 2022 20:32:56 +0800 Subject: [PATCH 161/379] refac: recover templated decoder --- src/rs_driver/driver/decoder/decoder.hpp | 48 +++++++------- .../driver/decoder/decoder_RS128.hpp | 66 +++++++++++-------- src/rs_driver/driver/decoder/decoder_RS16.hpp | 66 +++++++++++-------- src/rs_driver/driver/decoder/decoder_RS32.hpp | 66 +++++++++++-------- src/rs_driver/driver/decoder/decoder_RS80.hpp | 66 +++++++++++-------- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 65 ++++++++++-------- .../driver/decoder/decoder_RSHELIOS.hpp | 66 +++++++++++-------- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 59 ++++++++++------- .../driver/decoder/decoder_factory.hpp | 26 ++++---- src/rs_driver/driver/decoder/decoder_mech.hpp | 14 ++-- src/rs_driver/driver/lidar_driver_impl.hpp | 54 +++++++-------- test/decoder_rs32_test.cpp | 24 +++---- test/decoder_rsbp_test.cpp | 24 +++---- test/decoder_test.cpp | 4 +- 14 files changed, 350 insertions(+), 298 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index bb005c18..b0714527 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -241,21 +241,12 @@ struct RSDecoderConstParam float TEMPERATURE_RES; }; -struct RSPoint -{ - float x; - float y; - float z; - uint8_t intensity; - uint16_t ring; - double timestamp; -}; - #define INIT_ONLY_ONCE() \ static bool init_flag = false; \ if (init_flag) return param; \ init_flag = true; +template class Decoder { public: @@ -269,9 +260,6 @@ class Decoder void processDifopPkt(const uint8_t* pkt, size_t size); bool processMsopPkt(const uint8_t* pkt, size_t size); - void regRecvCallback(const std::function& cb_new_point, - const std::function& cb_split_frame); - explicit Decoder(const RSDecoderConstParam& const_param, const RSDecoderParam& param, const std::function& excb); @@ -282,13 +270,15 @@ class Decoder double prevPktTs(); void transformPoint(float& x, float& y, float& z); + void setSplitCallback(const std::function& cb_split_frame); + std::shared_ptr point_cloud_; // accumulated point cloud currently + #ifndef UNIT_TEST protected: #endif RSDecoderConstParam const_param_; // const param RSDecoderParam param_; // user param - std::function cb_new_point_; std::function cb_split_frame_; std::function excb_; bool write_pkt_ts_; @@ -309,15 +299,14 @@ class Decoder double prev_point_ts_; // last point's timestamp }; -inline void Decoder::regRecvCallback( - const std::function& cb_new_point, - const std::function& cb_split_frame) +template +inline void Decoder::setSplitCallback(const std::function& cb_split_frame) { - cb_new_point_ = cb_new_point; cb_split_frame_ = cb_split_frame; } -inline Decoder::Decoder(const RSDecoderConstParam& const_param, +template +inline Decoder::Decoder(const RSDecoderConstParam& const_param, const RSDecoderParam& param, const std::function& excb) : const_param_(const_param) @@ -336,27 +325,32 @@ inline Decoder::Decoder(const RSDecoderConstParam& const_param, { } -inline void Decoder::enableWritePktTs(bool value) +template +inline void Decoder::enableWritePktTs(bool value) { write_pkt_ts_ = value; } -inline float Decoder::getTemperature() +template +inline float Decoder::getTemperature() { return temperature_; } -inline double Decoder::getPacketDuration() +template +inline double Decoder::getPacketDuration() { return packet_duration_; } -inline double Decoder::prevPktTs() +template +inline double Decoder::prevPktTs() { return prev_pkt_ts_; } -inline void Decoder::transformPoint(float& x, float& y, float& z) +template +inline void Decoder::transformPoint(float& x, float& y, float& z) { #ifdef ENABLE_TRANSFORM Eigen::AngleAxisd current_rotation_x(param_.transform_param.roll, Eigen::Vector3d::UnitX()); @@ -373,7 +367,8 @@ inline void Decoder::transformPoint(float& x, float& y, float& z) #endif } -inline void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) +template +inline void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) { if (size != this->const_param_.DIFOP_LEN) { @@ -390,7 +385,8 @@ inline void Decoder::processDifopPkt(const uint8_t* pkt, size_t size) decodeDifopPkt(pkt, size); } -inline bool Decoder::processMsopPkt(const uint8_t* pkt, size_t size) +template +inline bool Decoder::processMsopPkt(const uint8_t* pkt, size_t size) { if (param_.wait_for_difop && !angles_ready_) { diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index d32ae257..1bce5ec6 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -79,7 +79,8 @@ typedef struct #pragma pack(pop) -class DecoderRS128 : public DecoderMech +template +class DecoderRS128 : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); @@ -100,7 +101,8 @@ class DecoderRS128 : public DecoderMech bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -inline RSDecoderMechConstParam& DecoderRS128::getConstParam() +template +inline RSDecoderMechConstParam& DecoderRS128::getConstParam() { static RSDecoderMechConstParam param = { @@ -158,7 +160,8 @@ inline RSDecoderMechConstParam& DecoderRS128::getConstParam() return param; } -inline RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) +template +inline RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) { switch (mode) { @@ -171,13 +174,15 @@ inline RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) } } -inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, +template +inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(getConstParam(), param, excb) + : DecoderMech(getConstParam(), param, excb) { } -inline void DecoderRS128::decodeDifopPkt(const uint8_t* packet, size_t size) +template +inline void DecoderRS128::decodeDifopPkt(const uint8_t* packet, size_t size) { const RS128DifopPkt& pkt = *(const RS128DifopPkt*)(packet); this->template decodeDifopCommon(pkt); @@ -187,7 +192,8 @@ inline void DecoderRS128::decodeDifopPkt(const uint8_t* packet, size_t size) (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -inline bool DecoderRS128::decodeMsopPkt(const uint8_t* pkt, size_t size) +template +inline bool DecoderRS128::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { @@ -199,8 +205,9 @@ inline bool DecoderRS128::decodeMsopPkt(const uint8_t* pkt, size_t size) } } +template template -inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS128MsopPkt& pkt = *(const RS128MsopPkt*)(packet); bool ret = false; @@ -262,29 +269,32 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - RSPoint point; - point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); - point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); - point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; - this->transformPoint(point.x, point.y, point.z); - - point.intensity = channel.intensity; - point.timestamp = chan_ts; - point.ring = this->chan_angles_.toUserChan(chan); - - this->cb_new_point_(point); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } else if (!this->param_.dense_points) { - RSPoint point; - point.x = NAN; - point.y = NAN; - point.z = NAN; - point.intensity = 0; - point.timestamp = chan_ts; - point.ring = this->chan_angles_.toUserChan(chan); - - this->cb_new_point_(point); + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } this->prev_point_ts_ = chan_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index b9695469..51716a6c 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -110,7 +110,8 @@ inline void RS16DifopPkt2Adapter (const RS16DifopPkt& src, AdapterDifopPkt& dst) } } -class DecoderRS16 : public DecoderMech +template +class DecoderRS16 : public DecoderMech { public: @@ -132,7 +133,8 @@ class DecoderRS16 : public DecoderMech bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -inline RSDecoderMechConstParam& DecoderRS16::getConstParam() +template +inline RSDecoderMechConstParam& DecoderRS16::getConstParam() { static RSDecoderMechConstParam param = { @@ -177,7 +179,8 @@ inline RSDecoderMechConstParam& DecoderRS16::getConstParam() return param; } -inline RSEchoMode DecoderRS16::getEchoMode(uint8_t mode) +template +inline RSEchoMode DecoderRS16::getEchoMode(uint8_t mode) { switch (mode) { @@ -190,14 +193,16 @@ inline RSEchoMode DecoderRS16::getEchoMode(uint8_t mode) } } -inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, +template +inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(getConstParam(), param, excb) + : DecoderMech(getConstParam(), param, excb) { this->height_ = 16; } -inline void DecoderRS16::decodeDifopPkt(const uint8_t* packet, size_t size) +template +inline void DecoderRS16::decodeDifopPkt(const uint8_t* packet, size_t size) { const RS16DifopPkt& orig = *(const RS16DifopPkt*)packet; AdapterDifopPkt adapter; @@ -210,7 +215,8 @@ inline void DecoderRS16::decodeDifopPkt(const uint8_t* packet, size_t size) (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -inline bool DecoderRS16::decodeMsopPkt(const uint8_t* pkt, size_t size) +template +inline bool DecoderRS16::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { @@ -222,8 +228,9 @@ inline bool DecoderRS16::decodeMsopPkt(const uint8_t* pkt, size_t size) } } +template template -inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS16MsopPkt& pkt = *(const RS16MsopPkt*)(packet); bool ret = false; @@ -285,29 +292,32 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - RSPoint point; - point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); - point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); - point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; - this->transformPoint(point.x, point.y, point.z); - - point.intensity = channel.intensity; - point.timestamp = chan_ts; - point.ring = (this->chan_angles_.toUserChan(chan) >> 1); - - this->cb_new_point_(point); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, chan_ts); + setRing(point, (this->chan_angles_.toUserChan(chan) >> 1)); + + this->point_cloud_->points.emplace_back(point); } else if (!this->param_.dense_points) { - RSPoint point; - point.x = NAN; - point.y = NAN; - point.z = NAN; - point.intensity = 0; - point.timestamp = chan_ts; - point.ring = (this->chan_angles_.toUserChan(chan) >> 1); - - this->cb_new_point_(point); + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, chan_ts); + setRing(point, (this->chan_angles_.toUserChan(chan) >> 1)); + + this->point_cloud_->points.emplace_back(point); } this->prev_point_ts_ = chan_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index f46aaacd..ade84e2f 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -107,7 +107,8 @@ inline void RS32DifopPkt2Adapter (const RS32DifopPkt& src, AdapterDifopPkt& dst) } } -class DecoderRS32 : public DecoderMech +template +class DecoderRS32 : public DecoderMech { public: @@ -129,7 +130,8 @@ class DecoderRS32 : public DecoderMech bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -inline RSDecoderMechConstParam& DecoderRS32::getConstParam() +template +inline RSDecoderMechConstParam& DecoderRS32::getConstParam() { static RSDecoderMechConstParam param = { @@ -174,7 +176,8 @@ inline RSDecoderMechConstParam& DecoderRS32::getConstParam() return param; } -inline RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) +template +inline RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) { switch (mode) { @@ -187,13 +190,15 @@ inline RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) } } -inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, +template +inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(getConstParam(), param, excb) + : DecoderMech(getConstParam(), param, excb) { } -inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, size_t size) +template +inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, size_t size) { const RS32DifopPkt& orig = *(const RS32DifopPkt*)packet; AdapterDifopPkt adapter; @@ -206,7 +211,8 @@ inline void DecoderRS32::decodeDifopPkt(const uint8_t* packet, size_t size) (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -inline bool DecoderRS32::decodeMsopPkt(const uint8_t* pkt, size_t size) +template +inline bool DecoderRS32::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { @@ -218,8 +224,9 @@ inline bool DecoderRS32::decodeMsopPkt(const uint8_t* pkt, size_t size) } } +template template -inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS32MsopPkt& pkt = *(const RS32MsopPkt*)(packet); bool ret = false; @@ -281,29 +288,32 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - RSPoint point; - point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); - point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); - point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; - this->transformPoint(point.x, point.y, point.z); - - point.intensity = channel.intensity; - point.timestamp = chan_ts; - point.ring = this->chan_angles_.toUserChan(chan); - - this->cb_new_point_(point); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } else if (!this->param_.dense_points) { - RSPoint point; - point.x = NAN; - point.y = NAN; - point.z = NAN; - point.intensity = 0; - point.timestamp = chan_ts; - point.ring = this->chan_angles_.toUserChan(chan); - - this->cb_new_point_(point); + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } this->prev_point_ts_ = chan_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 5c685a1e..247ee896 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -81,7 +81,8 @@ typedef struct #pragma pack(pop) -class DecoderRS80 : public DecoderMech +template +class DecoderRS80 : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); @@ -102,7 +103,8 @@ class DecoderRS80 : public DecoderMech bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -inline RSDecoderMechConstParam& DecoderRS80::getConstParam() +template +inline RSDecoderMechConstParam& DecoderRS80::getConstParam() { static RSDecoderMechConstParam param = { @@ -154,7 +156,8 @@ inline RSDecoderMechConstParam& DecoderRS80::getConstParam() return param; } -inline RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) +template +inline RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) { switch (mode) { @@ -167,13 +170,15 @@ inline RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) } } -inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, +template +inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(getConstParam(), param, excb) + : DecoderMech(getConstParam(), param, excb) { } -inline void DecoderRS80::decodeDifopPkt(const uint8_t* packet, size_t size) +template +inline void DecoderRS80::decodeDifopPkt(const uint8_t* packet, size_t size) { const RS80DifopPkt& pkt = *(const RS80DifopPkt*)(packet); this->template decodeDifopCommon(pkt); @@ -183,7 +188,8 @@ inline void DecoderRS80::decodeDifopPkt(const uint8_t* packet, size_t size) (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -inline bool DecoderRS80::decodeMsopPkt(const uint8_t* pkt, size_t size) +template +inline bool DecoderRS80::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { @@ -195,8 +201,9 @@ inline bool DecoderRS80::decodeMsopPkt(const uint8_t* pkt, size_t size) } } +template template -inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS80MsopPkt& pkt = *(const RS80MsopPkt*)(packet); bool ret = false; @@ -258,29 +265,32 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - RSPoint point; - point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); - point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); - point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; - this->transformPoint(point.x, point.y, point.z); - - point.intensity = channel.intensity; - point.timestamp = chan_ts; - point.ring = this->chan_angles_.toUserChan(chan); - - this->cb_new_point_(point); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } else if (!this->param_.dense_points) { - RSPoint point; - point.x = NAN; - point.y = NAN; - point.z = NAN; - point.intensity = 0; - point.timestamp = chan_ts; - point.ring = this->chan_angles_.toUserChan(chan); - - this->cb_new_point_(point); + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } this->prev_point_ts_ = chan_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 4caed4a6..21b36878 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -81,7 +81,8 @@ typedef struct #pragma pack(pop) -class DecoderRSBP : public DecoderMech +template +class DecoderRSBP : public DecoderMech { public: @@ -103,7 +104,8 @@ class DecoderRSBP : public DecoderMech bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -inline RSDecoderMechConstParam& DecoderRSBP::getConstParam() +template +inline RSDecoderMechConstParam& DecoderRSBP::getConstParam() { static RSDecoderMechConstParam param = { @@ -148,7 +150,8 @@ inline RSDecoderMechConstParam& DecoderRSBP::getConstParam() return param; } -inline RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) +template +inline RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) { switch (mode) { @@ -161,13 +164,15 @@ inline RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) } } -inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, +template +inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(getConstParam(), param, excb) + : DecoderMech(getConstParam(), param, excb) { } -inline void DecoderRSBP::decodeDifopPkt(const uint8_t* packet, size_t size) +template +inline void DecoderRSBP::decodeDifopPkt(const uint8_t* packet, size_t size) { const RSBPDifopPkt& pkt = *(const RSBPDifopPkt*)(packet); this->template decodeDifopCommon(pkt); @@ -177,7 +182,8 @@ inline void DecoderRSBP::decodeDifopPkt(const uint8_t* packet, size_t size) (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -inline bool DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, size_t size) +template +inline bool DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { @@ -189,8 +195,9 @@ inline bool DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, size_t size) } } +template template -inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RSBPMsopPkt& pkt = *(const RSBPMsopPkt*)(packet); bool ret = false; @@ -253,28 +260,32 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - RSPoint point; - point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); - point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); - point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; - this->transformPoint(point.x, point.y, point.z); - - point.intensity = channel.intensity; - point.timestamp = chan_ts; - point.ring = this->chan_angles_.toUserChan(chan); - - this->cb_new_point_(point); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } else if (!this->param_.dense_points) { - RSPoint point; - point.x = NAN; - point.y = NAN; - point.z = NAN; - point.intensity = 0; - point.timestamp = chan_ts; - point.ring = this->chan_angles_.toUserChan(chan); - this->cb_new_point_(point); + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } this->prev_point_ts_ = chan_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 478d1f04..b372a000 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -93,7 +93,8 @@ typedef struct #pragma pack(pop) -class DecoderRSHELIOS : public DecoderMech +template +class DecoderRSHELIOS : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); @@ -114,7 +115,8 @@ class DecoderRSHELIOS : public DecoderMech bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; -inline RSDecoderMechConstParam& DecoderRSHELIOS::getConstParam() +template +inline RSDecoderMechConstParam& DecoderRSHELIOS::getConstParam() { static RSDecoderMechConstParam param = { @@ -159,7 +161,8 @@ inline RSDecoderMechConstParam& DecoderRSHELIOS::getConstParam() return param; } -inline RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) +template +inline RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) { switch (mode) { @@ -173,13 +176,15 @@ inline RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) } } -inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, +template +inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, const std::function& excb) - : DecoderMech(getConstParam(), param, excb) + : DecoderMech(getConstParam(), param, excb) { } -inline void DecoderRSHELIOS::decodeDifopPkt(const uint8_t* packet, size_t size) +template +inline void DecoderRSHELIOS::decodeDifopPkt(const uint8_t* packet, size_t size) { const RSHELIOSDifopPkt& pkt = *(const RSHELIOSDifopPkt*)(packet); this->template decodeDifopCommon(pkt); @@ -189,7 +194,8 @@ inline void DecoderRSHELIOS::decodeDifopPkt(const uint8_t* packet, size_t size) (this->blks_per_frame_ << 1) : this->blks_per_frame_; } -inline bool DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, size_t size) +template +inline bool DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { @@ -201,8 +207,9 @@ inline bool DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, size_t size) } } +template template -inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RSHELIOSMsopPkt& pkt = *(const RSHELIOSMsopPkt*)(packet); bool ret = false; @@ -264,29 +271,32 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t s if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - RSPoint point; - point.x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); - point.y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); - point.z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; - this->transformPoint(point.x, point.y, point.z); - - point.intensity = channel.intensity; - point.timestamp = chan_ts; - point.ring = this->chan_angles_.toUserChan(chan); - - this->cb_new_point_(point); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } else if (!this->param_.dense_points) { - RSPoint point; - point.x = NAN; - point.y = NAN; - point.z = NAN; - point.intensity = 0; - point.timestamp = chan_ts; - point.ring = this->chan_angles_.toUserChan(chan); - - this->cb_new_point_(point); + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); } this->prev_point_ts_ = chan_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index d977b056..209c752b 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -133,7 +133,8 @@ typedef struct #pragma pack(pop) -class DecoderRSM1 : public Decoder +template +class DecoderRSM1 : public Decoder { public: @@ -158,7 +159,8 @@ class DecoderRSM1 : public Decoder SplitStrategyBySeq split_; }; -inline RSDecoderConstParam& DecoderRSM1::getConstParam() +template +inline RSDecoderConstParam& DecoderRSM1::getConstParam() { static RSDecoderConstParam param = { @@ -179,9 +181,10 @@ inline RSDecoderConstParam& DecoderRSM1::getConstParam() return param; } -inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, +template +inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, const std::function& excb) - : Decoder(getConstParam(), param, excb) + : Decoder(getConstParam(), param, excb) , max_seq_(SINGLE_PKT_NUM) , split_(&max_seq_) { @@ -190,7 +193,8 @@ inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, this->angles_ready_ = true; } -inline RSEchoMode DecoderRSM1::getEchoMode(uint8_t mode) +template +inline RSEchoMode DecoderRSM1::getEchoMode(uint8_t mode) { switch (mode) { @@ -204,14 +208,16 @@ inline RSEchoMode DecoderRSM1::getEchoMode(uint8_t mode) } } -inline void DecoderRSM1::decodeDifopPkt(const uint8_t* packet, size_t size) +template +inline void DecoderRSM1::decodeDifopPkt(const uint8_t* packet, size_t size) { const RSM1DifopPkt& pkt = *(RSM1DifopPkt*)packet; this->echo_mode_ = this->getEchoMode(pkt.return_mode); max_seq_ = (this->echo_mode_ == ECHO_SINGLE) ? SINGLE_PKT_NUM : DUAL_PKT_NUM; } -inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) +template +inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) { const RSM1MsopPkt& pkt = *(RSM1MsopPkt*)packet; bool ret = false; @@ -253,29 +259,32 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size_t size) int pitch = ntohs(channel.pitch) - ANGLE_OFFSET; int yaw = ntohs(channel.yaw) - ANGLE_OFFSET; - RSPoint point; - point.x = distance * COS (pitch) * COS (yaw); - point.y = distance * COS (pitch) * SIN (yaw); - point.z = distance * SIN (pitch); - this->transformPoint(point.x, point.y, point.z); + float x = distance * COS (pitch) * COS (yaw); + float y = distance * COS (pitch) * SIN (yaw); + float z = distance * SIN (pitch); + this->transformPoint(x, y, z); - point.intensity = channel.intensity; - point.timestamp = point_time; - point.ring = chan; + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, point_time); + setRing(point, chan); - this->cb_new_point_(point); + this->point_cloud_->points.emplace_back(point); } else if (!this->param_.dense_points) { - RSPoint point; - point.x = NAN; - point.y = NAN; - point.z = NAN; - point.intensity = 0; - point.timestamp = point_time; - point.ring = chan; - - this->cb_new_point_(point); + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, point_time); + setRing(point, chan); + + this->point_cloud_->points.emplace_back(point); } } diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 2641b99a..66a05d5c 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -43,42 +43,44 @@ namespace robosense { namespace lidar { + +template class DecoderFactory { public: - static std::shared_ptr createDecoder(LidarType type, + static std::shared_ptr> createDecoder(LidarType type, const RSDecoderParam& param, const std::function& excb); }; -inline std::shared_ptr -DecoderFactory::createDecoder(LidarType type, const RSDecoderParam& param, - const std::function& excb) +template +inline std::shared_ptr> DecoderFactory::createDecoder(LidarType type, + const RSDecoderParam& param, const std::function& excb) { - std::shared_ptr ret_ptr; + std::shared_ptr> ret_ptr; switch (type) { case LidarType::RS16: - ret_ptr = std::make_shared(param, excb); + ret_ptr = std::make_shared>(param, excb); break; case LidarType::RS32: - ret_ptr = std::make_shared(param, excb); + ret_ptr = std::make_shared>(param, excb); break; case LidarType::RSBP: - ret_ptr = std::make_shared(param, excb); + ret_ptr = std::make_shared>(param, excb); break; case LidarType::RSHELIOS: - ret_ptr = std::make_shared(param, excb); + ret_ptr = std::make_shared>(param, excb); break; case LidarType::RS80: - ret_ptr = std::make_shared(param, excb); + ret_ptr = std::make_shared>(param, excb); break; case LidarType::RS128: - ret_ptr = std::make_shared(param, excb); + ret_ptr = std::make_shared>(param, excb); break; case LidarType::RSM1: - ret_ptr = std::make_shared(param, excb); + ret_ptr = std::make_shared>(param, excb); break; default: RS_ERROR << "Wrong LiDAR Type. Please check your LiDAR Version! " << RS_REND; diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index a634921d..97c46ac5 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -62,7 +62,8 @@ typedef struct RSCalibrationAngle horiz_angle_cali[32]; } AdapterDifopPkt; -class DecoderMech : public Decoder +template +class DecoderMech : public Decoder { public: @@ -98,10 +99,11 @@ class DecoderMech : public Decoder float lidar_Rxy_; // lens center related }; -inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& const_param, +template +inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& const_param, const RSDecoderParam& param, const std::function& excb) - : Decoder(const_param.base, param, excb) + : Decoder(const_param.base, param, excb) , mech_const_param_(const_param) , chan_angles_(this->const_param_.CHANNELS_PER_BLOCK) , scan_section_(this->param_.start_angle * 100, this->param_.end_angle * 100) @@ -152,7 +154,8 @@ inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& const_param, } } -inline void DecoderMech::print() +template +inline void DecoderMech::print() { std::cout << "-----------------------------------------" << std::endl << "rps:\t\t\t" << this->rps_ << std::endl @@ -167,8 +170,9 @@ inline void DecoderMech::print() this->chan_angles_.print(); } +template template -inline void DecoderMech::decodeDifopCommon(const T_Difop& pkt) +inline void DecoderMech::decodeDifopCommon(const T_Difop& pkt) { // rounds per second this->rps_ = ntohs(pkt.rpm) / 60; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 7f9f6624..fad55e0f 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -90,7 +90,6 @@ class LidarDriverImpl void processDifop(); std::shared_ptr getPointCloud(); - void newPoint(const RSPoint& point); void splitFrame(uint16_t height, double ts); void setPointCloudHeader(std::shared_ptr msg, uint16_t height, double chan_ts); @@ -102,7 +101,7 @@ class LidarDriverImpl std::function cb_feed_pkt_; std::shared_ptr input_ptr_; - std::shared_ptr lidar_decoder_ptr_; + std::shared_ptr> lidar_decoder_ptr_; SyncQueue> free_pkt_queue_; SyncQueue> msop_pkt_queue_; SyncQueue> difop_pkt_queue_; @@ -112,8 +111,6 @@ class LidarDriverImpl bool init_flag_; bool start_flag_; uint32_t pkt_seq_; - - std::shared_ptr point_cloud_; uint32_t point_cloud_seq_; }; @@ -153,8 +150,6 @@ void LidarDriverImpl::regRecvCallback( { cb_get_pc_ = cb_get; cb_put_pc_ = cb_put; - - point_cloud_ = getPointCloud(); } template @@ -179,17 +174,27 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) return true; } - lidar_decoder_ptr_ = DecoderFactory::createDecoder( + // + // decoder + // + lidar_decoder_ptr_ = DecoderFactory::createDecoder( param.lidar_type, param.decoder_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); + + // rewrite pkt timestamp or not ? + lidar_decoder_ptr_->enableWritePktTs((cb_put_pkt_ == nullptr) ? false : true); - lidar_decoder_ptr_->regRecvCallback( - std::bind(&LidarDriverImpl::newPoint, this, std::placeholders::_1), + // point cloud related + lidar_decoder_ptr_->point_cloud_ = getPointCloud(); + lidar_decoder_ptr_->setSplitCallback( std::bind(&LidarDriverImpl::splitFrame, this, std::placeholders::_1, std::placeholders::_2)); - lidar_decoder_ptr_->enableWritePktTs((cb_put_pkt_ == nullptr) ? false : true); double packet_duration = lidar_decoder_ptr_->getPacketDuration(); + // + // input + // + input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1), packet_duration, cb_feed_pkt_); @@ -280,6 +285,7 @@ inline void LidarDriverImpl::runCallBack(std::shared_ptr b if (cb_put_pkt_) { Packet pkt; + pkt.timestamp = timestamp; pkt.is_difop = is_difop; pkt.is_frame_begin = is_frame_begin; pkt.seq = pkt_seq_++; @@ -352,8 +358,8 @@ inline void LidarDriverImpl::processMsop() continue; } - bool split = lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); - runCallBack(pkt, lidar_decoder_ptr_->prevPktTs(), false, split); // msop packet + bool pkt_to_split = lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); + runCallBack(pkt, lidar_decoder_ptr_->prevPktTs(), false, pkt_to_split); // msop packet free_pkt_queue_.push(pkt); } @@ -377,29 +383,15 @@ inline void LidarDriverImpl::processDifop() } } -template -void LidarDriverImpl::newPoint(const RSPoint& pt) -{ - typename T_PointCloud::PointT point; - setX(point, pt.x); - setY(point, pt.y); - setZ(point, pt.z); - setIntensity(point, pt.intensity); - setRing(point, pt.ring); - setTimestamp(point, pt.timestamp); - - point_cloud_->points.emplace_back(point); -} - template void LidarDriverImpl::splitFrame(uint16_t height, double ts) { - if (point_cloud_->points.size() > 0) + std::shared_ptr pc = lidar_decoder_ptr_->point_cloud_; + if (pc->points.size() > 0) { - setPointCloudHeader(point_cloud_, height, ts); - cb_put_pc_(point_cloud_); - - point_cloud_ = getPointCloud(); + setPointCloudHeader(pc, height, ts); + cb_put_pc_(pc); + lidar_decoder_ptr_->point_cloud_ = getPointCloud(); } else { diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index af5eba9d..9eaa75d2 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -18,16 +18,16 @@ static void errCallback(const Error& err) TEST(TestDecoderRS32, getEchoMode) { - ASSERT_TRUE(DecoderRS32::getEchoMode(0) == RSEchoMode::ECHO_DUAL); - ASSERT_TRUE(DecoderRS32::getEchoMode(1) == RSEchoMode::ECHO_SINGLE); - ASSERT_TRUE(DecoderRS32::getEchoMode(2) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(DecoderRS32::getEchoMode(0) == RSEchoMode::ECHO_DUAL); + ASSERT_TRUE(DecoderRS32::getEchoMode(1) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(DecoderRS32::getEchoMode(2) == RSEchoMode::ECHO_SINGLE); } TEST(TestDecoderRS32, decodeDifopPkt) { // const_param RSDecoderParam param; - DecoderRS32 decoder(param, errCallback); + DecoderRS32 decoder(param, errCallback); ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.split_blks_per_frame_, 1801); @@ -51,13 +51,6 @@ TEST(TestDecoderRS32, decodeDifopPkt) ASSERT_EQ(decoder.split_blks_per_frame_, 900); } -static std::vector points; - -static void newPoint(const RSPoint& point) -{ - points.emplace_back(point); -} - static void splitFrame(uint16_t height, double ts) { } @@ -155,20 +148,21 @@ TEST(TestDecoderRS32, decodeMsopPkt) // dense_points = false, use_lidar_clock = true RSDecoderParam param; - DecoderRS32 decoder(param, errCallback); + DecoderRS32 decoder(param, errCallback); ASSERT_EQ(decoder.chan_angles_.user_chans_.size(), 32); decoder.chan_angles_.user_chans_[0] = 2; decoder.chan_angles_.user_chans_[1] = 1; decoder.param_.dense_points = false; decoder.param_.use_lidar_clock = true; - decoder.regRecvCallback(newPoint, splitFrame); + decoder.point_cloud_ = std::make_shared(); + decoder.setSplitCallback(splitFrame); decoder.decodeMsopPkt(pkt, sizeof(pkt)); ASSERT_EQ(decoder.getTemperature(), 2.1875); - ASSERT_EQ(points.size(), 32); + ASSERT_EQ(decoder.point_cloud_->points.size(), 32); - RSPoint& point = points[0]; + PointT& point = decoder.point_cloud_->points[0]; ASSERT_EQ(point.intensity, 1); ASSERT_NE(point.timestamp, 0); ASSERT_EQ(point.ring, 2); diff --git a/test/decoder_rsbp_test.cpp b/test/decoder_rsbp_test.cpp index d535e8c3..dd9fb319 100644 --- a/test/decoder_rsbp_test.cpp +++ b/test/decoder_rsbp_test.cpp @@ -18,16 +18,16 @@ static void errCallback(const Error& err) TEST(TestDecoderRSBP, getEchoMode) { - ASSERT_TRUE(DecoderRSBP::getEchoMode(0) == RSEchoMode::ECHO_DUAL); - ASSERT_TRUE(DecoderRSBP::getEchoMode(1) == RSEchoMode::ECHO_SINGLE); - ASSERT_TRUE(DecoderRSBP::getEchoMode(2) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(DecoderRSBP::getEchoMode(0) == RSEchoMode::ECHO_DUAL); + ASSERT_TRUE(DecoderRSBP::getEchoMode(1) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(DecoderRSBP::getEchoMode(2) == RSEchoMode::ECHO_SINGLE); } TEST(TestDecoderRSBP, decodeDifopPkt) { // const_param RSDecoderParam param; - DecoderRSBP decoder(param, errCallback); + DecoderRSBP decoder(param, errCallback); ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.split_blks_per_frame_, 1801); @@ -52,13 +52,6 @@ TEST(TestDecoderRSBP, decodeDifopPkt) ASSERT_EQ(decoder.split_blks_per_frame_, 900); } -static std::vector points; - -static void newPoint(const RSPoint& point) -{ - points.emplace_back(point); -} - static void splitFrame(uint16_t height, double ts) { } @@ -156,7 +149,7 @@ TEST(TestDecoderRSBP, decodeMsopPkt) // dense_points = false, use_lidar_clock = true RSDecoderParam param; - DecoderRSBP decoder(param, errCallback); + DecoderRSBP decoder(param, errCallback); ASSERT_EQ(decoder.chan_angles_.user_chans_.size(), 32); decoder.chan_angles_.user_chans_[0] = 2; @@ -164,13 +157,14 @@ TEST(TestDecoderRSBP, decodeMsopPkt) decoder.param_.dense_points = false; decoder.param_.use_lidar_clock = true; - decoder.regRecvCallback(newPoint, splitFrame); + decoder.point_cloud_ = std::make_shared(); + decoder.setSplitCallback(splitFrame); decoder.decodeMsopPkt(pkt, sizeof(pkt)); ASSERT_EQ(decoder.getTemperature(), 2.1875); - ASSERT_EQ(points.size(), 32); + ASSERT_EQ(decoder.point_cloud_->points.size(), 32); - RSPoint& point = points[0]; + PointT& point = decoder.point_cloud_->points[0]; ASSERT_EQ(point.intensity, 1); ASSERT_NE(point.timestamp, 0); ASSERT_EQ(point.ring, 2); diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 4412d13a..8afd1b89 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -26,13 +26,13 @@ struct MyDifopPkt }; #pragma pack(pop) -class MyDecoder : public DecoderMech +class MyDecoder : public DecoderMech { public: MyDecoder(const RSDecoderMechConstParam& const_param, const RSDecoderParam& param, const std::function& excb) - : DecoderMech(const_param, param, excb) + : DecoderMech(const_param, param, excb) { } From 170df4e0300da02ff2e5547c4d6e1f8e8e043699 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 17 Jan 2022 20:56:17 +0800 Subject: [PATCH 162/379] refac: rename interfaces --- demo/demo_online.cpp | 10 ++++---- demo/demo_pcap.cpp | 16 ++++++------ src/rs_driver/api/lidar_driver.hpp | 8 +++--- src/rs_driver/driver/lidar_driver_impl.hpp | 30 +++++++++++----------- tool/rs_driver_viewer.cpp | 2 +- 5 files changed, 33 insertions(+), 33 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index f4ef5605..cddb8b41 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -83,15 +83,15 @@ int main(int argc, char* argv[]) param.input_type = InputType::ONLINE_LIDAR; param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RS32; ///< Set the lidar type. Make sure this type is correct - param.decoder_param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct + param.decoder_param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet param.decoder_param.use_lidar_clock = false; param.print(); LidarDriver driver; - driver.regRecvCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback function into the driver - driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver - if (!driver.init(param)) ///< Call the init function and pass the parameter + driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback function + driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function + if (!driver.init(param)) ///< Call the init function { RS_ERROR << "Driver Initialize Error..." << RS_REND; return -1; diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index f3f6d436..c2b533d9 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -79,19 +79,19 @@ int main(int argc, char* argv[]) RS_TITLE << " RS_Driver Core Version: v" << getDriverVersion() << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; - RSDriverParam param; ///< Create a parameter object + RSDriverParam param; ///< Create a parameter object param.input_type = InputType::PCAP_FILE; - param.input_param.pcap_path = "/mnt/share/pcap/RS32/Rs32.pcap"; ///< Set the pcap file directory - param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 - param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RS32; ///< Set the lidar type. Make sure this type is correct + param.input_param.pcap_path = "/mnt/share/pcap/RS16/Rs16.pcap"; ///< Set the pcap file directory + param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 + param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct param.print(); LidarDriver driver; ///< Declare the driver object - driver.regRecvCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback function into the driver - driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function into the driver - if (!driver.init(param)) ///< Call the init function and pass the parameter + driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback function + driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function + if (!driver.init(param)) ///< Call the init function { RS_ERROR << "Driver Initialize Error..." << RS_REND; return -1; diff --git a/src/rs_driver/api/lidar_driver.hpp b/src/rs_driver/api/lidar_driver.hpp index 30386de8..7865dbd2 100644 --- a/src/rs_driver/api/lidar_driver.hpp +++ b/src/rs_driver/api/lidar_driver.hpp @@ -63,10 +63,10 @@ class LidarDriver * called * @param callback The callback function */ - inline void regRecvCallback(const std::function(void)>& cb_get_pc, + inline void regPointCloudCallback(const std::function(void)>& cb_get_pc, const std::function)>& cb_put_pc) { - driver_ptr_->regRecvCallback(cb_get_pc, cb_put_pc); + driver_ptr_->regPointCloudCallback(cb_get_pc, cb_put_pc); } /** @@ -74,9 +74,9 @@ class LidarDriver * ready, this function will be called * @param callback The callback function */ - inline void regRecvCallback(const std::function& cb_put_pkt) + inline void regPacketCallback(const std::function& cb_put_pkt) { - driver_ptr_->regRecvCallback(cb_put_pkt); + driver_ptr_->regPacketCallback(cb_put_pkt); } /** diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index fad55e0f..4d3ad54f 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -66,9 +66,9 @@ class LidarDriverImpl LidarDriverImpl(); ~LidarDriverImpl(); - void regRecvCallback(const std::function(void)>& cb_get_pc, + void regPointCloudCallback(const std::function(void)>& cb_get_pc, const std::function)>& cb_put_pc); - void regRecvCallback(const std::function& cb_put_pkt); + void regPacketCallback(const std::function& cb_put_pkt); void regExceptionCallback(const std::function& cb_excp); bool init(const RSDriverParam& param); @@ -80,8 +80,8 @@ class LidarDriverImpl private: - void runCallBack(std::shared_ptr pkt, double timestamp, uint8_t is_difop, uint8_t is_frame_begin); - void reportError(const Error& error); + void runPacketCallBack(std::shared_ptr buf, double timestamp, uint8_t is_difop, uint8_t is_frame_begin); + void runExceptionCallback(const Error& error); std::shared_ptr packetGet(size_t size); void packetPut(std::shared_ptr pkt); @@ -138,13 +138,13 @@ std::shared_ptr LidarDriverImpl::getPointCloud() return pc; } - reportError(Error(ERRCODE_POINTCLOUDNULL)); + runExceptionCallback(Error(ERRCODE_POINTCLOUDNULL)); std::this_thread::sleep_for(std::chrono::milliseconds(300)); } } template -void LidarDriverImpl::regRecvCallback( +void LidarDriverImpl::regPointCloudCallback( const std::function(void)>& cb_get, const std::function)>& cb_put) { @@ -153,7 +153,7 @@ void LidarDriverImpl::regRecvCallback( } template -inline void LidarDriverImpl::regRecvCallback( +inline void LidarDriverImpl::regPacketCallback( const std::function& cb_put_pkt) { cb_put_pkt_ = cb_put_pkt; @@ -179,7 +179,7 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) // lidar_decoder_ptr_ = DecoderFactory::createDecoder( param.lidar_type, param.decoder_param, - std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1)); + std::bind(&LidarDriverImpl::runExceptionCallback, this, std::placeholders::_1)); // rewrite pkt timestamp or not ? lidar_decoder_ptr_->enableWritePktTs((cb_put_pkt_ == nullptr) ? false : true); @@ -196,7 +196,7 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) // input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, - std::bind(&LidarDriverImpl::reportError, this, std::placeholders::_1), + std::bind(&LidarDriverImpl::runExceptionCallback, this, std::placeholders::_1), packet_duration, cb_feed_pkt_); input_ptr_->regRecvCallback( @@ -279,7 +279,7 @@ inline bool LidarDriverImpl::getTemperature(float& temp) } template -inline void LidarDriverImpl::runCallBack(std::shared_ptr buf, +inline void LidarDriverImpl::runPacketCallBack(std::shared_ptr buf, double timestamp, uint8_t is_difop, uint8_t is_frame_begin) { if (cb_put_pkt_) @@ -297,7 +297,7 @@ inline void LidarDriverImpl::runCallBack(std::shared_ptr b } template -inline void LidarDriverImpl::reportError(const Error& error) +inline void LidarDriverImpl::runExceptionCallback(const Error& error) { if (cb_excp_) { @@ -342,7 +342,7 @@ inline void LidarDriverImpl::packetPut(std::shared_ptr pkt size_t sz = queue->push(pkt); if (sz > PACKET_POOL_MAX) { - reportError(Error(ERRCODE_PKTBUFOVERFLOW)); + runExceptionCallback(Error(ERRCODE_PKTBUFOVERFLOW)); queue->clear(); } } @@ -359,7 +359,7 @@ inline void LidarDriverImpl::processMsop() } bool pkt_to_split = lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); - runCallBack(pkt, lidar_decoder_ptr_->prevPktTs(), false, pkt_to_split); // msop packet + runPacketCallBack(pkt, lidar_decoder_ptr_->prevPktTs(), false, pkt_to_split); // msop packet free_pkt_queue_.push(pkt); } @@ -377,7 +377,7 @@ inline void LidarDriverImpl::processDifop() } lidar_decoder_ptr_->processDifopPkt(pkt->data(), pkt->dataSize()); - runCallBack(pkt, 0, true, false); // difop packet + runPacketCallBack(pkt, 0, true, false); // difop packet free_pkt_queue_.push(pkt); } @@ -395,7 +395,7 @@ void LidarDriverImpl::splitFrame(uint16_t height, double ts) } else { - reportError(Error(ERRCODE_ZEROPOINTS)); + runExceptionCallback(Error(ERRCODE_ZEROPOINTS)); } } diff --git a/tool/rs_driver_viewer.cpp b/tool/rs_driver_viewer.cpp index ae5712ed..b65fd132 100644 --- a/tool/rs_driver_viewer.cpp +++ b/tool/rs_driver_viewer.cpp @@ -271,7 +271,7 @@ int main(int argc, char* argv[]) LidarDriver driver; ///< Declare the driver object driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback - driver.regRecvCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback + driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback if (!driver.init(param)) ///< Call the init function { RS_ERROR << "Driver Initialize Error..." << RS_REND; From f2d677c1fcec1b6828564a1ac83525b06a8eea0c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 18 Jan 2022 09:57:59 +0800 Subject: [PATCH 163/379] refac: fix compiling error --- CMakeLists.txt | 2 +- src/rs_driver/driver/input/input.hpp | 1 + test/decoder_test.cpp | 2 +- 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 84762370..25df27f6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -58,7 +58,7 @@ elseif(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") message(FATAL_ERROR "Unsupported compiler.") endif() - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++11") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++14") set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -g") set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3") endif() diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index 29c0d746..4871fae2 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -35,6 +35,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include +#include #include #include diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 8afd1b89..035159e7 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -101,7 +101,7 @@ TEST(TestDecoder, processDifopPkt_fail) MyDecoder decoder(const_param, param, errCallback); // wrong difop length - MyDifopPkt pkt; + MyDifopPkt pkt = {0}; errCode = ERRCODE_SUCCESS; decoder.processDifopPkt((const uint8_t*)&pkt, 10); ASSERT_EQ(errCode, ERRCODE_WRONGPKTLENGTH); From 6e6272c22096ba4f6b6a05a707a40ecd31082317 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 18 Jan 2022 14:23:00 +0800 Subject: [PATCH 164/379] refac: format --- CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 25df27f6..caa1c578 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -11,9 +11,9 @@ project(rs_driver VERSION 1.4.3) #============================= # Compile Demos&Tools #============================= -option(COMPILE_DEMOS "Build rs_driver demos" ON) -option(COMPILE_TOOLS "Build point cloud visualization tool" ON) -option(COMPILE_TESTS "Build rs_driver unit tests" ON) +option(COMPILE_DEMOS "Build rs_driver demos" OFF) +option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) +option(COMPILE_TESTS "Build rs_driver unit tests" OFF) #============================= # Compile Features From b1e4bdcb30a8e303e9ff32ac2f3fa952a4ecbef4 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 18 Jan 2022 18:49:41 +0800 Subject: [PATCH 165/379] refac: update help docs --- doc/howto/how_to_decode_pcap.md | 148 ------------- doc/howto/how_to_decode_with_online_lidar.md | 193 +++++++++++++++++ doc/howto/how_to_decode_with_pcap_file.md | 194 ++++++++++++++++++ doc/howto/how_to_online_use_driver.md | 146 ------------- doc/howto/how_to_transform_pointcloud.md | 44 ++++ doc/howto/how_to_use_multi_cast_function.md | 57 ----- doc/howto/how_to_use_multicast_group.md | 42 ++++ doc/howto/how_to_use_rs_driver_viewer.md | 40 ++-- .../how_to_use_transformation_function.md | 40 ---- doc/intro/parameter_intro_cn.md | 44 ++-- doc/intro/parameter_intro_en.md | 44 ++-- src/rs_driver/driver/driver_param.hpp | 12 +- 12 files changed, 546 insertions(+), 458 deletions(-) delete mode 100644 doc/howto/how_to_decode_pcap.md create mode 100644 doc/howto/how_to_decode_with_online_lidar.md create mode 100644 doc/howto/how_to_decode_with_pcap_file.md delete mode 100644 doc/howto/how_to_online_use_driver.md create mode 100644 doc/howto/how_to_transform_pointcloud.md delete mode 100644 doc/howto/how_to_use_multi_cast_function.md create mode 100644 doc/howto/how_to_use_multicast_group.md delete mode 100644 doc/howto/how_to_use_transformation_function.md diff --git a/doc/howto/how_to_decode_pcap.md b/doc/howto/how_to_decode_pcap.md deleted file mode 100644 index e7bdad03..00000000 --- a/doc/howto/how_to_decode_pcap.md +++ /dev/null @@ -1,148 +0,0 @@ -# How to decode pcap bag - -## 1 Introduction - -This document will show you how to use the API to decode pcap bag. - -## 2 Steps - -Please follow the steps below to do advanced development. - -### 2.1 Define a point type - -Now the driver will automatically detect and assign value to the following six variables. - -- x ------ The x coordinate of point. -- y ------ The y coordinate of point. -- z ------ The z coordinate of point. -- intensity ------ The intensity of point. -- timestamp ------ The timestamp of point. If ```use_lidar_clock``` is set to ```true```, this timestamp will be lidar time, otherwise will be system time. -- ring ------ The ring ID of the point, which represents the row number. e.g. For RS80, the range of ring ID is 0~79 (from bottom to top). - -Here are some examples: - -- The point type contains **x, y, z** - - ```c++ - struct PointXYZ ///< user defined point type - { - float x; - float y; - float z; - ... - }; - ``` - -- The point type contains **x, y, z, intensity** - - ```c++ - struct PointXYZI ///< user defined point type - { - float x; - float y; - float z; - uint8_t intensity; - ... - }; - ``` - - Or you can use **pcl::PointXYZI** directly - -- The point type contains **x, y, z, intensity, timestamp, ring** - - ```c++ - struct PointXYZIRT ///< user defined point type - { - float x; - float y; - float z; - uint8_t intensity; - double timestamp; - uint16_t ring; - ... - }; - ``` - -The only thing user need to pay attention to is that the variable name must obey the rules -- **x, y, z, intensity, timestamp, ring**, otherwise the variable can not be assigned as expected. - -### 2.2 Define a point cloud callback function - -Define the point cloud callback function. The template argument PointXYZI is the point type we defined in 2.1. When point cloud message is ready, this function will be called by driver. **Note! Please don't add any time-consuming operations in this function!** User can make a copy of the message and process it in another thread. Or user can add some quick operations such like ros publish in the callback function. - -```c++ -void pointCloudCallback(const PointCloudMsg &msg) -{ - RS_MSG << "msg: " << msg.seq << " point cloud size: " << msg.point_cloud_ptr->size() << RS_REND; -} -``` - -### 2.3 Define a exception callback function - -Define the exception callback function. When driver want to send out infos or error codes, this function will be called. Same as the previous callback function, please **do not add any time-consuming operations in this callback function!** - -```c++ -void exceptionCallback(const Error &code) -{ - RS_WARNING << "Error code : " << code.toString() << RS_REND; -} -``` - -### 2.4 Instantiate the driver object - -Instanciate a driver object. - -```c++ -LidarDriver driver; ///< Declare the driver object -``` - -### 2.5 Define the parameter, configure the parameter - -Define a parameter object and config it. Since we want to decode pcap bag, please set the ```read_pcap``` to ```true``` and set up the correct pcap file directory. The msop port and difop port number of lidar can be got from wireshark(a network socket capture software). The default value is ```msop-6699```, ```difop-7788```. User also need to make sure the ```lidar_type``` is set correctly. - -```c++ -RSDriverParam param; ///< Create a parameter object -param.input_param.read_pcap = true; ///< Set read_pcap to true -param.input_param.pcap_path = "/home/robosense/rs16.pcap"; ///< Set the pcap file directory -param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 -param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 -param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct -``` - -### 2.6 Register the point cloud callback and exception callback - -Register the callback functions we defined in 2.2 and 2.3. **The exception callback function must be registered before the init() function is called because error may occur during the initialization**. - -```c++ -driver.regRecvCallback(pointCloudCallback); ///< Register the point cloud callback function into the driver -driver.regExceptionCallback(exceptionCallback); ///at(i) , the next point on the same ring should be msg.point_cloud_ptr->at(i+msg.height). User can set the parameter ```saved_by_rows``` to ```true``` to make the point cloud stored in **row major order**. - - - -### *Congratulations! You have finished the demo tutorial of RoboSense LiDAR driver! You can find the complete demo code in the demo folder under the project directory. Feel free to connect us if you have any question about the driver.* \ No newline at end of file diff --git a/doc/howto/how_to_decode_with_online_lidar.md b/doc/howto/how_to_decode_with_online_lidar.md new file mode 100644 index 00000000..9186c6ec --- /dev/null +++ b/doc/howto/how_to_decode_with_online_lidar.md @@ -0,0 +1,193 @@ +# How to use driver with online Lidar + +## 1 Introduction + +This document illustrates how to decode the packets from an online lidar with the driver's API. + +## 2 Steps + +### 2.1 Define Point + +Now the driver will automatically assign values these member variables. + +- x ------ float type. The x coordinate of point. +- y ------ float type. The y coordinate of point. +- z ------ float type. The z coordinate of point. +- intensity ------ uint8_t type. The intensity of point. +- timestamp ------ double type. The timestamp of point. If ```use_lidar_clock``` is ```true```, lidar clock time in MSOP packet is used, otherwise regenerate the timestamp on host. +- ring ------ The ring ID of the point, which represents the row number. e.g. For RS80, the range of ring ID is 0~79 (from bottom to top). + +Below are some examples: + +- The point type contains **x, y, z, intensity** + + ```c++ + struct PointXYZI ///< user defined point type + { + float x; + float y; + float z; + uint8_t intensity; + ... + }; + ``` + + Or you can use **pcl::PointXYZI** directly + +- The point type contains **x, y, z, intensity, timestamp, ring** + + ```c++ + struct PointXYZIRT ///< user defined point type + { + float x; + float y; + float z; + uint8_t intensity; + double timestamp; + uint16_t ring; + ... + }; + ``` + +User may add new member variables, remove member variables, or change the order of them, but should not change names or types of them -- **x, y, z, intensity, timestamp, ring**, otherwise the behaviors might be unexpected. + +### 2.2 Define Point Cloud + + The driver keep a point cloud instance internally, and accumulates points into it. When a frame of point cloud is ready, it informs the caller. + + The point cloud is like below: + + ```c++ + template + class PointCloudT + { + public: + typedef T_Point PointT; + typedef std::vector VectorT; + + uint32_t height = 0; ///< Height of point cloud + uint32_t width = 0; ///< Width of point cloud + bool is_dense = false; ///< If is_dense is true, the point cloud does not contain NAN points, + double timestamp = 0.0; + uint32_t seq = 0; ///< Sequence number of message + + VectorT points; + }; + + typedef PointXYZI PointT; + typedef PointCloudT PointCloudMsg; + + ``` + + User may add new members to PointCloudT, change the order of its members, but should not remove member variables. + + The template argument of PointCloudT is the point type, which is defined in the section 2.1. + +### 2.3 Define point cloud callback functions + +The user is supposed to managed point cloud pools. The driver gets free point cloud from user, and returns prepared point clouds to user. + +User provides two callback functions. The driver call one of them to get a free point cloud, before constructing it. + +```c++ +std::shared_ptr pointCloudGetCallback(void) +{ + return std::make_shared(); +} +``` + +The driver call the other to return the prepared point cloud. + +```c++ +void pointCloudPutCallback(std::shared_ptr msg) +{ + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; +} +``` + +Note: + ++ Above examples always allocates a new point cloud instance for simplicity. This is not suggested, especially if the efficiency is sensitive. + ++ The callback functions run in the main handling loop of the driver, so **Do not add any time-consuming operations in the callback functions**. + +### 2.4 Define exception callback functions + +When an error is reported, the driver will inform user. User should provide an exception callback function. + +Once again, **Do not add any time-consuming operations in the callback functions**. + +```c++ +void exceptionCallback(const Error &code) +{ + RS_WARNING << "Error code : " << code.toString() << RS_REND; +} +``` + +### 2.5 Instantiate the driver object + +Instantiate a driver object. + +```c++ +LidarDriver driver; ///< Declare the driver object +``` + +### 2.6 Configure the parameter + +Define a parameter object and configure it. + +To decode pcap bag, please set the ```input_type``` to ```InputType::ONLINE_LIDAR```. + +Read the pcap file with a 3rd party tool, such as Wireshark, to get the MSOP/DIFOP ports. Also give the correct lidar type. + +```c++ +RSDriverParam param; ///< Create a parameter object +param.input_type = InputType::ONLINE_LIDAR; /// get packet from online lidar +param.input_param.pcap_path = "/home/robosense/rs16.pcap"; ///< Set the pcap file path +param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 +param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 +param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct +``` + +### 2.7 Register callback functions + +Register above callback functions. + +Please **register the callback functions before call the init() function**, because errors may occur during the initialization. + +```c++ +driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback functions +driver.regExceptionCallback(exceptionCallback); ///at(i) , the next point on the same ring will be msg.point_cloud_ptr->at(i+msg.height). + +## 4 Congratulations + +**You have finished the demo tutorial of the RoboSense LiDAR driver! Please find the complete demo code in the project directory. Feel free to contact us if you have any questions.** + +### *Congratulations! You have finished the demo tutorial of RoboSense LiDAR driver! You can find the complete demo code in the demo folder under the project directory. Feel free to connect us if you have any question about the driver.* diff --git a/doc/howto/how_to_decode_with_pcap_file.md b/doc/howto/how_to_decode_with_pcap_file.md new file mode 100644 index 00000000..3d4963fb --- /dev/null +++ b/doc/howto/how_to_decode_with_pcap_file.md @@ -0,0 +1,194 @@ +# How to use driver with a pcap file + +## 1 Introduction + +The pcap file is captured with some 3rd party tools, such as Wireshark/tcpdump. + +This document illustrates how to decode it with the driver's API. + +## 2 Steps + +### 2.1 Define Point + +Now the driver will automatically assign values these member variables. + +- x ------ float type. The x coordinate of point. +- y ------ float type. The y coordinate of point. +- z ------ float type. The z coordinate of point. +- intensity ------ uint8_t type. The intensity of point. +- timestamp ------ double type. The timestamp of point. If ```use_lidar_clock``` is ```true```, lidar clock time in MSOP packet is used, otherwise regenerate the timestamp on host. +- ring ------ The ring ID of the point, which represents the row number. e.g. For RS80, the range of ring ID is 0~79 (from bottom to top). + +Below are some examples: + +- The point type contains **x, y, z, intensity** + + ```c++ + struct PointXYZI ///< user defined point type + { + float x; + float y; + float z; + uint8_t intensity; + ... + }; + ``` + + Or you can use **pcl::PointXYZI** directly + +- The point type contains **x, y, z, intensity, timestamp, ring** + + ```c++ + struct PointXYZIRT ///< user defined point type + { + float x; + float y; + float z; + uint8_t intensity; + double timestamp; + uint16_t ring; + ... + }; + ``` + +User may add new member variables, remove member variables, or change the order of them, but should not change names or types of them -- **x, y, z, intensity, timestamp, ring**, otherwise the behaviors might be unexpected. + +### 2.2 Define Point Cloud + + The driver keep a point cloud instance internally, and accumulates points into it. When a frame of point cloud is ready, it informs the caller. + + The point cloud is like below: + + ```c++ + template + class PointCloudT + { + public: + typedef T_Point PointT; + typedef std::vector VectorT; + + uint32_t height = 0; ///< Height of point cloud + uint32_t width = 0; ///< Width of point cloud + bool is_dense = false; ///< If is_dense is true, the point cloud does not contain NAN points, + double timestamp = 0.0; + uint32_t seq = 0; ///< Sequence number of message + + VectorT points; + }; + + typedef PointXYZI PointT; + typedef PointCloudT PointCloudMsg; + + ``` + + User may add new members to PointCloudT, change the order of its members, but should not remove member variables. + + The template argument of PointCloudT is the point type, which is defined in the section 2.1. + +### 2.3 Define point cloud callback functions + +The user is supposed to managed point cloud pools. The driver gets free point cloud from user, and returns prepared point clouds to user. + +User provides two callback functions. The driver call one of them to get a free point cloud, before constructing it. + +```c++ +std::shared_ptr pointCloudGetCallback(void) +{ + return std::make_shared(); +} +``` + +The driver call the other to return the prepared point cloud. + +```c++ +void pointCloudPutCallback(std::shared_ptr msg) +{ + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; +} +``` + +Note: + ++ Above examples always allocates a new point cloud instance for simplicity. This is not suggested, especially if the efficiency is sensitive. + ++ The callback functions run in the main handling loop of the driver, so **Do not add any time-consuming operations in the callback functions**. + +### 2.4 Define exception callback functions + +When an error is reported, the driver will inform user. User should provide an exception callback function. + +Once again, **Do not add any time-consuming operations in the callback functions**. + +```c++ +void exceptionCallback(const Error &code) +{ + RS_WARNING << "Error code : " << code.toString() << RS_REND; +} +``` + +### 2.5 Instantiate the driver object + +Instantiate a driver object. + +```c++ +LidarDriver driver; ///< Declare the driver object +``` + +### 2.6 Configure the parameter + +Define a parameter object and configure it. + +To decode pcap bag, please set the ```input_type``` to ```InputType::PCAP_FILE```, and give the correct pcap file path. + +Read the pcap file with a 3rd party tool, such as Wireshark, to get the MSOP/DIFOP ports. Also give the correct lidar type. + +```c++ +RSDriverParam param; ///< Create a parameter object +param.input_type = InputType::PCAP_FILE; /// get packet from the pcap file +param.input_param.pcap_path = "/home/robosense/rs16.pcap"; ///< Set the pcap file path +param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 +param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 +param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct +``` + +### 2.7 Register callback functions + +Register above callback functions. + +Please **register the callback functions before call the init() function**, because errors may occur during the initialization. + +```c++ +driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback functions +driver.regExceptionCallback(exceptionCallback); ///at(i) , the next point on the same ring will be msg.point_cloud_ptr->at(i+msg.height). + +## 4 Congratulations + +**You have finished the demo tutorial of the RoboSense LiDAR driver! Please find the complete demo code in the project directory. Feel free to contact us if you have any questions.** + diff --git a/doc/howto/how_to_online_use_driver.md b/doc/howto/how_to_online_use_driver.md deleted file mode 100644 index d3fe17d8..00000000 --- a/doc/howto/how_to_online_use_driver.md +++ /dev/null @@ -1,146 +0,0 @@ -# How to online use driver - -## 1 Introduction - -This document will show you how to use the API to get point cloud from LiDAR. - -## 2 Steps - -Please follow the steps below to do advanced development. - -### 2.1 Define a point type - -Now the driver will automatically detect and assign value to the following six variables. - -- x ------ The x coordinate of point. -- y ------ The y coordinate of point. -- z ------ The z coordinate of point. -- intensity ------ The intensity of point. -- timestamp ------ The timestamp of point. If ```use_lidar_clock``` is set to ```true```, this timestamp will be lidar time, otherwise will be system time. -- ring ------ The ring ID of the point, which represents the row number. e.g. For RS80, the range of ring ID is 0~79 (from bottom to top). - -Here are some examples: - -- The point type contains **x, y, z** - - ```c++ - struct PointXYZ ///< user defined point type - { - float x; - float y; - float z; - ... - }; - ``` - -- The point type contains **x, y, z, intensity** - - ```c++ - struct PointXYZI ///< user defined point type - { - float x; - float y; - float z; - uint8_t intensity; - ... - }; - ``` - - Or you can use **pcl::PointXYZI** directly - -- The point type contains **x, y, z, intensity, timestamp, ring** - - ```c++ - struct PointXYZIRT ///< user defined point type - { - float x; - float y; - float z; - uint8_t intensity; - double timestamp; - uint16_t ring; - ... - }; - ``` - -The only thing user need to pay attention to is that the variable name must obey the rules -- **x, y, z, intensity, timestamp, ring**, otherwise the variable can not be assigned as expected. - -### 2.2 Define a point cloud callback function - -The template argument PointXYZI is the point type we defined in 2.1. When point cloud message is ready, this function will be called by driver. **Note! Please don't add any time-consuming operations in this function!** User can make a copy of the message and process it in another thread. Or user can add some quick operations such like ros publish in the callback function. - -```c++ -void pointCloudCallback(const PointCloudMsg &msg) -{ - RS_MSG << "msg: " << msg.seq << " point cloud size: " << msg.point_cloud_ptr->size() << RS_REND; -} -``` - -### 2.3 Define a exception callback function - -Define the exception callback function. When driver want to send out infos or error codes, this function will be called. Same as the previous callback function, please **do not add any time-consuming operations in this callback function!** - -```c++ -void exceptionCallback(const Error &code) -{ - RS_WARNING << "Error code : " << code.toString() << RS_REND; -} -``` - -### 2.4 Instantiate the driver object - -Instanciate a driver object. - -```c++ -LidarDriver driver; ///< Declare the driver object -``` - -### 2.5 Define the parameter and configure the parameter - - The msop port and difop port number of lidar can be got from wireshark(a network socket capture software). The default value is ```msop-6699``` and ```difop-7788```. User also need to make sure the ```lidar_type``` is set correctly. - -```c++ -RSDriverParam param; ///< Create a parameter object -param.input_param.msop_port = 6699; ///< Set the lidar msop port number the default 6699 -param.input_param.difop_port = 7788; ///< Set the lidar difop port number the default 7788 -param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct -``` - -### 2.6 Register the point cloud callback and exception callback - -Register the callback functions we defined in 2.2 and 2.3. **The exception callback function must be registered before the init() function is called because error may occur during the initialization**. - -```c++ -driver.regRecvCallback(pointCloudCallback); ///< Register the point cloud callback function into the driver -driver.regExceptionCallback(exceptionCallback); ///at(i) , the next point on the same ring should be msg.point_cloud_ptr->at(i+msg.height). User can set the parameter ```saved_by_rows``` to ```true``` to make the point cloud stored in **row major order**. - - - -### *Congratulations! You have finished the demo tutorial of RoboSense LiDAR driver! You can find the complete demo code in the demo folder under the project directory. Feel free to connect us if you have any question about the driver.* \ No newline at end of file diff --git a/doc/howto/how_to_transform_pointcloud.md b/doc/howto/how_to_transform_pointcloud.md new file mode 100644 index 00000000..2327101f --- /dev/null +++ b/doc/howto/how_to_transform_pointcloud.md @@ -0,0 +1,44 @@ +# How to use transform point cloud + +## 1 Introduction + +Note: ++ Before reading this document, please be sure that you have read the [Online connect LiDAR](how_to_decode_with_online_lidar.md) or [Offline decode pcap bag](how_to_decode_with_pcap_file.md). ++ This function is only for test purpose, and it costs much CPU resources, so **never, never enable this function in your released products**. + +This document illustrate how to transform the point cloud to a different position with the built-in trasform function. + +The rotation order of the transformation is **yaw - pitch - row**. The unit of x, y, z, is ```m```, and the unit of roll, pitch, yaw, is ```radian```. + +## 2 Steps + +### 2.1 Compile + +To enable the transformation function, compile the driver with the option ENABLE_TRANSFORM=ON. + +```bash +cmake -DENABLE_TRANSFORM=ON .. +``` + +### 2.2 Config parameters + +Configure the transformation parameters. These parameters' default value is ```0```. + +Below is an example with x=1, y=0, z=2.5, roll=0.1, pitch=0.2, yaw=1.57. + +```c++ +RSDriverParam param; ///< Create a parameter object +param.input_type = InputType::ONLINE_LIDAR; /// get packet from online lidar +param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 +param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 +param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct + +param.decoder_param.transform_param.x = 1; ///< unit: m +param.decoder_param.transform_param.y = 0; ///< unit: m +param.decoder_param.transform_param.z = 2.5; ///< unit: m +param.decoder_param.transform_param.roll = 0.1; ///< unit: radian +param.decoder_param.transform_param.pitch = 0.2;///< unit: radian +param.decoder_param.transform_param.yaw = 1.57; ///< unit: radian + +``` + diff --git a/doc/howto/how_to_use_multi_cast_function.md b/doc/howto/how_to_use_multi_cast_function.md deleted file mode 100644 index 53cf9624..00000000 --- a/doc/howto/how_to_use_multi_cast_function.md +++ /dev/null @@ -1,57 +0,0 @@ -# How to use multi-cast function - -## 1 Introduction - -This document will show you how to use rs_driver to receive point cloud from the LiDAR working in multi-cast mode. - -## 2 Steps (Linux) - -Suppose the multi-cast address of LiDAR is ```224.1.1.1```. - -### 2.1 Set up parameters - -Set up the parameter ```multi_cast_address```. Here is an example for offline decoding pcap bag. - -```c++ -RSDriverParam param; ///< Create a parameter object -param.input_param.read_pcap = true; ///< Set read_pcap to true -param.input_param.pcap_path = "/home/robosense/rs16.pcap"; ///< Set the pcap file directory -param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 -param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 -param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct -param.input_param.multi_cast_address = "224.1.1.1"; ///< Set the multi-cast address. - -``` - -### 2.2 Set up the PC ip address - -In multi-cast case, the ip address of PC has no limit but user need to make sure **the PC and LiDAR are in the same net work**, which means PC can ping to LiDAR. - -### 2.3 Add the PC to the group - -Use the following command to check the PC's ethernet card name: - -```bash -ifconfig -``` - -Then execute the following command to add the PC to the group (replace the ```enp2s0``` with your ethernet card name): - -``` -sudo route add -net 224.0.0.0/4 dev enp2s0 -``` - -### 2.4 Run - -Run the program. - - - - - - - - - - - diff --git a/doc/howto/how_to_use_multicast_group.md b/doc/howto/how_to_use_multicast_group.md new file mode 100644 index 00000000..c8e35273 --- /dev/null +++ b/doc/howto/how_to_use_multicast_group.md @@ -0,0 +1,42 @@ +# How to use multicast group + +## 1 Introduction + +This document illustrates how to receive point cloud in the multicast group mode. This is only for the Linux platform. + +## 2 Steps + +Suppose the multicast group address is ```224.1.1.1```, and the host addres is ```192.168.1.102```. + +The Lidar sends packets to the multicat group address. The NIC with the host address should be on the same network with the Lidar. + +The driver will make the NIC join to the multicast group address, and then get the packets from it. + +### 2.1 Set up parameters + +Set the parameter ```group_address``` and ```host_address```. + +```c++ +RSDriverParam param; ///< Create a parameter object +param.input_type = InputType::ONLINE_LIDAR; ///< get packet from online lidar +param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 +param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 +param.input_param.host_address = "192.168.1.102"; ///< Set the host address. +param.input_param.group_address = "224.1.1.1"; ///< Set the multicast group address. +param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct +``` + +### 2.4 Run + +Run the demo program. + + + + + + + + + + + diff --git a/doc/howto/how_to_use_rs_driver_viewer.md b/doc/howto/how_to_use_rs_driver_viewer.md index 6ac12f4b..6eb91df2 100644 --- a/doc/howto/how_to_use_rs_driver_viewer.md +++ b/doc/howto/how_to_use_rs_driver_viewer.md @@ -1,24 +1,24 @@ -# How to use visualization tool +# How to visualize the point cloud with rs_driver_viewer ## 1 Introduction -This document will show you how to use the visualization tool to watch point cloud from LiDAR. +The rs_driver_viewer is a visualization tool for the point cloud. This document illustrates how to use it. -## 2 Run +## 2 Compile and Run -If user install the **rs_driver** in the previous step, the tool can be start by the following command: +Compile the driver with the option COMPILE_TOOLS=ON. ```bash -rs_driver_viewer +cmake -DCOMPILE_TOOS=ON .. ``` -Otherwise, the tool need to be start with the absolute path: +Run the tool. ```bash -./rs_driver/build/tool/rs_driver_viewer +./tool/rs_driver_viewer ``` -### 2.1 Arguments +### 2.1 Help Menu - -h/--help @@ -31,6 +31,18 @@ Otherwise, the tool need to be start with the absolute path: - -difop Difop port number of LiDAR, the default value is *7788* + +- -host + + the host address + +- -group + + the multicast group address + +- -pcap + + The absolute pcap file path. If this argument is empty, the driver read packets from online-lidar, else from the pcap file. - -type @@ -60,27 +72,25 @@ Otherwise, the tool need to be start with the absolute path: Transformation parameter, default is 0, unit: radian -- -pcap - - The absolute path of pcap file. If this argument is set, the driver will work in off-line mode and the pcap file. Otherwise the driver work in online mode. +Note: -**The point cloud transformation function can only be used when the cmake option ENABLE_TRANSFORM is set to ON.** +**The point cloud transformation function can only be available if the cmake option ENABLE_TRANSFORM=ON.** ## 3 Examples -- Online decode a RS128 LiDAR, which msop port is ```9966``` and difop port is ```8877``` +- Decode from an online RS128 LiDAR, whose msop port is ```9966``` and difop port is ```8877``` ```bash rs_driver_viewer -msop 9966 -difop 8877 -type RS128 ``` -- Offline decode a RSHELIOS LiDAR with a pcap file. +- Decode from a pcap file with RSHELIOS LiDAR data. ```bash rs_driver_viewer -pcap /home/robosense/helios.pcap -type RSHELIOS ``` -- Online decode a RS16 LiDAR with the coordinate transformation parameter x=1.5, y=2, z=0, roll=1.57, pitch=0, yaw=0 +- Decode with the coordinate transformation parameters: x=1.5, y=2, z=0, roll=1.57, pitch=0, yaw=0 ```bash rs_driver_viewer -type RS16 -x 1.5 -y 2 -roll 1.57 diff --git a/doc/howto/how_to_use_transformation_function.md b/doc/howto/how_to_use_transformation_function.md deleted file mode 100644 index 89b2e090..00000000 --- a/doc/howto/how_to_use_transformation_function.md +++ /dev/null @@ -1,40 +0,0 @@ -# How to use transformation function - -## 1 Introduction - -This document will show you how to use the built in coordinate transformation function. Before reading this document, please make sure you have read the [Online connect LiDAR](how_to_online_use_driver.md) or [Offline decode pcap bag](how_to_offline_decode_pcap.md). - -The rotation order of the transformation is **yaw - pitch - row**. - -The unit of x, y, z, is ```m```, and the unit of roll, pitch, yaw, is ```radian```. - -## 2 Steps - -### 2.1 Enable - -To enable the coordinate transformation function, set the following option to ```ON``` when executing cmake command: - -```bash -cmake -DENABLE_TRANSFORM=ON .. -``` - -### 2.2 Set up parameters - -Set up the transformation parameters. The default value of each parameter is ```0```. Here is an example for offline decoding pcap bag ( x=1, y=0, z=2.5, roll=0.1, pitch=0.2, yaw=1.57 ): - -```c++ -RSDriverParam param; ///< Create a parameter object -param.input_param.read_pcap = true; ///< Set read_pcap to true -param.input_param.pcap_path = "/home/robosense/rs16.pcap"; ///< Set the pcap file directory -param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 -param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 -param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct -param.decoder_param.transform_param.x = 1; ///< unit: m -param.decoder_param.transform_param.y = 0; ///< unit: m -param.decoder_param.transform_param.z = 2.5; ///< unit: m -param.decoder_param.transform_param.roll = 0.1; ///< unit: radian -param.decoder_param.transform_param.pitch = 0.2;///< unit: radian -param.decoder_param.transform_param.yaw = 1.57; ///< unit: radian - -``` - diff --git a/doc/intro/parameter_intro_cn.md b/doc/intro/parameter_intro_cn.md index bd2d3f23..4c8f8f3f 100644 --- a/doc/intro/parameter_intro_cn.md +++ b/doc/intro/parameter_intro_cn.md @@ -15,44 +15,42 @@ typedef struct RSTransformParam ///< The Point transform parameter typedef struct RSDecoderParam ///< LiDAR decoder parameter { - float max_distance = 200.0f; ///< Max distance of point cloud range + bool config_from_file = false;///< Internal use only for debugging + std::string angle_path = ""; ///< Internal use only for debugging + bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet float min_distance = 0.2f; ///< Minimum distance of point cloud range + float max_distance = 200.0f; ///< Max distance of point cloud range float start_angle = 0.0f; ///< Start angle of point cloud float end_angle = 360.0f; ///< End angle of point cloud SplitFrameMode split_frame_mode = - SplitFrameMode::SPLIT_BY_ANGLE; ///< 1: Split frames by cut_angle; - ///< 2: Split frames by fixed number of packets; - ///< 3: Split frames by custom number of packets (num_pkts_split) - uint32_t num_pkts_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 - float cut_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 - bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp + SplitFrameMode::SPLIT_BY_ANGLE; ///< 1: Split frames by split_angle; + ///< 2: Split frames by fixed number of blocks; + ///< 3: Split frames by custom number of blocks (num_blks_split) + float split_angle = 0.0f; ///< Split angle(degree) used to split frame, only be used when split_frame_mode=1 + uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 + bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp + bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points RSTransformParam transform_param; ///< Used to transform points - RSCameraTriggerParam trigger_param; ///< Used to trigger camera } RSDecoderParam; typedef struct RSInputParam ///< The LiDAR input parameter { - std::string device_ip = "192.168.1.200"; ///< Ip of LiDAR - std::string multi_cast_address = "0.0.0.0"; ///< Address of multicast - uint16_t msop_port = 6699; ///< Msop packet port number - uint16_t difop_port = 7788; ///< Difop packet port number - bool read_pcap = false; ///< true: The driver will process the pcap through pcap_path. false: The driver will - ///< Get data from online LiDAR - double pcap_rate = 1; ///< Rate to read the pcap file + uint16_t msop_port = 6699; ///< MSOP packet port number + uint16_t difop_port = 7788; ///< DIFOP packet port number + std::string host_address = "0.0.0.0"; ///< Address of host + std::string group_address = "0.0.0.0"; ///< Address of multicast group + std::string pcap_path = ""; ///< Absolute path of pcap file bool pcap_repeat = true; ///< true: The pcap bag will repeat play - std::string pcap_path = "null"; ///< Absolute path of pcap file - bool use_vlan = false; ///< Vlan on-off - bool use_someip = false; ///< Someip on-off + float pcap_rate = 1.0; ///< Rate to read the pcap file + bool use_vlan = false; ///< Vlan on-off + bool use_someip = false; ///< SOME/IP layer on-off } RSInputParam; typedef struct RSDriverParam ///< The LiDAR driver parameter { + LidarType lidar_type = LidarType::RS16; ///< Lidar type + InputType input_type = InputType::ONLINE_LIDAR; ///< Input type RSInputParam input_param; ///< Input parameter RSDecoderParam decoder_param; ///< Decoder parameter - std::string angle_path = "null"; ///< Path of angle calibration files(angle.csv).Only used for internal debugging. - std::string frame_id = "rslidar"; ///< The frame id of LiDAR message - LidarType lidar_type = LidarType::RS16; ///< Lidar type - bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet - bool saved_by_rows = false; ///< true: the output point cloud will be saved by rows (default is saved by columns) } RSDriverParam; ``` diff --git a/doc/intro/parameter_intro_en.md b/doc/intro/parameter_intro_en.md index a9a84fa3..5d370514 100644 --- a/doc/intro/parameter_intro_en.md +++ b/doc/intro/parameter_intro_en.md @@ -15,44 +15,42 @@ typedef struct RSTransformParam ///< The Point transform parameter typedef struct RSDecoderParam ///< LiDAR decoder parameter { - float max_distance = 200.0f; ///< Max distance of point cloud range + bool config_from_file = false;///< Internal use only for debugging + std::string angle_path = ""; ///< Internal use only for debugging + bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet float min_distance = 0.2f; ///< Minimum distance of point cloud range + float max_distance = 200.0f; ///< Max distance of point cloud range float start_angle = 0.0f; ///< Start angle of point cloud float end_angle = 360.0f; ///< End angle of point cloud SplitFrameMode split_frame_mode = - SplitFrameMode::SPLIT_BY_ANGLE; ///< 1: Split frames by cut_angle; - ///< 2: Split frames by fixed number of packets; - ///< 3: Split frames by custom number of packets (num_pkts_split) - uint32_t num_pkts_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 - float cut_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 - bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp + SplitFrameMode::SPLIT_BY_ANGLE; ///< 1: Split frames by split_angle; + ///< 2: Split frames by fixed number of blocks; + ///< 3: Split frames by custom number of blocks (num_blks_split) + float split_angle = 0.0f; ///< Split angle(degree) used to split frame, only be used when split_frame_mode=1 + uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 + bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp + bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points RSTransformParam transform_param; ///< Used to transform points - RSCameraTriggerParam trigger_param; ///< Used to trigger camera } RSDecoderParam; typedef struct RSInputParam ///< The LiDAR input parameter { - std::string device_ip = "192.168.1.200"; ///< Ip of LiDAR - std::string multi_cast_address = "0.0.0.0"; ///< Address of multicast - uint16_t msop_port = 6699; ///< Msop packet port number - uint16_t difop_port = 7788; ///< Difop packet port number - bool read_pcap = false; ///< true: The driver will process the pcap through pcap_path. false: The driver will - ///< Get data from online LiDAR - double pcap_rate = 1; ///< Rate to read the pcap file + uint16_t msop_port = 6699; ///< MSOP packet port number + uint16_t difop_port = 7788; ///< DIFOP packet port number + std::string host_address = "0.0.0.0"; ///< Address of host + std::string group_address = "0.0.0.0"; ///< Address of multicast group + std::string pcap_path = ""; ///< Absolute path of pcap file bool pcap_repeat = true; ///< true: The pcap bag will repeat play - std::string pcap_path = "null"; ///< Absolute path of pcap file - bool use_vlan = false; ///< Vlan on-off - bool use_someip = false; ///< Someip on-off + float pcap_rate = 1.0; ///< Rate to read the pcap file + bool use_vlan = false; ///< Vlan on-off + bool use_someip = false; ///< SOME/IP layer on-off } RSInputParam; typedef struct RSDriverParam ///< The LiDAR driver parameter { + LidarType lidar_type = LidarType::RS16; ///< Lidar type + InputType input_type = InputType::ONLINE_LIDAR; ///< Input type RSInputParam input_param; ///< Input parameter RSDecoderParam decoder_param; ///< Decoder parameter - std::string angle_path = "null"; ///< Path of angle calibration files(angle.csv).Only used for internal debugging. - std::string frame_id = "rslidar"; ///< The frame id of LiDAR message - LidarType lidar_type = LidarType::RS16; ///< Lidar type - bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet - bool saved_by_rows = false; ///< true: the output point cloud will be saved by rows (default is saved by columns) } RSDriverParam; ``` diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 83968e48..a4416199 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -190,18 +190,18 @@ typedef struct RSTransformParam ///< The Point transform parameter typedef struct RSDecoderParam ///< LiDAR decoder parameter { - bool config_from_file = false; - std::string angle_path = ""; ///< Path of angle calibration files(angle.csv). Only used for internal debugging. + bool config_from_file = false; ///< Internal use only for debugging + std::string angle_path = ""; ///< Internal use only for debugging bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet float min_distance = 0.2f; ///< Minimum distance of point cloud range float max_distance = 200.0f; ///< Max distance of point cloud range float start_angle = 0.0f; ///< Start angle of point cloud float end_angle = 360.0f; ///< End angle of point cloud SplitFrameMode split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; - ///< 1: Split frames by cut_angle; - ///< 2: Split frames by fixed number of packets; - ///< 3: Split frames by custom number of packets (num_pkts_split) - float split_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 + ///< 1: Split frames by split_angle; + ///< 2: Split frames by fixed number of blocks; + ///< 3: Split frames by custom number of blocks (num_blks_split) + float split_angle = 0.0f; ///< Split angle(degree) used to split frame, only be used when split_frame_mode=1 uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points From 46fa10a250742ef66397fd050a0c0854d78a15e7 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 19 Jan 2022 17:06:49 +0800 Subject: [PATCH 166/379] feat: support user layer --- demo/demo_online.cpp | 7 ++++--- demo/demo_pcap.cpp | 8 +++++--- src/rs_driver/driver/driver_param.h | 2 ++ src/rs_driver/driver/input/pcap_input.hpp | 3 +++ src/rs_driver/driver/input/sock_input.hpp | 2 ++ 5 files changed, 16 insertions(+), 6 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 4fcfd5fa..fc36d0f7 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -81,10 +81,11 @@ int main(int argc, char* argv[]) RS_TITLE << "------------------------------------------------------" << RS_REND; RSDriverParam param; ///< Create a parameter object - param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 - param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 + param.input_param.msop_port = 51212; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 51212; ///< Set the lidar difop port number, the default is 7788 + param.input_param.user_layer_bytes = 8; param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct - param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + param.wait_for_difop = false; ///< true: start sending point cloud until receive difop packet param.print(); LidarDriver driver; diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 9bd71788..6584a3bd 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -82,9 +82,11 @@ int main(int argc, char* argv[]) RSDriverParam param; ///< Create a parameter object param.input_param.read_pcap = true; ///< Set read_pcap to true - param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file directory - param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 - param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 + param.input_param.pcap_path = "/mnt/share/pcap/byd_cpn.pcap"; ///< Set the pcap file directory + param.input_param.msop_port = 51212; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 51212; ///< Set the lidar difop port number, the default is 7788 + param.input_param.user_layer_bytes = 8; + param.wait_for_difop = false; param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct param.print(); diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index 85e42004..d4a6324a 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -141,6 +141,7 @@ typedef struct RSInputParam ///< The LiDAR input parameter std::string pcap_path = "null"; ///< Absolute path of pcap file bool use_vlan = false; ///< Vlan on-off bool use_someip = false; ///< Someip on-off + uint16_t user_layer_bytes = 0; ///< Bytes of user layer. thers is no user layer if it is 0 void print() const { RS_INFO << "------------------------------------------------------" << RS_REND; @@ -154,6 +155,7 @@ typedef struct RSInputParam ///< The LiDAR input parameter RS_INFOL << "pcap_path: " << pcap_path << RS_REND; RS_INFOL << "use_vlan: " << use_vlan << RS_REND; RS_INFOL << "use_someip: " << use_someip << RS_REND; + RS_INFOL << "user_layer_bytes: " << user_layer_bytes << RS_REND; RS_INFO << "------------------------------------------------------" << RS_REND; } } RSInputParam; diff --git a/src/rs_driver/driver/input/pcap_input.hpp b/src/rs_driver/driver/input/pcap_input.hpp index 0a86882b..7ef4877a 100644 --- a/src/rs_driver/driver/input/pcap_input.hpp +++ b/src/rs_driver/driver/input/pcap_input.hpp @@ -46,9 +46,12 @@ class PcapInput : public Input { if (input_param.use_vlan) pcap_offset_ += VLAN_LEN; + if (input_param.use_someip) pcap_offset_ += SOME_IP_LEN; + pcap_offset_ += input_param.user_layer_bytes; + std::stringstream msop_stream, difop_stream; if (input_param_.use_vlan) { diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index 1652defb..2b4056a5 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -48,6 +48,8 @@ class SockInput : public Input { if (input_param.use_someip) sock_offset_ += SOME_IP_LEN; + + sock_offset_ += input_param.user_layer_bytes; } virtual bool init(); From e15266cc31848317fc2e0c520484c06342d19523 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 20 Jan 2022 14:27:48 +0800 Subject: [PATCH 167/379] fix: recover input pcap --- src/rs_driver/driver/input/input_factory.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 0d7cfeea..85fcd44d 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -33,7 +33,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include #include -// #include +#include namespace robosense { @@ -99,7 +99,7 @@ inline std::shared_ptr InputFactory::createInput(const RSDriverParam& dri if (input_param.read_pcap) { long long msec = msecToDelay(driver_param.lidar_type, input_param.pcap_rate); - // input = std::make_shared(input_param, excb, msec); + input = std::make_shared(input_param, excb, msec); } else { From e50aa35940c4af4b7dea11b113b0dcf47bfdeb67 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 24 Jan 2022 14:42:56 +0800 Subject: [PATCH 168/379] feat: support tail layer --- src/rs_driver/driver/driver_param.h | 1 + src/rs_driver/driver/input/pcap_input.hpp | 13 ++++++++----- src/rs_driver/driver/input/sock_input.hpp | 8 +++++--- 3 files changed, 14 insertions(+), 8 deletions(-) diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index d4a6324a..6db65de0 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -142,6 +142,7 @@ typedef struct RSInputParam ///< The LiDAR input parameter bool use_vlan = false; ///< Vlan on-off bool use_someip = false; ///< Someip on-off uint16_t user_layer_bytes = 0; ///< Bytes of user layer. thers is no user layer if it is 0 + uint16_t tail_layer_bytes = 0; ///< Bytes of tail layer. thers is no tail layer if it is 0 void print() const { RS_INFO << "------------------------------------------------------" << RS_REND; diff --git a/src/rs_driver/driver/input/pcap_input.hpp b/src/rs_driver/driver/input/pcap_input.hpp index 7ef4877a..491e52f0 100644 --- a/src/rs_driver/driver/input/pcap_input.hpp +++ b/src/rs_driver/driver/input/pcap_input.hpp @@ -42,7 +42,8 @@ class PcapInput : public Input { public: PcapInput(const RSInputParam& input_param, const std::function& excb, long long msec_to_delay) - : Input(input_param, excb), pcap_(NULL), pcap_offset_(ETH_HDR_LEN), difop_filter_valid_(false), msec_to_delay_(msec_to_delay) + : Input(input_param, excb), pcap_(NULL), pcap_offset_(ETH_HDR_LEN), pcap_tail_(0), difop_filter_valid_(false), + msec_to_delay_(msec_to_delay) { if (input_param.use_vlan) pcap_offset_ += VLAN_LEN; @@ -51,6 +52,7 @@ class PcapInput : public Input pcap_offset_ += SOME_IP_LEN; pcap_offset_ += input_param.user_layer_bytes; + pcap_tail_ += input_param.tail_layer_bytes; std::stringstream msop_stream, difop_stream; if (input_param_.use_vlan) @@ -76,6 +78,7 @@ class PcapInput : public Input private: pcap_t* pcap_; size_t pcap_offset_; + size_t pcap_tail_; std::string msop_filter_str_; std::string difop_filter_str_; bpf_program msop_filter_; @@ -166,15 +169,15 @@ inline void PcapInput::recvPacket() if (pcap_offline_filter(&msop_filter_, header, pkt_data) != 0) { std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); - memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_); - pkt->setData(0, header->len - pcap_offset_); + memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_ - pcap_tail_); + pkt->setData(0, header->len - pcap_offset_ - pcap_tail_); pushPacket(pkt); } else if (difop_filter_valid_ && (pcap_offline_filter(&difop_filter_, header, pkt_data) != 0)) { std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); - memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_); - pkt->setData(0, header->len - pcap_offset_); + memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_ - pcap_tail_); + pkt->setData(0, header->len - pcap_offset_ - pcap_tail_); pushPacket(pkt); } else diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index b49d1030..9fbbd409 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -45,12 +45,13 @@ class SockInput : public Input { public: SockInput(const RSInputParam& input_param, const std::function& excb) - : Input(input_param, excb), sock_offset_(0) + : Input(input_param, excb), sock_offset_(0), sock_tail_(0) { if (input_param.use_someip) sock_offset_ += SOME_IP_LEN; sock_offset_ += input_param.user_layer_bytes; + sock_tail_ += input_param.tail_layer_bytes; } virtual bool init(); @@ -65,6 +66,7 @@ class SockInput : public Input private: int fds_[2]; size_t sock_offset_; + size_t sock_tail_; }; inline void SockInput::higherThreadPrioty(std::thread::native_handle_type handle) @@ -255,7 +257,7 @@ inline void SockInput::recvPacket() break; } - pkt->setData(sock_offset_, ret - sock_offset_); + pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); pushPacket(pkt); } else if (FD_ISSET(fds_[1], &rfds)) @@ -266,7 +268,7 @@ inline void SockInput::recvPacket() if (ret <= 0) break; - pkt->setData(sock_offset_, ret - sock_offset_); + pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); pushPacket(pkt); } } From d6ce39921fb41c687cf988c908fb8fa5b8bd4a47 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 24 Jan 2022 20:50:52 +0800 Subject: [PATCH 169/379] fix: fix crach from illegal azimuth --- src/rs_driver/driver/decoder/block_diff.hpp | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index d1e51a88..410b0fa8 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -70,6 +70,12 @@ class SingleReturnBlockDiff azi += 36000; } + //process myself from illegal azimuth + if (azi > 100) + { + azi = 100; + } + return azi; } @@ -119,6 +125,12 @@ class DualReturnBlockDiff azi += 36000; } + //process myself from illegal azimuth + if (azi > 100) + { + azi = 100; + } + return azi; } @@ -170,6 +182,12 @@ class ABDualReturnBlockDiff azi += 36000; } + //process myself from illegal azimuth + if (azi > 100) + { + azi = 100; + } + return azi; } From a9ab22dcb06eccd4774603425a1eddb6f4fd609b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 25 Jan 2022 10:39:21 +0800 Subject: [PATCH 170/379] fix: fix crash due to illegal azimuth --- src/rs_driver/driver/decoder/block_diff.hpp | 18 ------------------ src/rs_driver/driver/decoder/decoder_RSBP.hpp | 2 +- src/rs_driver/driver/decoder/decoder_mech.hpp | 1 + src/rs_driver/driver/decoder/trigon.hpp | 6 +----- 4 files changed, 3 insertions(+), 24 deletions(-) diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index 410b0fa8..d1e51a88 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -70,12 +70,6 @@ class SingleReturnBlockDiff azi += 36000; } - //process myself from illegal azimuth - if (azi > 100) - { - azi = 100; - } - return azi; } @@ -125,12 +119,6 @@ class DualReturnBlockDiff azi += 36000; } - //process myself from illegal azimuth - if (azi > 100) - { - azi = 100; - } - return azi; } @@ -182,12 +170,6 @@ class ABDualReturnBlockDiff azi += 36000; } - //process myself from illegal azimuth - if (azi > 100) - { - azi = 100; - } - return azi; } diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 21b36878..65610715 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -260,7 +260,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) { - float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; this->transformPoint(x, y, z); diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index 97c46ac5..b1d916ed 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -200,6 +200,7 @@ inline void DecoderMech::decodeDifopCommon(const T_Difop& pkt) this->fov_blind_ts_diff_ = (float)fov_blind_range / ((float)RS_ONE_ROUND * (float)this->rps_); + // load angles if (!this->param_.config_from_file && !this->angles_ready_) { int ret = this->chan_angles_.loadFromDifop(pkt.vert_angle_cali, pkt.horiz_angle_cali, diff --git a/src/rs_driver/driver/decoder/trigon.hpp b/src/rs_driver/driver/decoder/trigon.hpp index c79b12bb..b63b3327 100644 --- a/src/rs_driver/driver/decoder/trigon.hpp +++ b/src/rs_driver/driver/decoder/trigon.hpp @@ -91,24 +91,20 @@ class Trigon float sin(int32_t angle) { -#ifdef DBG if (angle < MIN || angle >= MAX) { return 0.0f; } -#endif return sins_[angle]; } float cos(int32_t angle) { -#ifdef DBG if (angle < MIN || angle >= MAX) { - return 0.0f; + return 1.0f; } -#endif return coss_[angle]; } From e1ffc10744d619db957b8003eeb120f17c566691 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 25 Jan 2022 10:56:42 +0800 Subject: [PATCH 171/379] fix: fix crash from illegal azimuth --- src/rs_driver/driver/decoder/trigon.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/trigon.hpp b/src/rs_driver/driver/decoder/trigon.hpp index b63b3327..18274cc1 100644 --- a/src/rs_driver/driver/decoder/trigon.hpp +++ b/src/rs_driver/driver/decoder/trigon.hpp @@ -93,7 +93,7 @@ class Trigon { if (angle < MIN || angle >= MAX) { - return 0.0f; + angle = 0; } return sins_[angle]; @@ -103,7 +103,7 @@ class Trigon { if (angle < MIN || angle >= MAX) { - return 1.0f; + angle = 0; } return coss_[angle]; From 794223e3b3d25a838b2865fc279eaf9eddb6f34b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 11 Feb 2022 16:17:55 +0800 Subject: [PATCH 172/379] fix: fix compiling error on ubu20 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 99430fff..5dd171c2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -57,7 +57,7 @@ elseif(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") message(FATAL_ERROR "Unsupported compiler.") endif() - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++11") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++14") set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -g") set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3") endif() From 25a66539f76e45e6b39b1ce9097755b762fdd34b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 14 Feb 2022 11:31:37 +0800 Subject: [PATCH 173/379] fix: fix zero return from recvfrom --- src/rs_driver/driver/input/sock_input.hpp | 25 +++++++++++++++-------- 1 file changed, 16 insertions(+), 9 deletions(-) diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index 9fbbd409..a55f9eb8 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -251,25 +251,32 @@ inline void SockInput::recvPacket() std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); pkt->resetData(); ssize_t ret = recvfrom(fds_[0], pkt->data(), MAX_PKT_LEN, 0, NULL, NULL); - if (ret <= 0) + if (ret < 0) { - std::cout << "recv failed" << std::endl; + std::cout << "recv packet failed" << std::endl; break; } - - pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); - pushPacket(pkt); + else if (ret > 0) + { + pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); + pushPacket(pkt); + } } else if (FD_ISSET(fds_[1], &rfds)) { std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); pkt->resetData(); ssize_t ret = recvfrom(fds_[1], pkt->data(), MAX_PKT_LEN, 0, NULL, NULL); - if (ret <= 0) + if (ret < 0) + { + std::cout << "recv packet failed" << std::endl; break; - - pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); - pushPacket(pkt); + } + else if (ret > 0) + { + pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); + pushPacket(pkt); + } } } } From 15f41c9e99d9cd61eea7b0036ec7ebe284c292a5 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 18 Feb 2022 10:02:33 +0800 Subject: [PATCH 174/379] refac: format --- src/rs_driver/driver/input/input_sock.hpp | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/src/rs_driver/driver/input/input_sock.hpp b/src/rs_driver/driver/input/input_sock.hpp index 21a74a98..0375bbd3 100644 --- a/src/rs_driver/driver/input/input_sock.hpp +++ b/src/rs_driver/driver/input/input_sock.hpp @@ -167,19 +167,21 @@ inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, con goto failSocket; } + ret = setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &reuse, sizeof(reuse)); + if (ret < 0) + { + std::cerr << "setsockopt: " << std::strerror(errno) << std::endl; + goto failOption; + } + struct sockaddr_in host_addr; memset(&host_addr, 0, sizeof(host_addr)); host_addr.sin_family = AF_INET; host_addr.sin_port = htons(port); host_addr.sin_addr.s_addr = INADDR_ANY; if (hostIp != "0.0.0.0" && grpIp == "0.0.0.0") - inet_pton(AF_INET, hostIp.c_str(), &(host_addr.sin_addr)); - - ret = setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &reuse, sizeof(reuse)); - if (ret < 0) { - std::cerr << "setsockopt: " << std::strerror(errno) << std::endl; - goto failOption; + inet_pton(AF_INET, hostIp.c_str(), &(host_addr.sin_addr)); } ret = bind(fd, (struct sockaddr*)&host_addr, sizeof(host_addr)); From b0d9447879305416107af86934bedcbd3124de4d Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 18 Feb 2022 15:24:35 +0800 Subject: [PATCH 175/379] format: format --- src/rs_driver/driver/input/input_raw.hpp | 12 +----------- 1 file changed, 1 insertion(+), 11 deletions(-) diff --git a/src/rs_driver/driver/input/input_raw.hpp b/src/rs_driver/driver/input/input_raw.hpp index a02d8125..f7cd65bb 100644 --- a/src/rs_driver/driver/input/input_raw.hpp +++ b/src/rs_driver/driver/input/input_raw.hpp @@ -50,19 +50,9 @@ class InputRaw : public Input void feedPacket(const uint8_t* data, size_t size); InputRaw(const RSInputParam& input_param, const std::function& excb) - : Input(input_param, excb), pcap_offset_(ETH_HDR_LEN), difop_filter_valid_(false) + : Input(input_param, excb) { } - -private: - pcap_t* pcap_; - size_t pcap_offset_; - std::string msop_filter_str_; - std::string difop_filter_str_; - bpf_program msop_filter_; - bpf_program difop_filter_; - bool difop_filter_valid_; - long long msec_to_delay_; }; inline void InputRaw::feedPacket(const uint8_t* data, size_t size) From a673db1f3e799cf327d458f621e2f081085574c6 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 24 Feb 2022 14:56:04 +0800 Subject: [PATCH 176/379] feat: remove use_someip attribute --- src/rs_driver/driver/driver_param.hpp | 3 +-- src/rs_driver/driver/input/input_pcap.hpp | 5 ----- src/rs_driver/driver/input/input_sock.hpp | 5 ----- 3 files changed, 1 insertion(+), 12 deletions(-) diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 9c688ff6..7955c8b4 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -239,7 +239,6 @@ typedef struct RSInputParam ///< The LiDAR input parameter bool pcap_repeat = true; ///< true: The pcap bag will repeat play float pcap_rate = 1.0f; ///< Rate to read the pcap file bool use_vlan = false; ///< Vlan on-off - bool use_someip = false; ///< Someip on-off uint16_t user_layer_bytes = 0; ///< Bytes of user layer. thers is no user layer if it is 0 uint16_t tail_layer_bytes = 0; ///< Bytes of tail layer. thers is no tail layer if it is 0 @@ -255,8 +254,8 @@ typedef struct RSInputParam ///< The LiDAR input parameter RS_INFOL << "pcap_rate: " << pcap_rate << RS_REND; RS_INFOL << "pcap_repeat: " << pcap_repeat << RS_REND; RS_INFOL << "use_vlan: " << use_vlan << RS_REND; - RS_INFOL << "use_someip: " << use_someip << RS_REND; RS_INFOL << "user_layer_bytes: " << user_layer_bytes << RS_REND; + RS_INFOL << "tail_layer_bytes: " << tail_layer_bytes << RS_REND; RS_INFO << "------------------------------------------------------" << RS_REND; } diff --git a/src/rs_driver/driver/input/input_pcap.hpp b/src/rs_driver/driver/input/input_pcap.hpp index 4a27a048..2eaf9900 100644 --- a/src/rs_driver/driver/input/input_pcap.hpp +++ b/src/rs_driver/driver/input/input_pcap.hpp @@ -52,11 +52,6 @@ class InputPcap : public Input pcap_offset_ += VLAN_LEN; } - if (input_param.use_someip) - { - pcap_offset_ += SOME_IP_LEN; - } - pcap_offset_ += input_param.user_layer_bytes; pcap_tail_ += input_param.tail_layer_bytes; diff --git a/src/rs_driver/driver/input/input_sock.hpp b/src/rs_driver/driver/input/input_sock.hpp index f9487978..1a90174e 100644 --- a/src/rs_driver/driver/input/input_sock.hpp +++ b/src/rs_driver/driver/input/input_sock.hpp @@ -63,11 +63,6 @@ class InputSock : public Input InputSock(const RSInputParam& input_param, const std::function& excb) : Input(input_param, excb), sock_offset_(0), sock_tail_(0) { - if (input_param.use_someip) - { - sock_offset_ += SOME_IP_LEN; - } - sock_offset_ += input_param.user_layer_bytes; sock_tail_ += input_param.tail_layer_bytes; } From 142a91301cfc68f6a95d058d498c6e66b16eb3cd Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 25 Feb 2022 14:32:26 +0800 Subject: [PATCH 177/379] feat: add macro to disable pcap parse --- CMakeLists.txt | 6 ++++++ demo/CMakeLists.txt | 6 ++++++ src/rs_driver/driver/input/input_factory.hpp | 4 ++++ src/rs_driver/driver/input/pcap_input.hpp | 4 ++++ src/rs_driver/driver/input/sock_input.hpp | 6 ++++-- 5 files changed, 24 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5dd171c2..b5ebe9fa 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -17,6 +17,7 @@ option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) #============================= # Compile Features #============================= +option(ENABLE_PCAP_PARSE "Enable PCAP file parse" ON) option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) option(ENABLE_PUBLISH_RAW_MSG "Publish raw messages" OFF) option(ENABLE_PUBLISH_CAM_MSG "Publish camera trigger messages" OFF) @@ -108,6 +109,11 @@ endif(${ENABLE_TRANSFORM}) #======================== # Build Features #======================== + +if(${ENABLE_PCAP_PARSE}) + add_definitions("-DENABLE_PCAP_PARSE") +endif(${ENABLE_PCAP_PARSE}) + if(${ENABLE_HIGH_PRIORITY_THREAD}) add_definitions("-DENABLE_HIGH_PRIORITY_THREAD") endif(${ENABLE_HIGH_PRIORITY_THREAD}) diff --git a/demo/CMakeLists.txt b/demo/CMakeLists.txt index fa81d23a..abb51662 100644 --- a/demo/CMakeLists.txt +++ b/demo/CMakeLists.txt @@ -10,6 +10,7 @@ link_directories(${PCL_LIBRARY_DIRS}) add_definitions(${PCL_DEFINITIONS}) include_directories(${DRIVER_INCLUDE_DIRS}) + add_executable(demo_online demo_online.cpp ) @@ -17,6 +18,9 @@ target_link_libraries(demo_online pthread ${EXTERNAL_LIBS} ) + +if(${ENABLE_PCAP_PARSE}) + add_executable(demo_pcap demo_pcap.cpp ) @@ -25,4 +29,6 @@ target_link_libraries(demo_pcap ${EXTERNAL_LIBS} ) +endif(${ENABLE_PCAP_PARSE}) + diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 85fcd44d..1441e673 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -33,7 +33,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include #include +#ifdef ENABLE_PCAP_PARSE #include +#endif namespace robosense { @@ -96,12 +98,14 @@ inline std::shared_ptr InputFactory::createInput(const RSDriverParam& dri const RSInputParam& input_param = driver_param.input_param; std::shared_ptr input; +#ifdef ENABLE_PCAP_PARSE if (input_param.read_pcap) { long long msec = msecToDelay(driver_param.lidar_type, input_param.pcap_rate); input = std::make_shared(input_param, excb, msec); } else +#endif { input = std::make_shared(input_param, excb); } diff --git a/src/rs_driver/driver/input/pcap_input.hpp b/src/rs_driver/driver/input/pcap_input.hpp index 491e52f0..35237ec2 100644 --- a/src/rs_driver/driver/input/pcap_input.hpp +++ b/src/rs_driver/driver/input/pcap_input.hpp @@ -46,10 +46,14 @@ class PcapInput : public Input msec_to_delay_(msec_to_delay) { if (input_param.use_vlan) + { pcap_offset_ += VLAN_LEN; + } if (input_param.use_someip) + { pcap_offset_ += SOME_IP_LEN; + } pcap_offset_ += input_param.user_layer_bytes; pcap_tail_ += input_param.tail_layer_bytes; diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index a55f9eb8..a29b48d9 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -48,10 +48,12 @@ class SockInput : public Input : Input(input_param, excb), sock_offset_(0), sock_tail_(0) { if (input_param.use_someip) + { sock_offset_ += SOME_IP_LEN; + } - sock_offset_ += input_param.user_layer_bytes; - sock_tail_ += input_param.tail_layer_bytes; + sock_offset_ += input_param.user_layer_bytes; + sock_tail_ += input_param.tail_layer_bytes; } virtual bool init(); From f867bb696e205969b9d10c87f5c38a54c7967e1d Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 1 Mar 2022 08:59:42 +0800 Subject: [PATCH 178/379] format: format --- src/rs_driver/driver/decoder/block_diff.hpp | 4 +-- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 12 ++++---- src/rs_driver/driver/lidar_driver_impl.hpp | 28 +++++++++---------- 3 files changed, 23 insertions(+), 21 deletions(-) diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index d1e51a88..70cc43e8 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -41,7 +41,7 @@ class SingleReturnBlockDiff { public: - virtual float ts(uint16_t blk) + float ts(uint16_t blk) { float ret = 0.0f; if (blk > 0) @@ -52,7 +52,7 @@ class SingleReturnBlockDiff return ret; } - virtual int32_t azimuth(uint16_t blk) + int32_t azimuth(uint16_t blk) { int32_t azi= 0; diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 209c752b..90785d61 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -156,7 +156,7 @@ class DecoderRSM1 : public Decoder RSEchoMode getEchoMode(uint8_t mode); uint16_t max_seq_; - SplitStrategyBySeq split_; + SplitStrategyBySeq split_strategy_; }; template @@ -176,6 +176,7 @@ inline RSDecoderConstParam& DecoderRSM1::getConstParam() , 0.2f // distance min , 200.0f // distance max , 0.005f // distance resolution + , 80.0f // initial value of temperature }; return param; @@ -186,7 +187,7 @@ inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, const std::function& excb) : Decoder(getConstParam(), param, excb) , max_seq_(SINGLE_PKT_NUM) - , split_(&max_seq_) + , split_strategy_(&max_seq_) { this->height_ = this->const_param_.CHANNELS_PER_BLOCK; this->packet_duration_ = FRAME_DURATION / SINGLE_PKT_NUM; @@ -222,7 +223,7 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size const RSM1MsopPkt& pkt = *(RSM1MsopPkt*)packet; bool ret = false; - this->temperature_ = static_cast(pkt.header.temperature - 80); + this->temperature_ = static_cast(pkt.header.temperature - this->const_param_.TEMPERATURE_RES); double pkt_ts = 0; if (this->param_.use_lidar_clock) @@ -291,14 +292,15 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size this->prev_point_ts_ = point_time; } + this->prev_pkt_ts_ = pkt_ts; + uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); - if (split_.newPacket(pkt_seq)) + if (split_strategy_.newPacket(pkt_seq)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); ret = true; } - this->prev_pkt_ts_ = pkt_ts; return ret; } diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 4d3ad54f..7910982c 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -101,7 +101,7 @@ class LidarDriverImpl std::function cb_feed_pkt_; std::shared_ptr input_ptr_; - std::shared_ptr> lidar_decoder_ptr_; + std::shared_ptr> decoder_ptr_; SyncQueue> free_pkt_queue_; SyncQueue> msop_pkt_queue_; SyncQueue> difop_pkt_queue_; @@ -177,19 +177,19 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) // // decoder // - lidar_decoder_ptr_ = DecoderFactory::createDecoder( + decoder_ptr_ = DecoderFactory::createDecoder( param.lidar_type, param.decoder_param, std::bind(&LidarDriverImpl::runExceptionCallback, this, std::placeholders::_1)); // rewrite pkt timestamp or not ? - lidar_decoder_ptr_->enableWritePktTs((cb_put_pkt_ == nullptr) ? false : true); + decoder_ptr_->enableWritePktTs((cb_put_pkt_ == nullptr) ? false : true); // point cloud related - lidar_decoder_ptr_->point_cloud_ = getPointCloud(); - lidar_decoder_ptr_->setSplitCallback( + decoder_ptr_->point_cloud_ = getPointCloud(); + decoder_ptr_->setSplitCallback( std::bind(&LidarDriverImpl::splitFrame, this, std::placeholders::_1, std::placeholders::_2)); - double packet_duration = lidar_decoder_ptr_->getPacketDuration(); + double packet_duration = decoder_ptr_->getPacketDuration(); // // input @@ -214,7 +214,7 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) failInputInit: input_ptr_.reset(); - lidar_decoder_ptr_.reset(); + decoder_ptr_.reset(); return false; } @@ -270,9 +270,9 @@ inline void LidarDriverImpl::decodePacket(const Packet& pkt) template inline bool LidarDriverImpl::getTemperature(float& temp) { - if (lidar_decoder_ptr_ != nullptr) + if (decoder_ptr_ != nullptr) { - temp = lidar_decoder_ptr_->getTemperature(); + temp = decoder_ptr_->getTemperature(); return true; } return false; @@ -358,8 +358,8 @@ inline void LidarDriverImpl::processMsop() continue; } - bool pkt_to_split = lidar_decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); - runPacketCallBack(pkt, lidar_decoder_ptr_->prevPktTs(), false, pkt_to_split); // msop packet + bool pkt_to_split = decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); + runPacketCallBack(pkt, decoder_ptr_->prevPktTs(), false, pkt_to_split); // msop packet free_pkt_queue_.push(pkt); } @@ -376,7 +376,7 @@ inline void LidarDriverImpl::processDifop() continue; } - lidar_decoder_ptr_->processDifopPkt(pkt->data(), pkt->dataSize()); + decoder_ptr_->processDifopPkt(pkt->data(), pkt->dataSize()); runPacketCallBack(pkt, 0, true, false); // difop packet free_pkt_queue_.push(pkt); @@ -386,12 +386,12 @@ inline void LidarDriverImpl::processDifop() template void LidarDriverImpl::splitFrame(uint16_t height, double ts) { - std::shared_ptr pc = lidar_decoder_ptr_->point_cloud_; + std::shared_ptr pc = decoder_ptr_->point_cloud_; if (pc->points.size() > 0) { setPointCloudHeader(pc, height, ts); cb_put_pc_(pc); - lidar_decoder_ptr_->point_cloud_ = getPointCloud(); + decoder_ptr_->point_cloud_ = getPointCloud(); } else { From 54070782fb1bb8235495ba85be57e1a27d0c07ac Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 8 Mar 2022 18:45:47 +0800 Subject: [PATCH 179/379] fix: fix memory leaks --- src/rs_driver/msg/packet.h | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/rs_driver/msg/packet.h b/src/rs_driver/msg/packet.h index 01e92d49..ca713930 100644 --- a/src/rs_driver/msg/packet.h +++ b/src/rs_driver/msg/packet.h @@ -45,6 +45,14 @@ class Packet buf_ = (uint8_t*)malloc(cap); } + ~Packet() + { + if (buf_ != NULL) + { + free(buf_); + } + } + void setData(size_t off, size_t len) { off_ = off; From 4700786152535a8a14da944de8e53a0b80676834 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 9 Mar 2022 09:08:58 +0800 Subject: [PATCH 180/379] fix: limit size of difop queue --- src/rs_driver/driver/lidar_driver_impl.hpp | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index a79a1733..a5577360 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -387,8 +387,9 @@ inline void LidarDriverImpl::packetPut(std::shared_ptr pkt template inline void LidarDriverImpl::msopCallback(std::shared_ptr pkt) { - static const int PACKET_POOL_MAX = 1024; size_t sz = msop_pkt_queue_.push(pkt); + + static const int PACKET_POOL_MAX = 1024; if (sz > PACKET_POOL_MAX) { reportError(Error(ERRCODE_PKTBUFOVERFLOW)); @@ -399,7 +400,14 @@ inline void LidarDriverImpl::msopCallback(std::shared_ptr template inline void LidarDriverImpl::difopCallback(std::shared_ptr pkt) { - difop_pkt_queue_.push(pkt); + size_t sz = difop_pkt_queue_.push(pkt); + + static const int PACKET_POOL_MAX = 32; + if (sz > PACKET_POOL_MAX) + { + reportError(Error(ERRCODE_PKTBUFOVERFLOW)); + difop_pkt_queue_.clear(); + } } template From 7411607bb9b47c164d83661380ec549f6646d71c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 9 Mar 2022 09:09:18 +0800 Subject: [PATCH 181/379] feat: use default ports in demo app --- demo/demo_online.cpp | 5 ++--- demo/demo_pcap.cpp | 7 +++---- 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index fc36d0f7..5562204b 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -81,9 +81,8 @@ int main(int argc, char* argv[]) RS_TITLE << "------------------------------------------------------" << RS_REND; RSDriverParam param; ///< Create a parameter object - param.input_param.msop_port = 51212; ///< Set the lidar msop port number, the default is 6699 - param.input_param.difop_port = 51212; ///< Set the lidar difop port number, the default is 7788 - param.input_param.user_layer_bytes = 8; + param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct param.wait_for_difop = false; ///< true: start sending point cloud until receive difop packet param.print(); diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 6584a3bd..4ad22359 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -82,10 +82,9 @@ int main(int argc, char* argv[]) RSDriverParam param; ///< Create a parameter object param.input_param.read_pcap = true; ///< Set read_pcap to true - param.input_param.pcap_path = "/mnt/share/pcap/byd_cpn.pcap"; ///< Set the pcap file directory - param.input_param.msop_port = 51212; ///< Set the lidar msop port number, the default is 6699 - param.input_param.difop_port = 51212; ///< Set the lidar difop port number, the default is 7788 - param.input_param.user_layer_bytes = 8; + param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file directory + param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 param.wait_for_difop = false; param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct From c5297e264f89fd2275bc142da88a0a2110f6da08 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 9 Mar 2022 09:21:32 +0800 Subject: [PATCH 182/379] feat: update CHANGELOG.md --- CHANGELOG.md | 26 +++++++++++++++++++++----- 1 file changed, 21 insertions(+), 5 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 9accaadf..7e8605b8 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,14 +1,30 @@ # Changelog -## v1.4.0 - 2021-11-01 +## v1.4.5 - 2022-03-09 + +### Added +- Support dense attribute +- Support to bind to a specifed ip +- Limit max size of packet queue +- Apply SO_REUSEADDR option to the receiving socket +- Support user layer and tail layer +- add macro option to disable the PCAP function. ### Changed +- Join multicast group with code instead of shell script + +### Fixed +- Fix memory leaks problem +- Fix temperature calculation (for M1 only) + +## v1.4.0 - 2021-11-01 +### Changed Optimazation to decrease CPU uage, includes: -- replace point with point cloud as template parameter -- instead of alloc/free packet, use packet pool -- instead of alloc/free point cloud, always keep point cloud memory -- by default, use conditional macro to disable scan_msg/camera_trigger related code +- Replace point with point cloud as template parameter +- Instead of alloc/free packet, use packet pool +- Instead of alloc/free point cloud, always keep point cloud memory +- By default, use conditional macro to disable scan_msg/camera_trigger related code ## V1.3.1 ### Added From 811096b35ec9fd16fc59e3eec0b5a9409ad1252b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 10 Mar 2022 19:11:30 +0800 Subject: [PATCH 183/379] feat: update docs --- doc/howto/how_to_decode_online_lidar.md | 234 ++++++++++++++++++ doc/howto/how_to_decode_pcap_file.md | 215 ++++++++++++++++ doc/howto/how_to_decode_with_online_lidar.md | 193 --------------- doc/howto/how_to_decode_with_pcap_file.md | 194 --------------- doc/howto/how_to_use_multicast_group.md | 42 ---- doc/howto/online_lidar_advanced_topics.md | 193 +++++++++++++++ .../{install_pcl.PNG => 01_install_pcl.PNG} | Bin doc/img/11_rs_driver_queue_thread.png | Bin 0 -> 13016 bytes doc/img/12_broadcast.png | Bin 0 -> 11484 bytes doc/img/12_multi_lidars_ip.png | Bin 0 -> 23224 bytes doc/img/12_multi_lidars_port.png | Bin 0 -> 23361 bytes doc/img/12_multicast.png | Bin 0 -> 12267 bytes doc/img/12_unicast.png | Bin 0 -> 10593 bytes doc/img/12_user_layer.png | Bin 0 -> 10592 bytes doc/img/12_vlan.png | Bin 0 -> 15739 bytes doc/img/12_vlan_layer.png | Bin 0 -> 8219 bytes .../{viewer_menu.png => 13_viewer_menu.png} | Bin 17 files changed, 642 insertions(+), 429 deletions(-) create mode 100644 doc/howto/how_to_decode_online_lidar.md create mode 100644 doc/howto/how_to_decode_pcap_file.md delete mode 100644 doc/howto/how_to_decode_with_online_lidar.md delete mode 100644 doc/howto/how_to_decode_with_pcap_file.md delete mode 100644 doc/howto/how_to_use_multicast_group.md create mode 100644 doc/howto/online_lidar_advanced_topics.md rename doc/img/{install_pcl.PNG => 01_install_pcl.PNG} (100%) create mode 100644 doc/img/11_rs_driver_queue_thread.png create mode 100644 doc/img/12_broadcast.png create mode 100644 doc/img/12_multi_lidars_ip.png create mode 100644 doc/img/12_multi_lidars_port.png create mode 100644 doc/img/12_multicast.png create mode 100644 doc/img/12_unicast.png create mode 100644 doc/img/12_user_layer.png create mode 100644 doc/img/12_vlan.png create mode 100644 doc/img/12_vlan_layer.png rename doc/img/{viewer_menu.png => 13_viewer_menu.png} (100%) diff --git a/doc/howto/how_to_decode_online_lidar.md b/doc/howto/how_to_decode_online_lidar.md new file mode 100644 index 00000000..df6cd0c2 --- /dev/null +++ b/doc/howto/how_to_decode_online_lidar.md @@ -0,0 +1,234 @@ +# How to decode online Lidar + +## 1 Introduction + +This document illustrates how to decode the MSOP/DIFOP packets from an online Lidar with the driver's API. + +## 2 Design Consideration + +The driver is designed to achieve these objectives. ++ Parallel the construction and the process of point cloud. ++ Avoid to copy point cloud. ++ Avoid to malloc/free point cloud repeatly. + +Below is the supposed interaction between rs_driver and user's code. + +![](../img/11_rs_driver_queue_thread.png) + +rs_driver runs in its thread `construct_thread`. It ++ Gets free point cloud from user. User fetches it from a free cloud queue `free_point_cloud_queue`. ++ Parses packets and constructs point cloud. ++ Returns stuffed point cloud to user. ++ User's code is supposed to shift it to the queue `stuffed_point_cloud_queue`. + +User's code runs in its thread `process_thread`. It ++ Fetches stuffed point cloud from the queue `stuffed_point_cloud_queue` ++ Process the point cloud ++ Return the point cloud back to the queue `free_point_cloud_queue`. + +## 3 Steps + +Below is the steps to use the driver's API. + +### 3.1 Define Point Type + +Point is the base unit of Point Cloud. The driver supposes that it may have these member variables. +- x -- float type. The x coordinate of point. +- y -- float type. The y coordinate of point. +- z -- float type. The z coordinate of point. +- intensity -- uint8_t type. The intensity of point. +- timestamp -- double type. The timestamp of point. It may generated by the Lidar or on the host machine. +- ring -- The ring ID of the point, which represents the row number. e.g. For RS80, the range of ring ID is 0~79 (from bottom to top). + +Below are some examples: + +- The point type contains **x, y, z, intensity** + + ```c++ + struct PointXYZI + { + float x; + float y; + float z; + uint8_t intensity; + ... + }; + ``` + +- If using PCL, a simple way is to use **pcl::PointXYZI**. + +- The point type contains **x, y, z, intensity, timestamp, ring** + + ```c++ + struct PointXYZIRT + { + float x; + float y; + float z; + uint8_t intensity; + double timestamp; + uint16_t ring; + ... + }; + ``` + +Here user may add new member variables, remove member variables, or change the order of them, but should not change names or types of them, otherwise the behaviors might be unexpected. + +### 3.2 Define Point Cloud Type + + The driver allows user to change the point cloud type, as long as it is compatible to the definition below. + + ```c++ + template + class PointCloudT + { + public: + typedef T_Point PointT; + typedef std::vector VectorT; + + uint32_t height = 0; ///< Height of point cloud + uint32_t width = 0; ///< Width of point cloud + bool is_dense = false; ///< If is_dense is true, the point cloud does not contain NAN points + double timestamp = 0.0; ///< Timestamp of point cloud + uint32_t seq = 0; ///< Sequence number of message + + VectorT points; + }; + + typedef PointXYZI PointT; + typedef PointCloudT PointCloudMsg; + ``` + + Here user may add new members, and change the order of these members, but should not change or remove them. + +### 3.3 Define the driver object + +Define a driver object. + +```c++ +int main() +{ + LidarDriver driver; ///< Declare the driver object + ... +} +``` + +### 3.4 Configure the driver parameter + +Define a RSDriverParam variable and configure it. ++ `InputType::ONLINE_LIDAR` means that the driver get packets from a online Lidar. ++ `LidarType::RS16` means a RS16 Lidar. ++ Also set the local MSOP/DIFOP ports. Please use a 3rd party tool, such as Wireshark, to get them. + +```c++ +int main() +{ + ... + RSDriverParam param; ///< Create a parameter object + param.input_type = InputType::ONLINE_LIDAR; /// get packet from online lidar + param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 + param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct + ... +} +``` + +### 3.5 Define and register Point Cloud callbacks + +As said above, user is supposed to provide free point cloud to the driver. + +```c++ +std::shared_ptr pointCloudGetCallback(void) +{ + return std::make_shared(); +} +``` + +Also user is supposed to accept stuffed point cloud from the driver. + +```c++ +void pointCloudPutCallback(std::shared_ptr msg) +{ + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; +} +``` + +Note: ++ For simplicity, `free_point_cloud_queue`/`stuffed_point_cloud_queue` are not implemented here. This is NOT suggested. ++ The driver calls these two callback functions in its `contruct_thread`, so **don't do any time-consuming task** in them. + +Register them to the driver. + +```c++ +int main() +{ + ... + driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback functions + ... +} +``` + +### 3.6 Define and register exception callbacks + +When an error happens, the driver will inform user. User is supposed to get it via a callback function. + +```c++ +void exceptionCallback(const Error &code) +{ + RS_WARNING << "Error code : " << code.toString() << RS_REND; +} +``` + +Once again, **don't do any time-consuming task** in it. + +Register the callback. + +```c++ +int main() +{ + ... +driver.regExceptionCallback(exceptionCallback); /// + class PointCloudT + { + public: + typedef T_Point PointT; + typedef std::vector VectorT; + + uint32_t height = 0; ///< Height of point cloud + uint32_t width = 0; ///< Width of point cloud + bool is_dense = false; ///< If is_dense is true, the point cloud does not contain NAN points + double timestamp = 0.0; ///< Timestamp of point cloud + uint32_t seq = 0; ///< Sequence number of message + + VectorT points; + }; + + typedef PointXYZI PointT; + typedef PointCloudT PointCloudMsg; + ``` + + Here user may add new members, and change the order of these members, but should not change or remove them. + +### 2.3 Define the driver object + +Define a driver object. + +```c++ +int main() +{ + LidarDriver driver; ///< Declare the driver object + ... +} +``` + +### 2.4 Configure the driver parameter + +Define a RSDriverParam variable and configure it. ++ `InputType::PCAP_FILE` means that the driver get packets from a PCAP file, which is `/home/robosense/lidar.pcap`. ++ `LidarType::RS16` means a RS16 Lidar. ++ Also set the local MSOP/DIFOP ports. Please use a 3rd party tool, such as Wireshark, to get them. + +```c++ +int main() +{ + ... + RSDriverParam param; ///< Create a parameter object + param.input_type = InputType::PCAP_FILE; /// get packet from the pcap file + param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file path + param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 + param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct + ... +} +``` + +### 2.5 Define and register Point Cloud callbacks + +User is supposed to provide free point cloud to the driver. + +```c++ +std::shared_ptr pointCloudGetCallback(void) +{ + return std::make_shared(); +} +``` + +Also user is supposed to accept stuffed point cloud from the driver. + +```c++ +void pointCloudPutCallback(std::shared_ptr msg) +{ + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; +} +``` + +Note: The driver parses packet and constructs point cloud in its own thread. It also calls these two callback functions in this thread , so **don't do any time-consuming task** in them. + +Register the callbacks to the driver. + +```c++ +int main() +{ + ... + driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback functions + ... +} +``` + +### 2.6 Define and register exception callbacks + +When an error happens, the driver will inform user. User is supposed to accept it. + +```c++ +void exceptionCallback(const Error &code) +{ + RS_WARNING << "Error code : " << code.toString() << RS_REND; +} +``` + +Once again, **don't do any time-consuming task** in it. + +Register the callback. + +```c++ +int main() +{ + ... + driver.regExceptionCallback(exceptionCallback); /// - class PointCloudT - { - public: - typedef T_Point PointT; - typedef std::vector VectorT; - - uint32_t height = 0; ///< Height of point cloud - uint32_t width = 0; ///< Width of point cloud - bool is_dense = false; ///< If is_dense is true, the point cloud does not contain NAN points, - double timestamp = 0.0; - uint32_t seq = 0; ///< Sequence number of message - - VectorT points; - }; - - typedef PointXYZI PointT; - typedef PointCloudT PointCloudMsg; - - ``` - - User may add new members to PointCloudT, change the order of its members, but should not remove member variables. - - The template argument of PointCloudT is the point type, which is defined in the section 2.1. - -### 2.3 Define point cloud callback functions - -The user is supposed to managed point cloud pools. The driver gets free point cloud from user, and returns prepared point clouds to user. - -User provides two callback functions. The driver call one of them to get a free point cloud, before constructing it. - -```c++ -std::shared_ptr pointCloudGetCallback(void) -{ - return std::make_shared(); -} -``` - -The driver call the other to return the prepared point cloud. - -```c++ -void pointCloudPutCallback(std::shared_ptr msg) -{ - RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; -} -``` - -Note: - -+ Above examples always allocates a new point cloud instance for simplicity. This is not suggested, especially if the efficiency is sensitive. - -+ The callback functions run in the main handling loop of the driver, so **Do not add any time-consuming operations in the callback functions**. - -### 2.4 Define exception callback functions - -When an error is reported, the driver will inform user. User should provide an exception callback function. - -Once again, **Do not add any time-consuming operations in the callback functions**. - -```c++ -void exceptionCallback(const Error &code) -{ - RS_WARNING << "Error code : " << code.toString() << RS_REND; -} -``` - -### 2.5 Instantiate the driver object - -Instantiate a driver object. - -```c++ -LidarDriver driver; ///< Declare the driver object -``` - -### 2.6 Configure the parameter - -Define a parameter object and configure it. - -To decode pcap bag, please set the ```input_type``` to ```InputType::ONLINE_LIDAR```. - -Read the pcap file with a 3rd party tool, such as Wireshark, to get the MSOP/DIFOP ports. Also give the correct lidar type. - -```c++ -RSDriverParam param; ///< Create a parameter object -param.input_type = InputType::ONLINE_LIDAR; /// get packet from online lidar -param.input_param.pcap_path = "/home/robosense/rs16.pcap"; ///< Set the pcap file path -param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 -param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 -param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct -``` - -### 2.7 Register callback functions - -Register above callback functions. - -Please **register the callback functions before call the init() function**, because errors may occur during the initialization. - -```c++ -driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback functions -driver.regExceptionCallback(exceptionCallback); ///at(i) , the next point on the same ring will be msg.point_cloud_ptr->at(i+msg.height). - -## 4 Congratulations - -**You have finished the demo tutorial of the RoboSense LiDAR driver! Please find the complete demo code in the project directory. Feel free to contact us if you have any questions.** - -### *Congratulations! You have finished the demo tutorial of RoboSense LiDAR driver! You can find the complete demo code in the demo folder under the project directory. Feel free to connect us if you have any question about the driver.* diff --git a/doc/howto/how_to_decode_with_pcap_file.md b/doc/howto/how_to_decode_with_pcap_file.md deleted file mode 100644 index 3d4963fb..00000000 --- a/doc/howto/how_to_decode_with_pcap_file.md +++ /dev/null @@ -1,194 +0,0 @@ -# How to use driver with a pcap file - -## 1 Introduction - -The pcap file is captured with some 3rd party tools, such as Wireshark/tcpdump. - -This document illustrates how to decode it with the driver's API. - -## 2 Steps - -### 2.1 Define Point - -Now the driver will automatically assign values these member variables. - -- x ------ float type. The x coordinate of point. -- y ------ float type. The y coordinate of point. -- z ------ float type. The z coordinate of point. -- intensity ------ uint8_t type. The intensity of point. -- timestamp ------ double type. The timestamp of point. If ```use_lidar_clock``` is ```true```, lidar clock time in MSOP packet is used, otherwise regenerate the timestamp on host. -- ring ------ The ring ID of the point, which represents the row number. e.g. For RS80, the range of ring ID is 0~79 (from bottom to top). - -Below are some examples: - -- The point type contains **x, y, z, intensity** - - ```c++ - struct PointXYZI ///< user defined point type - { - float x; - float y; - float z; - uint8_t intensity; - ... - }; - ``` - - Or you can use **pcl::PointXYZI** directly - -- The point type contains **x, y, z, intensity, timestamp, ring** - - ```c++ - struct PointXYZIRT ///< user defined point type - { - float x; - float y; - float z; - uint8_t intensity; - double timestamp; - uint16_t ring; - ... - }; - ``` - -User may add new member variables, remove member variables, or change the order of them, but should not change names or types of them -- **x, y, z, intensity, timestamp, ring**, otherwise the behaviors might be unexpected. - -### 2.2 Define Point Cloud - - The driver keep a point cloud instance internally, and accumulates points into it. When a frame of point cloud is ready, it informs the caller. - - The point cloud is like below: - - ```c++ - template - class PointCloudT - { - public: - typedef T_Point PointT; - typedef std::vector VectorT; - - uint32_t height = 0; ///< Height of point cloud - uint32_t width = 0; ///< Width of point cloud - bool is_dense = false; ///< If is_dense is true, the point cloud does not contain NAN points, - double timestamp = 0.0; - uint32_t seq = 0; ///< Sequence number of message - - VectorT points; - }; - - typedef PointXYZI PointT; - typedef PointCloudT PointCloudMsg; - - ``` - - User may add new members to PointCloudT, change the order of its members, but should not remove member variables. - - The template argument of PointCloudT is the point type, which is defined in the section 2.1. - -### 2.3 Define point cloud callback functions - -The user is supposed to managed point cloud pools. The driver gets free point cloud from user, and returns prepared point clouds to user. - -User provides two callback functions. The driver call one of them to get a free point cloud, before constructing it. - -```c++ -std::shared_ptr pointCloudGetCallback(void) -{ - return std::make_shared(); -} -``` - -The driver call the other to return the prepared point cloud. - -```c++ -void pointCloudPutCallback(std::shared_ptr msg) -{ - RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; -} -``` - -Note: - -+ Above examples always allocates a new point cloud instance for simplicity. This is not suggested, especially if the efficiency is sensitive. - -+ The callback functions run in the main handling loop of the driver, so **Do not add any time-consuming operations in the callback functions**. - -### 2.4 Define exception callback functions - -When an error is reported, the driver will inform user. User should provide an exception callback function. - -Once again, **Do not add any time-consuming operations in the callback functions**. - -```c++ -void exceptionCallback(const Error &code) -{ - RS_WARNING << "Error code : " << code.toString() << RS_REND; -} -``` - -### 2.5 Instantiate the driver object - -Instantiate a driver object. - -```c++ -LidarDriver driver; ///< Declare the driver object -``` - -### 2.6 Configure the parameter - -Define a parameter object and configure it. - -To decode pcap bag, please set the ```input_type``` to ```InputType::PCAP_FILE```, and give the correct pcap file path. - -Read the pcap file with a 3rd party tool, such as Wireshark, to get the MSOP/DIFOP ports. Also give the correct lidar type. - -```c++ -RSDriverParam param; ///< Create a parameter object -param.input_type = InputType::PCAP_FILE; /// get packet from the pcap file -param.input_param.pcap_path = "/home/robosense/rs16.pcap"; ///< Set the pcap file path -param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 -param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 -param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct -``` - -### 2.7 Register callback functions - -Register above callback functions. - -Please **register the callback functions before call the init() function**, because errors may occur during the initialization. - -```c++ -driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback functions -driver.regExceptionCallback(exceptionCallback); ///at(i) , the next point on the same ring will be msg.point_cloud_ptr->at(i+msg.height). - -## 4 Congratulations - -**You have finished the demo tutorial of the RoboSense LiDAR driver! Please find the complete demo code in the project directory. Feel free to contact us if you have any questions.** - diff --git a/doc/howto/how_to_use_multicast_group.md b/doc/howto/how_to_use_multicast_group.md deleted file mode 100644 index c8e35273..00000000 --- a/doc/howto/how_to_use_multicast_group.md +++ /dev/null @@ -1,42 +0,0 @@ -# How to use multicast group - -## 1 Introduction - -This document illustrates how to receive point cloud in the multicast group mode. This is only for the Linux platform. - -## 2 Steps - -Suppose the multicast group address is ```224.1.1.1```, and the host addres is ```192.168.1.102```. - -The Lidar sends packets to the multicat group address. The NIC with the host address should be on the same network with the Lidar. - -The driver will make the NIC join to the multicast group address, and then get the packets from it. - -### 2.1 Set up parameters - -Set the parameter ```group_address``` and ```host_address```. - -```c++ -RSDriverParam param; ///< Create a parameter object -param.input_type = InputType::ONLINE_LIDAR; ///< get packet from online lidar -param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 -param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 -param.input_param.host_address = "192.168.1.102"; ///< Set the host address. -param.input_param.group_address = "224.1.1.1"; ///< Set the multicast group address. -param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct -``` - -### 2.4 Run - -Run the demo program. - - - - - - - - - - - diff --git a/doc/howto/online_lidar_advanced_topics.md b/doc/howto/online_lidar_advanced_topics.md new file mode 100644 index 00000000..2b776493 --- /dev/null +++ b/doc/howto/online_lidar_advanced_topics.md @@ -0,0 +1,193 @@ +# Online Lidar - Adavanced Topics + +## 1 Introduction + + The RoboSense Lidars may work in unicast/multicast/broadcast mode, with VLAN layer and with user layers. + +This document illustrates how to configure the driver in each case. + +Before reading this document, please be sure that you have read [Decode online Lidar](./how_to_decode_online_lidar.md). + +## 2 Unicast, Multicast and Broadcast + +### 2.1 Broadcast mode + +The simplest way is broadcast mode. + +The Lidar sends MSOP/DIFOP packets to the host machine (The driver runs on it). For simplicity, the DIFOP port is ommited here. ++ The Lidar sends to `255.255.255.255` : `6699`, and the host binds to port `6699`. + +![](../img/12_broadcast.png) + +Below is how to configure RSDriverParam variable. + +```c++ +RSDriverParam param; ///< Create a parameter object +param.input_type = InputType::ONLINE_LIDAR; ///< get packet from online lidar +param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 +param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 +param.lidar_type = LidarType::RS32; ///< Set the lidar type. +``` + +### 2.2 Unicast mode + +To reduce the network load, the Lidar is suggested to work in unicast mode. ++ The Lidar sends to `192.168.1.102` : `6699`, and the host binds to port `6699`. + +![](../img/12_unicast.png) + +Below is how to configure the RSDriverParam variable. In fact, it is same with the broadcast case. + +```c++ +RSDriverParam param; ///< Create a parameter object +param.input_type = InputType::ONLINE_LIDAR; ///< get packet from online lidar +param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 +param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 +param.lidar_type = LidarType::RS32; ///< Set the lidar type. +``` + + +### 2.3 Multicast mode + +The Lidar may also works in multicast mode. ++ The lidar sends to `224.1.1.1`:`6699` ++ The host binds to port 6699. And it makes local NIC (Network Interface Card) join the multicast group `224.1.1.1`. The local NIC's IP is `192.168.1.102`. + +![](../img/12_multicast.png) + +Below is how to configure the RSDriverParam variable. + +```c++ +RSDriverParam param; ///< Create a parameter object +param.input_type = InputType::ONLINE_LIDAR; ///< get packet from online lidar +param.input_param.group_address = "224.1.1.1"; ///< Set the multicast group address. +param.input_param.host_address = "192.168.1.102"; ///< Set the host address. +param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 +param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 +param.lidar_type = LidarType::RS32; ///< Set the lidar type. Make sure this type is correct +``` + +## 3 Multiple Lidars + +### 3.1 Different remote ports + +If you have two Lidars, it is suggested to set different remote ports. ++ First Lidar sends to `192.168.1.102`:`6699`, and the first driver instance binds to `6699`. ++ Second Lidar sends to `192.168.1.102`:`5599`, and the second driver instance binds to `5599`. + +![](../img/12_multi_lidars_port.png) + +Below is how to configure the RSDriverParam variables. + +```c++ +RSDriverParam param1; ///< Create a parameter object for Lidar 192.168.1.200 +param1.input_type = InputType::ONLINE_LIDAR; ///< get packet from online lidar +param1.input_param.msop_port = 6699; ///< Set the lidar msop port number +param1.input_param.difop_port = 7788; ///< Set the lidar difop port number +param1.lidar_type = LidarType::RS32; ///< Set the lidar type. + +RSDriverParam param2; ///< Create a parameter object for Lidar 192.168.1.201 +param2.input_type = InputType::ONLINE_LIDAR; ///< get packet from online lidar +param2.input_param.msop_port = 5599; ///< Set the lidar msop port number +param2.input_param.difop_port = 6688; ///< Set the lidar difop port number +param2.lidar_type = LidarType::RS32; ///< Set the lidar type. +``` + +### 3.2 Different remote IPs + +An alternate way is to set different remote IPs. ++ The host has two NICs: `192.168.1.102` and `192.168.1.103`. ++ First Lidar sends to `192.168.1.102`:`6699`, and the first driver instance binds to `192.168.1.102:6699`. ++ Second Lidar sends to `192.168.1.103`:`6699`, and the second driver instance binds to `192.168.1.103:6699`. + +![](../img/12_multi_lidars_ip.png) + +Below is how to configure the RSDriverParam variables. + +```c++ +RSDriverParam param1; ///< Create a parameter object for Lidar 192.168.1.200 +param1.input_type = InputType::ONLINE_LIDAR; ///< get packet from online lidar +param1.input_param.host_address = "192.168.1.102"; ///< Set the host address. +param1.input_param.msop_port = 6699; ///< Set the lidar msop port number +param1.input_param.difop_port = 7788; ///< Set the lidar difop port number +param1.lidar_type = LidarType::RS32; ///< Set the lidar type. + +RSDriverParam param2; ///< Create a parameter object for Lidar 192.168.1.201 +param2.input_type = InputType::ONLINE_LIDAR; ///< get packet from online lidar +param2.input_param.host_address = "192.168.1.103"; ///< Set the host address. +param2.input_param.msop_port = 6699; ///< Set the lidar msop port number +param2.input_param.difop_port = 7788; ///< Set the lidar difop port number +param2.lidar_type = LidarType::RS32; ///< Set the lidar type. +``` + +## 4 VLAN + +In some user cases, The Lidar may work on VLAN. Its packets have a VLAN layer. + +![](../img/12_vlan_layer.png) + +The driver cannot parse this packet. Instead, it depends on a virtual NIC to strip the VLAN layer. + +Below is an example. ++ The Lidar works on VLAN `80`. It sends packets to `192.168.1.102` : `6699`. The packet has a VLAN layer. ++ Suppose there is a physical NIC `eno1` on the host. It receives packets with VLAN layer. + +![](../img/12_vlan.png) + +To strip the VLAN layer, create a virtual NIC `eno1.80` on `eno1`, and assign IP `192.168.1.102` to it. + +``` +sudo apt-get install vlan -y +sudo modprobe 8021q + +sudo vconfig add eno1 80 +sudo ifconfig eno1.80 192.168.1.102 up +``` + +Now the driver may take `eno1.80` as a general NIC, and receives packets without VLAN layer. + +```c++ +RSDriverParam param; ///< Create a parameter object +param.input_type = InputType::ONLINE_LIDAR; ///< get packet from online lidar +param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 +param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 +param.lidar_type = LidarType::RS32; ///< Set the lidar type. +``` + +## 5 User Layer, Tail Layer + +In some user cases, User may add extra layers before or after the MSOP/DIFOP packet. ++ USER_LAYER is before the packet and TAIL_LAYER is after it. + +![](../img/12_user_layer.png) + +These extra layers are parts of UDP data. The driver can strip them. + +To strip them, just give their lengths in bytes. + +In the following example, USER_LAYER is 8 bytes, and TAIL_LAYER is 4 bytes. + +```c++ +RSDriverParam param; ///< Create a parameter object +param.input_type = InputType::ONLINE_LIDAR; ///< get packet from online lidar +param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 +param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 +param.input_param.user_layer_bytes = 8; ///< user layer bytes. there is no user layer if it is 0 +param.input_param.tail_layer_bytes = 4; ///< tail layer bytes. there is no user layer if it is 0 +param.lidar_type = LidarType::RS32; ///< Set the lidar type. +``` + + + + + + + + + + + + + + + diff --git a/doc/img/install_pcl.PNG b/doc/img/01_install_pcl.PNG similarity index 100% rename from doc/img/install_pcl.PNG rename to doc/img/01_install_pcl.PNG diff --git a/doc/img/11_rs_driver_queue_thread.png b/doc/img/11_rs_driver_queue_thread.png new file mode 100644 index 0000000000000000000000000000000000000000..feb3eaf21f9d07fc65063bc75a98689beb3be9da GIT binary patch literal 13016 zcmcJ$1yEeivo=g1K@ucbaCd^c6I_D@4er6+VF@9y5Zqbxhr7Ew8$7ry?(Vj*z_cvONweU92K1?ax)o zGgfysJTz2P#X7GJ?U{E5?-tam#PQoHf8j~sy_R|Z=75@V<@+ZDDt8>)B`dGMK-!-7 zo^@#XpDukwV`40JM?q&9nV_drkRUfQuy5m&w6ruW%3v<$-v>v3MMC(kpOp@snwoku z83!2~8{0(*EjTPJthwN)1iWooqn8ri=E!9F9^TfJ$N_H()BhiL<06nQ$jr|A`hHds zthys`>h=h~HzIzT*|Gv{e5) zFZ?g$tU&aGCWhf9@&j3jdRH`!8Pg zU#;ZSQH2bxakJlmyTk-R+zLFG5~oTJ(QLAxwOv z2Fnjj>=>uRWF6Ti3hjBtNUdoetY>S2X|qF)!-C^3-a0IM$8VaW+vN>=^e4@sth^LQ zcr8PWrtg{9NQG^lcKl&7{ebY7^N$K2T z0eTI(-hPe8NEvta-g`B^W1U3JPb3PI$k&ypwR%Q@HA57K3qk&%rL0#-{)+-W{5_eU zVPZ~n3anY%apXyyg`{Rr%X+X@;a6veqG6q7?{cz;X196RKSIO+nVkeL+BW4cR`^AV z{5ccVK{Hjc&m{dW&#HhlUSJf^;hsNgcf2#|f)`Ps8geXvVBe-EWW!G-s#J4OX4$WI zIB9pk!gJAtQ@5^vOMBAuuxi)uJO2-)52@s6hcW&>VTkThI}%;l)f75WYx2GbeO#tc)klw5^-r{3Tl&;u zW%v!}Fsi39Mz8Pj(kPN*tku0caGp?BL?{KIc+k%Ka2KiI&Lk7!us#k#YUAOsh0KN#OxgV+Iedi|qrPR`z5#h~d zxHQ_1MR4KuRaWo_^Mf)hG=PuN<0Hii?@uQ--h9K6OMAi>zM~33p1|A7D$E^_3wL-; z5KYld^S7%lg3Hdx=?Mi|iju!JP_0&?AWS{1x+ytgJXDd=Ka&K0J5f17jkT) zDdLxLEb}G1JM~%A`m3E!;CVgYa&a#*(6Q^PD3uC8KUMNT_<=X~DD@w6y602;vE|RI zTuXdOdL=ZVhb4L2w13=I-0V;IKw1;^1x0eVLbhBc$7Semc_lU9j-<1h$PGVTm+D}N z$2iQ`&x0BZGMs8W`YZ~w$cOV6vDCrne|Q6AZEs!KHi@uzYI!S23OVP!#i!-4=$Bug zNMY7hPGtFi%w}>(h~N{S6h9kje#nr%497u^+Z@G{+=&fzB$OBN{*L zM)HHc?@b^T9CtJFA~ZEEgsZ74qx&{*h_;YyLoz8^b12mky;vf3M?ZQHLdBs^Hi&?T z#ND|q;(vZ2PdD(kxefeEUdT1fZNmZ0%k6_wq#OA}&FgsrBAl&g=Mq-}uJm!u2IL(2 zd9+VPBgRJKGU-6Nz4!V?;tX;Ax$s>>m)qpG>sg-8Cxo3+FN@7yaB=(z_}iiB{8dIR z#a=&}@K2&1z>lpW#V<9v46B~v?W*J(`DCSpJuYI=TSNHYwAk3Y02qWAo}_~Ab$)MN zs~_G|MK4l{0AKe()?`HRSyJP16^55HeokjJz0^hS4bf!ONL6DWGi(YZNwEkf@u!L! zRDyT*Ts)CKUbRNbznVU!*Z85k6lrEM%+Stt;pa&%(EaQ%0(Bflye-@jnP56%+f`2O ze-QP%-x|?L#a@f)tYFdoijm_5v!GYjAL$ge13g`~9iNFM-dbM1FRpo;6V#?F6d=|G zYX@zqoKjTR6ZL#geBnF|rU(~o&hDBE==&v}P|3E(ob`|VAxhzX(%q1$XywxK5pnVml~^3igjm?~cmY;<9Z{g) z+!4?RtJGGE4Jq^DD3?pf#q6sfu{Guws5Yv_{nO05VTrz89cNYXDT?prVgzPmQYjsw zufKI4z~^QaFp^f`LRi{RXlcP%AnKZ$67aLofj@$QVd@C_p3fgfRHib&_uOQh8{9?2 zqGdDPAq4)QYC7J#)~x&DVia(|$Lxc!Ape<7Njg3Bo}>ej z42lv+R*OBw9RL0JDQ8!)zPUh<$*z#wZ~V?42Km%5M^?OXLo5w$ zk}XhL+~-`@e|l7M=pJXvV~haH3>?Hu0TX6NUF>l@*dZRmqsL4+d@=FGU?bIQdF zU4v4eXgD6V-XzGW1KFslHP#b3EG+9btMy!Hjei^ZBoMg`l%^utnP8R%$?1M!*%;$U zu2idb`4zTIJMQm{GS>&;)NSX`ZJ!QI1a)wF`vw8|W!WhrcYbiDyc^utM@w*`i`)t3 zOnTRAa?5gfPWO%ueZDVQc4_D-KXVyNIN2b}9I3J zDU4}{1OFK){+_Nabd~Vdbcm#D7fe34N|hpE3}=*7Bz*g6X-IcUWibB!krbVL)qD0V zRA&ovUOq1)+=lltZ#7kKhKj@EIyM(m;%(T;vWq<=kk;oh<^Xr}14|CZx#JwgSuzr* zw>Q4Sce+TNP{iG8`nY;aDh2%yW|tT_%2k0IE9K&;GuQFrzaEtQpv|&udmiL<4c&W6 zXz|I4he2ccM z*EC*w=uOUz_cWuppjc6W#=Z1uG=%$-ybZz$h3n-NT>fYpRw6lD#fO)Q5&@j88e@T| zKF5(Jj{>qarQXE2L|Z?8%f~0V6eelu%Ah9=#0!eTy9Hm((saO<&+K3-QmHu$MPyAR z1#(_VaUTmGT$ks?IN@gj*}~Ze)#hD^-=BIF?Dtemggq#?tiS>JnF~PHjeXtJ46 z!R4kturPfzbr{)<#Td;EY7)7F$f>JX6f;-tZHbmEtD^eXLbWl32o5iYO+N`SvMFP@4FO4uTgH_6;%c7H1gP^xh&vpR`2F| z|7k<{gchu%NO&1kQ_l`JuMNE_5`^ePrTk+fh0AEV{9_oJ-xQQIrR#qBG4Yf`11kt8 zE*`ucR3d4qjL*D0xf$UEKJti^I;+pkU_ZVQ@O zz{oJ>`0!;BL8Ld`6wT?c=ZpNXH92R~7m$buTmG)RgLvV%jB+*@@ckONtp~S*6APBc zIwF2mqvtb5OvAxuI4pRp2Qr#~+dBIYB&C@>qsQ}^w$UL%VYTu8k_SHYXb>;Q8*Q*b z4f7z^Gu(bmSdL<9>=9(EYJJo4!x9ORv7A_DznYcIO&$2l4a*#d?{SBE(g*RP`65#+Gw)LQfF;#>S;)M=SW$VY8EbZ3bs)jh{8}tG$&>Md? zBkIS5h2aG%68?&n^X6t2yT!mK&j^>>L6#wlh669Sb^S`~`EH%b2+Pv@0ap{_%85E$ z*%3m_*w{nc0^kk9nv6PYP;%>!riaea))~oPR32}fWMX!jdcS7lwgNX~O*z)pOUTKS z4%Kgy2^2)@lV&=~6hy1hj(R@(wt~Xs)oUuZGXZt`tveqd5{EOqle@gg*9~&sxFq+5 zw04#;nKok+q3iY%o1@ufJU8`8ES2b%0~@W{&u!ToaUZL*gb*5+MW_sa342w6*nUH0 zS{z%37H%(&t~>6V6wROb%LKGq(E>s-@&PSfx^RT@A23kHOG38QnCX@&$@AyDmO3YM zf9}VD1gsjss=fALzxj2QQjsulDmR`;1G5Hj$^ux){O)x_F1_zIgyN_mv6J4JexgmK_b(FkmbGT0>L-s@dbm1?i$?JD- z2Lk1;X`P>hMYyg}6Lz(&C(~nUyr!K`JL=wfNOo}MJ6ccu^9;j*B4WwmU2K?Gh82N_Q;sY8@{iq%COKZ}uOnSS}Orr1^*S*p&x?+XC?hw@Iz9~DJ`LD5xp7GCeIN3@C@w~~1(zvaltGBPp5xHcN} zYfV>K40aib!bBR?>kO@ztc>F2-zf9$i{EM?1Bt1aLv}tBREzEaB$W*sL~Tgu1)>}d zhR#~{N}M;bU;}H`ijy5)9$61A7<<9m-2V|C{eUXFD*Vj~;gNs&cYw!STSS>k6BD{u z6kxWD&8B%EpA@Mu_?`HtUgyrY_RM@5pa8*Y^11z*NjM6Yv)Ri8tZYJZs)|{lIt7cW zedt|#trt&~do<;06OrgC#Yh*j+~zb?#t3>6QdYEgs{kAP^aGK*GS2&ceJf7!7e2?U z#U`+p{RPQ=mmK+KQLV!_qY6ZFxfs(9@2sEAGzO*1A*0O7T6XVk|COMj3waV?P+6cF zMZLu(71v7pg)bryv++x3*Zc8tBj6I1;Y4i!HTuehRJHO`nX7C&;txg-*n6=3`>dVI zpns380?^kNe6GpUdqJ!T-d6itqxLNsDAc9Xkb~=ERev56o&}eMq2P~yWt%f5|3|8% zNDnq3dQVK6@$|sH3pnYXp1_(&kP|Qmn$Rq$_Pa2v9!&%iYcpvq3zFdMwsH_O0fv== z+g#<&7<6%*CT_jhoZ6Vfs7&S>+5`8#Y47cNW{5akd6Y9WIew>d;Ya_^V2ZWs`NYUw+Sxrj)LZt_=OD zLl2l3M?zWXau8hmtk->e!+r0+L2PEW71k9SIku_PqJhlj;4b#WJjnbL`PA&-8Vb9- zvWhnD>)5R{gBY`YuYF9px=Ie{cZB^wOVBod!&32|u-BLVvpEf{V0o84clp$J(bKT| zIbnnSt{XhD1^Hypy3V2>rq1GJR^tV#B}h}o@IKSTgJ}$xGweO&Ah=R zR(PAKx2Ng;cb*TbgkuWXgY6t!L|+qE!51iwd0*$Us|$qBdo#lQZ#Te^FN>jp(>kDA zc?y4w@7CPp*;j&Y;%TFP>{)#@#Z*mVQz#2}Fyq@1Q>w69IN}W?o#KIB}Ak>Q@Fly*b1YAXRLd3Bv`r}S(08+%uKI)yMy805^ zH1~SiYC#y*c32WPr}G+~SH&Y44-K2${B}!aN^|IZ-j*P}I-T^M#$;t|iruV4G#58~ zEucH5ts>t(Z78LLHLM<%v2%8dPB@eHwq!iCV#ftFwQR!!e`+EW)4K1#*`#UlrG(#n z|Ev6jhW!KcQ8i!Lm8r9l%BC|P&&1iGnaY;J;`pZE_)-nO)@L6I94{H@Ga2WzXGU1g zN=ba$m2UxK3TxdIaGi45gu}#KS82Z7H!O1RG88O zfnD)!2eDDEg_1A8$Uy1qof53aXYM?6Hc8e`t+eW?l||{-zDKhO!@oo!6jhwI*S^e+ zXG#;r^8VxGTR%kIL8(>w70MA?HFf zZ?XET6z960F6vLr=gvFZ3AW_w*vQV;ctf#c#&@JIwZ&TPP}dA><=c{X7CD|B=JsYB z>>xeuoOhS^BuD2C(+LmZ(>@maZTMv2mKA7DXB0i%JWvBFQ+-N zY@{V@Z;DRm1T}xRMzl61(1URzGF>4OgH*5rJh0~ilUz*^RA-zAD{UClp`P{X&hk3< zzl?%aSHX2LmQQDZ!LiklisIn5SH-{_4ntM`gPXZBh9rDHo668IOZfgG(6K0k@qwAw zMot>4VDN1*LM6_s8dP;J?9f-I0t{t+uJK(3eitM$YC2Gmg%k==sNCIuV(^%;=w8qv zO0?94L?=ET?AQ|;@XcY219#)nI^elOS?QK#o}*A3AKRGr`8Drn*7HJ3I1hO>NVvtD?l9tIE;zeFe(_P*E9`8MGNw zN2>1!CdG!vPNfeC;;y~-%A^I(v;jtuTkRbo5~@3I`51bmwe^_XW0oxKvC>pr>OW+1 zF$6utg`y^tBTnZ@TfbGy!166R(rTjkE27s(E@ zM=DJ7EIKT((VENLv)A@F>5|)S3W=i0{t@mO<6!-muE+OlYPH%=sm~JwaX@Q+~ zju8Z&czXs`6;@Ey)7ZnV-OTKD*8bUvEEr=%?sVa=Qbylf-1qg)7VjR9+A9$@;Sg03 z8N8n$IsbOVGuJL2C2AApTFGMWZP-!Nx(}4h%z^PP=p$zJKcQ zT3mbbSV{>>YH^4>hAh`GNi32B)5Lhr90vo`fP0U#{qF7`U3UC%wM6w>wAnV%-fn%5 z@T{*VR*p$=TO$`tzH@omM zDn-r@>?90VMwbbQl#~lxF`n6m>B9G7FSj+ht^2dbvy0tATj{8@?)~-YgU9B{l+Y$D z>P2z$?BCB#WjUsnm8PhvbsHY52yCI#AoG2mTr6zRW8iI$-QQk^O8D#&2QOyXQNa?Ca0L3PSl0;p=}iTPgPw76WsjH9pniS6Me22BgI{M%WA!` zJ+ldYuD(mDN*@SRvEF&iefHg%?sh!|xRaZoW=ST`Gb9-j={!6*J;Qz9`a_CTe+D{Q z8FwlHy){wn9P+`#5lVHfN&F;~6@g;jo`pLf?^9 z4kBt!Fm+a;b{68PVr%MB<0rWI#FTP^YUE=d^KrOn+**lke(Un8IoVR$^`Dgh{*n5`M_1Nq4O<~Ib*o(BF#oQt4~>vx{4b*yx*rn z2-Cxa6$!ao4zt{6$!wMmYK3{`4f`sHjh}d`|Mk+;bh!PBl#I3^4<5Tn)Oc%v@G3Jx zOSH(p3glfl<>$DzL=Q{_bBeDt_hA)Sa0!q``%@@QLk~)n$wd1DB(Mo&J2(?|aOLnl z2pw&V3F6X+ZZh;|`_x94}Yasw2ZX$HU%B6 zX|>zoogfTPKcv!2lg4pF2Ufe|q+CI<6)rZ*A;{*sKkox;b|e6^3!SqNNP1gXw|Ye6 zn~{J0?PAJ5vNyWb6r6I7W+!#Fzv~l$gtF%en1~mBDoHVWL*(@Y_b|@cGl%5fsN8tl4Ys4obR$55T5Eug9pNdv!=yUD%-N~4LUZNum)t}clZ;DE^JXlLx*KID|UHhcSE2dHSmsXSf{9T zveM0b_!P=7C0-?kt1A3@j~cV|6<;*FUjpZJ8s|>5=W9LmM6P3t+b)Kh97#X1L!F=z zaKNE#q4*u%mB-ZIsfNF}6PV;O=JYCW+6s!9l9oOT=zhdHY2yAY;h5 zOV-ZV>*xcMLV5ovAeysgV!GB^YS;p>wKP#*bZNc4s;Ibd+x)26Fh3A_3*IYsLp2YN@py}kbvw}i5H!69rB-*o6bF&Uhe~rRJUI` zjrtFSLpQQrA`9*Be^FpQPMb^W495=N-pO)3-w}(nZQGqz=n#Le@2m4}pAT-oS8+;i zU!|UaFTn*)po`nTCJ7Q>B_90Ai{IjR>lAsqojsXnvei5ET0|LvK#%*Gs&HU#>p&*L zyV=x+GOF39kLY}1Ix_08Ke3J3bo8c$nIAIyq3Xy+zvUpYyb4{(FH{^m>BNK=4(|l( z#6!Q7yeRV~GXrDf*p5EyjbKH@;4YjoJpirQwiRytvT~cc66igNf$s{5m%09V)5u!~ zy$BOE-;|jP5Y0|VdT^10XvDT=`MBMxaX!2`9TKR1HJXFeTos5P&H9*?I;u|Kqt_%K zzPAfgBLo{Ae(eMiD1pSP&S!QkUUf@@5W23}PZAsaU;5PjA4NvaLqRU7Xf0cBkY`ma zo_^3}xWqoXX&E&tDMsSV_L-bVQL^~)e?4%F^e%sM*SVN-dsRAFZAp^mwcmI03G0Tiysh&~>4kjiu5 zOcqlW7$hr*qlC;?`R!BzzF-{A+|oOY05>Bc0R8qy6E}eMv$2 ze%-H~5rFAa8ovMC5_+NkpM)2dv=I{qARwp_#>z4OohX^I}iK31AT4fYJpkVsVb-9U&qhGURn6uwS>`eD$ zj=23wWO?}gibK887cZbpZt{+*dJyotT7{kS=}5fg3L5HoX2$oRMN=Oc)xg^xCc4q_(Cb?$M88`N>+y=0eBbi;+NV;P7XG}%Qz>rXXDE?FcdY6yE< z<9aRB_nt`%-P_lvr{Kz9_(5sW^Cyj*gBqLNBI!7mDn6{n`npV};g{zJrxjUhtqYg0 zg~U0Q4&@6_1}4p($IIJeIx8=nU1sc`sjh*Q!z+R^ifK53bP$&f_QoflU*#!V%Buwz zJjCbM!#fL96OGGL!m+ql43{_0qwg|@V7w005vq%B20Tsvxu?0nmscND{G$brFzTDR z(}qFWSp{TIDD&ILuo`994Q(UKh+zD))yOT)wkjU=KnN(z*Mnn_&2+IcKhlPY6n03q zOYyLW>gxB`<0hs;_k(y_?w^j@yDr_6AEpHSu3sx4WI43lBrDRg_yXBI>5Q@h-Fsel zE*bvf3-HsJ{B$~@B~%oKOVQPZ9GZvx(doJ z0X^CMyED61#uiS;^pZjGVo4X<6c+~*L0RE0oshnQg!ve&^m~ zPjgA*s;ZXoG%3{Z#KYN{&x(j-^T)Tz0xF$lFN?00nru)|wp3h()I-;OGxvS; z)kwpJbnFHZ&#^&#^D_FMDJ?~tMc1JpH zY{d&0;E&s7FBG}b^y&nn?KSl|^>^IOJE+YpUv!4sI<6Y1`ZuFcLxtR%h&GQk-G3ML ztav}RZik$VQm|xoe0KnsCswUwLLQrFPwvhZZEO_I=Cn9>9$;#y;H)i?nl6AFluEHv z>u@qxpFItj^t1<-8ph^h%>WOd$UXZwf7$zbZ*a3t|F2Vap4SnGS8^oSlpOn0!jbPU zh3s+-9$qQI{(rKQQFs@yhYWJce=vWe_3VE0mfww5^|}3*ob8bVI(0n1P}lDQ199#icTij7#$}`LrAYq?mH*D1Qsk{CtM-|7#q&|3a7wL?5W;UQy8p z=?0(Lf6?nC`U`r6WZg-_`m*gbuzrZ!v64qk&V<^u-ZW!?G{$TcHxW;F*@uY1lrXAbUD(q!z|7iuv~ZV zWESGtcP13M1S3Rm2#msfgN!wbk$}5Jx+)F`JFVr)>-fO?miPXx%x!GBlVX%;<8FA2e{>LOw2;e8U@@1(yUksZwh+Uff*c);D(vYejwM4TUD$ zPOoq1mpFP%jT?P3!yHLU_Sd_y?cMB=&Y~QtMesIkoZm9w?S^3!zQS@z*-WLB;_pMH= ziD=*vPwa*{ps&fp>#NSqAVMXC(e7<#r3y5BHGJK!kOAHW&!c;c@I9ro5vtRKN%gsg`Ip$9q&L8iN1Txh0Ozji;@ zN7j}=QZF71%rp$@>qLQ;Q_fG&?P)q5Y$k8ILLimLn4Gc*ZzME=f^G`^k7&Tdr79@H zmtw8Ui{j?9vt6GXYz}6g{M;rwN&dZrFK^X1Do!hE;Se@38ZF#%)kbijgRG%gW%d9$ z5;!t<4v!~p_#vYHay4mEI`F#*>}IS*KF7 z-=}&_L|I(;VQH+Oy5H_pg>K#7?jy0K9IRD~Ns#N8P|PM(7QAb6NKhrGy{)q@zS$<2 zudWACTGv1jzI>K#7tMOCvp*W#eq~ZRevVefT^oAf$~t$$wsd^2D)OMgt8xPQd|aY& zeWD+nvsOW!Go@HaOtD!s57d}`y(0Cpn}XSPmBZ^uUSe0Y-GX6HVo>k4{E7U+y(42} zg29n8CNw!?jg^|e4kv+w_BkN-=ix~S$RUEAOl-8}oRONV(=Sqjx5N~h)>m}$9-R=W z1TPUF$$g(#U>`z>$layp;(^ab^JF(U5ciko|AsBbtJ?k?l zUWzIOQRp?KX>uo(|J<0`Xm66Z3?jW9BgF|Ny|ck?VM*(1zInB5#q+9)x`vc_A0 z2xIbqae$B2#!#c{pT1)bqRi#4(wt9gIqI4D@`- z3dT+YDBf&sXdG7zK3fWx8P8J9-WP%@9TS0#yGXF(=bo&z$d$Cnp6wvk14MALa%*Y( zN?LEw0lN|JO4rGE16p*SsFm+j`d2Nsbu$!lI7SbGjT00SGQq+3L~Wpl0;Ds9!1ibg zIQdU9%0%4rr#W4@U%MuzgUR`McSfT8?p=%MGY^_)_3P#Z{#Q5|>_~#g)6}lhjGSn} z)<8d^IIb`-cz$cFr-6eE8Z6Zr&|L5&iY^eqJ`pgLp_6Aad*oF6nB26l{^9osufq{$ zA?%SRt$hY#V%8kGeT`69U$<`KrPY=6rqb-hTRhK*ykDwHhU2;NAyJ56WY=Tw8xI%o zCcX4Md3!K4dpu7$vy|s_E@OD!g(A4XpRz}kyxG?G^5QAu-jdkUZn!}wE3}BB7s22%jlFtF(sjKO2nXwbg32^G{0L8~sL(0f8dvIc_sG7S%;n`vOb9dd7 z+Jop$F2*oVq0M<0bd8~`cn(85kR!>#2IKr&pm^S(;37Z8ufnVdOG;qCL(aFuq}00D z-(zDuaE4$F)bM~nsma;zF%)X(P|0f05o{`2n+Y4Ea&OLiGxV|W;^6vB*R5N=0yDE% zpXtYV)7<*`k0E8Kujn34_U6|78RZP3NuO=SriBse(1*p3Ena~ltN4M9mB3=$mv7$%3brpS? z-Bb88!We(Rs>dZ&h}%6$Rj$Y1e2A7@-K)#+sYGuRR1qGW=K(RxeS z+Eo`&_g0LaV8p#NrfXnU%(r}eWuK_qJtBC(92=0!O^3e z(Kxjf@YC?X)(pUrNY5w|Hbu9eq5(x#=K(c?&iw|rzErrV18JZ=YH8i)pPn`eu#4Pp zIK*{*FV@6;@jdWD#`iZAoMTW>PcINkF66@3U^Ex{$+7+-$uswPP`~V8JP{@K=SROG zNQ?}vS0aaeXSHUrv|5w;YmbqAL@zj@G!mSXFCm?;tJX{Trq851PkA6WS`r=%D+JM@ z`wrC0k1uxs9(?yA!nTVLiT=f19EgzpfBbF2zlEAl;`I}PX`fOtB;cQ_ASlSFNLNal H{P_O>Hgnm*=iGbFd7jfxoTj=07CIR^5)u-YlA@e864Hw@#MlQ71@Vok zu&0VRym41F@9ee8)dL1o%>#zIPr%g*sf{79_ zph;7&Z1CNZn*{TlYa%Ww;#6rF2@NmeH(7Ze8C%5p=y>bMv40m34x^yqby%&dGjf@6H0d#dIFvJhOH3K+=3!1gXJU*eT%EDVRBC zlDoTjWnA&6vS5R2Wn;zlZ}p-T5mo-emJr-~-Zh&y0fO3gaS2BKgI- z=iz94?lCi_)bpkbq?o=xR`ploW&PDbeYKqN1>5B+bG0t%N1{Wo61gDGZ1bbse6_&J zoWo8wgH4;o6x|XW7C)ETP-`Gmg06DaIM>(kXk)Uoa2#x{O?mgjUgVC8DqD4HG*FfD zv761-X-LMXJD`C*krM!Zy3rz?4t0PV00D%58|DIz#+%D{SigqCR4(Nnm?!Yk;!Z5m z+I=`vlas2)@&GmUPeTw}zYlWsG#VjytVZVj?-z@jl>maRV~13oCV>y-Y}MyExyRos zVH^3oiO3wyN4r?fHKB1mhbj;TkK4gaB`N*P?h%i>C&+OH$hETGxQ*4{$1Q7GB8w&C z#+b9(RMLyZ!QS3&+HOuo(yK-B8?$^-ck^Ef-^a1IGua6Wle%Kzyem%iT9AG-1)xhv zVPz^=J61g4aI`o}s(YW^h``f!s1+kObQj-K`)c^o4-)YeKWzWX(+P5TnM+Z0yKa#I zK3W=&3FVnuy0&Kb^U@o|#Z zSOK!$<-vbSf4{Z83DW_(n6XgZ=><+fbri?%H6Bbi+I!44E~(76;}rj-X-u$S5rZ4x z%^dBf_dI2P1a8bz`z2ds-Fl?-cC|AVgE+EvIEzIx`REu{y*jV8rwbGh9hyBSAJ($I zp79(ju+GF}N`T~~c-pTxr4g1^{l`+sRB~YQ81Q4|Rk+`Iw@F=fZl+|=GhDiBx)0#@ z3HYMKekbYS;;y?B))!JyyfM-O-kfNI3Y8#zy%XOEU6CfkNV&X+m8rJjyX+A>S#{;8zt0>rV7#IR%;`3=iPh-5oLT?1 zs))Gw)_GUPclSNzL)98g`=rymOXo6o-mXYV!b>ehY`D1l@-GL3(Oys8?mpFX6mZ1E z>m_nVx@y#U#kr2HvYx;GM{>f~H&e#8<#G;oz5#pUF{m$;e5$Ug1Ik3BkWOXQ#~f0r zHiu1z*0c3V!*q)6Ror}8Z%Cw`?x^$CH#KbwT69HH{clKbIL<7$pF-5}0FO4hr{0K1}bYYJGL zRTUH%90G2OTglSNm8`gKs)WA@;)F`bim~}^R6?w3gXZNAm?0}3=XouL!N1x}d*ElC z7hHWmL!{t5&ktM9w}0p)bG@s6cMzE21Q+=g1u<+I-7KvI?o5d2f8dkkRlXeOx-x(* zcn-rqZA&;@UuAvW_-^qi_(ng|EbD_&x4hhWTpRT90THR8n$sTSsyE-J?(E`C*;WRSKWB<}%dxe^NcN zN^Meb*(eeAj|A$@d)_dt-TrhSA)%~<_HU#-LH*84pUHo4r3rc&UGYM6S}{JWyb|i1t*kd%Jobp+Ic=eF==xVL_mGw)tLn?$I?2T!jyZa z^1q}ZT6}q^kZIa1QEi`wr~+&-Reiwrv|s0a-$Q7HXNY3$73Y%1X4I2)#Kiv|S+udrVYmNVG3HKNUiOEau2k0!r4rO7Yx2vqyAl zm+4D}B%62KDQdv2vY!~u{bep6Kh`xeMqL!*TzJp6cA6&K>8scB+Gj|oR{2guxyJBLt-}{pnkXC)@z&h zBBy%76YfuUEy4s6k$5ki-TJ#z_&9|Ne^t9w`9jPdD#S=~GnernZl5CR#e72CrS~<} zx0){A{`IqfiJ5Z3JmIg(zjzH!on7=gsP9aGiONb`0+npTLvTV9p6}oe?sIoS9>u0p zn^GMSG0%?@E_qdQl}BhL?VA$<2BDc$Hz=<c=^#Yu)FH7rjzbQ0cq}xZr;~m#iSKypL;sgtCL#e*r#D zv<_**K2W)e<$u)@$|9ZAl%SV_FFVaGFR(Ziht+wrFH`6w%){A6)9W|!;+yJf z0dQEH4S^T-<`O{FgCOFyZc+%Mn35KEvhU5YDW^e!wjtow3({|&nxJqw7){IJlKl~r z{e??5hZhml4ESH@A#?0vwNzl}_f`L1t?Z1)C27He=Yn$>IQZ1|?Mz)C_IEE@|Eb z_hz%ove>;odF?eBS>qlifk%_2JiEE6q49~U=qydi;k-w+509B(Lc1e5;kZkV7Ehnu zLfzGs14QvhHqRNeN(+J4&E#I=4ZuPI@9z&K7gX4Z=qOY8cm$=-N?%Y0eH814QCM1w ztNZ8?>iznqt0#{ZB_o_X=;6W+8T2qEA023Nbr~ILqHqCEz(oAkeTbJ#z0{(nZ`($} zZ)x$YEG<7PP=;i>rnuVJ+P+41#M{0Q-r3pV7ZfBSB=A`Ve0Y(Ok>Q__q=SD|I<35x}4h^V7hhJBm^MRX5$jE53l=tSvr)?l0R~HB< z$&r6zFWYQH#GyEYm^EU6`*|#>=K31uaXv%C$f#X0?}V@oNl#C&wY4=>k$wiv7FmTQ zs)3zc;R|1b^L(n(ovrp$rYH4*GjA>?*r0)?vKQaCD0*m8DON5rPA>d82!8T#Y0y7u z!q*8~BdI?N=l~|1!Bth&UzW(FI*md#KcB%7E6B*mIActu4o07{Ut}mt_A9ZTRBg%ov)4L@y>LX6i(R68+m)X49q0%1Y#hzY9=vDx!=*7`bvS z%REX{vBvXeb0WS+WlkGz9NPN&`oj>hq{b%;s`uu)RTQz%fXE>$gr8Y(S;qG>i0LY+ zA&RYw%b>z%0scbMp_NW&;^L>t>bvt8$;o@4<3tit%&W*=_)U}7wB*R>s1_@3@%{Zs z@I4-_T;r2m!fwok=PrANHEpI!@l$`^&8rpnZN$WCs;cMN#rFg@J2uOJ5MgP;J{C<} z^r(Zgv+8gC#c}l_SVlB+WO#4npyx}qbwGQqAhDB^lb9&xp!epD%~%X+itfh^?U#op zZl#r#do>yxhye0btkkA|`-Y5+?DO`}oe0lFLr(_Aa53tygw-KIaK?U_jjBOGunVNO);{otBYk(bxSOjm^9b^h4f5&Vp5Wok^Yk% zL@;@0w|Cn!KoxrK@F9+Mpgzjc#U-(?PZGdk68#Q+Pl}7*!D}#GmGQ-xE$=Nz;#b-W zcT?i&d{LI1aoZVV8zX%!)R@73M8II;q}WQ>V4@5Km&}y0R2WKWGAoK87PzU&Bfh)+ z435}~t&4Y0gU#%?1JmlLh5&iSj5n8pvX6vTi!!YUqvj6zH6;ELeAWNPNS0K_EUB>@ zKv}BEyop<-O3x}kMObQBe%VXctB;;?d~(9TBceo4Ue((hGR1^QS?0L}H?QPlHk(zS zEx=aLs=-pRQ4ja3py{9QfyKODQ(1^Pbj{4#%K3=^x{KUFt0Bqb+f*M0qpLsdc0 zcSbdvYJcg-!rv?Z8qz%GZ@%FS)ZE3U5LdJalVX-{?JG)7PA*f&LW$V=6*qysLySJ- zLevHwu|;2R@(NMrKGRv7%S%@P_4CT;lG<~~tuB=iaBy(k8uRfBkByC?%{pcxZZKqR z4dE9M;*%8A=Pw?N)?0QDZm6xR8@vg*M@7+m&FIZeWU~Y`iW!lKx3$b4;fpw>iv zXJ$b5&t`kdBOHb*RPfz~^CUoS&?+zxK_;u0U(>($QNwETFVJNjw)}z{P^6&a#Rmp( z$+9G*ZCPoL(+ePc{H}7q(%(nR5swf*#(Em=T^)7kr7(}|8fe}LD|iJ+E1lr3_K^d= zqb*e5xuYy~&*7UA&A6J9N-2_+NW{e9w7`j5HZj|h`oEdU5}>TJZ6w$HM46L=OsliO1*VOlKKMZ@LMp*-9yq%R2 zcHu;$9yJXO5;88zNd>$6t*D8Ikx&9%1breKp$(tse z=Ou`!#_ty}n>OMDS_z*NIY3o4sWPRklV10m%C(kUbVF|(7KyZk-`aEQ%jblOF0ogJ z%$C*SN4*5umA6%Ob&)j)&@5GUHpMkH@mM#J7&{*w9mNh?^9u;<8Ax&&_mB`QEH2J1 zZBhx#6U3UH5@N?Fsj4@3vrV0*iPjHl$|78>_tX0g^PgAt@r|h}Ty40ZW%tc%&&$Ou zf{`Ge0%m(xJb7BYR>MCl^V2FHDKeD8>PS`36GoQu7ybp~<4VynF|niD(mAk~369F-ERnPRc@9iVP0;sJWq(+##1NV6Ykq;e?#K0M z)dZ6)?Yq)8>#Z=)QPt=E8D~zRBkRG30)P8Ycu_LT`tDaKvR`jcKNUkW_x~2?i2Wd& zWqtwCcC;w>IVYne!}irq99FE>zWW6R*ll&Wg(fTN{>I$uP^Wf8*9CD@@JVuER|HtM zYdot&_^W6PzfIC6x?wj^dxzNdg7Y!M=YC7$5-oSs7mULIR&bzs#RnD zl%$&q=z|?_;~hKR0nUUX4PKt{+XIq5w8&$B_h+;ql#%5CX6cdI2wjrVhL@u#1Z6He zADy^+P?-1c1VfgwODZd)61e*OCp_k%S@wA<6O~2)Qoz^OEkv}VK4?)caz_3jc=~t^IP35^S)Am0VJ$RRD}=bb9qP)mwtR zSw{!zLJ<<2aEHC_%X=S?;m8)*>`Ko)`u;n56dst-Wvv}6IzY|?k9oh(Oxe<2IsY(+ z#jf{{7dJT;VtTN4#};e7yX#_s9I;GDpuN>%9GYM{w>Oa@9ke~eQ{`|UQJ;Cz`WQ39SQYMXc?S9YE?hCs0beyC6 zP^`@kH8WeJXYij^98knu2}f)sIXOp-Bgf4FZr@os9jBa3%`Sb1q@(o5kD3z-nNglH z(u6*XhbH_Tf`Aj0(+v=59v{g*hRBy49(Meh7&cdSNu&29+Mcz&h8c!4H-7-#p zME=&ne<$QN8Mb7ICjXJj;mCqvC-qyak5)mfFmNdRpvak&NA6 zGSLNdwAIlFmzh7~DAV<&e0#kY)B%dZf7xC~7N=V}Cs`qJ&abP78c;FMO!c5iqVi%j zM)UPUy?`wn0a7f}#>JBZ{M! zg;@z?q6WV--bro?8>UOoU3@2{&7gG%V8L^DX+;W+*Bs-}u|d?{k5*k7(#h7Pe(3GN z%;JlAM1?faIArC_$Y@#ycA46Bc z!6&H7&< zaCc(OJ;_wXHOjnCL;N7}YcTgT(b9;hu&@y6?tr87765YH5yb|$;>XFM#SG~*H0}h& zN0a7c;EHVFZZk9&WG&W{NHA{=3H|TPE@4pH3e5u5U2mTNxE0>vy);U%hQ8Qrm zrw-Rw6nTrgi#0r}Rm=F?B_{UeUXZk=*^+b|21urd{+6_L8SVG7z4X@sZi}%)wWd_b zm|+>*3oX{zI&DV|!oaZxL_0-!#_6Vx zgZ!R4tbuFM6WmM=$V;;&5*3UuZ8gijU*c)ZC~rl6iPL&HPs%P8p&hRCZcxw4w86@f zgdv=;smT??^j#gTqf`X_HZwoKQBLXib;;`=s9+f*PD6dc@ODva@nr;x57a`>oO|!V zhU!_$>>BT+(8NLSxtX%~>teq6Dbo%N*t=r0S0fFo;hh|>K%*<+>!5k}M{)7vICWE~ zW_XHBQc^h)e>wZR20msL&0n1Q9q3FMkr#%RTXM9*%F1?l+ zmPlJ%v{+tGIB0~!=)R=9OX#0SB><=+meHYff>A?n55!CjvoTC z%n{m+ayT006Jb;h<04F%x)ML_grBmUt`GOw?8mYW)ki6^$UA!xHmGThv?7b>SE5mN-Img3S?>4Bs1RW`63nak?ICATFNhe5Muv2J^R2TlH27baY>AQD!*48hluWD**nFJ-1oB7k~$d2;!oNB%~ z%#Xs6X8`+WHTWl+Pikz_9eHm~@bqyFh=A%=dh(65H1uy} zj07hZZ$nXPeWmYe48tuoP*YQ1SqY(~=jHwI;25*jG!GYrl=B@mF_)20Vep8MzUE5Q zmH*ekxtOA@e@z)#+Rc+`>zI$@eTbDOdiwuP4F|*NOvq6p>PYl7g zx58$qj0n1Z_hw`d44}xyutvNb9$h#gbqP-u8;JH9mU%RM+4Y?wXgq$;CD)%~r`+a; zwaqmQ*5Y?&j-aw2*Leu!U*jrGF;$gOnnloMb*wn-A;YnuX_6dKsWNamEcyx%k(!}E z8Sr}ZYRnc{$<(To*rxW_YhoNsN^w*T_E4le7$(y*?C#Q(eN!KST056lm-s>E*8+Cp zoZAUqoq!s}No#}o__jPo?bq6YD}gxwf-h-^cGes6QE9m3Dy+6H-hDQTm^5L`(mzXw zS-kJ;%Z(PGaNWA91AL?FfGlB$cU+z#KG+|8Y!XQk<0vbEV4eH|f-^HSie6qAg@w*e zE-ocaO=)~Y60p}cxf8XJ!%Ze5tXHjZRW0RIuID~c@(j- zHa0eiiOKWLmNY`oXU|E^1QP;99a)y@24*bsDk>P8_xnPfcL0+EDiZ39@!tXFp@{;p zw+*i{M7oVdHVwnW!uz9wuh-V9^bi0p6F~>la&pjoKR3D{mi@%lb?w1GsD-6FE$bh7 zP7m7W%f%eGP1j|O(vC;Ckz7db`MV{qn!J(x(9Q1USQ`9coT+&C*y7P4eLRkunvW>W zJr)44*KaUVbLC&Q3cN_K){K@i8@J)mEgJu5S&Zd+O0~ zU-z}cP zwk~Lz<%y1tMi8BnwyM%j!l<$kt9K^}t8pLR8Fe(~CFKk5!ON|;A~8pcvjwQ@GRvx} zqQM~ZiA5EV=eebjhEz)g#q{a#C}MMJ%9K|MZUR}(E`4V^capiPC}LS&%LeW#m=dTmzFk&ss_8An zI$oNeo0AC%kw9d$$gjr;8ir`U7_yJZiBE|@3o@Sj&fv`8!KeLOylv|EaT3mv1Ft zYfWap;MSYnyudHD+12l(KUFT7mRQC(HxEx5o0D?x9SzwV5XN)`U&Wl#{XN`hW-Zn( zzlMW}Z0D;ZBBLsoB4UEdieeCQqBYX)!P$j{3|D=hrld0mF#E(63X!%zGt-_i8&r092r1VE$Q zg~=!Bf+&li$iR(S`YpxC*;$@0Z13_}$6%Bg6cS2O>tOZ|VPRD8n-ja|FRu(i@*!#z zKh@L_5!d2*$4k`K*5Wuzi#W_LEGwGvEBmMs3bg&Y6G)53Pk7s+0Yrp2vd)1=zSrH2 zc#6OHl*Vaq4AjEE$eR^yYkqlI*#si9O3YEw))wW+ulxhc#-X91U>MPL1s?A=00%pr zY_JOb|5d?g1BQ7a5C+jWD#kG~1$)&rHe@gQ*b^IVo&qoNR+s4Cn;R>0UJ2`VBdY6( z|EX2-$Q1hD#7vHqCEce`@bfiNO!Au0AOGyhzM%fGCCWcLk;JatB>Pw&V)tK!E@^bO z(aP+$oIQu6eS3s?5YVmreedX)dkp+?YVgJr!X&+pQlwE2-vFj31Nb9d!u z_=r3cud;-@!>*{Ou>pXt9S_Qplu=7z9uk^7t^>+b_^v)cK{m1s+;KqX*C_OABcpgH z>Fida4}Pd}=-3hd=`TjA{WOJ8laJmjJRunyC}HsBDW^CR>F&UEPcBx&ugD?1kJ$x3 zlQu)+EJthkyZd0$Qx@7P%mj9K3{=pfh)`(;@vgHw`s{B`)PFuWZk!W6-IQ*!g=NcNKY4uknq%dTB~*@P}Sz&mzApqF2$l2q~MY)mPUBqd;*lX}N_ zal$lZY+PGaVz4xkxcZs~gJhKuGf*A*UK7CJ~j=O+`gER4SMbX7_3 zjCwc6>?^m2Xz|8gm62e)vz6&_qon-32&oOGH&UEp{XxCnf@bXPr#B2&w-#d~0F^x| zP)gjH#@H!jlLbut9Jf~d_QLm}t$@^wZE5`}Jh6IocO|U*gT64ZAo$96JT|udO6Br? zQD;{cMxJVGuLycvubk_;pWa*S#3t6dpt{6x)lEE0ycTCN-K3^Z^&HHI#isi6mqMtaZoovz$VTJYv)6=LO+&f;w1Fdu}ueIHH}_mXdHM;$Y{W~pQDYgz zPy4D)p~rr<^w~wh`k}X#XX6<>coH^!v=?H)w5sIx2`MQNW+%K09Ujs`MTf8Of`{TI zpRpuZbyeZt3udk{uK}tJnw>k(54#Wpq47!!33_8hrn~r#`SU0KpBweX1*m?KNo!#% z;C_G-<#jz^xHZO0;r`ke)?)cr`J)$AEuyLdtG{)lQcN|%;9&!hX~<;WUZLr2Trn^6 z${7V2+T~B;md{gDRW7L^#it=LhK=@wZJpQWfxxHv&7DkRO}>2$fqpLx3;5%kK7S8X zHHzxX5m;ER#a{yKJHj3ROz3>?w}jc^o)jMn3U6=knc1eal*d);`u-G80fg>QAqKB3 zAe@raw$YN7j)(iZoGeDt08u-#g0bAOGbt50=YgRPCXSk>iN(+qS06%w7JIH>5tixz zJGF-wo;gHN1b-{#nQ(l5KM<^xUOM3KyD?HGXe{eu`==4L@YD{Ha%MAHGn#;SN^6e2 ziT=(QC>*|gQLb@SHF?sr<669Pn4au8S}vZ@bsxC8aYu3E?Ki)^uIA@Q48Q3ao0bf1 zexvt^o17^T_b0yXty^Cpgmdom4@&4_SYRqcwwv8Bp5L<75Cie=HMrX8m?&9=-^NIL z=423p*AR)V?&mm&FRFHC;FiVR{q*)-u#mYY z&0_EKgjw$we$|J4s*cn3&EKRAhlM;A#ZW0fY>scw3cg>N!RpTxz%Xbhe-b9I>73IE z!n=(g$MS}LVTEEXOCPB2IhTN98Tsv`e#jA99a@J?(nDaT#~HQeo6N7fC)MnLtm}MbbwlDenyLqHE}7zV`s}17#;%LnCW{(Z};?(aTOv=WD^^II68?!Vju@ zm6f>#Mkb4=ZqHxC4&chOK6OqB9ly~E(8i4(%cYA{g)2Vh?348He5*!)YqMN6^?O-ZkeFjL4c-)ToQyN1Oc=xA8 zh&n>3dS4R!h^6Hu^~iCVTb!aMaj~OqUcBZve>gYSr9QP8*jH~dLu>N%$NW$LAHg_1 zhF(h)5<3PrH148ex5uak#-@vjulGkN6p@x% zov^qZ)L174o)e(HSHh)79MKx#b z_@@O^-c4IBG0LFmh>Ty}E*pcY)z??=R`Qcza$)?p+Q2^f|Ddq_?+gCF=^6f8<9qr10*TnCPmzDR6CqbdQj%Af J1Ik#2{}1)=n~eYf literal 0 HcmV?d00001 diff --git a/doc/img/12_multi_lidars_ip.png b/doc/img/12_multi_lidars_ip.png new file mode 100644 index 0000000000000000000000000000000000000000..48e1e13829ee74fc173d0e735a6cb53986b10588 GIT binary patch literal 23224 zcmcG$Wn5g(zV3-7KyW9)gS)%CLx2P)xVyW%2M-=RxHs+&K^t$}-Cb{!|DJv3bLZ?A zbLP&AZdlFgrm9xe;`cnyw+R2DAc^$h(+3C$2qbAKF=Yq{$T{%$i*WD3&sWxPrQk2{ zc2XLS5D>_{Zx6^MT4X#32x16nG2yRn8Ar>mUif{>cjx0rCs@}uO>kNjA`DPCR&euv z%!P|WoqQyPI0I`iP`xOSgd(!|#4tWNx4e*Oru!B-J6gIuz!jHmlJ0`TD1Szf+> zwvVS9D&ieVmNyuEyq=QXbFnow?bvDOtYxhgk)c+?6j#D5m@`|whNp_ir5cWtAXfvw zBED}-(?kP)L55Lf=-b;#9;q@F;Nys?k*^Nlz{iQ-3*$?{$GKN5N!nO%ACf{awMApu zPz#tA-Tg)rz}{D;Qy3XS74 z^13(#eb{1tZO{zS)UCnWx>(I1hb=N0X${~@&E%6B^D=9)vbxQ3R?K1yEi@WZ+Ki18 z1;%fmArL04x_PL_B-XeuCtTzzJsXY98*UH&G2-3`WgOZ75VSfRZ`K;y$Oxvo9&vGV zv8yON?4vi$9cX;aybbp`0nq7sL}n~8svrxRMB)E*NaWkCcAmm>1m#T4ZTxL6*AEX# z?D7?*O6j`!-l(_cf=Hw)3YT7PKD%F%4~+OLh{l-Tl3+hQaJW15JKd){uPc&|he&Si zKT{6r+OQQQDr*}1CbFtrY)2E#No&cNfAgiYB}^fU^|dQy^ZXKnSe|k#e?)2eWK(-3 zO{gRx?NVLe^HbT+oCH$$vob6PwMV{ z0&)K=cp6`rShIf!+O94JZetXvURk$Q*!ENIv@01*)Otvwm9H>YymjF3c(0P|W6y5Z z;IdmY;K)Tu*0otEUF=gPX4-MjVUj`oU~(axlczV?uTi$@)b5CvZ^Ci7pZ*H-%Q&Mq zBXz-QwUM9}wC&flf7;r1K9yR@7i`xrFa@^ll-s;LXPB$hD6xu1}Q9cDhdJkc$_3%4V!|uTZTgMq?oWUnt(#MO`S2|<7RYhl+A+L6C zm%*HlCZC2g7Hur~c#-%*qLGT4E~jF|y5J~V;bvFYg+DL0%`aHdS5Dfoj1I)PiQ&C! zc1|sRD&1C3*Pq3aAk97YjP6$FA=yDOX;6z`8r4W0;c!RLKiT~$&_s9aY9ln&b$5jB z@yy!C7f4R`u=pACh>wq~v%*)PyMS_RV}_(-C)~Zq!!DO2+WGo!j&E%Fl-yw!slo1e zOC~GBo5Hoy>|=f|IcvTiQ`WZa#bRmY#Vv}A6n=stfL0Y$#QQn3r5AJ*d?&U6ia_lp zZ#;KT%dqck5W?E}}Gq>erw?rB~lS8bufwP}I92+mee>vuDp^WHfM&u#2$EOIog>AaD z|ACIo(x2%JUh-Drp)MY>UcE40mdR=~g2JfOlDH`+s@fU7k8-}v$Mj!knqcwmG>kl5 zztAvcHC=b)^Adi?*nUPX{A>MK>*wRfmn_YO5R_G&;gobi1Di>C?fVw`WeaMTfGVR^AHH2vtM*lmPQ zimqL!Bd+kgftkN_yCwM1%tY>R9QqJo5FhJ9+$X{BDm+}JpMOk~I~}A=si&r_ykR)F zm1E@8MBkv|2cwbFI=Ca-EPzD2)^m7?(J8L%;1zVTNENen*UME@v6&EQKX|w-Co^p+ za`ms(zN~NEq*IMzIB62Y<{-^pS9}3;y5-a1d(Noaygh)dw(BbsOO3%E-sFV zg{7jo4eg1d`+WTEm|qm`(1|+?cojISyKNm>z1tmeW+R!lg+4_axHq4 z1-X67ar=Q+xt+b@hAO$NuAXeGtr46`V{Me0!#MnG_1wN9ZV9UvEt5JAO0hPINkhYd zFz~Ee^%vztU0_VnP9-03`6;PED)_VjlbS3blf~rR`e&b0;`_CQ^vKN*ZO1uvbJQ2B zh1;tvw8dABHt5+k-?;(l!WnRvfNF zoVK`(Kw!ww5T#<$J80#tHAljvQhw#(ux&A#yyte$EzZd?9U1BZa@Xf)3wNg*D)-?s z)~#yj_d`IRS{aUkCG7OuQ?=ozgv#W|mxt)GBR;JHS#N5A<@tsY+}_{d<-NG=9QN%L zcaBWcDz{%=De*Mmhw_cp(ugpEQk(HR%Uhu_<^*n@T1kQwe)Qk-gTqMMVgB#rJ}t+_ z7>dz{=W# z4%zpM(paq6^~w^Ro+FgeCL*`@hJfsEX~11m9Q^ptU;N^&lDDd%P40hQH2i<~h|MoJ z6E7M^$}&*?5J^c%NA!#Xb#fwIsD&SMof-Xw%%DQoJJ;>jTv|S+rOO%^d~U7?y+zCI zv3;v=?iC%R;!6|bOG;?kzqe;3m8vSMsf9vVQJ=f@z+GVQ#wr%HELg~P! zepjrooTwpm^DM)C_)P~4oE=Z*S2Z;iB@OA?0U)3hCf}O0Ky2TM> z2MGh^?`?~^-n*F7M++kzF1_Tt>TP6VLMT`NR)TK(5nTBdDhfVE^%qK@qoYsMo&Cx3 zCiPvI3rLFp!X%}s`AIYcQTVj3(pckX4(dr`Bl6HpjddD7p&YOm+>InWd(^KZXeo@k zW8AwLj#b}O-fC26hl!#3oE-m%hz}u%9|L;!tvq$=T6`DN=$?H9A#%RJ$OcoP*K4+oGZ`seSO*5+NzVUhZG6}D0P&>vpzX&^$}~{CMbuT z_E>x(0rmoV_8Yu6R%$&tv67OAVTP!w!S6U~;e5N&;G0~aLIuD$5EVS81`8bQGc(gO zGjSOiataD#?J&iM;0Zi2KY@DAb&O$sh)YWXlWdKFgA;0_@m2L334}b*%)%n~_iwl& zU^sC5Gb<}bXpgXpib^Oo@89+|5;!@?OG}%lkMK}YhMr?kR+-)sx+EvpIPQ+wIgs-y zbD5M-1#EVr!MFE*(1%2i5B{TkXNL52IW%+QopDD5HfUeqC!I7mXrnjW$vI|veb zug{tJ?a~(v{GFusTp2Kd!g3?M`wq(WEb9uEZ_Q!tZ2%EL_of%ZI^;Lf6^pekC+Bdwl1C4<*e-SpQ0 zf4u<)^S8Cn{l}wVyTlwSRR4?0x9E}m&$P4%DI=r5mGXWl*BFmr508v|Oy!J-XxmOa zU6$3+A?VVpvaSw8j=Zq^6jG6pnArO(1OGiDzMnoW-Rps6jNrMadUEjUX;E=;ae2}w zA{5;z_MYV~aYFjgFU(pF)5n z>naM7rM5;&LAvYMWz&gg(wU$LD6OrHPfbmIH8NJH>%viNUc49LzuX*vQAZ&7gpoxG zI=bG7iR`iC`s~6>3zlL*Wy@oW$|(G8L(?;l|5jjw&e--3irM&hkyi59DLzgQV*IV3Be zbmSY1c(Th|YV{h-G~1rLx4~-Biz_{_3DOd#^(2j37n#=XkhUsv)NHKRe&pT|^RXKx zmm?6!VD+gDD0Dg1c%6Q?wXLv|OQbX4juGYSOZFtGO9dZA3mX8*d z`N+b%Xu|xUe%tH570ngi#Hl^Ny&1x?y>m--%F=VQ^~tHeGJk`p!J&IFT$}5Z#$+pc zV`*S+lXva^F4nZ1z&+Hl!I_b_pPu!UmQ^(D?DQwltdN>uCjbG!H$+Nm>hL3a|*Yh71|bFp!x67fk%;vOCzAQ8-C4A;Zhk?ro} z_zfLGRm{+dy5~7!Rm|-{OmB$1=;gkh!P8nQuid$&iyoExm%Q`^Ul(t+W*=R%zRwkI z#GQ%)^d^VR<(RLJs#~N8ZdNK>NDD2mf4X@A%!i}LR?jB%;=#7eEqe+!ZVp;O`Pkb} ze~_MT4m^u>&)|dcW~-cm2wtbF2u-&{>jfs;D{6Q5nY@i==4e`TWkqhw(1>o^5`<4R zj-J(&bHx4aE3r+tA!a$7)aqFWTm1 z8>`}KLrHRwxPU;%%sJ$~-vk>SsQ>VK5;yu z0yb_(D~tFw?Ff%$J;GHoq{;iZd^ise{0Xq5_O$jR=KbCg{IN&Ho_8rfnkN#Ja&+(m z^Qw_fLOy-u9mXba*=NZ;gcEM#4+twIk@MFd@4d0fvwcJs;8Pssg`pte4R`IArwx)B zX#3v(xu#u6^dw19lt&s58RQD*X02UlxA*Mrot?Q)O@A3X^c>qMn%miYU+1%X*_)DW zzZ$-tbbRzcQ?mW#g9Ig{9wMEdoCHDA%p+waL!~gv7%Xw!gHH0hapRQ?d?(`bM$0Cv zKQzf+U**AqHOApMZ-(~)EP>JuA`E-!lLKv=cry1i-H4Uz9l3lp)=g4P*;X|fexQ>G z&%pqU4MFSKB_$SVX=!&Zy9zWTBMUmJ{bTXy0GpLR5A~MC<>dv%#o>$1JYGITJ{^J? z`R~G#Y4H#>tV%yz=;!p!rI!}t>=RoDO-w|KULd-OE4_%$_xY~X(5~nY=2jNp%+_4w z#Cfs3@?_E1$F<9RSbatsf9KO*)Ph(1bR_vx@ikz#K~p{bmB_L3k@7yaB2PelWcU&G ztRGA5Vt}BWD21m-p(FYJvU0PGPi;Wt-|`g>zNqvTeq&?v2m8!409$`fS>xDrHzxC^ z-({I8m6oRFqZ) zou~b1b{*p*pWA1GGlpv)x&5p5N6&gEDzSAqJ-f(WnbTHnNmJC-oUXxD*#hD($aocM zP(5D9c;xtQ-zf?zi@Zp3aNRMWsXW=*Fhu0eOMnj8eR@5qzUoI#-WY#pWJdM2p!V&HB{tHtA2JB0)MC{Nk%B#$}x$9Z%f@m1Dg!U7yjXOuI+RAd@H78Q|%HqUj z<6gz1r(4B8CcxvV-b&^IT}GDJ5O0V6#QpLN)Xb)F+@DzTO-5F@4&>84A(rehnUJ#~K>(O6x zI*`iIKlmht#|Hm%+JnA*BIa`{M6_f@HM5c;K-ouGHc~kvz>e4+56hC(d-yb9@U)Y*1x-vYeiz-a zjH}Y?$@SLmQse22U;i3Bmbzc^Y_`vFnjpRIGBsmq{%V*$8Nhl_?=B3JX86VcjkJjn zEVGkZpZvRWVRd)>#ozasGHjhh?p)egT(o~gb*6Q{2%&AVy(ea9d4!(T=J3BF%#7-^ z!!=74T&wQ8we#R(vixM9F6r=$pnDNH1Uzr^MsU={A10df?k%H3dct$p>u0NYS|)q( z))Hv*Wu;$Y!So^WcZubBvlv*GI&&&+)t>g|_vU&(l5;$)r7~|~kAeqH9)nBU-mIcG zS#k_MNc3~QkOgv3PbW4ywOqiM*nt%SDSxOfGzp7?GP7j#X94=SHjrybf~7w7;ubXw zM~aa6yKZ{4K-dXER)T>O6FP#k(9@0&v@jwllum3`Ah8b<(}7c1+i-<(iSZ(@vf01R ziuZ#$WMrY_onbP}aZ7bSgMC5?2bs^&Gxh3qK6meamzz`Af0-hYE`zwUFdIzk^NwUh z$S&3C&ZB%B;7Cx}G1na{vZMas8UndS@O8n~=7UeFOjm|2GCkLE%YW zDs#CYN*O3(C`Y=2x+f$KP#UI;;gIR4BP|^sOOoKojO^Z)E*y;nA zb3djhE9JW|+c{efZ$Q3X9Pm<9Z zJYTxE?^PO2jq4bA1DT8Dd(9y)%Z2fs*|S3^#=B51`Vg(nixug7T@N z`K2AT)A7jMHnvQ(0y0#+A_zm`<38n1sP7ey1ra|$LyipKzMY> zb)r4?LssKy+=C32#w&V`Lr!n@k5yXUObe{BM5(LDv?V$}hf7prpTh*b8cFB63n_a1 z1ly#86dK{sp#v0@tl9dv6tX=(HhjJGz2=yn?QSO?5(Z=qCFC4pGpG%1y&f zac`B#`eU&IGWGAhZMJK)JWisRV&)cK~{!B4r8Ia?B+ zlWg}RF-kA2XK%&tZX9Y+L<2-I(nU|{$3`!Ej7vTuoC2(W>iHa>XO6t>-WMT`AI!qi z`T1OV`FJlMYI}97zi?3a>wp3>Ugpt#=5-+`#7pOtwQAxbB?UnzI-j6-Iu!R$1C|+7 z@-qh*i99k{83uO)CwtI%0jPY}O3B)Bf$zyOFKK;VU#u#q2RA1Jgzp+Ei+sA*J!bJ4Wk!tNDCYJG zSJt|5TpsuZjQsL9LH3RPv3&|s+n@uFsB65cj=K-`x8v2xUSW4ntU-B18BF2R0bTR2 zcNrl|o2baJF7l+^@lvvSM@xR(dzjj*FOk1UBb{xRd*+!9kqg11@oAv;H{$GXCij8!1B5G1f79X<Zj?g6k%_UCy3@-|thPeRp( zN)lX_OzrtN;rCchs@H_ffDY}pFqzEdI8H=eD2~U9y+~;}R5u6(!ox)qP^59Z{^d41 zuGt?Zanr(w+tAsvGC-pHQwSY+G#;u3^h(Tg{KN*V#?sU0voYgC^^hoI7 z1x!qb+3}z$;1GA#{0Q-<5FPvlyDk&_1)^?tUjQAEpHE}y!@^vtFQhOII9KXC(3iBFlM(L@DhLCPaM+kDDH1jV)e9 zwIve&@x=eOk`Wc&o+i{_ad=Bu*H}Rv;9G;9zLk5KZz&6VTEwlfXzf@N;4(!?r z`TOFsGQobZ;UTD>(vWeXwBV|&g3R?F)8c#tm4Rpslr|(?`$8uRNHg_&43r*B5DYjj z8F)?v`m%D%LKwt!tgS~0Jwj$NXHNJ)6jeB_1F6o5na}9pUoq@j1h##E`!I43MfsoU zb={mQVW?q561c>umiXy9k?-SPAk28ig1DSWn1bGuxBN&BKAD)vhi9PdZ9?mofPr2w zNM%FI5~c0Vi#5-D0M@YO{t$){DWAyy>jHU@G=0DiK>~!!*+G*8VgAyPQZYdAUx!LN z^tYRuDMJ;JiV~wlUhmciefbvo1AVkS@9-0sQ<$Tn7D@hGV5dX^hq4qZeMiB&w2%q> zU*_}}j$$KTT7P{sn=2V?2a+!2b-ROKEn1o>Bt|OaaN)s1Y;2#|2y*u4UEp%0#af|9 zu|m-aMx4&JPV7@(8qJoet(OOXq7SL6R7F z?*TS?W}nE4{Pc-~qGu=kjMILOapj{*fkf0Hg+!Q^O0YyevtCk5H90xvH3#^x%-zV^A0|Nvy?M(|^1t zCLxE{W?(CV1|AAOv`K~HvGKQl_&SKf0^kA4iELCsAj z*4*IHYt4z+iPTGQ4mn6`zy-owD}R0_ihwvQ*0I?0Eteg3Epa_*YS#86b3Km4XPt

Iq+A-Ci44E>tE!J6KQR5)YZ28>oj6GuFlQx^XraHt@GAfcv1-j?h*sqTpP?$OEN zHLUFB*+3Kwkc2twRnTVkHf#+T`z|4{T>Bi!SR(zrLh4}@jO)7t{!X9P9D;BjQ0|!U zKLv@v0cGQDSZEfEerZk2ul4TMR$1e@W@!C2lDBzhXosBd&eo+s{T%Y(BD*ROfA`8^ z>Ko3b^)hE-y1?u{R8Fc{TJ+A;1R}w@Om{gv8*3O-ceELZNK7&SVl;=_ydz`qZ4Yx~Yeh%y>2&*si| z*ZMucA0pY91l24g2Dsk2?Sh7bqv$096+R?QMozx&(qhkrA0$HZ=@TBB(EUoA8~-R9 zCug4Jrw;GC204KfuD_9e;_25)L^E`eAE~KBj^hF&gK?zr?*qVZ16!&!bab>{g42Lw zyW8r-^`ZqKE!PUNr?fwWQ!KeYq>y@sj6zF`e<_7icO|sO70BrEPFUQxIR3T zsT|cn6PaKvC5nCRShe3r*)^ymYyUzu&D;eb2ih4}&!ib?CD?`Le_~-C^%h)LwQH2U zix^?tEfDPJZLBu@X7CMjoA~~}x0;@BE8WbH)dU&{O0UTm1|vepO}4@??z`Ain4ItI z#_mQxq#>95f!l^yxmIL0wGt@OX3i$cVhgBt)HMlRXr38prW_-+?Unx1w$3y5ku#B+ zvqRE-Itsff#)gUR7D&R9#tNB2Cg+wZ&3nW1&EHmk{ zn&s0Qc-2LhyBBLFF(zE%wcE|hd!|4V2}Haxtd#F#wZ3y6^H-9h+*Ul@O6zFj$^ z;YO*{2Q5ZhdA=&Uyl$9et(qHFcxMFr%4}!Nh=U1}I0D)e;+LjizV^bysn1}q@^3vu#6+@UL>7~8Y9<;dcT@FqW=;TH|V}3wG zgqdKA&JlG;b-v+VavsQhI%t37wwkT>|QS6EJ~F|o~>zV83&NOi;fm$f7gq1i9}CpC5SCK|*ns%tk+ zt)hOWs?%Gc$j=a|1l)1x>b-LrPXtiiUttU@G-gtgEfUzu;4 zeOdN{om)L^C|X``FvglTWE@m|1_Qv*#!;EeJNAEw4cBX2e9f@xqS1WnfsZ5$dx*Tx znmgHqYi--N=jNcpfW|v6BYF0Ej(l^!e}f+^_@;Glqw2SMeNRiR{a#|Eig1?EL1Pw76^3SsF-&k1}N3 zGjGgpv%~Y2MV@^inQ+d8e12s8<@?&BQI`uY;3K;`I(kF)UkB20qR8L}TlOGrJdL>+ z+jYCxH~kucP3HjfD^|aN)C{gOMm7&Jz3S`H4rRARf+xcp)D1s0oYx4gtkKORS6BOI zc~Q;gOQ@rV-Gn8d%g+Kt50)$GoQU$FktfX^p}Qr_W;fe%9k0kc%c-N?`_hT6mw4FT z*80e&O9Xg1e{50=f$D0pzN4E<%cn(4K0Wlk*4}X~CfU+`u)3EcLpBrfAC;MK$B9!L}$$6+|t`nv!%SW&;lA^I0Y0PwGgH&?gLDH?y0h^7KDe7M!0FF z?)Thv-i*4J_nQ{8w(ZjdE?*85!o<`A zuu=#5w>PJ?y9W8Q1R`m*wc-07$^0)$0GvpYu;wH__nxGs1~1f<CPYjQp6&*(b759VY=WK-%ok>ZE2dVY&(Cg`wW0&w!Qft>K-T35cw4P{Gt$CSLw z>(^FeLNe^tid8A#9q4D)OgvyolGRYtmr%U{D?v0tTO|aE)LIR#fMSaWvL!wqok)~| zNPI|EaL2#j(#@mm?#x+=N^db=>^sd$u=s6)<=nLm1^EFxi3d0|qJMvVhYL2EM{uJu z?LREW7r7g{j)Z~ueb+CZsF!M4R8um$egX^i>AaKYv{vxwyux<{#{rL$^dy(a?bN$)8g+MDw0^2ey?Ll^a>3u5~imJCAwen?uJWLQ`jb7LgC<>sXjr#W-QjbsDtO47~%)`^(LL3*=V@^Otg9kX%L*3f4Q5)1_E|UnQ=NCC_+4o@ zO7%48_Z*pr)e+cJmIkNzPYu;bZR5b}&xHfAlRi{(Y=%xfLpyP7Iuq9KtA!N#TC(A1wV& zZ@%F3%UFWye+IB*C1TjGO6`&sBqlFi-o}&peso9r@u%= z2pvv@eCM!euCm?uV(u`Fl9iDDjK*L&ZAtVml29yK%c`yBDF-Z8)=iakThnYK_{m~^ z4)*F(^Y1OP71L_>agqxtODGsUO>Buy&@X-uJD{gkZ-I4)N&PdKiYC!}6aT+?83AMD@I=(uUFdP0h6(yc8V9YjApp-rbN?u<6 zXudkob;UE5AItN8HG4&7?3Xauu%mzp^M=O}s%x#hcCBLxLZy+uWqzY{r*@^NhYQ)5C<1 z8{(gHxEB(WgSVF!QW2Vs`Z&gWYBxll;x)joip=>Y6!uwjt4*L zBWp-RNy%yR;;^gG+d#&+{UvuiX=&%%Oi@NhA;DM$VJxg)Vyof>M7=K6uli1y8aVZ?-$f`&w>pAtIq$@OH*d*GGOc(^SII}f$=r*rJaF$b4z1*0#l>yVv}_X}AJ0?A1A2YG zh+cFwt^BTvE;1zKJ)6AcBRKKzVOo@cZXnF7^{y;FTEuyqc*AI=-XpbbH@=cGHRbro zu;%9G1cfK+$>L17U>%l>)*EzME)#AHT6eEblc2)!HH zK2P8Hf*f>%tU)%OmHN1i+6)^T8&XnI#9-QKYs&~714CL)<}*2YaBr^|Sl>#^$$gEK zywVS4YI@K(pTMv1vf;Ico-rn+B@{@HBURXfozw1~Uhm=F72o-4|l)no54QHPX~MU-ys1Ky^sGb5^#aR>hKTG9UtMlGz?El>9F2f`ZJC*!jVWf zwsK(mD!Co|jVlh1Ei+muSHWd@kgI4~|6sC(v~#ERD%=O@1q~J(;M=~Yl|g^`DLQ?g z^KDD^2PF*ML#BKwY3`}&&xCo~cQj2m@}a~{nwagEmNxh6#a^$IqjlNqSpPvaVZQvV zb$v|@cC|8`O$RMJjA}-FST%5&%v?I#0>BZa{bxl*%2yj9u+K>Jc%= z-|44jv(?4O+t8DnI4S+d@z&>08)vJ`SdZmAz=agF(vi5_(U`jHy2wwnyLLT#*So|i z#k0M&;W(J6(!Bmb4Pql^vyzrw}aUPG1CjGeF#mqbffjWy1+cSeVVVbNn-l1KW> z42C3U1_=`}!ryrDUsyB$Y$`a1pEgHqb0Wmq3JIlZ3{lh^H`In^!aG18Uw>F>l)G6^3>Gekg2rrTkEqD`zA$n z*W|H7XNx&>K@&Gy#|0|`x8-}&KTUBs5%Gi4C`95!&ddl3tABD!Pu3Uu7|#b|ZMPW1 zFH>DhN%mYa&CqzE z{bTmtqeN`1VW*zkOQYfo_RWD98-_*kRe*{)9U z;BgIaSU@-r?`^;$36r(kykxsIJBvqTQ&!QDcXnoHkA@^eb$wy=x_%RZ!0D#Eo3kN1e!^6YDY+yosyaqSd&T=kFw?+vMK&tII8{}7$cbbYtU{c^XN z>anRcEd@cjfWf$Pvn!x~*sRv*vBpElV~Y3=hp(TL|IUklY7^r)qZxz9dgAqLdO)|f z$&7lpEN#41@MKT8!LrW7H#o{3j9N&XN-RCpNCn0>PtAJNA0scfmJ5~xZ8cw8o@0$Q ztZz+7mgtvWYzu6;TQ9Y}|9|4-S7vhZ!aYs`67_qeK;OiQ;hPjXEAsPu2Yw7S@xuiW zAI9S>;BW7LQ|%0$+okl2%-_0$Tdr5aA36^QhfxE&R5ITmm{Hii_W%+4Ln}o^Ab}L* z7s}@hbj=_OutQ>^ockRkcYs25>49moZ?Rnm$?Bl>vx-`H<1<8&)PR*>qqGWi+CzTN zqC@?ER4gNeJ8}G`mzVDbI#1rRVzA;VtQ&^?zp`eo8+?KP3XbW~e>m$_xkN?Wxnr{T;Y<=#sxfqD;-xKCO9;ZHNf{xi7+eU0k?0YSfgv#ljbF=P& zF&X_Ma5o!lRd|)K+qmgV;dnKzrA{%vwywx=u^l9f?K1r`L@Sdzd60>EohB9=P4IS$*nMy%bef*=o>Pxh?3HOhUbP&V zl`Nt49@2j{C?(?0*44e`!O3Py?ueGwn*$IR2?BzMZgBjhClBhUldZNkCdUDuDgA!; zrz#IE#N*n&?4Cp!UDQ3bxi2bM=DX)3q2G6-5H9ZZuIzea=wTGS6Uo)KenCp_K1Hl{ z2&P+pxNxh}Lwz|uEY7xLv|afTYQu2s!u``y>xMsAoHsAy@ziup?mwi!$S;r4r_n@? zH=CbQ=ZghI$u;*j18c=h~gBNGMW=Z)rRD8q#uBHx% z`lJdEs6=C#mD~G{lj||^VfMs7!;r$!X$R6Izy|KCmC<&HLvJUT*FTXQV9v#kCbv{? zYeSY)fK2E&0_JIj!g?rd<7re^qu-uM%i*Uj@#?@P2NxW+P3x3wU~mig&~TKSc&BFP z=WM2O(X^TBoE(pYDgWc;A?q%^q#rG4jfISA`NxFUm#P+z?`}Tdt``0N9VW}zhS|fU z-e98>>aPS|s+LF%6ce+X^$J~J{L%E!PiCvd8vk^hC-qU+W5f2qw;ccuZca(sEeBKA zkI!^kfG7f97be#e?T6dbj#Zz`Y%kzUwPwP}PB~uV{=++PLB#Cs-5Llkxa$Vt>8HMC zm`T@`TI(DGbIJlM0xwpj{wb?PKpls!ue}zeL1M!(rCjwm)E^t#3HR-tE$XUr|Ebq! z>t>BhYv@TNPG+qMe&rwXXaTH9FhA6f`deqtE&8mKnx}zpyR0rp^MKouWXsk3f8I6* zv|LooS-9nqDu#^9*2^>hlx$pW4FUk-I^*gnEQ){&+fQl*r(Yt!ziEm?zA)+wsr8uH zLd(~c8w3d_9|$2+uqe?v{ZjZv#qNRZO(Ag`I1`3V(@fO_9TPFm`RJAdX%x$WHlOPi zL~|y5wo6Fly%P?w!Nh0S%zZdpoW%Rk*IGl_x=TNDc_1#k1tzLOMRP^oAy0_@uR|W> z9wDIfk_{(AN~xjc{e-I0J<7iX$}Ik(`-9w}<+?YSvL+nb_mBebQo!@zT5D@7@<2sN zNp4lukGvS3h?nO_N$&Oo?32i^4OMRgefBjy258EI9whjoh4A;Z4-;k(#?H=Y`bTC1 zn7+O~>qqglULQDYrtc9d7s4P07^GEXBT z%b%E@51X)BvWL&lH~o#qoRDsD9Ph~V#ZeBvE4sSf1N}95WI+ef|K@kC6V17j=dO3 z!92Z&#?Z=zgWL!iCZc{?4&a*{3{(z0eh74Ek3ZisSs;YuB4iP3?u{mcj`)+Pw(G4be zZy$x>`lIkhx?kJC==0<>|D3@74>C1s@^9b1d9`_Q)2fx{S5zPi-w~C)jc0XSU0q$6 zbj@*xc%$gRf7~SP5oPk8eD^IIyCtWmXD7G!dh5Zz`;OSgXDll+rvp^+D-9bH9Gc_ zJK;3*tPQYLN+q*8okkYeMf|-orLbRON+qGV+*WKaPLSv(I{;|^X>8gY$aUU(x<2u% zu)=@%;FASSsoC$+fz!)c%Q>6QeDD~6mHfd0-q2CXDF5wBeiYdDZZ}X-aU^JvkUbcJH)4^cAdqMO35jR0omRYu>XvT0uScYM;0gbMno-x z-{W}#`{3<8iSacxEIyBWq={-@A?nD76?nlW4?_w9kd1kf{QKX%LLi<4zcc>W*hr!4D>z zQXMp}%uc-n@A5TW^MgdhWzy4iuwKZahi@RWsGJ+YP~_`+zFn3yG1=)-1#hT(WhsYO z2C^ac%%67cK-bj%etbP%_H@%R&fGgceXOXz(eykuqLf!&Oq{^p6SpZ>r*h~BCnY{e zWku$3K(pQD!Z#gbjf#*QN8}-;3W$J;khD+a&J|d~j0+5d`kd$wIV@gLkdiN-=2>&< zS$^HV8=I6#VeTga_*JxS=M^$q4s#R`qDNRr}Sa_Lkx@fyH^N^Ps(rq7oc|Y z*w(@?lOu9oq~OcO`M|6ST?{J+PyfUO>b3*CA!7OQr4khn4qd*Z5@pj8A2!{f-5E)! zoXJ$Jbv@O~(o#KE21}lQX#@m z?VES8bA%Y=2(e8TXmcKt{SHSb@;Vb%5PZIB;*f_sf1j6_cC??yjnVibFv(GgMfpwN z$;rv#UAJ7qa?gk10`wSVx`U&wU(hJ|d3k~0jdWm;ru)|dug$#X478hTB7q4bNq41FI zjkQ)(R>mqf$*ny)xwwqgYlwt#{wg*sx~7}8$M0t9bzUACB{+brw>)jzC&DF06vZD% zZ@!4Z)1;^NrU06jh~lzJ0-p{&ch(HJYkxsE-@p zb@zJqz-G{vQd7f8l`|O-mmxoFGvT&#J6LsQMImshqln5SC{mP5gs-wbR0Z7L1}bl9 zYVI8zq&aUSpc;%bv#U7c!_GN}Z{p55pYz2sA)fQ0RI2vqH2&yX*T1-*QXslBJ>kZe zWLB4@{{WvCCQ~3%pe%iZ&4B%TMufw~wto_N!KyO?YlLe%Xwyz53ucc0Pex#AI1-h( zq$F%LGa?c)3k!<~LrPw0simZ!6aL~N=pzwcdVNOfF5PTLOf*TR!e%e?Gc+_+e0}A; zR~F89H~+6R;={N5dwZRid>8k8`%WGeqv#^7T{EjH_yegKYg>;#EFGi~VYyTq0G0AJ zSjfCQLnqt)E#}v|$n9XvKED3M{Zq}@%%$?Q1$!>n=k3Qb??W_v$0Oz| zn?qwGx1TvVBo_6bDh`zyQiQ1kh=q7D0w1yII2P30hPf=uRr9nNFkm3%7w9yp7Z(?$ z3Y5X^O&Bx5CH!PCvO|w4OTJSNP%fPQNU;YfqpntiwLK@PpS9Plxndl_;88&@+y1(-Q&j{M8*^4WnB5-bQ z;3A23eg!0{Ys*MVN;+*(KQ#Ke(0aI%y<&4>Y3UDmq@5TJdYyF$z4Qod`5&k@xD@)i zFYbrv*b@{~%2mzHtx2{=5?x7pOF2Oj=n%*lvaqHZ`J{(xeX^;JcJ!DsZpD~Nn3F4$ zT~BQ{X#g`2i+y92bn<{v%}4NTv)4`$$q_17PR;oJ_4K>+JIDpAWUyJKsi|eBjia*K z6;ANzL*W}=Z`7w8esklZJ)YOlkYfDEm~IISLN!QRZ~^0Q9FE_ejHC2bZn-LUnR$4I zXUq9nIl2L6l7<`M?B8XMxyTI+_+~XD^#`nOhH9!4x)x?p^fPhCDZ~r+a9$9Eyp>9_f$Q&X^0e(u{ofN2yuC8VV&-{Me zwDk0$-OIZAdU=Ix-MZVAU%$XRdXAr;hkA>t{aaoJZoOr;S@4<>tZ>aG4i{W?&_v)! zzJqaW?LgvA_0dSio68KI|5eI&g*DX%TY~~pq?ZpQi15)v5h+qdiXaKnL8K=%At=4~ z-a+X_dWR6CgrWi>LJS?G_g)OW2MGM}JI{Z2?#{)&+q2)bXRn!A^X~VVU{~(EKuOMm zMjpvX-Aa{0?eEN8OG}nV$Cok_k4xIxa`D=iJmSu}Yu55I2RZgmgc8J+diio+!#||^ ziE+iDK9<0IZZyeY5d7YrC!9v<+ry2#)-qiw85TcgjoqQ7+g1C8xxhzi5|njw4^oNM zfEtcG<=?2ODN}|v`PYues>adt*^Lw4c~7M`92n_QFIv?<7#8rXI0(i2coy{h%L={B zXXP^X=bL$uIx2ktVhD+vxNYM*-t&UH~uthKA(#TH)hT77_( zmiqzITw`2YRZ4Za<2ipw^=R&_lc7~{I?QZBY$--~Z9{qYs9Obs*0{xxDr`IbWEeg<^!_tl5u-iv27 zjjhjGmr-wX_D61qaYWOCjg54Ev2UG;()yM?og$Q}I0FO!Wd_4@&?0>+>uM}}{B+fv z0s>a<aVIp7`yz6#U-KY@8Kskkkvm72K9bl@Rjv)jYbz~Y}Z^Wnr zmJo$P=bD6@^p$768pjyIABok*ENn{hcAjEiZ6VdPab2oY?QD!jV=J0Wo{h`zgy>|S z+pOH5lpMw8KU?>$)J}8Whp3`^P-ZuTD*nd*|b7rsg6YM-mW+L zEIQGhf`TJ_Dq!QGDWkVyaIa)Bl2bj>;7Q7)7DVSKi1(}T8)pKHuVs<7h~^?MsPs{8 zk6|^<#B<=wE1D?nYKRq>p~QLhF^kr#(qLxRZlmu~{GXX>%u=fl<+kzNC28H2_@i#U zi*3M+Iz*dZ&)1{=UU`lZ_v~{5QNFMQE2xc*OZev7IR@|T`;sq<9Yn`Cqwkl9sk0y- z2t-P)7c*KyUlP-3S=S^gK^{p~=rgfK)Wc$Fl%nUWIB@0DWx*}_KlQj~_krJCk`X2p zOkqz*ikS5(Egj>Lw1{$N`M5!35g>t$C9;JC>!L3Z0m7<(PPBq!irz)nFea1fLDGC9 z;c()~PNPSNWDuHG>#w8pdx$0*wWOLD;bE~#@Fw-MD&8+)BSu!8swz4fjw>b5$u19Z zo}3URvf0@rPrx@NGTry1IE+jMAIXq1e_WNp=NaM}oLW|Y?QSk=;1 zraM7m*pu{ME+gdn0PfjmKEfbBwCkseJ1)_6R7}on(<*q(KlgrrSjq;K21iE-)l9W~ z>fb|JrYYISmH#O5GYTOCPJtL3l?8HobjV-ZPfaBxSOK((-w_3pj}n4d^lP#m2TBY^ zx#7vvsIiP24abBEN6Ls~w(P&`Hl)lNUTY=M2p=GM9$ioF9-knn%5Tcfmv~2gc-$pg zm#LXQqTFB3%F>eAMo7ll89dK**b_zYq zs#H^o#JE?!Fi0b{4d;E5-c`O8uGx6#N+Wm&R;5THFm5ebhk*kAc@6u848|0tDkde+ zs?q8QBp8sxp!%l7f@8^WL;ko?Dj2nSJf^o&>OXprIC2(dF6P+=nk0%AcXF*3lNUS= zj{R33sZ^DIj~@CiKB|-QyTJoS>*NGZxT4J+B}&V}QWk&q+@oj^v14iY>78NCdJ26b zLe|jAA~tGq@p7T4-OZI>;XHWoUvNXbxRGRJ7jY8o{oHc09Z zsU^wQ0y9T}=XZNObcCcG9SOrU%fFweaLen2^Jj3Z7XqHL3`vZ0$x0f)W9&u40CSbU zN&;Bi81b=aB4OJP)aoy;v?IdzEIa zil$`?o+O;EJpl!z5b2c?-ZQCL@}~Mpn;DY^PXxz)z|AlMyH3Sz?f`awQN8->nCi%r zd|NS=_&Uq`S3AT}j_rvF(^$D>mRO!2ueG%w4C#+-6R?$hRusruT4P?3`e`etEh=Ea zDXl=|*h{z2q^TnVb zxM(IHXCl;8Z}mVw#%k~i))X(NWT9`{R;(?f1PeQpnDNjK6bmujs)%$=;hNERkTTLP zkWZilFgy@=an`#rCE`3?+mMAd1G2EQm-~S~Iv`__OfVsEhM>Jl3ZD1TlW>kskL}S? zxcmy~M2(3W;6*sS;)HK{sZL(Ed4JAp5gYf4{P&Zk^`+GERl_3g#gU+`8WVL^Wf}1) z{m8Nq9hp-e*Ph{tar6(HtGe?dVsX0$mAXQGzQ>QBC>3hsrI7}}Y9-TMW+{AC>qEc6 z-NA_3v45yeQ1uq>bdTT3zKUsBO;BEqqyL^m8P;Pvq+- zWE8t_=YK1Xe;|7W;+K(;xmfV(=sQ~Pt2BUxLtZkx`01hn;9V{3$t<~=npqQP&Dl*`?dD9=jrpUpLB1qKg}~4e5eCwHK-;1vpMD&$ zCL1NhE8a?dW&nVTT-g-0&gK*(yDxhjU_EO8|5p%inRo-^PXk@wgj`{hqS&E+K?*tm zJ^l=SMzDIY5JN?3pT0mES`hirG+>dJ^iHUIw!0*lC#B~+pmCKZik6Ly4d8NNtSNWn z?b`Z@$N(RFLAp15ogM;KLMF{;2N(2OM{9aoNBv?$!wQd|R~nU=3hU+4nIb1z5OJG6 z7m6Q_^;yM2v1$;X&GBVN`N=$+8+@OJK_l#j=Wq8*u(3npy3H;5xWY+ZNcuYl||52ZY zlIQOy3xE5V41vE*B~0BJAJQBTG(z#kg>=M{&NKqgT9TCiY{fH)UjOf=(2UGIi^Bon zehF&lT1?iP{dTiH|IlBq+0}F1%e-B(}3Yt?a=ky{!38z)7tj9ceR&1 z<;_mEY{)#ni-nB#U$+5pIShtP0N!x}MO>dYtx0ze9XEg#hF<(*_Ve$xsc=gyd^2<2 zvWtdzF6Zl$ic*jvpcy~sy`0w#yhiEomgVGM)#^3 zShOQDUp3>;y`Eo_5lvQ}ORxHL|22e>BYw|5t)ZIjqkeYuP}q;5o*#LPvF8cJn3;GH zP1c$Y4roz{;nn=FUj(dySCoVD{*;^ZpWihrfH@YT=jH?Mu6S4r8S?WiIwW+y#r;u$ zOy6OB*pf4_ud(2Hdc(e%9_3lsp3x@p6|6=+Xr9r{JS;Lz6Bi>i;}b(sHgDGkZ)J0m z+I_aVJ%kz0X$$y`VJ>niNK1K!Q(thibl9A%RYAJ;V>1p<@iSl2rS?OWeXd^DZsy+} z-8q}o+gDBuWLQaixp8SH?0eGp>8yR|c%VZzFJQLbn&}~W(c%`2xcQ#*W-OcI>(a|- zJ}3gul^MOEiw9a04L{z>TS)J^3kS)~=oGN6^c)YZ^_Dlet)h}Pu1!>ZgK z`~rQuG!>BjveZ>j9;-JeDN%|Ho5R)aZxmoz{1po9^Z&(8bttIS+?YN)@CdvXDIXs9 z6UqvHqT;5?oB#Rc&JO-HQz>4BV@umu+4jGr^A%~ z?gM_1Dl+5~uR1tE1fC$d6{mN%A9fqARTwJE^!p&WM6j+qmq=)-W z4mbj42WyA;4{K@{G&)`(0$f%J7-g}2_Z{b62HAi@suH}+T`Ad(rSpGxT)PQNBN=}{ zBs+$|kfQj__m`X&vw^}LTf&c>7b6;PE&$Jt+6H7jM6xLtH+I~D29x6^MU5V86oNC3 zF}F85?O(S`#pGm55f_!Ut`n%hfqF1Iq~u$gMP5TLtJ7{SoY(gR(Jzh;@rC4D)PDD-;By`J=;XeQ4_S>3pl^*al z8{8bxg0nk+LY4ZkC0AC`ap}xt-wME|a6s{1Xb<(L+ZPp3e|)U_{Q3vwb-(HNd6VOl z1&@bmPPg=v&%|)_zko<5W43=R23q@=4iJ5TgWTo2eJpwwT4UHFD5z_88-ppXbz)_m zzGc9A9t=d`G@Y-@?;M4Ct$qWaF{G!L|JxO#4MuL|3Ap zSQa#7MYvp&TwxN_Gfvd%>3SpRG<&0N>W!TS$cYqqj7POzhbmv-PMhmJjQit#ZXz+> zD9uHFE88p_n2V=I?BN1@D)E|IP_eHRLZooy8 z*70!fkPGg$W_jf|;E*b*Xc~UkEchsl%_$sIhzmxan-G6}Jcg~>A_f{Q7>npP9J~VB zZ|~-bhVYiz={+rO4*YcY%a`P*r-(2t>Pp-SH|qsSchFdD3Mtt^SDit-W1G-|udp1f zL6>h9{P5#NM9ex5^V`EZ`47QfJFhl>hN0V!DNNmLKLR!X6xCp~HLqr!j=nDB?*A~u zQE8s-|D6wp3c%b+l*a@B@&khXCKUSGI)E-K_OR&)T1|I9UW#v*K#9JNPGECw;mLyk z^&p)N18oGyxDq?Y>H0p(tHLZ$QYo5^t0gwW7R&&u4Qw1tq?YOa` z!2Z2GWckhHF;t6MUS9s>#Jyp=+phIkui6VzmRsgwo;Y$7!f(~c7)e4w|Hi4m;q|9( z>8B*0u5!QnIINOPES@w2)-?E`Ae9DRQ9J)_$-KSA!Ib7}it;FhmAgTwHV^Zq8#9gj zDtR|rH`Cc&v=)~EUwtWgA4>mddulP{)C}mdM_GH~6bC8;YV-fYt4?Ry&9&~kwfx>U zmLPq3@j6`AGtcHYc4unW|7tN0+_OfW}u?g0m>zl{a_-6 zYPHhIth*SdwHm%*7NqG0Tg0r7%dv8(9rO zwre*(?g;n^lD@9pvphH~NBb{D`LAx7Z5u_L#N6fphps6GWp)VKJHCW<4rC)ywbl#-NnHy; zlDl@-luiN5FVn*VQqRrMIp1bmPa2x*H{|ueuHL_=|2aUwZdp+PUtsmdrqAVw;({xB z7a##X&e4)e`*$^mS>}w-I4#slb8V^jw#yHNZXB4flU?-*5NHDr_(hzxnVZiy&?<4I zA`PDf#j-iz4JbVQRVns6g2NPc z4#L!gtrv=uhHKJ4Zyc=myV;4{gQ`Bg=1p?s8*X%@gq^`4#-Xy9eGSGZCp*e=Gn8?Q z_34bq;&tO=A~mN9=r6pgZ_Ti_RDXJ(-0a}wjE#DAU|&dWnGCj9(NX!9Flpt&D&P_3nKC{O6uI_uQ$P zTQgL>u$$uT>R!FNdp*y37U5qNBoRO3eg*>rLzI>hQw9SAp9g(jg@p!vr|jX41pR=s zm(p?q14HWj`+z6YA>o065ravK39GtiovwMff0=)Kyn0AaZ!_KKMI$*4q8K8z{30e^ z4$q+WD&w#rQ)pS%Fu$@;(O_BeZaLp*>mqJ*@|m{MMO+Kx50bQ$KiKkO=Bmy2iHq1w zyo9(_dPs|55B^CXqw}#YQ~QWfsQvBji0t28 z9NiSqmNnHhF3G+$AP1@im+N(eyp9Nk4hCCBYIRwDIf=A_BM{;aDy4aKg(_=OpHhoMhZE6mx;XsBk53*+dL+r%ad2oXsK;^Qjn2fU%=ns+UlK`H zE;XM@F`+jBeK*XBC}qRbOEV^^mia=-cZlHhkKL zz`Z{d?kJ_4k##>?=vXyh$Fg#P{Ehv%^!$3NK=?JL;KX0m6%3W_0cS`qAXK(ZTwUhes!Jp(kN92vo|!w zT``hH*VnYh>N6 z+Y}MKeBdw~MGpD1kZ`h{JKY*sjaUcV^KZG@Xm34m_VrXlvK1QT3YARp8_*kU0jsv6 z`<>J~M1Y0t&rF?qRl=U6p}oeC-%&Zie>;wr0yVjt;h}XXw5p`xaP>G(|5lywEy-r> zc;c3G>!Rl-_}SRIb%j&gTZF&F?GXMv&4n#;{r57X>+~_fTZUMqJV~%#pS)6%Xnt%$ z>BOZD+u6f-ZuWtAr z6Hh$2ZAlih4v$@N&cp@XqGm7Oqsqt7 z`>{jky1-F=5$I-b>gcXTUf-?a96QLV0*Lh7_XJ*#H)wu4<5Fn5m#ECppU5}!$pva~APY>RVQ26{UPLT<>=mXyKD>zcMNg8<&a3GZ z^YZYxNvjy6_w}L9DhG9=p9~z>M737@Ee-oh+^GB3+Y7hlAp9!Gq00%KS(|cmMU0e1Mh)(2zki7x%l$J~mKyId`%>=V zLxR4_Pb2<~3!%Oq-oyQhK$qpgd4KH{1361)pl*_$3U;o;gA6{0V8GbJ>haq!Fa5?X z3H)c<&00abbM?_`*6dub=0cKJ0f-8g>&`w_vEC^HlZb2S?)~#}KYKVPUI*Ua zb!szn?idBXR#Qq9NNvM3h(hmX*#3q78pZ9Q+I%TQ_%O*I>PPs*G|HJXD5Yrk8I>Fv zM?`rAjD<|kqj?xVPD~{nE4+Wg1uQo^ZIRdnXeT9DRtcG9#q_v)7`G3 zg6i+K{E4smz}Z%d4bBzo>({SB!ono|Uj(WjF6X=Sw*`asCVQL+eQ@hW^mmAIHORoV zZlEGlQ<#1BG4Kyfh|*g?@jCa$AKVgIJ@6%vM=X34lqL!6@m(m3N8B`D zl>lh4dtHC%PKue_6euUCfvxj1anTrl*BD*TT}M&b4rHUdC485|&?$mmU(mhc)Q}Gz zohh`vaofUd+(x6+FP45Ul6zX8GW;{2nWn(-H^(E>BS(=;k2tmKz+A=nVVeBC8dl2D z@~Erp>(q#hrqJDt4Y@ezt&1cdMtLON#{dM#^_0}&*1d;Z`czkqy`eaIZ{JS*^fZz| z0-|Vx-In}zY(rV zC`J7dVOS%8cJ$B8oxm}s+SQR7f~T@X(!Y+Jo3(z>33~n%^RHk4|9$Sq^Z#j>@c%)i z@gH3{FbUM(IZYNOK|+9!jE*krXh&G22mK(CV-+)D3=lGh2;J)5vfp%V!%4}O*VV;u ztqgrY%^O$z8@N2#&6-K8$w-TfLm50t z%e5}>BC{xGjj5@riE(j4a&mIbQ%DJhClB3{=nURrEi(5|}*JS^Cn}Vdn*7ccM zsLQ@SCi6`pXe4|oVw5E}e^{zH4uCF6SZw6MdD}TD08ml zH!zTAv8BcRB5_??)lWs#FJu1N?ILBzVP!Dua$D9I|JVrGHmGDoyNW0A$SJ(u># znZ3Qr4OOLP%@5WIu6)k0&>?{vtYX>C0$$)Q%vuQ{@OBP#>_KWH57?J zh6&r`Y^5Ozn>!&W2ojQDLn9hNxt1P&w01?I1Qnvqqif*;o+M7$s6n>z?12sdC>%cM zJ#%EX-|Svj{kz0U&vI1>mU2;{b4eJuxVW0Bse}IDpN2+8EYn#&`J({x-O0jPUR?(x zxy0@hl|wG-EOAL@`x<*Knq2;@*LiW8?(Gpn!i9&Mn3|roJ^T}nhf0AK+Gd#;(!#<* zvr%5nl!Bd|ot&IJE;+e@k@=X1rle$Uao**Ty8_+Xq&*1*Vzlwfo$oM3+(R4+Vu~#~ zBn0~N=g;;$*<5-IGcz;xT=;BkZ1w4$`F~^mP!Z5@jf{*&b?17twB&Mlg8ADXs`H!E z2zXtC5^1;MyM$-^&KzspF4o@!id|0X$Jx@CG;!PYAp*dXD-udAGC-S$h0Tjv#C%Rw z1O4(PoPaCtlWwobUt1t){&i8b&|YaK?7n)rEC#IESniA+GyKVQey@^}$|BHi`NkAx zi2dj-fCAA3j4tA=+F}$Y?LB#KY>mZ5fWCV2ZeFw9HZqH4L1_95#Au z>0f;X5fKpq6*Jhep+dw$M#`iLsdckA|6r&Kkt)Ks{X32=dmd)_#DW6y8CDkU^L&wJ z9nD!bdS1S93QCTUq&d}@nOSKmxxO>k9cP|t7lPv1@WCAtX6E>)F*z0%R%sap5l)2D zp$OTj>!&RZ_ZTZ<6?EHJnBJ|!YA-DiGNUrN<5!t^S9-h=mwo&8@sY5cXk-H$Mpzactj-1B0S zOKWljM!{@uXs7vd`G?9!b3%yvV7b?+?tqEn!7Gv8__9h!!cAaTby3a1!D9V6 z^S=C$;X)z&)7BMPdi5q$W7C+#ZT!Q~aukjSAADs;1}i1f&S7qcyhU+(1J&ZsIv)zt zi}k*m{36G7_Ec7{G4qMnQ6BG(O1HthdER4Cw3f-Rv(TVVp_U31Hw_FuUZG4-Nxmp*k}XV0AaDQRIFryhP@%oCWl|45%7ong#)qqJ=umaDJfU0%I%z;3|3$7Eqs7(KA#n7+_m|2Ihq-V%&@%`y>)AR;Tx0b*O1&& zWoJCvWJNRN7g+b%c4tMh$u({)FDthtM^Mj!sv%N<#P1Ea(b_xY!pDQvtrJflP5s;_ zUdI+V@pOSvZ92~L`R3eoGjh>syjEDFK(b1l0et|eb27{6dOITsH6n0YBACVsH(0W(j>Y6 z3v_c96`^5ag)W}-AKWPE=><3SL@u5nZg|<)mYmBjp@kPL;F;tzhMw_`#*19oZ~1`E z1S(9gjjq5tM`Z^*1+V}5p$SG}^SnYg6J2-^m&Z^dj zPEneaFHgb`D3OT@k87picDDq-Xa7~=m8 zhW)B|Ot7~iS>|?Yg$CdV#&AV#IzQBtoj(#={PQV_Hk-`dqcGES-Ql!emzYB2McY%qI;g{KTOhLTFCIvh4eYby<^8XB`xQ$jBChyq>6T^mFS6A)rI zUl2p+8`UA7h&Q%RFv|XPU4*Cl^&Y)as7kmAsoT zEpzA_<2xO%Q(xnYAp{R**Y1-1?#adm{YGbX=*#6lVxctr#3n>N=Ag^8Tpon<+iqFj zJNd8KOITl%$}~amE8y)|>ikZb2ueI)0*o#T=N+AL1yBtHmX{XrCja3Dm#JLft%u!KM1oP0W-wPu1 zUX5;Z=6FXMV%0AW|8g3xTc@P9Ytv^9MMb5A@K= zFmTdIrz_DLi$Rl%K^sKGCK*BW@D@OTlL`PhfDnB79=bNWgAg z^_$F35uJpL5P|_A6b69+Md}xsSk=40SByQsAL8#_xn^(DUHf-VlBmd0+#mYBPus9L zK2=e4R1i5T&F`tK!%Y6G-1wY_rpFzWIs%VWPgEZfZj-nXFxVbF7cE!A%)q0wFhkPHxDPYQ~pZsrEB#UE3KzmX@ai_lWgpvIlP)!x;08Gu&^BlCh2_ljmDE zhJKr8Rv`~R3yuFx0r2k>uX>(EyEpQU+D$wQm|pmeUlg?o%YHLIM``!-%hnj{VY8(t zwcT$pX+>HvW}%RemPbLCl#@k;P%OvGZK_d=ti!uIzXdt*gCnM^gFH`c^zcvH!3w7i znbMHn?xVSQk={A>I1Y0(rV`uQM-kp1kPvf3@nR8Mq`y1?G)G7y8h}9pJos>FO{4%V ztw1TM?xhAi%9z0sMhG1viz~LMsQ&4%vM$nODdu8n0@mZzs>ZQ#))DkIfk01q&niVWUyzgiV-WrcyEt-c0pDbv0ou@RYj zqiJ#FGYXp_)Aq~G9{z`p?v4lSs5B=K!_XB6lYn+VZvI=VKYvkwK#vaE>FVsFZhxDm z;P%i2GNe~Xwk<9cYomvTxqCI;og;dCaFYI@X;$&i!+tcqyDPTe5_uzS7n3a->%I~bjjU2+#_dhO`*oGb?N(%byUlq}M z+p^m5xP95OBF^XhBbS*f_H(W%aqP=MPOo6BciJA_q_Ihry4II}^A|cR7`7}hDdy&<$*@~#f=&gOjs|(iNdjj+nfy@0zidxIBZbcIw)-= z*mNa*6{x1KreNW~B%v>u>bC!3D`Y|%Q{VF||0w1X(N53hgLY(V^xL0PEpu6-gNC(n zGV_P_F$!);r@>NlJtycL#hmb~iNy95Z(XJjkDO<&Xmmx~c^BoHe^VX&nN{Xr1SgOO zvd8m*BK`&Ek&^D7CvaoD>|em$Q~A3Cy%Y{o#1p@{fkQz-VPIe=>u#MWrBCE58mli` zz3$u`U#j+JFlx5fM;);iZwgVp4C!vGcl0MDToMQ`UjpnpyE3zecbGhtn+Q)&xQ^u% zk}s+s^R>xQM*M;`78DK7v*d8|=i6XRCCc2a=d959Ib5+EPGa;MRD;1nfze^nlCxqr zgJG9Lx~b?Wnj-L33FN{s1zTW1u|*er2CSl4I6~ywatsmSDM)wSZ^6XaV%li4XMNQo zTQ7wQRB4nm_3{1{yuvbUKFfp7odStX5*4Ojz@vQJxJ;At4%bt%Vrh`LPY!|IY22)d7i{eDQUZF2G699?Z6 zY6|?Ep$~)6Le?8{mwlm{o)(z6D1HMMPbXex4yNbWgd+q|en1|};??1k#Ta4EjU(SR zPe%fygG(Tc;%?Gt?0&&f?{B@1fH|G@-O?=%U{1L5Mb|`;yjWfmPQ`kwlhB-%NYc__ z`t)n!pcX0C?W_ckIvA_qy){wt(aeNXl|C{u=^O&+55l~O>IbT=0m*nH4zXzibB1s*g=PHO9r*?znu)u* z`OcG2#yShHtOPX`EL;ek*oA*poKDz?%ok4&#ozK z{#%kO8@3o8<(rmNuTUb1$yB60g)lXkw#iBiq$slDbt42r#z&Sxe?w|mb zpMQebV~#nC@AzAmiWz>v9{%8IR-i!wofE{MnZlt-nZloHi!83w&0I;VN^tZv=1t;M z)WY@YDiC#yues{^HYi#?DE`})Q;NVaBrYRppTU3)@e`tjY#e2gh2gS#GgEKCFRP^* z=1m)sbAaTm3;sH#J?@sRzNlmxCKo;|397K5GOG~!_}-zEJPc4w3Z8BH%ogV#LPirr z$RMVoTX6j9rxNat6cdF-l!rkG06=PT{Hd?@iI(ajDmj8pMQ@7RbS8c{4H>a?PDSU( z21|tp?m+8FE}^M#PC>$sA~4SGGNELU@l_1m27dXI!h^=--0&C(A{HFY?|4dhvK6{b zgpAN;u7f2{Wa31K*}_GG{;YLFoW>CyA^R8YMBV*_47-rHbX6#%UTC1$Kx+Vs$mc2g0-BoO zZhP?P1|hCxOLbTha)~VTQ2VWFo8P}Bq{8agKc&P9sYKMa2t&;3Jf zs9&h7qW!p4MLwc|n_I?R+Iq=_=++6SmJ{oaWnBVug{1-DFJap<1%=oT24T6!agYwk zOMQxq!$xMn%9srRS?D=44vEv;(|x`uj>rV|6fEN$3~`%3!J-$@nf>cOOVEe(?Po&d zFVPwMQ%&&k2iZb4k|ju%AOxsxmiUZt0AwSQL>72PfOG3Km?3spA7lXqINtaUWGWpW z`ygA5kAOW7N-JuoffdZ33PWE1dH~v)3?%|apS$jHPU&Cw8M=GVDIJB9s$CQqEfDtA z4d4l?M=1)f2Z%_SP-CwzZwWa`iDiY@V?(+SxG{m*egZ56FDwPcq3JaBN~@at#~?gT z6YywKE{(G)xqPA`2`T5y;bIcmK7cO~||9=%1#Ff%VTLIU^05Yn1=JR*!{ zwJxeH>g9DI+C_Q|VW#+O*_zOgTti?OjyO`jhzxKEX@-SR{+V?6bi~%Z2g}$^bZN-N z1{;j>9sR0x_z*Ht*jCsl8$EaOPovE$VbedE=Mj>{lL8*2KG*^q<4npF3&SPh7)K6= z*FCK2x_uoPc_NQiA#=)%@A)lkY@(9Q+YVL`;|Qct_M*%8Fw^nGLQdvVO))~B{K#-> z;1JyK5Qwl9Jr}S+eC~2XUAz#ne-auE#j}P7!~S2znqGwvi~|;j~;Bi3bHO>4QY&e$Q1}7j=#*_hnbLM+-C-W+n zUz-h&;0Af(;g#n_ndJpXur~DmMN<9J& zKaW{Q(FHLh$;`nUp2PPbqi#o5<%^P7yR*W#N~WncRFvmwR5!>>JKnJ2zz?XabA(k> zX%@)MSlW`qPgHnG_>ufnK3O&3(&s*4+V8?G(lG1jS)Hrbm3XH!Vvm$9rSKgXI!-Xu zV9StxJf2%?8Je4-{wvJ%k$I4nC!QL3pKV&d zl-#*{zo!5jI|~zn^bz zW2OF_*(dTnv)Ssk!lN@SRu~!Id+4%|!GW8X46@oOPy#uudl7tk25KuVer^c-z`2sGNL=qvS9 z>a{JkxiKcIC9}C)=zm`4^C<{3q3zw@ZUmV*6uwq-X+ z4{EAP_;QdY;>gEek;lOCE!G!)(w`uW(ezX+_oQJ%NAJ-thJ?H!FO?ln5_EEIhV z{wNbPT4D8|=Vpyw`)G|}W$1`1S0k!Etf!*pu22(3Ec3YOm7&yUCJe-Ys;5$^InqV2JM&*%T*uvS7$5Ua~*s&4CyUy$S^Hlx(PH;o1qMW4`25Gw9O z3YxuJS(U_$ZjGIQXxa2F#c4@{?mU&8?VQmIVkSGtyIlT(Q3rUB{l1uUbXR?ahlj*D ztX-9OA2hP;aXX7Z9M+lsou~dojr*VL+MdOW`sy}jUUx{HJa*V!8)}LwOu^{3-U$ci zS@IG|HtD2)`K+-cQrm3(#09Ei>WFKD$t0a~e(mqCmugxY*ZR@kTUi($BOCWa-Km@- z@iP+bXvM44oMHKgQ)Y03_X(F;ejsRwg>+Pv>8n)U=Qx`bk+v&ijqreB3!TV5Yy&`lS* zb-7>0W_N3PS@wcta}zVYR23BO>vku)#u6OrJ}4iS;vXQc^Q~gzL@|Bn13O9|-pAx) zM?QFul%Fm~EG=YY)vMYSClp5Gu-cVLM3owsSv;-1*J5-I=6h)USqK zY2-RQandTj-l<$SyQnc4F8ih-7hraf`eJ&J*i z^a*e#La6TzlRCzq?ZGM7|LGv*>Xda94#LH5edvc-=#}O=u7Kt>(kQ3T(2pN@&8L%@ zUarV>FbBKgSH!OZ+7GSIKH$1J_IuCU+9%wL*VmGh_G?PRhvwu&E}xq8H@A1(G>jyd zF-bkGZ*BW3=#Hlu{!Vl%Oi|9HTRb-IV@Y~^%|1a$6cOBvWq@;X_NggHLc|FFE_q&4 ztn(H^Rf8RklZy}#H~8i>xs@v^Fm@e%z&tYxQ+!gE$Kb=@2I%DSu5?93&fYW|8_xf; z_aL4AW0yo!N(N8pyKGlM<`}p%Te5q+=BaK|K*(^{Zo%#TeWDkAof*>RdOIL(cj^Io z4CB8Mr%VnUCVI*q-=x;9a7Jjg;EaC?bT%^PHy4ohc~31rvDdlT0*U89=df@CNOt%{ z^o_~zp1!^?_GaaLAGO{~e?K8Bzr|Qhl1vLo$osyVj(x#5TsA%keUp1o5*{>==dZybe7L9P+0G#Et9ym$u<_KBRmq zmy@2(nEZ)d)hDD#!BTOEU#}YOrf(Sg6T=0}+8thBi?SbJZw}V`P71fSL~D3{_bfM0SVjbC)%q+qy2&`UC9MH#xQT`7jp ztL~N7ahBmRxxHmCr!;A1g)UW}Q>&=xU zw>y|!=qHk_hZ=6!p+l&U{$BSY!^l_mo!mDV$|47E=3DxXK#=33%lKgO*+9^ zFT(JjgM-oda2&_gn!%B)bZN)A;Ey;RGET5@z3V$Gs?ns~Eyrg#R+IB?G49={&|OY_ z8dJrQBm0es^A2st#jdJ2V^+ygEhoifNhExF#rGY{!o?Av1%GQocOuYNRAZ_kSgj^WadBc z1SE`|atTPY zE7L_>C?*qbs&xvWD>hN20i~<|K^3?(Ybrg*4IUVn7X>xzvQdM9RFu%MgVD1`eN2!c zAf^;IWUHGA0YOia(-~n+XpzmC|21f#Y27pO>E?iF8<#Hh$KQ$LFP!e1Xd7$@Ne|o7 z(vH*=^Z^fh58%7#X_)2FSxuCcmH#Z#X?z22K_YCa7gt(w;X@;Z25g0qt9=Tc4N&2< z$3+6cnVrGd;_|%huNpesVt>uJS500>jsjcV)E>3wbw9O)O^l7Oedh^&>COj=5T@tm zf}(@=cj^@8h()xzCtoV9E{I6gc2~SzZ zT1Qz;rFXrfP*qhG1s2M}(o#ewpm&QH06+vb0@p90K;`}FK2#>Z0sd@ zf+`?|bW*R3k^}P-FtVhoN;1rzR9;TbcDd6)go3YWDy6otjEi)}@r?SHL}Sy39&7+^ z&Ya(0%a0gRpukSe&50>1qfK4irb!t^TU$xTj7vAP<-3u+G`#E0vhfV}$O!)YE3XRu z(gc+E_V&(H|9+AyB>N}nOuGmy#Z*Z{Beci@z^J##jF4~YY`4q00({6BDSb=+$NK8p zO>8<=Z(fqa?0>fGy&>dSqTwJY#_A4JleXA)$%*e{Lpxgb zXY*Oi4%m_(r#3QYNCE;fIA;&xzULr_Ww*Vgq{4lXF`CZ*oz3jsl%SI^bynk9=U>ue zPnC-pwyWtgGl%!R$j4ztUo>AmKP)>89X)F@PzobT=Yt|ca>F%AE}x=(=rV6X#e}rW zEhX*YC2D_CL%QMPIKRL${$qit`6`s^Ixv)D+A~Dme2-t()6V}y0AM1!j`_K(9qwt9 zlyDvUeY@ICaB#e9Wn^`+sb&w@fU(=vqXpIEaF(yb`&fJ0jz4zydKAH1qIV1Tbh21& zy2I*yF`C(Ovv!%q*76{3+hW6e(52Fy!hS+M)|MK;s6Xj5D!Rs)pUp7Y@xQ}MYx#~y zx*t)BsV@@Yij&6#XBaZntLa0?xj;E#Vd2MyyHCE%!(pA#hkph7Z`x%&5>rKGcm8eW`!x9>nk!`lWK2jOAl6qUb%IQ6Wm@`j*a)< zqn(pW__`g(?$t*-{WT{Z!46s&&Yz}Py=0?;JC!?s^o(3>ppqT2TXwd=nLv!UKtss& z$Xizs58eNRm>g|6(2LL{=6T)s+YJ$LIijNG46~kr$TW%5P2#cR3|V@86@pece!$}# zOAWoA#-&thz-V4gO*}|V1`;X!E-T9~DhgRy(FUog{x&*0JNNePJazO1a;u)4<{?nt z=7nS02R7>%whI2hH19WJY2No_zTSmAt==?|f7J30@Ad_j=ho za@?^uJTATl12aFZ{OON*WJQp5Xdh{tMhq6(Ew#wI9X94Yyj0l z^dxX8AN+ykt0G7%mzczpC!P~IG=GN7=1n)yBu8oW-3w0psLbtL7s zGaK!BV$Aiy>E`rQzw{DdF5LD zWH-f3cgLnC>$d_{`UXQmZ!p6WBux0w+AG0)?T<(d>0UfHw!RTC6M&s%vlMj5Y>Ro~qyXQD4C{Fw3Tu!1XuwN6C{Hrr4zC;yXcdwmb42p`hR3+YLJm2x1 z5C%aHYo%WxE!-x#(=pWQ^Bk4+uva`C^q#{9&dxCZgJI`c&%^N+VXpbXoSHXM`})rV z-O*7Z{$3YJiv0X|?>WR(&w$9-4ZUyzQ=PEGn&~#wruXvv9*JxVi;5N3%=6VDI+ke4 z>x~M76w`)PuVDKJyOWLN_k+zzmAn6+l=QqWhvs=XZNv_b_6crZzFLbkqF0a7&|Wh; zd%7Ysv=jTh*I7qgW6;oT<_{lG`A0qmrRB)KaAobx_H&CzE9TDWDCc%%&37t|jf|VW z!>dzqEClW+&K>v-w<0yM6A=P9^!h7^(6h@sfXn`c_jJ@QDgHXhy2ppCI>_2Hb3%o_ zCqJ81E4BxpdYbDzoONL1=6tST747%~Jc^4*!7gfH-0dfiR%^}CPHhRnwZ2L@1S6mF zd*4;1J}Mgi9CgeBNuSDV7as=?=B0!dynD6_P33aAp}9grU=cj@r2@b51b$lG(#0*94e;s*#W)PgR#A&opD%i5{C3aLZCxREk$+ADI(N zIGnX|IU}EPt-n3hX)xEoXx)Lz2Q>2fi)$j6T$|*0FHrX-+NxIO^HB9D))od=Sgxs^3cI)u{pOC1v93eQ4EBB) zQ(abF)ts*2?k0t%UiX4SFws1I2h5A(HGf-8tcaPxZocG?_`u)&PpRZNzdX_>YhSmI zvMf(qq>EU*fThm#&2Z$J+ZlQ`;`gYHo5hET?U7Yxz9e4kk4Bd{g_gv{DuO`U&e=0Z zrbUhm-bgQ3G46-1i2)qm&rKSx1iaNJcp~i zuDa{s;erQmHHb}+4LI-5*aSd1fl)0}{uUpn zH~#$`orIRN%H)i2D1$A##-d{kYz>7P*j;*87$)2zhnG5S+fNwzoX756R{<@l4pRG@ z&GhP+bnq6>AeOIwjq&PZD?*Yz%sdDGpTho|$9mKP#}izRQ%myiOBh8_QkHj%*7Y_h z{2Uv4tM93&%Q_>^@;d&Fa1C|pzb6lNIv&>ZfBy83WN3x$Wf~eCwPM|*xsE7@!k5m9 zpNy0%3=a=Ce0{vKUTx3G1w4mmRIMQUNdB!S+-sZGQa&p`S-5zpvtDLtwA+~Y0R@lE z^sU?XrNIwP-YoZvbYo^?`9TN~qq1}Z(eZ^bE(idhI%f^>WGJHpv|Jl2>U>s`T)JJp zzH9s|lomICal1Ot{b~~wC$;Q4U%0>{^C$j+*V8%+_pQwTpIG=i=~4Ntx`{05Y4ZyQ z%caz!3y0mh95sezdM|Ez>Wb(3KZ4`}Cc{5LDaLBD4Ij$?3hiGkSk8!`uzZOM=KN!F zsq-yxQ%q}IP8L$)I|#zb&5LK3k6zUZ{gmKUX(Jq$ECjhqcH+Bih)@@wmlojp>kZPn z_(>pJE1PIkewVPlrTi-{UqNPyI5dCiUWoOu>Zn?j?ZY_vNd9CkG6rO}B5|pZFu@+&&KjSu*#%v?dmY4VA_0>CuYa13C z0UKrSM(x4Qudvnc3&_$z#bfo^(6cGTuXl@2Uc2N=W)@n;;^&+uu<+GYpqLS`=I}Hd-BppR-v_oy`sw%rBqP+&e zNPX=Db6^uMUeesVnHe3OGzdN>Hl;Gyu5Aln2o;@aT zhH1($UJ-7x3;IjK3$%};Tas#DoO}h$`^x@<`siL5gNQs7IW|OX+OWkkLnE6!Q!Gy= z!^^8NU?HWXrGJ^fxPtWR?fQ&&E-oPD`=(=CI<{kkPFHt_&@U@y*O9Ef9+lKLAafC?X! zRam9MVyPGep!GP-FP}EUY#i4W&=wYe9IZ;D{M-Do+T7e6G3&}kOe~1EF~otQH1;~TvLx6ka06;Qoz64q-3W#Aq5HNx*DH$fGEMjtA zy0ph>?EAVQ`KJC~%80=0$%kBdL8V9kDkIXS&|QAz286S-WcXk5M-Sb=kyXqukbYd= zz<+LjadUI}pH)Ohp&&xSBhG!-f<>Vi-M{A(>#~l1xGB(v@L++b#g%Qtc_@xV*Y#jvTtmb~IokGw5LOEdwEG z5cV+m*yjXgzkgXhcOvH9A%jC?DNyb0?Ik6r&OUws+is|3OL=;BHoVBT#oHfP48EIw z2WXM2f;SAQQ($7$4#fb759ONj#`o8aSzRZm)oaeuYg{l)#R{P?B$YA=zr+$pbQ9DY*F!}xqB z3ivj7&*Y3>oU;s3z>0&})HJ)kE`X{!i1Zs~qXtZmHd#_Vf*TAB7x?%80yH0&mOaj3 zbxG;y0If^Og4_x4kfXG%bQjkQMX&CIZ*XvNi@sKFa-kD>Bz`(cQtH8^4MtPs>x?mS zNQ&P=g@%TvPL;(rHn+`=6`Ag|M?H%K4)5*P*c*oQ#&YH5a8K5g=PhxL(f(d{y6A}7 zmmL0HcW38^PUex`{(xp!G0^UDqgiVLH&JiA!$tX7^oO&j%-87XUz*e?(JlnBnGW`| zOE^THha?jMFQ?0@lCW1iMMwz~T0J?de>j!|joA z#8RgZuWSl^Pv)&`J|#a90dhjJ43s|;LO6lhF)?NL9bX=GhT}UELZac3_9R!c#dR0m z9!p@LXrBXLW+^O*{@?)X+^}D)UryAA^{Zm!4vKq5PNzP;nRkf@J4G8C2iyoumj%=) zl9sfA0g+<4j--YgqfXP^9D2x68I%0-&sA+B<7%ZShhkUWNX||zsCf$6l&@v;?ypya z-0sUPjxG2R>A7VwemapmTu;!P9x~C&cjM`lAMNjv+<+wo!OG&|P~{f6&6oP7rpY2& zk+8*<;Yo?XI`u&Z*j|)Hmy<}AD43a;xBL92s#qoj2YkC@v|!ic306aFWqQm(*$n0H z9i!uv;X<15B@49H7iXrzCw#Y>9!481Wj`~93oL9bNOC7{`dVG+wd=!TVvtzU$NGe2 zC~g|QFCDsFZ|oG=-Jh7tV~eA=2}fn4Z}!^&m)3#sGVxZHdHMOq1K{!^VLpSqV{;Dp zx{DMs#=49BH++AX`fm8zwGrK>NuOb0h7V+Uy{B_KDedw5zX2Mk$)iYVlRqcRP-wk0 zY5r7)U!H4$lH@h11E*7`--$|8?34FEQ+*Jw`&>%N@e{+w#-?w8X=-C~Y6_)AHwN?- z-hIebU*E{W!@{!TQFP(N^?tF0J#)mSfIkad3?)r(%a}ay*b2syDpW4;&TVYu;F~1N zolI0HHd}-c3FC~qn#34%IR2FCy`eZ@Cx)toK{0Dr`sJ1Qo4b3^M1>wULP*+sfBQjY^e#fH8|MW=ZgnU7pHsTt=9iU0`*Ns_s6Z5YboGL$;tezl*Be)oZZ|m>~oIr zz+y*D>UQCwO6O_c5`S1?h=XQVYjT8^G=qSMq+Fpo)Yx=Uo%;*LXoI6A)S9pRPv5G# zF~S)DHB&8{Oi#N;5(=#N2G!$F5j zzN#EVMg1fB+Bu)u@`Dmj{Rr&}2@FY)ks9pyL(tbJcqbjd11}hhc1O_RVU*w62w??*AXHT=iE}UDO7VkoF}c z1_n^+j-hK1(E(|YPLXZ|1_qFnMr3FS>FyAuQ@W&v2I&%pW(L0T{ocReTi-ADuDk9! zXP@)j=j{9JefByXSIKv;A9Y;a7LtL#$Z@{UD7GvAW0V}&=8uApp{|i9=#Nxfx@P58 z=$rGiv$HDLCSilu<@nUn2!;yv2IXx(yWzd3^?e@zm>(NPYzANS9)7PFQXrH1X&5IP zD;AruO>+&C<{HVH(k|6WOG|%sE$CrPaB@0QhxPDd_Z(%1t>nT_lvXtthH9bUM|_Da zkt_xah?I7-PWZq~QuQ0ZH-aP26Gp}-5s@3sl!Ul;i4Z@mNpDdIC&AD6wZb6KCWTESXVO*{xNL@q2x)0;h(h|3%_dKI$I5}7aG!>}~J{T@zRj0L_TNIDn zhZ2*K)jAr^*5Q`$ASP109b%I-DSm*WrJd_%EK+C^O=LwI7~zLktl?A9WKf_fY(4&i zAxAQ#wm6a;Odw$WKC$>FP%S_vMvadv2`G2F-m4|3!!3sBq)}i^z+48AHW{;BKYtQj z!x$}zV`5@{BcTQc27BGBPmUXb>^3$wX1>nOf=qUr9gO!Iw=(%|sU#V=AYzf6^WoAw z0_G6%$|QZO5_xj7viBQ(CYf5F)GKf8UR}isg$07Yshe(ip`c!1aXujMQ~;K&~wg2PIJn~eFB~iX= zc56}r^lC$_UVc&vFUM_<|ItWXUF{sQZOZ+)IY#~5wN>~#X?E41{D7|VUt2Z$xH_}$ zuk!(AlP_ZN?BxuZEUGBovzD^}IxjDs3wqB7NMuxpU~$Wzj@f>`|5ltjr}YA@P-H~f z=uQuCr8z;Scj#Fxz4F(m=93*ZdmFDurJ+HatHs{m$!aU8H_ibpWq_q>Vs@4+_|kRM zrw!JwZR=L}LD%}xuRSZf#(EjO@K<7oF?sK+R%tN!zIf`-DJ%7%7}_kZnV6+h6F zr>nH(cxkIXV9-I0lNtAc!H64DsO}W471imgffpUdw7E_fH7K%5O!jQw4Uh35hju=( zD{-Gitv)=m8WNoTpg;5^LTu*ab~Xc_e&2Zfktv2=zOx5GB@g%r)aPH;={|c@33<77 z!@(V?xBD*f84;B8bunz&fU^#lh6~ zQh=IYm9R|F{>i4Dlv;B@C^`7RxK`zu(qH0}rzXv>IdbESviRKs^?_3oIpRUHjTAk7 zZNQp1ohYt}L@>!@kpXc%0SnHqid(D!36;Xv(+NU;fxHLd{WaQ3-}uStwK=0=!1|jn z2$*|JME7N;92De?IM+G8Se;ON19HPBl{9X?091e98o1Y zRS4YjzCqV21UAJt2Vw(eXbEPCwK~qoPoHbe6@@rCgxO(7z2u1T#CmHEhcsK~(rEEo za8Z?cs{2RE>A!-`J!zD`XNt}0D%R<|6xhWA;9GIWZ{$!Fi9wQVPmSOgUu;D*aM#H# z8Ms#^YOaF+_HI8TFOmqsejJsSR_!WITW;UU89GU=7W!JW>H&prRU)U&Cv8wnE@j1J zRWSv9zgXtW1p*Xh9u8cv$UsCN^13u{|LybK2->VJp@xueH6oM{Of@x_pn7)1C;Q7b z9sgqxJr?sI=ePibGTQh&KoRS2ON(;_7P?^(2~5 zI$A|r{CtM!M;eG6K}LkyMi>>%2wSQ(`6?%FjIB%SGcE>(*Uho@ERWKu?Wj5|-hAce z4Fuon3(Cv6yCWCt|8>YjwWKBZypX_RO*bAfUeIo0=o%wDf}e&xE+;(UKrk|5iWgIN zhDTeZoiNc^5#?%RRL(s6up&wmPg)QRP<&A=tjkdrq2WqZrLJ6~m(LB6ER#lI8NKx^ zevCoHYsBpYzZW$lj5KtMrXgX4-W6jJ`W1eP!>0 z4}CsWk4=}V6q$ZT57H@%uoXlDmMebd`9TXfF+QX+9WA7@g3qlCycZ~a^7c>ZQ+E2? z92$EIFgK{|IleC=qP7Sx=G4e8RzbZKyqZ%h)2s*9k8)M{=S3nOz@a{9L!4a6tnYn} z1TP1e)J~_2cy{9RBbU0TT%3=XL+1A1FIlIJyyNc+5;$nbik)+lPOm{iCxs~Agj8l{ z3uhMROkqpBG7r`kbQuunaSb2w&bH8Qdr=cdKL;mjOXlt{<=OC|>msL0wDDlk{mnv+ zA2|_Ex#<=y5XQvtN}cLoI!Y8V!v1vXS@LVV0Q7z@=$k11hYj|p)q%kWo>??3q4doo zWCrihzHUDo_3}aaxCY54YeY@)FPExpIbS+@F?M0?Nba9oV(c#BMXmAI3|zDf4EgT% z@pko*_0;w}%E{cRwRo7%%={j+qCV_S=9fut(O@jfud}lNh$?1kxnoWNtGzAIbImY( zpIr}QPD9`EZbCGe%`Q7+xgn-bAWtFqjg`#~eSxtvt2HqX!y&hUC;2Up$tz2cG9^7E z^nss(0wtj$Mw|Bt{M~=YQI*+!H-M?(1|NJFG_bcuzO?5-qtUQG-M}2pa>0PL2V3=Z zp9kK3$+jl0H;B%vR14va%mB}{_jx|4sfBkUe85k?8H+vmhPi?7!253-fleU7gk1ZM}2{* z9tQtekS6_W0S6RPxKK{g@s-%QZ_$-Bx zImCO!M=@yc-Nx7}-`ks=gM+*uKhp04{ZDhDT~&CH$5+^x_z5!rYF?vPm^R1-#JGVn zIfmjV%_ougIv5veVaiOjh3Sag{Y4N4QUU>`XGQ-Xk8>PT*M@C=(-|JA4EJLfEB*J^ zHkARDll7stpT+0tCNInP8U6oE z^C1I(d}CJz1Sfl6vN=6Dk6MCDE7}q&X!tW0|6D#f<%?6qnu}*^IuDbrb`%ZTgCmD? z4vdqjYOgQ2nl3VD<rK z(IF9eCBJ<&MB_eO1TXh|=pJN6xnR z*M7PC5|kFPUv@ZW(%|p7?ea5-TfQ6nD=KwiXP$ZMsM%j@$Xj++3dtgSzjI=AIz)o9 zINd)HWV=^AIAffi^WI<+N3Xtrz-P7`DRjN)ED^!l-ni^k=sxhNV4CO1XV;U`0>~_X zPVzI!7kad{f3*?6vN0Cix_BGUxze;lA?1CLy% z2IQF2D7YI^66$5*$pbVH&#G;|u;-PmrR|b$Xc>QFegGI-I1Q9eDcj!7 zE5d%`8+z`15utAz3Vm{)_S_Wu`EHVl%(U(63OYIN6g?t2wsVkIvtHQVi3_}C7~&0p ze>(*^{jiY~U7j@NWAiyMgsl$>0^95*rxE;WMs3lOd}zGOUtjiNcMU^L&HGY!=W#3B zU;EoSl$`ZCo&bRbNdaj?5>8v~#-2~62SQ6hx_oaJ?@E1XaUo=jqYU&Qms_4o0YW(N zilmW}%;Fr|XI)~xx|Nc={ST49l}zu_!l}o~xjg3z8fbJm{L7hA*%wNz5_X~MAEy~_{Wo+cu37ISjoMvO}MNw^^cm+V2+U(YgC{|Po^s>J% zEKG5sjD%?4Qv5a;xEAs_zAkjzrF!Ca)$(ym2e=if#?YDN??bdu&@-5_9pEahmU*KF z+mz)goN#`(Y3i3a#(2-(-eM`q=O-?(?|dUZmVtSX_T#cWa|8ISZKAp(D2y{kYvN9( zZtr81bvMTmg-~;@-7faflLSdN(e^w28B-|d9bAw> zw+&59Eq&$7SQ1ipyYaLPHU3HOZhmb$46!{kOu@ z%OoK&PxFZQuHOdj9_Rx2#4nY;4+LqL+4&&$ms*wD*O$}%N0Ei-r=}8Kk8Crn=6&0T z*;Y>ZMHeT|6uP%i`q#^Ap&ZsJn_?I7RKA8)qHf|k7D*EKt#Tzbn= z{+gIGO3L$!f4Cz$zNS=+WDu{Mx{~hhWas7v$HsPFf4UWZ+PVPUbyX3N=DT>lUGbzI zlVCB}(@#BB0HIOHmhBK7Zqw$V1Q}m^bi#U)(?Z-ub=W`~GRnx;B%Vv{Fgt(a)#%NF zGqV4Pp|Z;uO{$7K-XM#U?)M|ZYdH+Mbk)4TKGMJBzPzjM;jk{ZdZNb9Ht6JN{Y~@^ zGU7sJ((LbRvE^Hrc%IS9t>;Nja;|K@xoY*s;drlNC1KzYv~<*vOMd&{QHceoVU9ZD zkkWJAvD@!V&4=IM=s0)obFM2ycpP)KS@lj(R!wzjR7C}EbF;*J%ZdIGYItvnMx@X- zGuiTcqw}QD93c)mw3=IVYo3d5HHRLD_ilMfs?`=}-|5DX)SWfMLi1Ve4c6%OUU}K^ z(x{ebKtyeKmdl-~UkqD;EU8NQ=CIc3qB~OUd*Qata)S>^AwaUHwH?I~Fz55YI^**^ zIt-C}bC{ZXtU*DPMo)7H{CbvOFt{ogA6C#8K^ATdBU(88>vfpqKL87j$fW09zkS>x zcy&wv-Lii|h;JZvanvi|%;*$Q{)hdoDH5ML(}!+|6<^qhR2Kd2%(<=qjb*U&aFpyu zjza7j5!ta_(PYmpnIxJLwPMtLPXA@2bPVg;q9WBr<&cE=@^;+N*_ldZ~y!z?b>F2 zF1a&IF#kPpoAJbH`NtLCRmTLI`($Kz1>#$obl1X(+)@u}Mx)}U|I+>A9dj~o>cxuV z5J9D6utKGwishJ=hbJt^)X0aJBSo-A)E)8U>d1F=E9hz5YTC5pnQV3D@b&#*JD^>X zq3E;BX1n_|G@uh#iJ^<^ZR13{V(mp#tkByz{T^TjhL!p)XaRP6N5130{)P z0e93hExxCzfMt)hLb1!{_O+0w&gRo7seR!7Hc#@>sH>26`^j%1aZp=CU?YQ4t)@#C z2f*Yy!24J%CMosHciY4B)H5fYRJwJHoqbbL?wDPV4`Kh9*ZrJpfhi^qIqVkmWc6vh}%yZi?z)%;DayGEo;yvQ~z z+UCZWm5A2+!klqG1ZTM>i3%xPJsk}+*!PRX&jRE?H`B$-o(}EQULy6(Ir__YnNs{q zAY^LNr_UA!X(e>a*Q!D#0Rr|~3(Cjpzyy?8*inx0taH%wicme#&{At3>D_2PXdFve zWw;X^^?r8TcLDhDNI6SZeWk$kK)NIN&gKl!o^u~|7K(`cX=I5PBG=_KYwG6|KsC5FfJQ<5t$K$ SjX4t=>$Rfliwdw=(Ek9jq9D}( literal 0 HcmV?d00001 diff --git a/doc/img/12_multicast.png b/doc/img/12_multicast.png new file mode 100644 index 0000000000000000000000000000000000000000..fc39a8dcd41cef575b5da6cc794517ec971629e0 GIT binary patch literal 12267 zcmb`tRa9GF_$^9tcej*6ad)T1-QA@rP~0tnQoLAO+=3OC;7)KT4#l08BEj9|<~Ppy zKiro)?iu4e?7gxxcGg;1-?!)b=G-$zTT=-Sn;IJl2?D4^qvp*&};;a=k zStL6$wV0rSqDPuUHZ1fM_^+OawSxkmv zVysF;BafwGO@?Sym60nDU+c&c8%H2+BmU9Nj<`Mf8>%5gIAK9JQw=tveajSTfXNWf z%JBdBQ+{a6->)31wTx>Q;s?uN>QJn_^WVB_X8!OLI(cND*))^B-`TLEj`QEl;@O`2 zpJda6vJz+dQhg4V#0h`G@@Y9vUUV(8{5{q_2I}MC889Z+rY{IgZ{1+5TR*iez#I1+ zD}TupoXw~exl=v#n_AgD4bolG2+bNT_gT8-dx_M71f^(R2JI$0M|Q@uW~|Ii&uDhF z0lFm0fU-r;ti4v+hX^uQ6LwLeQSdde_FC;Jymwnr<*I(FY0E-s0Cvqs))vhC zuzcos@k=XsV23KIz9#VS$8U>7uZu*hy!~G&r5mw3hWT}w#$un|tU$IJ^WJEB_I03Td#{(nLW9O3~!g&ze!u(kr}{>cvZy?OYX~j@;$RF?@b(5&Z-ML1C9zg zyq^x!oQ6!GQ1H;oRWpRkTz7p3aBxHGoAK;aw`gQsTFGpg5PWcSUs&IFpPbwDDJ1*x z`e^m!K$_(v0HvbB>gB@V{w2pN8A4TadESAdCUr#ye)ptuFLChuEfp9p{**u!1$T3C zZ(KMR0DrpT2M-r^E-#n{StRbiG}q|@e8wx5xtIa=oiNWULGZ{GbgyN8*{Mq|SHv$; z`lLE~-qb1NX7Wm+!f=o0i4nXcCgD17FU&n3Zq%{bb}s z7qIUMb{|){A3TyfA>S%W`{fTjlzeduR5)V0AI#5$EZ$0iWv@J+8h5k5>{ge8R*kOa zl!Omr>1hiG6Vf0RrJh;0t+X?u3x@fZXCu(`^EDB>w7%f7+^yu94|9`WRua7E$ZnQ# zSiPS*h8Ge}DDbU<{Fgau9P{f`H5zEwj_%V=GO9*pdyqpL<#&UjHzwI&*wCj)8WYdQ z)($rx6HAh1yOoXkDbLFQ^Okbj&*x+mXJuPW?i)`lDpgjaqZiWM0Yh_nNQKWX+2DO| z%Z*cUSE9QXo|o?{eqFIVAWtfW?(}O*SI}R+YDrkJ`M zZ!FxIS@+e1He?Chkl<-U&R)?UJ~I7h4gmh)bfk9Ms}tHOp8HVe!uP;AD2;BIgm!Yv zL}B&FrfEezrluD@+Pinm9mvnpf0AFw(UVXm!K?Wq#>EqyG?!t9^4IC9S!kfOHQ2YOsSHR zxShk;5%78j70*rXHiU$vU+2p$Z2dgZac z?nj-qBZy#Vv6?3&8ORK+`#v5xbOZ{FSz5|G94$|KEQ`1ma220f-o4rl-X}^0htPq` z=;wp$VxLB1vH@&7%@@~ zLf)nfd0sL1pP{X8J!2eWr;JziIKBbq4rKJ}^q|*Ih$kjBfzo1O*EGi=dy|j%P?ao`-NPLR5Pq4In-$-+k&R);-OXTsXM&G2{nyN=jY>U?zXnJJ$mJW(9@uhiKH&ksJ0U5KROKB{vg<`9{oBoT}hEyOWf1((A{10 zbCQ#5aKe5w-S}aiSdW)Tu=M4fAT5}mV(pPQM+)5Vd?j!zBbKK2%(5naI;1km7LS!? zrZZLqIz8C<_oZ*-f_ShUv3ZpYvUSDG#}7Bi?6bs~B_vtOT#$LuX>2y0%w3TLkyO(q z8l60%WNALLZ%8_E+Z1Li0PeN8rM$Vix`K9prMlkInV+X@Wqf2SH_RES6|lpV$C;~> z1qvye{yPC}={0-Z;w_vV4-SiOxFx87R|nI*q`Lx6P4PF*Xkg&E$pGISAZRPhM}I*- zA8D;Um1a^bc`mmt7j6amMseJcPL^-$scqa8F?~wpdb>uJ?YGk|`cP+fd;G9`cLjyK zM!S5u)17#_0tI&*qtUlLNJIR$Z6?+p117qHw_2+D&fk{EHu_k}Pmj;e}3I1mUIzBa3$Nfa`BAFJ#`l~P` z06pq#<|f^tHD$zq!SIi_U-mf-)b)@c$x6ni!}Bn^|6XkVO#PpD=ITu`%k;z3@|lAZ z+luO&tuB27cYfk1OYmmU*d|!p$-x?3< z-R|A>XhaX%!6P0Zy?T*Nl7PvqYlLiNnBTQ05+R*7pFNQfb4ms98G6z!K<+G`-B0l( z&(1N7N!PP*NgKU(v}bt3;7iAMgfsTDgibL9Xa06i=x?Gx5lPfh(sJSWo5@@Dr$;`} zzje+hQB#Qlk6-uEa7x!&Gmf~&aFBvAR+55C}eOHA>0c87%w9lQzBM-el8%urq=A zsnhY>{!{P~rM`g?@6=qF(oVdLiq_3*vU+xtdG)`zJfYFRk%it}5hXjPC#7*^9v#U5`No)Ki^_7wtjI zVt;StYWXt!PTAS#*9X?P;OzwB=aM18?i8c=VuVg#0^)onr;&%;0MD+PGdE}LO839R zQiPu%8(rS4_7HJ8w5?)_pBPK99dg+HA4bv57PVHZ+(Ewu=gkjtZx}WIx=MC$GDq)r*Q17<|hn4R=R_>KZrfg z_SNRQ2U=!Oa5mdc07EY_D^42?MAs-w9^o?-5q2K zRhraC3MD=hSc(3On@d~okz44>g|}VqcJ8^{C^({1uv|**itLjyLhO#_3BYh|3$tc< z0C<(5EnwLb+~cy+P)PUGyI|xHdnweoJ36I7A@eiI)G4RK$VwaV`=q0l(f;B1z^zJ*o2fJ z$~)W@-;S-D%L$oaSpY9MM*3`Q=CVhl{&ILDz>whMjf~~}qHTzz6_3OplKXNQNvMQk z&>Myl^Ff}i`1@TzIV>;UIq6780}YbEpI_KLp?f%9|vyO5~@ppS!UJgqt-HeIum z9wTMiPn^QJSZ-#e&j@Tz%-Th@ym@Z(&2GFu-&VUUdQo;fYTOT!_KU7|GcQh**f#EL zsn!92?-<)g7nav9>A;t9IG3F&ReCQi`aEKr{7)Ztp59*lgdKhc-j8bS?rN7-9xqIi z>LpmlK2NKp1kpDy9o+16F8OBPM0e&j%m+yw+u72#2}}3Iw&&mFF^cBd{7diERc>;# zK2mcj&8QGP>~_QjY;E(^9HBviIw{%%$fCG%CqAsE(0Hi3(D;9p!^n?_stpXDi#`rL z`>nJc;9qRg%Uy?h#3M6wpNg7tL11(Bqb-|zTQ{ej)B@Vs9hnoBJT8+gM=}4;$0R;Y zdet&zMVb}#zt-kjYmL?Ug|2UL`?9M(IF&OOd13OWmBev9=xWnTWxXNvgw76yyE6;2 zedpp)P66Hdc4v?@wZ?rd_a9HKeHnlUZ;OETf1cD|9$%S*Z-d)|UQ$_-PH`Ce^^*g$ zE2M)-!T`7Iy8x#5J|REI{}-wKZTo+jk{V;Bpdwh z&TL1{na}*ducD-cQRU*&0*OuXbhltJgOg$dS)E4*n_Oh`2`_fX3kwR6XVjrixn&?- ztcY|;Q>TV`e~6M(5C&KKO0@hN`9dA^2MouRwc&c6YP->E5lY%p2MQEh%B*kOy5<+kGJCs4N?zze@AQuVIE&w%cD* zC?gr(8%7hKMIrBZzY9-IwLo;Y>8Rn&t0@V2K5rQGu`nMhDk_R7fdo)*XkpkWH%n{G zbT@H1uk_XlgwFNiFQTf)eg=}%xTNw}X$INvWh+z=CV+?i%%6+{N4 zEbX`q4SiK!UXF<#*1cCXvD!ry`QFb@WcUMr)=nF@(?T`yXt`0}z`$d@eM)`WNQSC5>?otU*4v%n+f62^ z?4Kf>0ObYXkVks6JDeYuWY9M_>WEYepJV* zGq8rA8&6f03u4KBcT_vr96mBKGGh!3jJsxNNX~O;uzKHWQl4iQn>HaP>fYX7UT0xg zPyX>+O6*El;=DMW{LQ1ppE~}J!a~!tvkfdY_%7e@y5-0O$YVXW;ziEKIiNrD^KGD( z9fWQ|!ykSab1G_R;PKucWvIK4{{*7^)3(mpD_tM+ZSA6o?4k59j%F(??Y?gwqPKg^ z|1KaPph?Ys64UCs!Mt%$rKq&33V6KQnjWwc2#Gon4e$M96FPSRMlaM^&3FA5r-LDh zcXS3X$=!()m|)!jVxFavVMml!R?^Ndk3Hdk2rHg&%9m|BzP`D!qg1>e71ZDy9Z9$! zKV;m1bg6tG(=*cvZS3mGy}tI{naGKy!~F09S?Nr|N{*37MjG-sRrk8>X6~+YG55QD zjgGhm1NwLs=}wa$yx!24l$7{6d?+BaedB4C-Ktn&-}*|pugT?;lT(xwWGjHaOdosW zrv7T07k7%PM_4bRja)w z{AJi-g91o?BOvJ5pnBNKsD!uUx-dVl$Vtyaiu-$ZR(}?U{BIR!GbDa_O@isg&+3Fq zJ$=Q%*@WEid2f^N!#c(X_3-rluh^A9pw0flJ_1!Lt(p_41U^o!uBw}uEJ5OvdoMbO z$owjaB3dnUOr6yGx;@qoOE*{ZI)fItmnFpCv6YusIJ&yh`+Q3xwDtb9*QDX1FZk1%+{`!e;k28`PYP_`!1v(O2hy8&r`jf_N>+$d?Uh+SW|L_E+AuCD7O zv>HhWfI+{1P+HS+RhXzMg`AM!NAXD|CQN9O!nuo-nR*dY9~LSy>X-M_)YLUDS;|bZ zqO|MH#DssVn08@sb9w8wjyx@g}8b<3e`@Q3+rFpuoJ!Kt2-`3u)Qlx8~svt>^QG^*GOSv-@_J>+f zTuRGb6HTK?w|~n60V8DF+mxz0Mn+1n3G=F95cdEoskOC^+ATbEJHAg&pOoL~^|j|m z5TXGws1km=NElZ9HVO*9kxcCA>2a>PilWaMo!xq5Q}SX7=hg5kofu^zvi-!-Ht>lO zd!=sg`0x!S=I_NtWnN0#;U8}us+L+j7+qXkI4#@4ujhrAP0ip(M{iS9fh=Drg?nH& z))~wxDJf&0T#Fq)lB5F9E|au8W^0Ew1L$MqzbG^PsJaFI;YF<3eSp6>J^j&Mru zknZ0OTyu}}l~A9iW7AXx1%-j=O_S1HRsl=fNyfn6qfEt3h~NlP_u-?uTcq7bqEnY> z(9CQ6R57BT)FNo*;ovE(hSAT|MJpEmB#v=@J1Y4=jv2wq!&6dM_uokBqrH=3WBm}< z(#wS@mL21`d&D-iQry^>qJTq@Quz*%N_UhoZ{8Xz;+K0T!%_6xsTG?qf^5zf zFY=4GLN6-ZdibxH;CQwe$T|#thW8AdTUW;q+F-F>nO&Hl-q_G$BJQ~XvvY97$iJDL zn*-XrW{5eFvzC^YBJh<_N|~L-!5;Rd=XI@rHkU-9GrX$*SB|L;rjB;7@@SQv-FSDh z3XfoIzr)(--Q5SXE^$AY5JNGfz_c=78`Fx$d2PAp;1ktZxJZXt^d*b!sL{|_zP0BNrR(lnX-@qTG zQOF$5$~j}pb-4;RPEueks*z#aSv09`g!Lo!_t51)a$hl0Y}m8M!!2dgb76pW%L&u4?xPZqnZ(0V zgG8jAfh>PCFsg_DRfJ(N?ixh_sv^x&)`kY|)YMeB3QLZlbNk~%o!wgO_)n@xZj-eoY0ubHFcDZY*tR{wI| z5>Kc=DODPO-J+5ISMP)oY@LeQSevuSo~1AyH6VZFp-~<8=>y0T&5QJU=q)XrFq3wJ9qAgd+P2XLO;o9D5Ar zDmmFlutbQRN9<7}bt=@>L0cr*z^`ri8l3(-B`3a&vC_|bbh#x~?2U%Qr<3tb_@fg) z4erqK$W>J8mz5R|JKwUQF=Ee*qAmV<{?=+W3ky09!^&UJ&<5iHeIs*g1M4W+(({r0 z2PX2o-;BOtuipJ(W0cDJfle}&iU*5z%v|hw?fM$&4{uv1UN$KucJKRBTIHfC$RHkC zjU)^BMUW6_L7^Rv4bOTtMcr3(%7wC$T5Zk1{HY-$?YupBhJ*|6N;#hRGhQE}LbMDz zYCQb#SU8LdfA^YqU!dwgC=$LQ?QtiIr0TYJ=&?<)oH90frQe2!<(~&?*!{y6e{SwP z(~bR^j$1COw=@}pjlvwz3xtDz>ar4ayd#u*1;Yp>^p~qL(91vVxzGvqY&cMUOIDy< z$n_+A&X@6LbaeaK%~xfpW6oue+Qd0?=M?K>_RgTN%)fz~UmMLK1u%QfBFa8PoLu==S*@^$yONti4t(OzB+#1`9Q?e5PJ;AvGr=+;(%QbC5Bw??T5#A7OS zz{LgTsh@I1K=s=y=I3tD-h00Z6;{{heW&bb`--MBh@!j#Lx8qh{VfA!KS2~PG4sem zOR<7-==thp0d-TvZ{c+8Bj#?e)5aKdPCe#mLfZoVGp`0V+#6Jx_<4HOB731xm+_qh zB+E8$cn#Rk*SF4bhWXa0Q=BN8Xtibd)1roUL&=Pl~%tGI=f`G#4}|}&aX{L zIwm&Ul)&%(vy2|;%Ru?r9kU3e&z=GC9M*=rTBpzh)pyPy z`EdLc&3tYCiywpvsxq2-4)bpn?yGDL->ckl{9`Th-%c?yZg3znYjPfT6Od@{t;s>s%1xBWRE_2m|6<^P0jehHWPi3 zIb7}*5|*H#b4$6b#F0afS|sQ|fQtfLw5F8f_*Y7F6BJHpr-z+<9y)E7|1G0@H9y7y3j<;ZtSPWvJ=z8%~N? z^4{5?j$%d1&d$!N%hqD@2^FDK^xh~ni7Kr-(Y1bbI-ZTXTN{q5wj3u?qR*hKNzM=u z?E-SneEV8fy~hE1jzhXtu}wvvk+lzuyIJ*y&|=2OMwUa+u-mxe8Ww7|0aW8 z$l2t!Sj^))7zv5s`+r`52q2}l0bXi^uC!u^4CLT1dapy#6fEle$LC1>Hld1SMJi^c z%JeYc@V>CDy0P##{Fe)3l$7%>icGCVAB*G8U5HKMR@}9WXQBZjDrkm9r14ia)Cc8z zH+ZKrH*#d}8c4QVOFw*h$BqmOo2M6+HpJuv=E(x#Dz6(7*>V0*B2kxfAo3J*v89$( zoJekkfp_fkP*W4R0VSBYuc7DjNX#z}G^80C`Ncc(O$=zr*p2)JJFTa;iIW=$i^OqyS?Tdj; zs7*c!11`EwYD9UpY!LURT{wz=k9A-j*1|yI5QBB0ItTb=UaMHf=0T<5MCZt_wm?OP z9DhX0kl`z@=lSE<#^sdM+#eD}T(dk$d#?G_rw<=(Rhg3zl~JwBf#I9!%jFT2rziP0 zL|^g=?I8gl?pe=%TN6%=1)VJjPE_t*eUM=jSlg}u6JW&q>cZn)X!_<$ zu~C3#Kh=}8*|8XK3MDZ+QCO?aG-T+MQ$h#jSxC~Gupl_k+CqX{$f9FVBYla3(o)BM zL3OwxaRDZrrE6wRdX4`|TQv#tIhm+x^f6-Om1)z_=7h{z=x$N8e8J_-4WFoJ^g&y4 znh^;VV-CRN~w*8A;zoA+z?$XGlYK^G2Pu>Dh@HJJD(PKBK*tka7&+PXN+vin59* z7QyR&jsQO@^GyL>(`#v6(_u#;JRLfyMR6V78B}PJ*IvcTfMBRlhN><(cOSk!zx@O) zf_(i~TQ)VN-rqaw8yM>9m_$07%Kyb`Yj5+QWs$(@`eDh8m?oVu1-E(hH5jxo;3dT= zGw>&r(ye_{u4DQ^(#18~r&yMXJMxbmDjx2rJQ@cU6?UISex>)oISHG(ASDLzliHRg#l7_+2eko-w zPfcy^N=gd^JxdxA&`-RxlKHMILq|vFywVh}&mQ5J+0fWX6eAx!V9P{|rTulA!^nLp zjc4cvjN3ZIUffcEa?lZQA^P_hW59k{$*DO7LYnzxCNLS#J9I62n-_5D<5x3Nr`$0e zIbFgld?N2N#Or(X=I|k$4nW6RSWutHY$ss=)3Wd)5g_NXo*#qjr>1QMO4m9hPpn%O zOuy$G?Y)r%O(Fz0kH1(fs<8&q9{QD}o zhGxX0in!VyU-OTQjFy#F6xY=euQZ%W{#VDcB!!QT?46vjWGEvM*0{hP2Sy!Ap*$8U zn0#nJ12zS6gx1sVFJ)5E{uk>=kvf#_rdbTY}_#?WVYY6nbXUMlHJkaemja`jaoIPCA!E+;b&_o*@zen?Hqu_^FpFbRvMTk=it zBABw^czO@nM$4BJIUE)o2F0{8y@aiA%1p}4NvuVs)zyP_DBj+_MfL)EgQYX1AFscE zzk9&p>FCywdBTe6w+?)Tk1N}Qgok&j%(-p12!rA-!-tyc4k@tsw>^yi)tryH z`6ybqkA-d-Y4w)12{}OKL{j?vPog$CzM3|fEi(TVNBx_4$4t2ka9?FHyusJ|&)sv) z(7Y$g;V&OkGOwMnKaV)v2x=eMwjW5nPtD7W#=z1);#EUBUp z@HV&QR2Hyijv;LZ4L(i~-n(1C@;%UkQEAyevO{6FA6JkOni9@I0+{}AL(yzsE0f)>bge=81 zQ<7F|yFKCz2DseIGZg;-!99BI(J)>f(r^)TlCb!}Cf%#XsQ+a<4N=jN@^ zi7&6NY%&YAh%%2nbO{p&cvEaY>XD2RNPa_PSb0T7S!wBOW5bxOHu(abH{UVCrdfw* zz0|K?5E(^a9aFRL2)QG5@@ zOh`g5!bFop2+Gq4B6kU&K`33twfPJZZ!-yPPk^T7ts52#bg8L#~3E`j0>irp#g~khq)_ zXn=aigOZkZ?4Ka#q%%bdLUwf5#UIxHa-D!*Jhxz*&hM0&-u7X&ozU%7E0_L^U@a%k z3kfO_thm~On;S<;*p`ix0OcjUYQi>Gtz2(_WsPczcBGExGArEqq}fje=` zA1AVh$EY+AA=Wi9P%sHdKmS^HC~$(HMXI|zsjT7tqr-HyxdHM+J{E}A6Mh?hJTz8o z%7_ZLuBNH!JC#83jG&izd^{c^TtszY>2g(n)MFPBMgGb}(^sz{O=Twob>M%-N4pWL zQc0;YwZJ!&@wt#kU}=`J~D{t2An|^a>*g)nhK8jMSjZX%rg z7nGjE0G6J}7Y8G3SssG9T}RTvpyQsgO147K{j~Y@JC;C)m6^#$X&QbmEkC-AfCVa$ z8(33K$It7*US=$wr`hYFByqbwWPf1ge;igwEe)$dVkKPF3=UDHR?orJPfA*WMZ9YR znQom?+wnluFb4LIfN_PcfE?1#3%#9bT}f|+7?69gGZUXULl*ZFGB-|5)Ks$pNc2?% zmOUn;`&cHg%E`0Giu|01GCF3M!u?~vb&I3z`C~v|;1rKf-?IFRO2USuGybvcf)h$6 z+LBzJjwC^rak=JxEOg?XNAoT@OmzpqLHKG@e1iN0z5(3{?A{(^>&R$t?nPmgYl)&s zAR*jLJh$ocjJ0dwE`wqILi}BxgTS0{yL~q#mPL0Hc8VhH2hPR;II?8y+dVbL`tMmm zx7^sGWp44LuO1xD?`#2Ozedg19$8@SSBy+b!#vGT#^;YnA){J%i$f>2#|B!{WCu1! zjj;i@f3-X=u6wyYGK5nmdZTF(4UXNME+ulmt=!DpA}BnYKe27STCmw2`wfyD8b z=DW%U>7iD9Vy(xOHMr78BMWk^3Ur1&HCM_!bF6yYA6`Do+@QE(yXHxv?G(he9L1;^ zceG%mBxb^|!VBr-g>KJ8Rag|PtZ?1dB_}$sgeE-0P<6hg0g^Ivhnzw>QqnZS9XDQpznj?F@1tBoZmI3NT*zW~x&DMhCEqP*AGAEK8J*V?5O_YRjL!-I zdfTNh>{-BHle z;`BtM3^++3d&A=x18M{A3GGh$p8Fo?BP1XlNMmMZ>fq>@Uj$@XX@(8TSxGCmd4v-_ z$Ri(^#nm~-L2?>!ksSi*pQH#H$h@qkZ3l)~tXFT;j;ZgvdRV%K?kJwK(?GdRIaRZ? z7r_&vH3^?Rm+pQQcKk*5ckbAsq+WkUX)0ykp}%(JzTK;xz4D#bzlb=FzSB_8 z3C;gc9BHTQ74;SsCrz2gbur{Q1F+kz-SjgYf zaV3ETM@H!oHjKrPKg-ayA;8OaZ1z=b$c{_Y>UjAeCXLnJ->Hh1UOwTxsNI{!qzY!C zuI^!@(-}ly3!^Ik4PgjPH3l;Rcb_RlXlc?9^vy_?nibjobPvYOI_&9Htr3IFm z1oDn%jZ*m^VOd5`Y^BeQhZDOv`(MBHMHHWwjhWjsa!XRjCy(8QZlhk3U2jzf3g#*; zwc}$55i9k-jp)M&Quu#rQ~#e=`2TN*`{m0kFATQV4(de`2=_jcih`zmwXF4*{|78) BYcK!+ literal 0 HcmV?d00001 diff --git a/doc/img/12_unicast.png b/doc/img/12_unicast.png new file mode 100644 index 0000000000000000000000000000000000000000..65964a26ae9c2d8bd9bfd8df744634a340cd38a6 GIT binary patch literal 10593 zcmb`tRa9GV^esvYEpEjjNGVQm_u^i(xCeKa;$9#?DG#>b(?K|@2sS5;BaMMHa5g*x}cdWrg` z|5VzJI$(RM82g~15&Zn`^DL8-fCdeX0ZmmwRzEQRs30ic?0wF4?;dx{rEWLtx~ju# zPUB~?+S*n|iWoCqAbpHAKP6fbd#IP~bn1Qkw#0GDAlBc5C?G*CkGrciF2-}F*Vuo) zNh|~#`ng?i_-x2Ht6mutEEV`N2lW(cg>snh!KAL|#X5TLCHKUpbfA>c3|LVN`s^?> z%ZUFulZ#O!!jP?SR;a*`C5ow1`oDL%TaS}T6&R-+z?=h=3a$;uOqIUDTD@x|8U0ag zF4^Nml6pctkf$oOfhIxMQ;1o3Y-hvu>0lKqf4wmUsb%`Was?Q;I!N1FLiVw=9#3i9 zt^XNyNJq4UbI?kxpM+Pq6(X53SIsMb==K6MZfBtRsX7&F^!!Sx=)Qsb4YS+>~A@H zZ0O$6eUK{2>$SINasKkhEWFWpnOcDJ@tCEl#P{u}4K8>Ps8@p||>%_4ipeXRg% zYrcbYo7mFqU`*L}NBIW~SY zkVmXsc_3M*gDtaut-Emz z5mG>N*&tgBoTBg8`p%2?p(0D#=Q+(H41E*0^s5shyB*s9y43*~7JHy2<0}!cV*y>Y zSWm#8mwMv*;k6#UcD5>wx2dUTft{|JCKhwVle+j=>3itg8(!K&JLi8gWfp!+_2VAa zkNqHQ-c`;W!0|8XOBtL1%KYAK{E9Mm^ubR*RVUj!-{62!3Qx|i>2RR!G$r6irn*7= za3=d#Asvlydh{XAIrN|R{D)!wA~0t7*Mpfvb8^cKj#j+3cjg3y7Cp?o3g3{pR6XEIC$kIRvB*Zh$9}gUw%=2&io-g zKt-!Ewczo(u+w9>W!)L{a7*E3;@~)d@6_q9WlmSM#PcZlAiRv<*_m_Chm(1KP(fG1 zyCYfys_|Mld#=n>W*-gB)c9b_4i#aZ}otZ^^EaueUd9Ll9G zJ(TQW>W@WHMMVW*y!d5!yHwz3c3yjZ0hvRD9Gz#KHelkUry78nX(-ZvJnbR(A*MGY zbpg6x8xa<#badM#VRePh_wU+Q5p{QIqiLFc55@ds7ejXcX?M$YdGwC zRIC3bugsF56`t}UNST%Yqt45)Yp#5vx1J>J14#uZl*5S-^@G-FPaB6 zi0!SZPqY;NSO`HRAKC9c zi)GgmS=o0Kp)-fT7FL(zANCf->vNg(H%HqdmUb|pr8|Vj(jE5WPkfnSY7P7#e0=Th zHXs|XKV=jw@v| z=>E5zco(qvocb~_{n(-Xh~K^aHaQ0E@?B5hySRnDx}PKNyG>c<{i#}yIMacQ-zUS0+elHocGoM9dJNIptsxhWAbwOkM zI6Ds15zb*Y*WCLAUX@1eKz0DLIlN=3GrRZh z`3J_NjC%@s0}s6eScH1vmIQ=;;W-Ruf4V$Qw>t4}^?*-(> zDDT|dPg7-i9zPbIb<5yep$XhLxc7i$$_pPP&0Ha0ex!A3ws{2`ZU{KPBD_elJh7W# zckv=+-FsLMzUEkHSd+=jKEAG-Z^JZo*zq^yZsWL2`s&?F%k404=EVeM z)Bl?~XQblKG{HT3~?BHxXC9hVHlX^F&g(sxgSfqF6 zd&v6r_}sEwL+>yWX0{w4>@S!-lod83nUP3avz(6*Af*3 ziHDC|t{;A2wphI>uPGQ_3e1a0D@Z+^7Km;ypb>Lh4`Gbo;eeX!O_9?ry<%-d3cizi zE!_XDpf*G|Dx$B|VP>7-!AGU{sTiiyu%09kK3U^v1PHf?i?$XE}!s!mr*R5_K_7{I60-se3TqmAn{?%4X*qk6{ z)Q@5SWKx27p+p$Z*6$I%M+dLdR6c32P|?zrI#}`$N_Xbac6|Z)GO20`sx_CzISR_L zkq&r~rhq`pud7*J@e>o@T--}Y_Z>u7SP6~PvHKG z*;XP3koD=H(S2R~-}S#qzot|df+TG!(EicUPS5>`!(4P8B>6Z)R;a3L(l?>gk$?Pb1U}oWsL+hDMOl7Rv`Pz~+6cX; zq@DOYwxhz5j;2teV`6HmTB_@aM~b1z9$NzhC`Sq$L(2QdUIs2(X-IwQr3m^mJiEg= z;{5cnMKAl;cbrVVIJebSui=7#^Z7ZgVj!+iZHTRHj1f>t6!4OzEpb$)37GWw7}mJ# zS~-3lD(trMvrIGZD5(r*jSocDX-F2 zCwEOvjbqL5BYY9_XBo2lqpmZ!tsHrA7H$f`P@WQMV$_FHD(SI@d0tE)&$PmU#_~hg z+qQO__wBXnL>S<*IW#s9FCvBKD~jcRRA2=YB_j+;i_<+x>6C zm)nfZh8b&^NFw0KX0@q{l8Q>U@`tF9pkU@G>qpXCKarK}&w2GKGXuFA-x7BaPX>r% z^?@`8sGJ?R7!}2*n{A5y z)N;|cZEo<%VVN_pjr%Xxjs6qV#GJCCO26!zzUi`4)6hhYbn_}Ua6mFK${F-AX<7^= zYmpvfjoEUGF>ii?W1W3{Gr}MCm8s~cpsk1KFRGB5kx|-g3X*gV;gXY%{dIURif5@o z8WtG@Aq9?___*TY`}_N%4EnL?YEcG6-TE9u$s!xShCSLNVK7*ZuqIIq2g9obZA(iT zC^bhorW&Iy)L8q|^(Y=8A;{R^kKL+p3L@iqbK)N5ROFOGlnP-)imGNyI$`XAV+nF|@V0?CQu|+AbeY$M~iQNmj z^+}4if0xssjZa9}6#f(j0UAfq;ABekTpy6fvZjxqZ3fXrx~1YbqX8C&u7{Nt1HZ(> zsK**v@cY=F0$2*{t*q(=Pf^%*$4*hGx*q%j`cyL!DR$(&ScDK2MU*_1FG^Cjlww6$4Uo*}N7t-jx`F#!fs$|@#fQwK&7SVy zW%|@;-JjId`-g}5g8OnrF(ny|LFJVSpenYW?SOOZ;}7G59vv!~@I00zJktMtBk}1X zQq(@eFqwld4sUKUG#G&=CnwQuK&ygn&Aj}Ql7E6m6{|zEUz(64D>Xz%1bXl!{@@Wy zQ>hQV_m?XsD)!8V!3@k6nbTB=l9e1*fU-nYG2The{Abx3-=LW9!G&GaJb{R*_aQu! zT}c`fTms}(adC0F*|!6e@7{@B1s$$-rLK4RHw0fFBO_kZpJiQyGH&s%udkC#3K%mH zzSVT&O0fOxDy(jqqm5c+A9Y-H2)8VIQh(&L#vHsBT3WKgT2$aV*(Ut7w#)KH|IYmF zgUb@}ii?}P;xYfo%e~mz}qrIWgnsJg6`eQQ*!RBn*+;;w|sp#Iv~E zrkLrj%R~L?-TnQ@j<;xvym-OOQWPv0`4?Z{Q))<0SuUq*ac8|Lct?_;P*Ghoq?@?A zYmZui2`(-L7Z=L?lf91hDZX5_nfWCZ?mU_Ue^OMXvJXKUvW3hCx~S9WnI!!YCGhj} zBl%e|i|*!?yY-f-NfJ59++?F;3>okP+y&ob#Sb*Mv=9?08?`u-K`C3^*VVMN2ssVw zY{CNwrPkN+2nbMktQPI0F;J|okS#>yy05H7u7<__w;ZUGTgkj51^(sNZ zseVDB#J0(pnwkbHR$kAdjsZ)VeohgYsV7{5s(|v|sa-33LOw#fUX;lHQ zqc(2JHD-a(#7HM&1E>D8=)A%=1!@z`#wfc68}YQ5+V+_RH4>ILYHJKho`8HTEh)XlIMvn)uNeO!DzYQs6!RMyq8 zrm0M?t(mELHCk=SX=@uA4nGD;(l_e}izd~1ifV8a*bjeUl6ZO0Fsdhp9p$O7*IWUu zi|25t>dn+;9;-w)@$D7UzES~?x6bbxdz3TNoG^JSFf&f~JHtOw#Q z`lh7?$$Gddvs>yiz{u(~zKI}EvP z6la{=+;)CkOw#zQ-QfMv>p)AggD^wp&G-=#od=zwIACE%(3W-6i1}c2iMim@B@4{L zUyK${{(D-jRPe|*y>D~u{5ilcsBC^#<|>o()+JDJ~8h9O)?)a6JvVqUB}b)t#t;M3mwK*wvBgMHc+zrGn(dm;RQa>-&`-6m>gbEvA0>g z_Ae+KF1)qRu^w+z;1kYGQ_Dw6V#DVDWvOBt%rXv& zGW*#I%_>r4X*UG}&dp#YrA@@)3mne5fA_=e11u_9j|Rja@EWy_V;=5xh@(x`WP@D< zjyH6k)BGa+SA-*}?Qa2Sm|huXv(?5P;8QpYzsP{SQ#C8|Undi>TJQ98aZ--khR_ey zNGBR|hQP}^I&!WK7PERd$rsl6LB+an*sNAivzsrA@XK1sOP_-qwcoLY|LG)}cNc6Ih8*n< zF1vX>U=K75*ygZ9yY9{t*l-9()3I{xj4@>U=Cov_{=lvj6Ted6#Fm*^G6RC_LzE41 z)>JUwn_6aj`bHopyI24NMOYb`Q^MALFTseYe+_OlA^<31ECcnBZPVsXpDq!;{H82- zJT_h!Qw&Mq?QOX>78Y+<#It7F=b(BZ=8jQ&ZTlm}mXS?kjW|nOX6ib@H)PjNQt;Rm z-}~Q1ZmS@YB{ieFe16=rct$|7_3~@M*aF`7VdWY-G1@^im{@O}G>C}UqH#jZRtK;n zX=?fvzE+r_iP4AP&*UP-yv6j319QHOdrqe4@k%F_taC>F^XLIxD_0uV@=u-y zCCx8o-a7C*l30OL5gdTU&0%Vt=r`H@&#=5dQOd^3RcKRc6Jbye_w&=SWGTeb^p8c6 zO(x~=Z7w;YV;IZ54(L=T$Jk=C4k10UB@Vj{PigrC#Z)(f3{}0aMpILLk?6GQx(f9J z09RRFB@hwB51V+!w#dum4N)I`5}daYn2idWsxpX28VlGjXZJ5nEnJGEV$QHuTpNO&&a#_*U`qOC7+N z!F@*zSDI4%o+B%E?a0Em0dq{dj$0x>8T80_Vd0mauEwXFsHeF-y-+h|C%s)=o|k=v z5UA%Y4Ll!VHEytZA>n_>Mk``m(aGC3o~Ruw_qwmVyO@~d+l9`DmtbACu}u!1ljr(H z-FPhNFUDB(X@(4Nl#T0s2wAY|&2h(WhzMi_qjae=$9DB}jW~Lh)OSj-*y9E%W;xl@ z<%^jFVi^GPY%kQDth_m~6RBXXEOU^NRxI`~83W6yy09xw6tUD5hugxkm-KwbfNL{k zwI#Cm*(+F^#o*_heK#*lNZ(O@B$RC?2KC`cX7G#py*49*E>M5K)P`Cqy1K4DUyO6a zSeF5-G3z)2OZY~ANAqXM{y_s$*mYPL$KoA25B#h|Q2-t_GLoTp%^z7N-)pWlRY@+) z23~JnypzhDn-VP{eXBEmE3)C8?keIl_8oa=jps-xVjE4%ZX`v=LX2sLrCqT_oMBf2 zq^Xh0u+tXeHV{oj*jX{9wS8hF29y>_<{l(l8Ds|CMWWW^3yEGyO;s1e|jR{W7#r;-np zj4e?IrvzR9(+j-c=P-!wOS|R#o-n?YH_LM`P+;JFUBKOr!Rqq@QWHt-5Ss}yCT9hj z3bUAnA_LIO8Y*@(avaLE6I&r{ZWDZQEic4n3culH+wyRn>MY|Gn>}xi=X=IY&H6m0 zQ9F%VCB+5|txDK5Mte#9_cZ{D({VG1E}BCMO^&eJYqAWa@_bX&WYmgFKCg^l&gE0j zoGnL`LdC+8&J|{lrf+=Zr#vG;`4SwAvRvtit z=dxYaPTkhWX8r6$I{hWTqjO)WRrxa|J$4VtJ zA;sUY|4Y4E&t-}nL7{7LhS0l@1cxQ!3*xLL!;|mre2ksH3bhx1Am_2r0Fsx~)~1w| zv6z_b5?9xi*Y>^^GZ*ll9?N=ZeK_HM67P${9;TN*e~qA)u0hD+OTe&Yt$WFot~%0vdE2 z;NpOSD=E3HQjQ@F$oQwVv9gp~K{XW>mGzVlN+B%kew&bbu;4(O3z^7<$wJiW4_=A-u}Iaw3MRU4fboKZB|$=Ug9 zadG5b+{=L(>L`X@vX5yFs5Lf-asD$~njZ$GS_^=OV)UdM5&;p^kUMPhu4k-;%^Agy zqQQXpaUUroc^sE}I{k1QmlKPxCL~vaEc){1Cq%R`ZX1)iwPo4+L_44vZ{gjF3G!{a z8p|JA08?G13pT1B+ zq=f|^h8zkfj2#LRTx6d%dCz*n?hxI0gam1-4ogiAJevai`~#<_ywUP+nkVz7uAUxG z*wl;7u%~m??T;3pmXx28T{c3va$L#b*Qb(%ixaHz3nnCv$u&YX#k?imgQBWQm*xTK zV;k;(SmHDx+Vc)+x+!PXF82ql$-L{L^rs*41MtaaX zoW3?OHLG>~vTlZm3{EavKCVQd7vCT}SAeQamn(PQr})qE;$ASM4l+E02yHU!>lb)%SV?jK0G^&P&)YNjJuH{~`W zxvta&TKveauIq@~g(&6Hm^iw*5BXa;27daoVe#+!(7{nuH9VYtUFu$?v}t|;=5v$> z2gAe*cQsMZI`LK4QP^DuH6MWa-z)9qG;8x%vFj`$S6ebd%-ZFoM}7QErKi zBxKYcY(!OaabYf&nxAedu(K>2xz}W~>^&Ly_y;*5wnvmSWP6H*qV2Z?U5Gb#iBF4p zdDIQ^R4A{c{%AyCCW9`9?3*6DYpK!nOn+yK3rb>@qIO$nr}%)-RbY=6s#>I}@aAfG z@8&o_dgw8pjW(W!_S!CED? zS1-3Fw3AD9d%3Q18%a5X$-Ze?>_ZCM6Ukf*=1{B-lqWK`K)ct`EmevUg=jJcFAL64 zKCj^mi|}t|BF#o82xdzvB~22iXsGZZ<_R59pEe;mIkKDjBIO$pFt-R-wqc6g+j+~* zxP^uCq);By?o^?cg9EEuO--pRC(0I{xCsd!DhTY3>gsJLYGZp>fJ*_{9dcWx&66Gh zPkcNMqAMvW8Onvu8-MT?zCGIS&Q})BvPSu!KOihX)6dxBWXgiOjiT-1E31DTJ!C$= z$BpvL&~cX~YXcKTp$&U^nzxY}AMSdK9vxlc<9$;324yKKu%)l+BkZH}?up;KN4YHg zIU3T7aL3PPlc2pX>q`(#H@BGg)drqh9S(>XGvX>SIdV)?r=*26w!igA*HcjxFsVg& zBi(bdC%@c8HIRlSFF$w~REwLeL^8byAM3M{c{7N;efDs;(vrSDB^7UHDmV|Dn_bgT zSH~TLa9hg;W8#tntx$&vP0jgXoB4UA%9?6+t`_3mmv*+jb|^PMZWO&CF>RpdBwd50 z;~^`c@v5@scjGOos-~t}bK6uos6S+7#Ux?KMq!QDzu$z@#I@B8(dj& z?0?fT|KGbpyv$`MQy~Wzy;i2Yi-wF?17~2YOkQUD8?R&JjO9{rdyLx2mhwsH8_S@d zG8$x9QJz2sRi{{f!4)H;Sj9Wod4TspS%R`=_h)z!dbFL^KO|_H8d!Z8%rcS^d}4n+ zcF8nMA9qLa7ll#!G&VZ4m^Y~*aq8UnjHZc@wBDSl?n~WA1RwoV+SKXnVtAyfbdZ?K zu86i?+ovX(OZ85n{dM@xC`EXT%m*}S^MFSIiaJ-OLnTLJR7d|lD-uaAU6$GGgKZM=puN>nB%=4dQ)tS)#`e3Kc2n8sd{p62T)G!g1i%(9x+@BfoTIprCz$Phr1W^0k#rCA{b;t0 zExi!LiK2EVzpCsl{#AN-9{m;Oei(NP`TJRE^eE4`j&NF{XOaf)OQS9wL?2rDOgPk^ zxi@s!^!8uvD0u+`mQNB&bAPn>6$C6OrB9Zfo9C!A2eYaf)vdNb;{EqN?cP1uO?Ul+9v~=^KZnt(!2WdL5!F3gRjRaXMoTM;>u5ETg_6Y2h;^pzJr(oRsU`khv?>dC=XM z$7WTbQsA7($! z5uAREGYxF5PO7ctMzs#>50=YsC*rkUEuzw#k5Pa4*{D~;%YV~CI98N552-irr;5kN zM8C^C0lr&?rLN+@X}Ygv+V3Xd+g>$)mgh7PId#8hTP9*MroO-*zOaTyMAQ_DrNeq} zUrFeLnajJuE*qZY6Vah~`fFypp7VS4k5N7i$2Tl8oIh6&LS=qe2|0K^uwa)H#W*X` zF{PsC;~SplzM$~Ax|rI@e=lv`(URZOU+|b@H*eu7Wf^>{-hTHxz1_Lt2X2fSJne9&(fnDBv9&`meEAQ@zeQoD)Mt7@&U6Q+2ygPSiUw1ZN)I9|APoB zytAD2eKz;jbPP-6aV!(q+B2*?nMw=0liRbLTC@yh_Yk#1f7<(Ia7VYQHgWKjSC>zg zy8t&Oidj|^ekW=1YiQXUZvSDeH2=e$TJB-*E|WC+lc}*iuzwVBBB-m literal 0 HcmV?d00001 diff --git a/doc/img/12_user_layer.png b/doc/img/12_user_layer.png new file mode 100644 index 0000000000000000000000000000000000000000..d7b31a08e165d44a9903211197f3b126ff2fc75f GIT binary patch literal 10592 zcmeI2Wl$Vpx93UlU_k;w29jXG-7N{h-JQWb*dP;}kOYSWXK)z?hr!(?4DRm1J?Nm9 zym#+bZPoj(+*`H#Wj}PE)74L(I{kE4pXdDgAF8S>gZGT$843yto}BDQbrh7RDv!Pc z7RKWqWTL(NXt14S^*|^n_+5XuC-E%!lqe{#P~<+o*94~?EP8@TCa>F0jvPG%BA*Mt zjzfE+6o)_dlwp-IGay@5gGsuSD2(K1wzF0kQ3DBwiR|`M^*2%tZiIxn&%QpFeg)_)MXm%ydOV|9GNfgL{-umlZAL-1D~yz(~=i$;?$qL{`&j_mg$R6egf~X9{p_2 zpTFh)Ivp4>qS${=&b*6Z{Kp_l**|pu7>p{H{@1>Cc-0sC*M7yL`%LuLmIud zNAxs)dD^Ht)=K_8%zih+H~0{`S0bNYJp1#Pe~V;L`p)`U@#T^26+WKXXlwInBY8H; z_W6dmNAvxAKY{h+b;|4Ju9=4&lrDGRMGjZ^2htE<6zO>DLFScborY|yPSIYdL=ZQ1_TFFR`M|}$UWy*5 zUy}~PX|}j_Ql1ZapIc1i8#g_#W>4`d+1WFxDMkK3pff;~))0Y{tjRn<-&&WlG{akP z@xkHOF7ruTei#O2q|gK)j;JQ@Pl0Mp`}N^>{xr;UTb_+2CqHmR61fol7MXl0NZmlx8T%8;IhQ+?*zW2gtVl;PR3=-X>iKcnlB z&R$fRHSA^h52kO94r}#Q)~MlD7?o^>;W{@f zO8^9%rdO_|TE&4PTnoNGx|BZgw4_bPS9B4!+{tVz86W~F*){DaQB)Z5-r|IEB?`F= zysM4ZuyuC_oH7QN?}Y^-1|cgOB)x;bbPab~J`5AgpME%T`0@@~()$zQbiN8~o*%Ev zz7I{&%bwzNPD+L=G-`+&y&!d@(p6j`>%Tg1lIkNBLt6Yw0qd}R`Tp?@LFsy<3yzTf zn$~snp>m|XK~l!NFYBw0==LvK<-0^z=Rrue_pw=u9Zbh5SOSJ^t(ZPDMDlj8b|`Q& zo+K`2zHz>J{n6HR*2Y<7wy)XwWh+)kYL>E4NDEeCs>#*OiUuNM^ z@;u2+(B!XbNdw&*Un~}a<(!Y>>{qQvGLhal*cDu)V?V(aX%%0Fe;k!CC1B?WpV{(3 zLEFXJ-7uh^hg|@~jai@Va8?i9h?{}q?$g)8QjoflzoIO=#}OId*}=)~*S_M?0WUrB zGrWnfJb7+>3kG9qLNi)godo11#pAhg+y$}gyG+e@MRu!f;p*~C{fnq}7QUDpXJa4T z-|UR?le(MVvmlIf)TE5BKiplsI=CmAjJl81d`JrwTF^u6Bm9hasDukPE@KnBfV#O2niEB?M*gbPgY{z(hT9o(-;^A)&%P(vZEi$FDr<^d z*Q(R{`SOwvFgv(vSaMz!)=#rO#MRe$$Ly;1NogGj1Jiu+HI1VqA17flJ_#gr43a(o z=;-X=MouKc?h)mOar&dR@ZH+Gss>lzdO@rY6B5SJ8fZ1h0oz-CjYYh zqRw`2y8PCNw67pwBb^Lm_s^g4-T6l9H;c;&NgZ;8yLECuyl+fLgw26(xPV1slHt)g> zLhIAI=&6S*T%>Wq;%~(8a;I99ew?q;1hA32_yN7T5U=p7SRt5FvmqGbapG_PSp~Tl~62eTNms&e$;NRbRa$Ph+MoS_gK7S$}?_1euVOHn!4wY7LH)HHH&?x)5g-iESL!}t19RJfU%*9+H{=r`lkPV$0fkhm|o61>OF9vGjSvp4H=GHNM{ zhk+>|jJq9q1IKowEKjFQkhvLGN0eY3TJF2nm7zyVJH3O+iCj>ekzenwOs3tZE!2}Y zB$asL^t)fieTI%o@Rz+)I2ogkb5_D5Y&OP(RP{~=co(VYHJj4W3*fJmjCzN#RGH_z zFPqL9-5%MaroowxIV52zd~&MQ!QKUWaAeJkJ1|T^}oQu;}v2TX(o+feC zaM|^0w&=Q};sk_QF8_9q1MtL=c58^l>G-l@oq5?TQsHi`&YSN{>t&mih&63K^)iAK zsgnv4W5eOc+sZ~KWF~70&p$nhF}WqFn?Y%@L-Vk`(A!c1FQWumNovaf+SX7`d+3T6 zIlKIxa${<5g<1JZm4eyrQ1T|sBe~4e_FZ&(waZYQXi9zI=+3C^+4ed4R!%(p2YM*u z-bTN>`RTXruT(5j^>4b59p}%mv4a4UK%@k-HP=ykq4HJ)2W~XobN4%bL>8;#4*P>G z)3~E>QIEjJA(8)5n)~;UuaGEnS%Y?-jiEt>>5E(FwHB-IRYXL03UXN}rainX9z zRNtJ+^}aF0N+0Y=8jvTsha;_7-Ha#7jt0I7NxtMgqT?b(L5&PPgBGmz-Eaa8hj)p) znbzYbU(&hqFk@H(!^XN@uP1UtW@|!c_$A5bVASxv#ERF57&#$;v2QOAqPOdUYhBlK zaUdw@RM$9{<4Gh{WeL6iO;RKC)%(ksatA&`1s=Cxfli#VldJkce28{%t9HAH{i-s8 zf9a^L-%C~$o29f}Au~V z=4rVzJO|woZFM}DT_VU8=eCD#mX-1hl5sKR*Jaa8S#+JV$roijOn-;pByAe-dfw>g z(-GCLvoI9PWsfp;+HA!vAN1L?^MVUV8zvbAy_P->y6vUI;iGZ6z9z32-$=Z+u@Jy7 z`<${G`+cN3oh5ohc@wKz*wTfQ1)p4m>_%sx9WamiUSoM&N0{FB5+euev1kSg zf;Fse*kpYNEGZbT>S(`yZM${8s$kB)Dc|OgD8XH)o=0i$!Ig3Bh|nwdXN;ghJJP}Q zUU5bHh??#gEg^}nI*PYH;JnMMx_ff|)4%Pj*hoHQRsY!viF(bzJ6-pjs@ga*+r-n)Z#{In{T7O4w;@7lT)2h^&jGx+ayiK zGnI&>ZI!NE%|5K}dEOOxn+Tn|R+oJX*ircs?9)|K*VrZEHD-xCx@y(uJIw^=*>b+b z-2tMcufpLV`|cz*%3~ZzkIr(jg~j~ce#VIyPlI>Np;liuTP8RjVjz z&}iyRRfN$g*@+DFzF3&_-2v;erMTF5^7-xI=ugL}Oqa9uMP=wtJ(wI5(?_abksZf| z#l!4&Tj|QLA~~0S{xMl-(9?3uo7QKW4_J~i9cgJR+n5^_+fhbxNy0dD!5u%I zUrnRTaN&~HqJt3M!dS}=^H>F-&6%d(S7yuEo~#{Y^}jrJ>fj;NiJlSGISuO4Fs4_b zuwEzxug3q8qb+OC&|tl0I#jU@Q(J7r`;@Mrluq5l`mR3>Ry1D9U2=mymeno^Y37O# z9G`=mE9Mk)z#DismRYP_Dn0`-+)~=yS{2iQeFZI~7!3_)$@er3FMb60QRs_^sFJdh zO7&c}GE|ZVY1Pgue*7wB;!!A>wxu5B{+fz1QaeSIlsOh&ZZj7Btv%A}?kV=C8}1BG z%DzHVbDJ3lLSNA_L*Z#b^`1&1Y9{!~Xc>)^lVwEvv#Mhn<-LXzH!thg=GL_qNEpZF zak!~yE8Ajcb;|UWgQ_bHYpsz>3p{yc#Y zx2Y`Ul`Sf(A7-{nkU!>%oM-&m$~ZYbU(kKdD=-Fc8S4Futhdew+M6j-ODL59O}0d< zEWjB#$|99(sS0}k_`qXfJwZdB4aDYsG>2&Gd_55Rak%vPexe}DVxEchp@|gM>%N-9 zH$9$;N%B@|jzmreD$uTgx#F^BFaB7&kZh7gyDyL`3MUm%xQ=I?JEQpWAFXd$c_);_Q^yuMcxaa_p>~RJLBF5-cf z3j%3xQ^4QXtc8N zH29R+3)9|w+0u9fjlowWU2Zwb`p?=9+Ju6|(HENfA3?*(o1bV-f2?Jknp7%};3f&< zzoBeD)oT(^6vU0am%p2D2UroHUD65q5T@Em1`|1Nzm1k~a0p!NZEs;{I!riSWXgB7 zF3s!d7>@-b-cH9d#`dAT)oeJ0uicLp;2IEpQ-F}Z%^}QDPf{e80h)4?t0i$Jk7vxp zUOM$yAnNw}+$ka%+TtqGi1DP^%&i*1+E1u_=tZTfqE@k#3&YrWP@G;G@hgKU1dTyum9L}s2E zP*l|`u+u~R)Z0fk{{|}ot)^Q`1KitFP{1*m#!+z&12NHr$y(LJQ;Z6^1`Xfo4E>6N zx2Hy_7&$2`c31$@^e5GUQk7xfFnh_k4})#OY}ze&V}+HYngrdR0jreh+}cd;L2sz- zlhiTvEPq{6ryI+!e7_+XhX_(u;2WQ3Sf(NrTQ@;z$-q5 z#k-yTgHTlI$DYXKI!uBqIifhdCZLDbYt^7Tol-`d+j{hM%m9}|l31d4&Qji=jmg=G z&k6J1Uy|xKSsB(X6VSe^`mTt8y*2YZRXKxGn%k2uoSdByWKCMPZ$Vo}8(VL3uv{PF zmInJ_KB-gbTbS(hS7#_gziogx5W3R)hA7MT-XYZsW;gzMm19tz^YvODMqVnAI`8XP z()E)vcCa^T)0Bba`UQSvV)|xtKvb3B{I}`7M5#sG^??KVE0x=b-@^=a&*9eO<2q>_ zHWP%r4xFZzY@$uR@gX8o`InpAQ5SY{=#ozfTfdUbJ=W5LwmPIKF7;Hjz;Nw)yf9RC zG!d(DUAY!cqb854S^U-e>c)MJl$e>qPR1b zF@v2!bZmteX63=fVI;;iaOcb#jM!~YeK!!#bK7u4R1I_5JW`4!=exm;qPbTF7bTv! z$}J@~5cj}YeRtzAQuDX~ zXJeq;jh8G$3RF9iTzpXn3B1u;PQ0kdeY``dF+ z!DNLj>R}=$U88utxe zc3@ab6!sntGmv_SA!`!4Vh4HUEeE)0wnTVCjK*(4t$g1ixuOJ9UD#hOJKhx2zzh#E zkWbWBS3h>ouIjfu(?STo2(ZSf_&Z+e;bLeu4MO9}v-V7YW^Prz^l7}jNM6*pFj|J5 zckneY#miFA4o2JsYjBaT>B|ypgEEdw_})3epGNWml7)H#`mir2PYmnu91m4R!%v}1 z_(RJmz3MAF5G3RApCG60OCcKb?00+T8!Zk%`)31;G&uClr^GF-k|fL?Qg3xi@HZ+r zko%RO>;Vwp+t^v*NS^L6#)m?X`(rzA=n#CuIo>$5rmAkm;;!lE^pv=i#8sYyR&&9$wBA{yUcYKo>jj@$Vq;zZCsHXyU&PvR%ydTZH#*?fgForP`}~ z$mT=Wxi-DZ)V}O*iRG;K!)GpDQ#Y5qKEW99?d2upBCZuAniE+pGThmG|4Uv)t59qKW*gh`{OJS%bU7`it5=yt(31T%mQaHO*D~< zKfYvg4or58^emX3w_3xK8-`~yf|9sh_#3kg3pTa}K|>U(Rz!z}E58W6Zw1(M*5WX5 z=X4-sz+y#suEMR~8HJP`AIu64z8Ck8alQ;hBk(ZsUD2Gnwak{k$%>#}AYNv^_;^>7 zdh`@lzOPHQVL)Iu@nZ-qU2L&Syl1GK(jT5A>?fSUF{@DxCE!avBzEWfo_)SdXQE25 zn>g~ts}0F^nshwrxgY)bJ>HW950A4$okpo{T&QDPuveRORHP$!yK&U^Dhj3{E%;V@ z5P||j6ZJW|QYziS7$F|rt37~x^>+VCKy5xvZ6x`+b@{oSnjNybO;U>ZvxY)7|2^*6 zWmdMYU+p{vL47%h9P|`MNRbEig1yE)dcbedqI$o$wvCwe0n|k(OnURU#!0w4IawU$ z+7^qHL0xfxc8RK8QV)Yc*~9D8Py#U@QD?gJV*pOF`gRXPx`H=u6-|1cmrJ$CiFKMICYHBBtEJ1poT{XCo#Bs?~Xa zi=`?kRo&``YHhq@x3PeVA1^`4#J#v~214=LI@4VKu2_wwFY_0Qv5l2o79t|Lp@%GI zx8-6SB*P3?nsZ)M1xRh0`^iSJNS57T13r>lb^UuB>q-RZ>k!eb^w&@=yy2 z55!bn*+LcD4K$aZWr3OW3G0F>IZC`x038oKNbGiEvj*Ky8ZGgrKtC?!Le^8Fx^=7 zj=PGJr0(jmOzMePh9DDZv|my%*H~y ztJgX4?vOZj26tCOF=(y77F(00nmm(bz4yDw;-kz|V@SR-o!DGYw&Q@m)T}*k;V%VX z{xWs$A~1VywDsq1D-T!jjomm3?DVX6r;o_bOXWo+OU|{U(!t)((P5S}Nyh41zdtco zIN_R!VP0CLdjz`;LOPJ2ICne+<$X$VOC#!oO{wtFP&=6iZM&|rXoeuYM+RAlivi@j zgluGRPkX4S1DNac3yrplVhQ3Ad+?LTNqB^4?3jK-`OWLQ%xPIaum4N{$*0oPS+4oD z?`kr%bq@EniGl2e6cO`z?A@svI%Y$Ku?E)#-|`=|+A35fhttVoO zP2@{jPsAtj*xgt^=IqPDx3Q+@PXEX#eUO+hRC|qu_^AqOqztAve|z0d49M;wj;@*# z#`cN|-+L=t>u;8&-Dv?BOI$zkr~w*c8*W{%944zRRjNhT9H=ixuW2$~FSAsqP(5Jp z1#@q!f&3MXJU%fLO6qB90Vn!O3i^o|vcqiEd>LWvA`<{8Pp0-Kh1TWDC;4)(^OKVE zze}mzp{nKa?mg@WGi%^iTS)Cz&>k@y*&~M^StN&yJ5vzzR(L}T%hpY)$0@L9=EzRE zmf!AAAJ4A*fRMY3HE;t8(gcuZC>r~_hwk3=m{cFsd;*3x1ZoqD9u5I3z7ak-qgaPjReqe8B(&gFt5`x0tyW@Jg;VIJPh1xH<1sp z=^*Lo*GgY*yM)DJ8y!Yq963x=Nsb3aF>Y>RDIDSrxCQMiE7HMFnq4IL107MPK%IYV z{PpGQC)=7MjPNh3S4Ow-ws~!Pjf2D`fqf$yi0NcDKvLJ}}StCPdRpA9ilg`r~ zmB4Vkl_F`AL@VDkfmL5rTnL^TlWERyIR~ca_7R@IW#`lYzKx&8|7VO;JWLtJ_ZM7F zv)=8DgR33G<)b}a^e1Sn^?39hCf$7C0z#5uK?^UNc@#4O$?b#U%NJw>FWcxZsXu)7 zq9CKFExiQ0o)L&N`J}{(*H(CxZZd|#nvxwiLB$!|q0Ru429=ovK3!=yXmrVq+9;J? zW0I7m1}68;u_gDQKuIA_VA5WqAlW@xqt1}Yn6&58gCqAM!a`7$LS`4&p#2N+;I?=L z4lQt@mv=e4et!A`{m)+jAeX5UQKUGzv`FHuqlz&ot6iabq(r=Z^pwFa&)_m5GBS_u z02Nh;5Q+Vsw$TMVIFFmb`?d7k@H49?w@kVF)Km676b&juks34dTV|uN7xHu$J$xOs z9YR$egrM4lti39g9bMtzSVaXA%38tWxrrD}ubCGaaq`ix2;g=%LE}@bSz{eYM#@0^Sw6(t44THh0B=-^K7%I{BiQoM$y~ zPr4cZ(=nG1ALrboJ^8yww(2J;4T++cvu*AUR3Ru7@TQBhfA$}v<)S7ad0RNWcs4ZD$naXZM7u-ocq zMo34IBm-dLD4{XDD%Fojz~UO(_3ARZ!;%& znB8o@voSk@`KpbmE;tbtF(6l-(`2y25y>s2q6mkMV#SwA(ZYG^*LLy(hu?lydSc#& zrCQ!Wi0N|m97E^27|yxHZK*$byA_X7FXvKvW9^^3&N`&kC7L1CQCbC1!tz>pJzIWF zWeh=m-o8oR=yCKY=-~xDF%qH`>A?UAi@P@qabd^$y4z_f_y#9wv5E?|{BV)@sPPep zAt!ml#r1c0mc~`K`Q4n0U`bP5vp?LA3km4QH>*9; z-3}+w?n2|yjs}0%NMtH9C?dWHg|8>+_zpNlE355n-T|- zShY;6wO1kNzq7zrW>*2$I&5={wwx5aJjR0}PEH6X^EaV!d|e5h_}SFeR0kzii)GQj zzx;L+Ez;*H25PeilVT6Kp`QNu+RhzAF^`l znctwgr@yeb_gcWuUqLKMEo&-@475csw#<_d<120WR?pA)0X?@6IuI_U)i882zqY{V zvpc_g`o=~2E2~nW@IG)dec)?Nnk)Pz>i8W1$-t_W6KCEX(A@MFhR~wcQggi#YBRRlnfr{LVz(W|yQ_l%Y`or7 z5~W|c-Qe3IoTYU1vh%5ty5`P(DC{#wCN0~L$LjgDrJ6veAgGb(o>+nwS&5DPabK_J zObf=mL*N9YUsERBZLW{VY1UV7|M9MicN{L{Wn+!)FWmR0KJkiH;u+qotTOGQ%$L#lR`amKOnes*O4g-7XYFo=sc8x1JvsNjMmsQR-iyf_)3gEnwm4;w!o?4%&Q$1S7>#e>#^TZxx; zEt?EuJo65}y6npndA;b~9bGRFaYA#N_E4%{d_Ei>B%(|6hteg%U?0zTfWepY780it zHQKam{^Yp}Ro;=Za=@3(54zZ3Fu|Kc$>s#-Dm+cu`WK$(ysYzR@Mkp-Xe@x$?qJRv zlq99+O}NbNU#+0y(`xMm7s8##LL;^ORjdTl!|!b9B2w_1o7CrAaW`}KSuBLWZYW0| zKvME9TNBDt=m(n(-Lf5H$YQqX4v#eNKeTGCW?@060&Q>-aDzUQ(~JES?@oNnT#>}4xn&{oz+Nd3 z`P)1z*VC`#(lg{kcPZ9J;bfNK1$~CEhjQHKQVdIO1DH#m?#XYUd+Fh0QyqT5Np0md ztw$w~aDYZ3j+9KybUcxmX~WOcctnrlmrKCXa-th=|7!5iV_Uc+r`Y?Bw6RVcet;2b zF&6*O^ZlnJd;gSQ{nhzV>fS{Me)~%g@5wAKqXQpReE*RDedMnH#Q4`U{ofD-{_E)f fYgJ+U11kDADTbv~8RtjIB#NAr^2gE-CSU#yiS3-= literal 0 HcmV?d00001 diff --git a/doc/img/12_vlan.png b/doc/img/12_vlan.png new file mode 100644 index 0000000000000000000000000000000000000000..55f224b41673d34e38d64fb2e73f426f54c2d214 GIT binary patch literal 15739 zcmcJ$1yEdFyCn=EAqk!!K?8&U!QCx50UDR!5P~%B?i#EK!5eo;aCg@Z?lkVuxO-3Y z-kR^;`_DI1^-tAM)o}XM=A5(l*?T=}J$pT2N($1LXvAnpNJyApWF%COke(SJjsstz zB7Rpb_!uJoytb3kazsMH>VEnl$1`A&AR$p8eUT7Vb4xu~bWg?WS-d_`BzN5Ru44SN zFyr9<`8eDVN!gec{P}J3muwN-=uczUN!>evVZ;EzG2LE4cTV~rIBIT_g>1bj&qagW zkSiSyyhnzI#}+T{j9n7u<`$Fn{Efzr?k>PHoob3#YBNqluEoW_IrHMgUQq_&h~)

jI^bS%wSY6 zkGer}_Vn<9BcF>`wo^WTi<=IO0Pgn$C#3Z78vz2A*64RGJ@G$VqSRfN2F1(Ny5seJ zFv;0&E80$86sP|Ba!K@M^I|gNVsjoxjMQ|`uezv)M_xl3eouxE@}38(zz+FUF$b75 zjA^6Qd*%YCQUzv;wk~I^e2z)E1Pf%M_%6-41X*;V1h0H*#;%A!IdK+?_nBZGQ$PAN zw@6~Wq!OvLtHSv=8nSe49#{TVQ{}117W-_mlRp>4xGuokYQYb4AlxRv$kDQLyd^;q z5Cv_jKZmwZlux>->Tvnb{hgxxuk*lzh_Aw7wE&k#5xJ$NJ-(4IBpAP~S!7-g@kf+&WmlqQt5jA@tJPTUW0uvV51C ziP`|*qC5=1E@=^sVn`}FoF~1RKDBPpN#nLFzTMQ2oAZ3k+}emM`fUJI0;vp^dQ0jF z(8;A8!w%{9y8Dz@uO`>%P$u{9mNczp>6$Ep8_jnU?!R%88h_)^Enz zK|gM{*}5Nz1_;v1DXKBcQZv`Nx!j=aP5wRED!i|FB8{!U#nP~ z(8?U%&bR84i2Zn6<8T!q21-UI`v`9$f zcL4unX<(Y2UNa*76^%_+8vX2SeYMCK2AbGSdcEWe6&N}7+OgE-Zo@JP;xCpyk)HXhQ>*?(*B^n$Mgp{-G1BV(dX8^wv294>L8Y0$w6WlmaoMaJWMY(n3^ z4Z83?&DlBdANq&21jP|3jR;&Q(VEA7CL)Q~5=&KXF|GCZ?IxdnqkvJv*Dr%5a(0D@ zcEj!*g}NtrB%Lw$nk8BTjcjMhJWDbTSWvB_3MVbTiFaOU9eIw)uAR&YES?1rUS9A1 zo(0ddSLu&qL(TK!O?p>SYa{*sdWuC```1G6^zSjmZFS^I+R`svL0fqcmd#a%ms1); zwPr_aBOS2onI+R=gFD}^zV|Ppy$A<_A0As$eRm;oi&e?JN(*w->)F9jvWJz?%#F} z7#pl4$d@C<9mT2q0oZnDd-B8gs~=iLO298igacESvHa49MhC=?OLPXtY10jFA_N9f zm82@R4b{a@j(mCjHAHgFel6L*imJw7v2NACL-XxCA66?*Zk*S)u(T|)#99;DR&2iL ze|9>bN?@Qn}l?-hbpsSZLHJf8Kdy2VbwV)8=P&>kT+sJ94qab^d}stOzjyj9)TL)blT9wtf-m)o+rg)o^$rIbX^3rsVaeiXFJ zRreHapDRdby7Z|3t>48I^Sgtzt<|)7rL55{ul0)fM!;Zo<+m)@_S;%@j@EP0H?Ydz ze5ICEYSF?+n-ddvyF)i3<;}FiXDs>N)b_XHVGwGq24{Dk8-vZ}iL%v36Wf#DV*+0r zY@VHw6HY-KNxmP%LgvQiyD=xE&K&&=$+E(&8NFfL3h8fV2ET#U!>MN~_9uVWJ3gL8 z9vGF~`i04haMj5{;VIn~ybUNhg%TDwzs8JK$*e5Gh4 zqi3k>6kEj8-}H4F3c$!YQa|TnzP9%(^Qj#awVM|HefP2Z%?^SRRZoqnaVGXe8~h+? zpBoV3covz)Ma)s3EU=y4RcU;#)vPK-=kKz~OQLnN`;^0mYBdKl|r4jVQ6#f{BU&SFz{!J~z3$djp1L_dIgYc$?KgXY;>HCPdwq&3fnxdegfQ7>HwX-(VRB8}QvOLc}Qvmxc zO?sEx!^YRzMS*6h=3-WYVV~l{x#T<6@UM2cA5@c+4K4?#BBxO&2HPFcU4GfS7u15M zV;EZ*`k!HEZL5dg2AgfAyu_C_W_OndR?Dq{r{LQDh&1o!i%HyjM`=Yz!h>z$M|p)3 z?GA%Sz369ZT`<8%UHplBMUzRk*a2NQ#>in+7me~~*73*V@3n4GA;TO+;dsWq6XBS11@Gzf#5{L=j_Dv2^S3Cu`HRZS`pT<(_ zZW(m8usH9gM3Po`FqF02(wFs$=)-^9Dx82j%0Fhrpfskd41QnRR~^f^qhh#}n!iu= zR&-FFJ6Wg{o|AW=!8HZ+>7KDF*0ph0A1FWG%TgL7^YNcV$F=H;i~X47FHfOH*=vvs zpX_EnlbI^=)pboBgplVb2yT8==Qj+{zV24Q*D$Kt%?}&=c-m40&-(of0?!JNtr;QP zP&X6QElK^}r)*TSKK8;wZ5WB`u^V?PXib;vR=`)8{6)OVv`x)vXkYPt^Bar#NY%-W zU!+_ce>^7z#`sch9a2HoS4B~;m)lBQSm33^nu1bk{8vuS@&krkuu{z88e{2!anCIS zpD_BA6Fp~WWmIuv(;Q*rg(O49cPI@%yrtiB+?Zy-vGV-=6DCl z$#;wjOTV+fnTlXhXL+77#qsXl@6IE^JmR&>Ej8in;X&d;0^ymrbA5iV(+aATWVzZr zqKIJ*WY>ZQ1Hx1b{klG5&bqbfhFE{7A_g5E$LR)-V9+eJX^ctuO z?5tj5d zJP=vB_p8ROV4Na{SAi@~0`JwEGWeqm-jfWxCjGS{_oNX&1b@7K`*cQz@^$M|8%he-P5++O;I(g-?9BZYz*bv9MI5nF1+79`r3RgtUrsdDR#-N zvFOf#-JyXC$>vqA{a;PM_>-1q{XO`zY*f)S#iI& z_;OgI%K^2pqEB8$+yQ-R(lT8Yzg9(-uh?Pe1DEyZEMoWb=Ukt*KRHi7q{PENM;~z( zIlHD6g=`S~u88d`Ufb`m7*2z!Io?@vi@1S^(^YeONj`^~pSGq5a* z)?Cal)w2sA-r$}JdfpLGb)>i#xgWOI$n(Jj|ASN zqa|CEP{UJf>|j<*z4@9dF1PQ$sJk$FFP%e;0?gE6pN1)w%XE=KK0cGZJx$`coVZF$ z1LYZoK^5Bj#wM2Wk2e@?1q6yjnWoEEtrn`XbLtF}lHxCmBhrCiQjc2S7t}#%_%gg9 zp4e|U5Ys)|L7CpZp{EK$u2f(OIucy1{J&6VeI|DQq0UCUyqy#q$%1h{P+QUKHwRZi z(2l`2mC}E|jfFdO`qk{tcwO8#xv$k$(J>5D3OTY)lo^OiO1DY>P)yhF-j8W;)6+lg zO&y3DIq0=euUNe!)SRUTh)Oo zqVJto@{MEojT@|w%pJC9-+nvdkiK-KUV7t0r2m=R4ohyyE2@Xq^X*oXK#NeuQyxIL zq;;bu)G_1JNZ772tT==x)zI~N?R(vgj3JeJ>CN1BuQE(Z(v~1*)|+H&-vc~ygm&tM3QY9ZP%Xme|_KbBdltRwPup+-OrEwty0<^ z#Kolvw>vzw|EnB)aIu+dFHW>b=5&6hH)A7{s`$SZgl{*Rn$D)~&gRZ)>346OuBeZM zQtu?(6;clszA|h4a)7-h-J?!*T*9E&6zmDH`v_OJ)Tp%i>$Meiw5g3T?a8R8F?{~Q zz|3w}cPp(tViU5o%Z{Z$?!b1nBp6WO>%>u3du}t+5_8S*t6A_)_G#_%Zdlba`NlDE z_zqidgJ>YJJ+tnvc3lG`S~p_q8;OqdKwa-HC)6b3x!7&HQwotG;TN-B^$tW((}y^n zk@vFT^o~N?hj7Wh60_Z^CQmNA=D>d|wO-zr_{fZWY*~luQ89JNrIc}9@m)$=fRgU`t0)0c+x+J(#Q67$1nrc-4b zMb4B;>VNbr670{~24?kp^;ccfH;TfwQhDlL0m!=-+-WP1c1@be!k5RtZMTTW$5BRzGUyO!NVgulsN6Ya{mUn(4FqadOIDN>5iW)sls@?~7S zehYjqbNJ_aaXGS(Ed|OquwZr4jK*P+X?x+D?=Bw+SRK@`)II6TiRNLS^MF$y{;f{> zsvZ|YU`|zdNiH}_(5-4`$WXc`&b(Uj4q$V4VZ30UGSJUA<9OB#xdGU46K4`npRHiC z7@ahB=(?RnST!E=p584mX8s@KS>pRsp?DsfPXfUDp`>m<6y!qtZb9*9eIE(zL*TLR-@G^}ucSM{zP~KSPU=5bb!@7Z2c{cs^qFLDTN=~bF0htr zZqB`XN)2~Y7R1KKcD17?lpkazOL#EjbtIq$918w*eV@18A;~|-m&`dcZH!w|9XL5t z^NWx7H#U<5cheG77E-~(T2=U$r%@hiE^HXU{KcCQS^-2P&VUX z|Ltij;1g{X>0TRsZoo(ND|G~A*fU%3PU$HfjQ)|i&SqH=%W+sBVg+ALOT9Lt26y|c z{fB<~Tsw(iLw5RHU0c79nMAK{)}Gc$Am6>uF6`c;mvK!o+H<^yvB83`K+m2h5&!+p zPMO4v)CR||YQa01r;xJtlOvh;PVIdAu|K>eW_fkEmA0X9-_1rV!^(v=_H|XhajAP! z0n~tG{_>NrPu|b6zocorc6OI1)2fQcBV?lOhO_@EXXgJ?&M3|&w)XB?U`Dr*67`cV z)yC!NfQ%1Q*JN~Ofd(yRiSQWPNH{;X4=E}hpp0cTCfbx0e*R251CHr>bVm<&?ink0 z6@b>+BIFfW+)TCe*(0taxi3wDM#&0-noA=WuR6c?Ee!`w6tL5awhpy!l_WwNf2ArK zR5o9&B?)cc@aldUzj(fx9aF#Hahvv&&k@;i%7K8%CoQMVnYoK!k`Rm105>WsiYz*R zi<_|>UPk+MGo`2J9l&Iv-abZpE{stS4&nUc@oVOOk!%POm%+Ho4u5;-T_m^sedEWJ zj{CusraRZ;$*uIHYxvAt0}@k~!Kx9gm0@`V8Ex5AE82bsP!EE!-^)DXAfuqx#M1z)Vl?$AI@0Rjy?Io91z8Njx!ptzm8QkRV%)$Vl`1Al*r$Qx9KJdWwW@c=eLy z^gX5CHJFPS>NfB|2YyCQe4!xgK$}eR;|JUU5vrHJ1*!k11R*;6f3qd!{?9hpkBw}G z4#`Ig^8?r{a2}b(oEE{ApHxqF#@?%Xzk~z=;hPQIbgdS!w>tj)2AEux-;FiIDASVI z{0@a3spP?VtSt?KTI0w_^C z{B6|LlrpE>8Zm83z6%8A<`u*yZ1o(t7=wxPfte)y`MaH*0Qs(VR!sS>?$HZS<599% zx=}~Ki%`BkF|P_zwvI%Va4?v7x>Tp{783?EH~)-6ns^K?#tOg%Ot4}Geu<@ZJl`0Q2lKwxo1w2dvi$PEnOEVXQlJb&g3(UBE)8>H*lswg0S$8ToTN0q=wGwTf(oHIzGDrv;2Ha*G3)8Cx4qNl6(P9`0Q~L0YWS?-4G5 z@jE*^KM(8xaY8D;w)qIbX3A&<1X3op|E}iZD(<}+4#HVe3aeewRMV_*T^82X2@DdW zL<}Gj5D3I0AXvM)vsW5@p9=(sWbG#9qnheEAAaUF$HkgY1EIw5vyftOSZ$aGfZ{8? z&?rCLS|8`dWltS#+eV8FTf%)xa;E5SdH54LY8iEz-_=@A%ul2G<>S%Y+4Mik?GY0f78d5_=Z6^b z1}z^+(_tn;B#n$HLF-PXzNrt$YWvHd02BO}LqEKQAK{J6Jk99#yyuV=Il7*7A5cIU(Yj1>@gi8f$QiqW-mT|>m8{lyyEnx^CH z&LGlwD;>$g5Q`-L%3kS!k;M#3yNP)7Ilve{23p!OsusBw$?rZC(nTQV!9sJnude=@ zoI;Oq?S*JnN(l?Z-GA5A#Ahr!;R1#LgpCy1GGD?QODDwt&;;=Y-I^R{vufxxr?7O1`X#ZCEq6Jt&zS?+RcpEGRQ zep<_nY$FwovbDcipG8YcD^0uP8~hoWe|)&*Zh#Eg%;aQHDU1xei(<^-R5C8uxJu_u0C9@*-;gOR>%B15(K|W~TP&@teCw-2q8}al>(?*wI32`> zzq*z8r1i|Vrfax>1w2ZuV)0i#@LTWl#cZItH=VIouuO{&kyl@R5GmYxSX0($hu;XYR}W?5E{E2+vZzl@Wdgr%ZzySN z&mXjVAv%qteWw&QoB5juS6KQE>01Hl$Fy~fz3yUNq4T`7XA2#|bx?%p7)zha=ZQ~@ zjNLAzdlr@mc%ne8?D6sO2jn=Tp9V^w9aUB9?!rpCzcJ83?PcWTy2`DKEiFcWa6;;; ztINIbTo!D2Y@$OuJH-&IlZlBbH!m-b{!Z)%OL&sKuFwlHp~V(LZ@~9Kv;tKIZL1ah zJCvFxfe(lP^Wg$9x8h@CC)iB7SH@L9X%3`!mxt>Urw+mo=MyrUVjBv5KTTFI+z^X) zr!wOZwd`50+4s@4vo{#1h~#D~BjiI{re9W9NH&lk^Wx$;3NpK_>{|^#u~#Qr-L+oM z?{J(ErUUHeXmWG{^6s7^hFcyFj@Tf5v0VK&jMg}ndR-f_ESv=E)l0V|m(CNfn>ZHL zin4$Z#HRY*-m74-r2H>BIwa=A`epAH%`-Ta{KX`vog<4<5&vXuZSB^g&(6U<$`y5g z?}ZqFn-?!~O>$KYH2X>wUB~vWViQy3J`wIMY|;hcycF%jlvs3nb2-VsX?_Q{g>sja zl#n4OPYAatRJTSL&@j2EsCTi>!=#eU)qkkL5<4^%6tEggSJ?r378WPiF?$8fv4Xqn|(F?Ip?AOk~eBf`EkIO-$J8tK)u&QYYmP zG}cW!bPmuOLAm`uBjRZSNR~y2Daw#lM!^QlCc3HbiXjLmL-L;D?ohjVO{a%6kAIJM zf^*>S-~G3S)D}h2Ajd_KsOaiF^caf=_UqG|`}zeNMo4yM`Oj=*6n?H6h7b6m2NE_p z3L`SKZJ9`2oF_M4LC^d_Xf*uWQBW8)6;kl8`-qlo*c_sQ|m?J8;N6xui2A)5fUt?dO6ASN*=SuJ@?*dyPwM z1F(>xCiAm9Y`qW!@X2UnTQaz~(tg{=?mpbQ5634-?K$LlTn6W7LHs-^RZ0zNz1*AM zTj-1*D-9)$iGL#EEIgx7eGy`_!i%-LyUPm-gl=Y2uw>-t(`ajJ+mVJM`iD5^9~n7H zx^W*}>Btl{HKjo;#~A+yHh;Zy#G5;=tEn)qizdU=+Npq$BJ`Um4*6yGw4~6G6FESU zlh4vsFZrZz*IZJy0_Kaz_hvmkLyJCX-q`@{l-Hm5F@kado)X-f9&-UKpEmN0kUmdr!$&%K6iHbN$kE8r><*k{oDxQ(kB`v>PsRY13!U(8kF2QNrS4B!Q)lL_Asz zujVjD@aFO*sVZxFEIW*_gp~6|Na^Y<76{jUa%O5`d_15mFIb6nmd&%O6jrZW3Su*m zjlkI9(KG${W8$-AnX8ylO0M&);$14 zUL1m%NogR3?dC@cXIly(fRT{QeA)hGUALZCu5Mf8Cj`FaqYf(b%F;%5cxV!lXkYz= zpXWqocyd#7in=g+x*SoDZWWXaDN^8kw9*Q)CYci6rH~*PukAE?B3Dc)er-`(y);&N z?Xf+-Gq{hx0C1s~H?LE)aLx@I$J;rPF!P8U1Zr_Um^3ySv$e{-%`7kfnapA4GSBRj z`c=`mD;wCztOpXy)kffld}0{XI+K$OGAhcK$-AvlNNZKhWa>{91!)J~x-tbk&*rdKT&ukW+ras4Zo(VgbzcQDmr{4mYh?-Lc{9 z`YZ`v{Oo^tndyWQEzgC(@tsC&uf`OM56VhYs@jTBC;n;VZP8a_nuzr{?u?m8i@6v( zwcS87BbGFdZ6%hL*4Nap0_Hua%v3NS*Gb*$)(q!eO_4UZOydTsz694jDG zJbp-1QV-rzHy4*B{F)SPY0FTH{QSdu8>avU_|5Cc_{GmpH3`Vp5_rz8oK? zx_cEoYE{1Y-U-vr%FeUH#`c1plasWZjMEi$5KZm{brA2zZ++h{1bt^7U(~M~kfhms z;I@huIl`x=O6CGl?_YU`6TUMSKM9 zzvpKIic#!?Q` zzl46EDZy;mJaLFWgcEVKvYCj!_1%Se7xSu5K|4}yn62{BBqldwRSuLp;#oPC{9t5I z(W<$2uFj|muXRb`XQVt5^Y=XZfK}HfrMt`QscGZf1~xI#V>i3;<{e~|A?2?jVVWpI zwMuAq$>xJELP9E^8HU=&`9G7-Sx%>??0!Q}Z0uZ@I{Jw8B`Yo}Us7Z4hc$jgOO^fp zY(?6oo~mkBtu>T)uP}#@*Um8D0iq~};JeE%0*#9{?cWR)m~~D4^iM<7Y;kdHyyzjKMj;r1zOMF*1&VJ1&F()udz_T`zrRx80Ohg6tbGS(^_^RE^Z+ zxXjT=FiVPvtUn`z5fRylQ!gv8X;cW9w2H)8C!t;0tS=7;{KLtr7o$3Mrzp z@2$Y3WU2kvjF|13fu=g<9Y}{t=)6X8mG-NK9vzcToVFg{Kd5hJ=6Sw`A)z@`wy%r2 zHkIECtF=cvxQp_9sM-ld$?RNtK8E>j=VyF=5`Sm+Pvk4HAL5yJrQ!uG0+mfR{YiX{ zYub=+yN$!gZ>abILT}*2NQu>6uVWk@xU=n=gfPfd`VSRnMDN^~H^1VX2BPJ3ik36Q z*{qrqgOE-0UpIz1c#Z)jIRMqER&mzISRP;!=z5s^tc4b@we^Zi7Ln<9!DQUX`)AGp zpZaL}icG$RNqK;!dl5Nq1ph_$>bJ_?UfT{V3&6nT zF$#HSz7fO|o2(O*MKaFGf{4l=I9^E=ugah&M&;9eh{zwyi>I%}XS@xx8yQyAy1Bxi zb@`D%Kn?&zRoB*j(;^@u;;ZK5$=StPs>X0QMeiRPFdE+&_fe`IidIAWN*7K86ynlF@hJz!vxmgem4fSVQyriiHe~8ieI6-DWu#bFXzQ(eGDZmNMx+QgCy5GVA&EF^nLjXVt)S2P zq$V(BSX(5vk*^dA!qjI<^dMBej~wqOJ__(Wspr!(hk>D?oXpIhY{tF65)(f>O z{Lz+EPu%eWR)$O|oOpYnUH~Kx4i3J*Sq*J4Ir)Z2ExZct`kFAsra^hD1i}S|*k+V8 zYqh|NH)r%Vr?X(*cy#@hmG$cSdrma zBP}Tw?yKjBR_0(Sgr3fa0Gt8V-<>f5M=k@IJHpx7BewI^VIq%@uFs#9NYF@3o_H)E zl9j9u=bzZCIL4gQI;1hPGAW`{Q@uj4$lvgV2sAsD3u`p$vH)1;A9Bo>WrTk~EHuZfw-1r@vaYMgNr?)8pE9B}Cd6_9u`bNT$e# z%u6)afejGrI4qpPS7mnAt7Ch58FHbfuIXCsG3IlHtq0y#FF=y#Q}}-W^^<&mkPX`K}EKKp*APh#RZxo#BHfwBmI$*Jc}3yY<3o{U&z zGWi(9TYc+&jGqT2CL$vGo9s&{hHDOMR%Q`D|dEaTIs{5WgO__zw^_aX#bWaR*fLyVlB3!eayZrmFP50MZ%V}w#y z5U_LgvE}I2m9aT-psZ{XtB)XJ(rs*PJSk^dp@?#mv9+_Y@o}-=BYj_J(-2buT07=M z2C3xNUJ1epU3!D-)icf&l_MLyRydw>y+>q*$OcStaqTa)q=bi~S->n1YlD&$%Re8H zuR^5G^AXB%ZS9+^oE#lJh!DYRv(;BxVW0@+&Mhyi|1u!EV02L|2rqH+-vBvR=*a}@*G;Lq?40$r3m;0Q z^`bFGu|vBMK}jllayN-g?-?3mL|2uP3_pEVcjiJtI~~Q;>Jk5;#=rLDQR5x&u5}^` z@dtuuYombRCwUKa*3H7%YWJUQ5jmyz|AmRsLt%rGm>CDMfqok)N>3*XiyjX+2I65%UpG_f>5fJc93WH=Y z)1MlHnDd7yid_E)go;5Rqs3Co8zeaz8|852D}3EZV#dAoKT^JL}|rsW?(MrHR+#CeGO zS0z_$<9}3w{U2+)!l;5W0KRwlu4PMMWQl8PkFm=SdvBJCAClBv7rVfx*Gy}CYL92G zjQU>WEc<)S^=$w0;fZd?;pikR4QDJB!YbXG5ZxX_mJp5FNbuo;nLaU1Hv(@e{satA~^7U?WWHqxjo=U5;n|cx9)=1C&7p-D* z0P22yF<+l4kLbe=$?MkcH)3Yp%`fB`e8C0WeG&%4!s$8<>2J=q9GzI+K`QH*%yvB| z>M!SUXD=sJt!mb|MkBvcB$#uAFDbLb#dDf&kfdo zWRYKB5~Nm#;wxHzTzE|VuMVlg$$#UJdgl!cPW9|7k=L&Jk}OR{uYze%*W{Hyk*u04_wL;2Eob+obLv1NvH zv}0G_R8Q8JQuQ?aW}IS$z7a%d#JO(hAf7KqE`Y^;V^ofJyO~I>)GZv-2uX4Z9RG)e zBg1_?YU!ZMBRUTG~>Edc+Cmu1rYzY0+C;CiIsPvNCma|p)=V{z9@EQw;6&!OxKK#mgz76wkkix4{~7izVei5gv7wzufMd;g0v7Bcn)j5kg)j>>r6kn8Umt#zVdyJ}|e_7`m|bY}{+; z8V|wopLh8XlRV5W8KuH^q`mBxlG#JgBOGOcPMH-aS zs*}iD9vH7P4A?D^-ec?ty2m7uXQDqQ~oFn~WdmcLib?CObzz{bjRhaZ(V50d}J&%*8b;=lU*8BSA+&3dr6j_>ly&R|4UG7+9( z|IN_iGP9K%o17*pCqD7mM3E*tEpo>UoU4Nl_ey;Z3XJ36QVbl1~-A_xp4WF-C zIHCoC*L_WLCLVbVEz63!!+=N&| zXu$IE5VU17sF+}v?ECtvbu!QPEo(BbCF(7>?O5LA)daj5?mbT720>7b`ZNg!lWeX52rj#tzw%$&31)8?31P>E-`^%!8k%t(3PpSjm zfBAM;#19d!9vNDZ?4B4}YyR!D*nuuz;ts$z>D0};Ak~g8GwhYsq=NG`xtlhQA^iu|Kof9#-H<7!W0kp@Xg2A#g|^U2>&*zKKR#{ zpr9XP!sLlYPCx>eC(pPZ?9iFug1pSk*!|~yC5!#OGLZxiy1K2&K?15n-}|nhaSX7C zM=YS#D3vo0&o=W{2}x~v9aGx)fNGM`e$-sS|Ho(!sjx=mR&F`|R&%Uloh40F#s3{2ng6R(qB{&5Df{gE(i!XJ^v)c1ZEsE1O%#4nJ;4Mp6N%+-#q0l9y-oWOgZCb+9X-f0pU4}l4PlQ zCpLu|bdYRbt?T3Z#BGZ|y6#JmR4b6q?>ORL7Q z*KpU|E<+De4`N-$gocI3U5@$3Q%C{%@#3$kgBx*6W9|Llh<~4wiw%Aw{yKtA=5K42 z^uHy_Fz=C-+SkG+aj1je(65DkTftp2Sfh)9ic1b&Tw9AHMfmsbod@IAAu7}f5G@fqcM{olwUFaf<(M;zJ~tYPX#|f(Q0>e z@uq%fZ5uX6d&M@)zp0ErR=#|vpVQ38KzF>7;WWUlBLAW{0eK9|xF3aVNxJb1UI)ICr87KSy?9i&izBJxzEt^^tJrz+aYD3o#v`B|M|A+qbSa{d=N01(~Lx^ z$961tHWRGNh-zw~{s?>su`JhuW< z%^at|eoHfP40E%CM-b4?9S9G*$+DwZMzUe=wKX0=racM6&eL>nSI5|K_wDTRcO#ee zecN6~1uL|7x839?eMXTB{Nz%xf_bY*BHv(6I4LyEw*?eP!m%~I+PL$1mJ`x|QVcdu zvQ0AG3H}*RA0Hduw%Wg9VP#6(J<#MnJRBu)z}=sVcWt?d?V4Y<(IRJ$K9yz$wDM*C z5D7Xfb3ofi#XBJ85H!Rl24Gv96F6i-7W>}5e6tlXk!-aPw$ca1kU#LsY^SZwI3NcJ z=~mGu6zM^^8nAll_g}NDB9O8A!_%tDXm21bzwp%x)2ACq3HqwZ@|6->7$EX3U4rUuy@5lP;X0`4jTWM2np24|Qv_8A9Kcsn3@SbvHz#;=RKVFRD zr7C}F-c=2{%Kjlgo^x3!>wQCw#}d_Tzc0CK!?#`@Ft?tAGn~(dc~gZ@ z)qazE@G2@PDzEr@{QF^nDs$lrXtAwm_Px2ijBtzURcWpo&x2of1t6jgTXI!2C_Eje zxOYi06ByA%<|B1gx9@`*(wz_5W^-t>d#Urjt*kp7so{2{6Wx)Q-#;GmCAA9Wh&dd5QCeN+qe|&TSpBHW zWtLrDyk>r_5~cuNnaq={ z`cT6myl-ImbpAxQJy$Gdp_Z^?a3T?D0^PW{W;Gr))+zS#wN_`&V9o_(P})S^X-#Jh zUo9+tBKbZZF{X=a&^wlv@2R&=1#*$kZLx?7AWSG}Qf}&6hD#LIqW&EY-(1?G_++0U zpJ3Pao7;_T(2Si`fI{d6Yj?bZLCX1Uw`{b6Q{IsYV80rANLV1N)FGu5 z$6o+5`lHJS2bljtEC;20yzeOWB58STT+@|3EFk%a&t-Ay6n5}nWHBalIT3$5!j-8f zxf@e5?OOKTJLwvikHgyPa`i=7$>z*I5WZ(ggL~A1|6`B>3&8bBBGm(i$OUdxff`n|$oI$$xs$5X|Xf|OX1i%pvTOuF+MpJAE6+XcBDo+_Sz0S*CS=_j+y-&&?Jd)fd@_Ck?vAZ@|8b0t7PDnIuG=Y@mZ|FuyUyO%! z{c_3>C1_$+?Yp>(MQJg#qr$gOfu&lYP5V5UU(0~6L&TrbG48h&`fHU%qVu(2k>|zq zZ&xsWtfI_=gz33S<1T?js)LS>!KdUUTdE78VbP^FBIb|w5@F{{T^{HI-l`)Von|!6Y1Z!KX4Z&#txTmuWk*Ilv z*>kW|Sk9j2k0y!B3eu5}v*AB#o10swcsb1x!2C&%g(o<1&<9C|#K~tU}44d0&ha|Hp3^2t|m%#V#YT992=# zV|8Jr*f1hAzH7z`vhH|m?9P%tK3;KByK~5$S>u{-v@O3%e{j2b>6a|rlg5BsmcK1= zWOFt(z1vmF=GQfG#XQfEjooV8HGeXdmQUntq>oit?>LZ8jCAMiFpcAH$AOi2dw(=26IOBz`(ccmOU zwpXjj&R`W*U%r#aZZ%?}FFH7m8q7QQO-upP1*C)Wida0_k%S7P@}a8&y{ZJ0q_%>E zMgNDH9dELMB^k9To=*~L@uvv~fM-MQoU!JkjQFO%+7l}Gz&*D_kkg3@NBx@vrqpn5 z=M(vz{^R#Q;)A!f@C+IS>aIMWM-ja06|=iB10X5z1U=Y-;hC>()3r|(n7SWI`s2hO zg#2yULZPncUi(26m`L7=#ry+>-lJLSn#xw7?sY7;FtI~LPumEx! zFuht~D3jiwn(Nkr^v5bH2is=rPdEgOA$NO2&CibFT|Q3ypVArUo@xZ&+@MVuY})96#IW} zg28U2J7C&9@c1hq(yUtxd3R4d0fYc5aaS@+VprapXj9~j25$igcz|#rC7(Q?$F8(kN z$<2;U5+!>Su2N7Kb&6$9ZA*NoK-k1>_Qar?_BR;b9u|zzx3r8a}jen ze;N(gXAgx(Q1|n(*pM%IZ)|&}eoTvsF|S`HsLeRq=NB4Dq^#{PzvGi`uTSz9%YE&U z*|YD@sy-3l+DKQ}aa6YFpn>1l(mk`tK6faHPx_S|THnl6b;QMIOvG)1N^&_dh2rQ> z>JSK~VhJAt8C+6ofhh{^#IIk;xX;snvu3PkgFV%81uJ!po5;5hF0G3^>Ml~2e~1j0 zlbU}zI^jL=iP29-iA;6{)Za7#2z3p?t=o~v?e@xK^Q5n=`4<@sVE8aVoNIz(w+b-h% zA*`g^zbr{~=@g^Kuk*&I7R=!&V5l;kejqQ)Mlu1QCn=r{w_$SQE_ALg?y#FpemML} zK~n;A;bu$%g@;FP4dlDJGKEH}6{-y{MqXrx-A+1D8t}FD4If#X_G(5i7V#rzW{R1f zd5Gff={}or*#zD=FS-Vuh+-Q1Hnshdeah@zS0RC!pkEn;3?Do>dVIvLH1D)bN3CT% zq?3@k*_ekt?Jk#~?t9S{ZtQP7O}3bV_30unyy0(tts|3?&LS(3NSR{ee{f3Tr#g`y z7P0wGG8?mS&pq}+qV2wsvo>OM>q+Kgg4U^Fbc;XnWJYpMB4mNdgxI!#v$`6nBlXUa z3gSh?Bq)}VcB=o*QwW_WvdW0;G7}-!#)8OT5fkj}|0BZ4)MZx-vm!I_)bf`7btun( z(D5UlmJb31^|c-*t8iy4as@lL>^7L{*65!*+#v4?)d-9& znaZnO^O2DGyHfDbHZ?8!SYJRKmwFAmJNBUCAHbXj3LN9+r3co%McPI)Uagkn@)DEd zQsooZf(2V#OmM~jYym70eL9zh38>Z@VOsz3%|n zODx^r{{M@pVco^w0vd+A*_e!hS9TEb$!rxWtDFlx1%mDZyk&TE)k&_~eWNdvuP!mc zc@IF6OmOGp#6w-I{nz51e-6sTwCSI3h5yz5V(GqcaK?iBwWcE95-^%NlWTmB zf+MNhS-r=_U6DMrY7vFMEfo6Gsooa-wJ8jWx_@(Ovfl{&dksj8RNCBe8?xF&(WxEW zRm+pE62mVJ(0vRuZ1#Md=mWTd=A1fF8=@$M?4i;l+sH!=``x?ML6#cx80v2=+VqCX zNTD^Nb;7WQV9sfcw3!C2D4!;RmuLxo*cxGhJZT?3N7_XZuc$9Y|CmB<5zy93C^BNz zZ|soNz=@?AgJR{>X!^6q5|bqYJ}*su_2Xv#W6?oZd`eI;SyMv(MHiprXjC6tem^YHJV;} z^QsLW6;=+CE>fCz1bR%j~xD_fLB&bXn_!D2wOSkJxW2#!{F$k*-^ zq24rx&HCydKgzUmEtM0HQYuiBuK!s<_3pjr6!H6z;49-N(`<~1o%xm^DjnkskyY!+}qhqEyQcMM%fQZ0dWXn0!KG!gz z0^Lbvlr0Xhq!=`oUV_4>FuSJysPt3bpCzz>{gc~tO`*YzTBl-ilYYB1ciNzvP*s!((xsI>oH~>HWpYbX^g6MukUM1?b1lLFMo_NP)2q>ZK#Cura3Km>FBN<;0@EB+P?vOv;?2!vhm8Kfeu9nb~tnFSUti ztn5{gTNb0;J0cjq{;AiKV(`2o(s7(OcIg1-ZA|fI?G^dTImIHc?itHzOQXIjTIwOu)tmuU*&KEDovzuXMrI?!NN4;+oNLYDPNfUx+%2B^9jU%H&LC)!XV$PBv31^c?787R@D|`6mYwilWIz8*KJCLRjrjg|Z-Bt?ie;ORzm8m29jwdN+E zrQIk^`^TDms2)`@VMM}I@~T42HhDfXt+bW2=9Iw0ez?(E+o|Qa!dm$da>Zd?E|(2eC5$C&C*y8Yv6?&j=s? zKO(%w|09HV-<)dZ&^ihDK0MKWhJ?f2naK7|7PA10?-#N5Z%p`@1k2ifkME8e1;Yej zy~iwTzx5&4FAU_JJ&LevZ9u2zm9?StRlN<8D6Yka9D5<_8& zgWZXGm8691`aXA`BcBh4Ako;41^i~-#T}poYM!ccE;xyGdvv-N9iiM9jYFHAI?ukY z^R%*dU7tx3HQK#TI82@h)#q40^w=9!#cX0{3suwM+nS0%bkC~3Fdm4Q@idzOfUh$; zh50*51eRazaNLi)CTbT+C=f)ly07$Be}yH5PWpnnO20}sGnN3h!ChY-jWkY%<$p(Q z)rVeuxqaOuS=sV3_(Tb?gyS{ue>VGEe&C45Zm#!5=Qm(@!JfT+?vwZc%`Gdos$JG9 z_o=;9bx-+iTyP&^;XU?q)8?w-lD9hKV^4E<0ZrtRAndNXMTUmnh+ngZxI)oRIMa{I zKeJqI_f-6y$sac}_^(e|K2$mt!c=7j17{XrHv|od#Pn}KY9CA5hy(=}BFUv;GnnWg z-&iJiG|cBGZpZ_IEK_^v(e}_4^KZdVE|+N=OlyvIXw>T_PE@YYQvCiz2xdy(-WV+T zdf(#rYO!lMa3|s_4)XdQf@pRrJ|J6)V%BAJBD$I3F9c>5+XutGgH3{!1LTN}fC#z%cB1WAf z5<|l%>N%0IWNOIwrIp-LLTilmPHCPym{!go)}3vG$H!4!Z$>Hrn_6@NRFk0YPjfem3* z+@3_w(2<^(xRenPVb5-&$F0>}lIhB|^5=@V=4)!lc|+?A-JwfD;&VtjqpYTSi3&Cu z;dtcj68ggDB?X%j;NZh_wmn#B7ntO9%o}@r!_t}Cok)etx6`2MpvdGEsEv(%TBFIQS7ED+S>xrdFfcRhBh>W zruWLod0!TJq z&}pK%W(OA7_R@PZ{n=F$LiTyRu3>aVrc7-k&x}t(Xqv3Bdg!<6AuHGc;T3DgC6e4; zB5XxVGzhb5``IdO?5Pau&6;bIzk!dv5kVJ?=6HJV683QFV(0yY&JrM40;&``?G7o5SD-m71-G^2d=L2<*OtyS)s`r+)r<=`Q<^b7%eJc-}f)cv4_kO zb2e!Coj*`ygd1&6?@gb(Z~E*~gI&}6i4`l)oLc~(>Y2??);Ix$7H>e0%i|IPNq+Mq zscWrEpO)7i#sjqsD%i?Z+bx_t3HmOz#Gioc=U$>qdUD;RAa+1uCkuw);KXFB=e4V- zS3^laGv#1$W3#89eVsbQ8)Bezuv^_g$>I+Qgr%&|sd$_4>e*_RuT$2^JJ0 z3WQul@!8MI`V-mOV*=LRok}?DP8<+h915Gx8MQZ**i@*URj434{#OyTLm2-8?&Qk< z2Dtlq-(7V6h2{jR#+L)@gXWw;U=eJ#;q3 z%B3P#rHe_i4!=c{3k}#sFTv$`X)$b}rhG2ghb4hFAwDYvY&4nc%;)5S^a3|j9|X{b zd7FmWTU+&3(1dLTS~#!vlBB|CV^Xnol(|l5C89_n=OgOx{sqe4bk02wd_@zSJFz`PBfSVDt literal 0 HcmV?d00001 diff --git a/doc/img/viewer_menu.png b/doc/img/13_viewer_menu.png similarity index 100% rename from doc/img/viewer_menu.png rename to doc/img/13_viewer_menu.png From d45753a2cc86739bc157a6b4435c900cf133d399 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 10 Mar 2022 19:12:59 +0800 Subject: [PATCH 184/379] feat: update docs --- CHANGELOG.md | 5 ++ README.md | 152 +++++++++++++++++++++-------------------------- README_CN.md | 162 +++++++++++++++++++++++---------------------------- 3 files changed, 145 insertions(+), 174 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 9accaadf..2def9a9e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,10 @@ # Changelog +## v1.5.0 - 2022-03-09 + +### Changed +- refactory the decoder part + ## v1.4.0 - 2021-11-01 ### Changed diff --git a/README.md b/README.md index 6e01e7e1..664a0a93 100644 --- a/README.md +++ b/README.md @@ -4,9 +4,9 @@ ## 1 Introduction -**rs_driver** is cross-platform driver kernel for RoboSense LiDAR which is easy for users to do advanced development. +**rs_driver** is the driver kernel for the RoboSense LiDARs. -### 1.1 LiDAR type support +## 2 Supported LiDARs - RS-LiDAR-16 - RS-LiDAR-32 @@ -16,7 +16,7 @@ - RS-LiDAR-M1 - RS-Helios -## 2 Compilation and Installation +## 3 Supported Platforms **rs_driver** is compatible with the following platforms and compilers: @@ -26,148 +26,132 @@ - Ubuntu (16.04, 18.04) - gcc (4.8+) -### 2.1 Install dependencies +## 4 Dependency Libraries -**rs_driver** depends on the following third-party libraries. They must be compiled/installed properly in advance: +**rs_driver** depends on the following third-party libraries. Please install them before compiling **rs_driver**. -- Boost -- pcap -- PCL (optional, only needed if build the visualization tool) -- Eigen3 (optional, only needed if use the internal transformation function) +- libpcap (optional, needed if parsing PCAP file) +- PCL (optional, needed if building the visualization tool) +- Eigen3 (optional, needed if use the internal transformation function) -#### 2.1.1 Install dependencies in Ubuntu +## 5 Compilation and Installation -```sh -sudo apt-get install libboost-dev libpcap-dev libpcl-dev libeigen3-dev -``` - -#### 2.1.2 Install dependencies in Windows - -##### Boost - -In Windows, Boost needs compiling from source, please refer to the [official guide](https://www.boost.org/doc/libs/1_67_0/more/getting_started/windows.html) for detailed instructions. - -Once finishing installing Boost, add a system environment variable named ```BOOST_ROOT``` which is set to your Boost path. - -If using MSVC as your compiler, these pre-built [binary installers](https://boost.teeks99.com/) may save you some time. - -##### PCAP - -Firstly, install [pcap runtime](https://www.winpcap.org/install/bin/WinPcap_4_1_3.exe). - -Then, download pcap's [developer's pack](https://www.winpcap.org/install/bin/WpdPack_4_1_2.zip) to your favorite location and add the path to ```WpdPack_4_1_2/WpdPack``` folder to the ```Path``` environment variable. - -##### PCL - -*Note: you can skip installing PCL if you don't want to compile visualization tool.* +### 5.1 On Ubuntu -(1) MSVC +#### 5.1.1 Dependency Libraries -Please use the provided official [All-in-one installer](https://github.com/PointCloudLibrary/pcl/releases). - -Select the "Add PCL to the system PATH for xxx" option during installation. - -![](./doc/img/install_pcl.PNG) - -(2) Mingw-w64 - -Since there'are no installers for mingw-w64 compiler available, PCL needs to be compiled out from source as instructed in this [tutorial](https://pointclouds.org/documentation/tutorials/compiling_pcl_windows.html). - - - -## 3 Usage - -### 3.1 Install in advance - -*Note: installation is not supported in Windows.* +```sh +sudo apt-get install libpcap-dev libpcl-dev libeigen3-dev +``` - Install the driver. +#### 5.1.2 Compilation ```bash cd rs_driver mkdir build && cd build cmake .. && make -j4 +``` + +#### 5.1.3 Installation + +```bash sudo make install ``` -Then find **rs_driver** package and link to it in your ```CMakeLists.txt```. +#### 5.1.4 Use rs_driver as a third party library + +In your ```CMakeLists.txt```, find the **rs_driver** package and link to it . ```cmake find_package(rs_driver REQUIRED) include_directories(${rs_driver_INCLUDE_DIRS}) -target_link_libraries(project ${rs_driver_LIBRARIES}) +target_link_libraries(your_project ${rs_driver_LIBRARIES}) ``` -### 3.2 Use rs_driver as a submodule +#### 5.1.5 Use rs_driver as a submodule -Add **rs_driver** as your project's submodule, then find **rs_driver** package and link to it in your ```CMakeLists.txt```. +Add **rs_driver** into your project as a submodule. + +In your ```CMakeLists.txt```, find the **rs_driver** package and link to it . ```cmake add_subdirectory(${PROJECT_SOURCE_DIR}/rs_driver) find_package(rs_driver REQUIRED) include_directories(${rs_driver_INCLUDE_DIRS}) -target_link_libraries(project ${rs_driver_LIBRARIES}) +target_link_libraries(your_project ${rs_driver_LIBRARIES}) ``` +### 5.2 On Windows +#### 5.2.1 Dependency Libraries -## 4 Quick Start +##### libpcap -[Online connect LiDAR](doc/howto/how_to_online_use_driver.md) +Install [libpcap runtime library](https://www.winpcap.org/install/bin/WinPcap_4_1_3.exe). -[Decode pcap bag](doc/howto/how_to_decode_pcap.md) +Download [libpcap's developer's pack](https://www.winpcap.org/install/bin/WpdPack_4_1_2.zip) to your favorite location, and add the path to ```WpdPack_4_1_2/WpdPack``` folder to the environment variable ```PATH``` . +##### PCL ++ MSVC -## 5 Demo Code & Visualization Tool +Please use the official installation package [All-in-one installer](https://github.com/PointCloudLibrary/pcl/releases). -### 5.1 Demo Code +Select the "Add PCL to the system PATH for xxx" option during the installation. -**rs_driver** offers two demo programs in ```rs_driver/demo```: +![](./doc/img/01_install_pcl.PNG) -- demo_online.cpp -- demo_pcap.cpp ++ Mingw-w64 -User can refer to the demo code for usage of api. To build demo programs, set the following option to ```ON``` when configuring using cmake: +Since there'are no installers for mingw-w64 compiler available, Please compile PCL out from source as instructed in this [tutorial](https://pointclouds.org/documentation/tutorials/compiling_pcl_windows.html). -```bash -cmake -DCOMPILE_DEMOS=ON .. -``` +#### 5.2.2 Installation -### 5.2 Visualization Tool +Installation is not supported on Windows. -**rs_driver** offer a visualization tool based on PCL in ```rs_driver/tool```: +## 6 Quick Start -- rs_driver_viewer.cpp +**rs_driver** offers two demo programs in ```rs_driver/demo```. -To build it, set the following option to ```ON``` when configuring using cmake: +- demo_online.cpp +- demo_pcap.cpp + +Please refer to them for usage of the rs_driver API. + +`demo_pcap` is based on libpcap. + +To build `demo_online` and `demo_pcap`, enable the option COMPILE_DEMOS when configure the project. ```bash -cmake -DCOMPILE_TOOLS=ON .. +cmake -DCOMPILE_DEMOS=ON .. ``` -For basic usage of this tool, please refer to [Visualization tool guide](doc/howto/how_to_use_rs_driver_viewer.md) +For more info about how to decode an online Lidar, Please refer to [Online connect LiDAR](doc/howto/how_to_online_use_driver.md) + +For more info about how to decode a PCAP file, Please refer to [Decode pcap bag](doc/howto/how_to_decode_pcap.md) +## 7 Visualization of Point Cloud -## 6 Coordinate Transformation +**rs_driver** offers a visualization tool `rs_driver_viwer` in ```rs_driver/tool``` , which is based on PCL. + +To build it, enable the option CMOPILE_TOOLS when configuring the project. -**rs_driver** has the coordinate transformation function built inside and it can output the transformed point cloud directly, which can save the extra time cost of doing transformation after receiving point clouds from rs_driver. To enable this function, set the following option to ```ON``` when executing cmake command: ```bash -cmake -DENABLE_TRANSFORM=ON .. +cmake -DCOMPILE_TOOLS=ON .. ``` -For more details about the tool, please refer to [Transformation guide](doc/howto/how_to_use_transformation_function.md) - +For more info about how to use the `rs_driver_viewer`, please refer to [Visualization tool guide](doc/howto/how_to_use_rs_driver_viewer.md) +## 8 More Topics -## 7 Others +For more topics, Please refer to: -Please refer to the following files for more infomation. +Multi-Cast function: [Multi-Cast](doc/howto/how_to_use_multi_cast_function.md) +Trasformation function: [Transformation guide](doc/howto/ow_to_transform_pointcloud.md) +For more info about the `rs_driver` API, Please refer to: - **Parameters definition**: ```rs_driver/src/rs_driver/driver/driver_param.h``` - **Point Cloud message definition**: ```rs_driver/src/rs_driver/msg/point_cloud_msg.h``` - **API definition**: ```rs_driver/src/rs_driver/api/lidar_driver.h``` - **Error code definition**: ```rs_driver/src/rs_driver/common/error_code.h``` -Multi-Cast function: [Multi-Cast](doc/howto/how_to_use_multi_cast_function.md) - diff --git a/README_CN.md b/README_CN.md index c805ab0b..661dd0f4 100644 --- a/README_CN.md +++ b/README_CN.md @@ -1,23 +1,25 @@ # **rs_driver** -## 1 工程简介 +[English Version](README.md) - **rs_driver**为速腾聚创跨平台的雷达驱动内核,方便用户二次开发使用。 +## 1 简介 -### 1.1 雷达型号支持 +**rs_driver**为RoboSense的雷达驱动。 +## 2 支持的雷达型号 + +支持的雷达型号如下。 - RS-LiDAR-16 - RS-LiDAR-32 - RS-Bpearl +- RS-Helios - RS-Ruby - RS-Ruby Lite - RS-LiDAR-M1 -- RS-Helios - -## 2 编译与安装 -**rs_driver**目前支持下列系统和编译器: +## 3 支持的操作系统 +支持的操作系统及编译器如下。 - Windows - MSVC (VS2017 & VS2019 已测试) - Mingw-w64 (x86_64-8.1.0-posix-seh-rt_v6-rev0 已测试) @@ -25,81 +27,49 @@ - Ubuntu (16.04, 18.04, 20.04) - gcc (4.8+) -### 2.1 依赖库的安装 +## 4 依赖的第三方库 -**rs_driver** 依赖下列的第三方库,在编译之前需要先安装的它们: +依赖的第三方库如下。 +- libpcap (可选。如不需要解析PCAP文件,可忽略) +- PCL (可选。如不需要可视化工具,可忽略) +- Eigen3 (可选。如不需要内置坐标变换,可忽略) -- Boost -- pcap -- PCL (非必须,如果不需要可视化工具可忽略) +## 5 编译与安装 +### 5.1 Ubuntu下的编译与安装 +#### 5.1.1 安装第三方库 -- Eigen3 (非必须,如果不需要内置坐标变换可忽略) - -#### 2.1.1 Ubuntu中的依赖库安装 - -```shell -sudo apt-get install libboost-dev libpcap-dev libpcl-dev libeigen3-dev +```bash +sudo apt-get install libpcap-dev libpcl-dev libeigen3-dev ``` +#### 5.1.2 编译 -#### 2.1.2 Windows下的依赖库安装 - -##### Boost - -Windows下需要从源码编译Boost库,请参考[官方指南](https://www.boost.org/doc/libs/1_67_0/more/getting_started/windows.html)。编译安装完成之后,将Boost的路径添加到系统环境变量```BOOST_ROOT```。 - -如果使用MSVC,也可以选择直接下载相应版本的预编译的[安装包](https://boost.teeks99.com/)。 - -##### Pcap - -首先,安装[pcap运行库](https://www.winpcap.org/install/bin/WinPcap_4_1_3.exe)。 - -然后,下载[开发者包](https://www.winpcap.org/install/bin/WpdPack_4_1_2.zip)到任意位置,然后将```WpdPack_4_1_2/WpdPack``` 的路径添加到环境变量```PATH```。 - -##### PCL - -*注:如果不编译可视化工具,可不编译安装PCL库* - -(1) MSVC - -如果使用MSVC编译器,可使用PCL官方提供的[安装包](https://github.com/PointCloudLibrary/pcl/releases)安装。 - -安装过程中选择 “Add PCL to the system PATH for xxx”: - -![](./doc/img/install_pcl.PNG) - -(2) Mingw-w64 - -PCL官方并没有提供mingw编译的库,所以需要按照[官方教程](https://pointclouds.org/documentation/tutorials/compiling_pcl_windows.html), 从源码编译PCL并安装。 - - - - -## 3 使用方式 - -### 3.1 安装使用 - -*注:在Windows中,**rs_driver** 暂不支持安装使用。* - -安装驱动 - -```sh +```bash cd rs_driver mkdir build && cd build cmake .. && make -j4 +``` + +#### 5.1.3 安装 + +```bash sudo make install ``` -使用时,需要在```CMakeLists```文件中使用find_package()指令找到**rs_driver**,然后链接相关库。 +#### 5.1.4 作为第三方库使用 + +配置您的```CMakeLists```文件,使用find_package()指令找到**rs_driver**库,并链接。 ```cmake find_package(rs_driver REQUIRED) include_directories(${rs_driver_INCLUDE_DIRS}) -target_link_libraries(project ${rs_driver_LIBRARIES}) +target_link_libraries(your_project ${rs_driver_LIBRARIES}) ``` -### 3.2 作为子模块使用 +#### 5.1.5 作为子模块使用 + +将**rs_driver**作为子模块添加到您的工程,相应配置您的```CMakeLists```文件。 -在```CMakeLists```文件中将**rs_driver**作为子模块添加到工程内,使用find_package()指令找到**rs_driver**,然后链接相关库。 +使用find_package()指令找到**rs_driver**库,并链接。 ```cmake add_subdirectory(${PROJECT_SOURCE_DIR}/rs_driver) @@ -108,66 +78,78 @@ include_directories(${rs_driver_INCLUDE_DIRS}) target_link_libraries(project ${rs_driver_LIBRARIES}) ``` +### 5.2 Windows下的编译与安装 +#### 5.2.1 安装第三方库 -## 4 快速上手 +##### libpcap -[在线连接雷达](doc/howto/how_to_online_use_driver.md) + 安装[libpcap运行库](https://www.winpcap.org/install/bin/WinPcap_4_1_3.exe)。 -[解析pcap包](doc/howto/how_to_decode_pcap.md) + 下载[libpcap开发者包](https://www.winpcap.org/install/bin/WpdPack_4_1_2.zip)到任意位置,并将```WpdPack_4_1_2/WpdPack``` 的路径添加到环境变量```PATH```。 +##### PCL ++ MSVC -## 5 示例程序 & 可视化工具 +​ 如果使用MSVC编译器,可使用PCL官方提供的[PCL安装包](https://github.com/PointCloudLibrary/pcl/releases)安装。 -### 5.1 示例程序 +​ 安装过程中选择 “Add PCL to the system PATH for xxx”: -**rs_driver**提供了两个示例程序,存放于```rs_driver/demo``` 中: +![](./doc/img/01_install_pcl.PNG) -- demo_online.cpp -- demo_pcap.cpp ++ Mingw-w64 -用户可参考示例程序编写代码调用接口。若希望编译这两个示例程序,执行CMake配置时加上参数: +​ PCL官方没有提供mingw编译的库,所以需要按照[PCL官方教程](https://pointclouds.org/documentation/tutorials/compiling_pcl_windows.html), 从源码编译PCL并安装。 -```bash -cmake -DCOMPILE_DEMOS=ON .. -``` +#### 5.2.2 安装 + +Windows下,**rs_driver** 暂不支持安装。 -### 5.2 可视化工具 +## 6 快速上手 -**rs_driver**提供了一个基于PCL的点云可视化工具,存放于```rs_driver/tool``` 中: +**rs_driver**在目录```rs_driver/demo``` 下,提供了两个使用示例程序。 + +- demo_online.cpp +- demo_pcap.cpp -- rs_driver_viewer.cpp +`demo_online`解析在线雷达的数据,输出点云, `demo_pcap`解析PCAP文件,输出点云。 -若希望编译可视化工具,执行CMake配置时加上参数: +`demo_pcap`基于libpcap库。 + +要编译这两个程序,需使能COMPILE_DEMOS选项。 ```bash -cmake -DCOMPILE_TOOLS=ON .. +cmake -DCOMPILE_DEMOS=ON .. ``` -具体使用请参考[可视化工具操作指南](doc/howto/how_to_use_rs_driver_viewer.md) +关于`demo_online`的更多说明,可以参考[在线连接雷达](doc/howto/how_to_online_use_driver.md) +关于`demo_pcap`的更多说明,可以参考[解析pcap包](doc/howto/how_to_decode_pcap.md) +## 7 可视化工具 -## 6 坐标变换 +**rs_driver**在目录```rs_driver/tool``` 下,提供了一个点云可视化工具`rs_driver_viewer`。它基于PCL库。 - **rs_driver**提供了内置的坐标变换功能,可以直接输出经过坐标变换后的点云,节省了用户对点云进行坐标变换的额外操作耗时。若希望启用此功能,执行CMake配置时加上参数: +要编译这个工具,需使能COMPILE_TOOS选项。 ```bash -cmake -DENABLE_TRANSFORM=ON .. +cmake -DCOMPILE_TOOLS=ON .. ``` -具体使用请参考[坐标变换功能简介](doc/howto/how_to_use_transformation_function.md) +关于`rs_driver_viewer`的使用方法,请参考[可视化工具操作指南](doc/howto/how_to_use_rs_driver_viewer.md) +## 8 更多主题 +关于**rs_driver**的其他主题,请参考如下链接。 -## 7 其他资料 +组播模式: [组播模式](doc/howto/how_to_use_multi_cast_function.md) +坐标变换:[坐标变换](doc/howto/how_to_transform_pointcloud.md) -请根据以下路径去查看相关文件。 +**rs_driver**的主要接口文件如下。 -- 参数定义: ```rs_driver/src/rs_driver/driver/driver_param.h``` - 点云消息定义: ```rs_driver/src/rs_driver/msg/point_cloud_msg.h``` - 接口定义: ```rs_driver/src/rs_driver/api/lidar_driver.h``` +- 参数定义: ```rs_driver/src/rs_driver/driver/driver_param.h``` - 错误码定义: ```rs_driver/src/rs_driver/common/error_code.h``` -组播模式: [组播模式](doc/howto/how_to_use_multi_cast_function.md) \ No newline at end of file From 75395043c955fde4e349aac2d3c445ea9804561e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 11 Mar 2022 14:39:08 +0800 Subject: [PATCH 185/379] feat: update docs --- doc/howto/how_to_use_rs_driver_viewer.md | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/doc/howto/how_to_use_rs_driver_viewer.md b/doc/howto/how_to_use_rs_driver_viewer.md index 6eb91df2..7965eead 100644 --- a/doc/howto/how_to_use_rs_driver_viewer.md +++ b/doc/howto/how_to_use_rs_driver_viewer.md @@ -26,11 +26,11 @@ Run the tool. - -msop - Msop port number of LiDAR, the default value is *6699* + MSOP port number of LiDAR, the default value is *6699* - -difop - Difop port number of LiDAR, the default value is *7788* + DIFOP port number of LiDAR, the default value is *7788* - -host @@ -42,11 +42,11 @@ Run the tool. - -pcap - The absolute pcap file path. If this argument is empty, the driver read packets from online-lidar, else from the pcap file. + Full path of the PCAP file. If this argument is empty, the driver read packets from online Lidar, else from the PCAP file. - -type - Typer of LiDAR, the default value is *RS16* + LiDAR type, the default value is *RS16* - -x @@ -74,17 +74,17 @@ Run the tool. Note: -**The point cloud transformation function can only be available if the cmake option ENABLE_TRANSFORM=ON.** +**The point cloud transformation function is available only if the CMake option ENABLE_TRANSFORM is ON.** ## 3 Examples -- Decode from an online RS128 LiDAR, whose msop port is ```9966``` and difop port is ```8877``` +- Decode from an online RS128 LiDAR. Its MSOP port is ```9966```, and difop port is ```8877``` ```bash rs_driver_viewer -msop 9966 -difop 8877 -type RS128 ``` -- Decode from a pcap file with RSHELIOS LiDAR data. +- Decode from a PCAP file with RSHELIOS LiDAR data. ```bash rs_driver_viewer -pcap /home/robosense/helios.pcap -type RSHELIOS From fb9a058149afd24b502c5c02726ae364462fdfae Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 11 Mar 2022 16:32:43 +0800 Subject: [PATCH 186/379] feat: update docs --- doc/intro/parameter_intro_cn.md | 177 +++++++++++++++++++++++++------- 1 file changed, 138 insertions(+), 39 deletions(-) diff --git a/doc/intro/parameter_intro_cn.md b/doc/intro/parameter_intro_cn.md index 4c8f8f3f..abf8e69a 100644 --- a/doc/intro/parameter_intro_cn.md +++ b/doc/intro/parameter_intro_cn.md @@ -1,9 +1,93 @@ -# 参数介绍 -## 1 参数定义 -参数文件`rs_driver/src/rs_driver/driver_param.h`里面详细定义了每一个参数,如下。 +# rs_driver 配置参数介绍 +## 1 参数文件 + +文件`rs_driver/src/rs_driver/driver_param.h`中, 定义了rs_driver的配置参数。 + +rs_driver的参数主要保存在RSDriverParam、RSDecoderParam、和RSInputParam三个结构中。 + +## 2 RSDriverParam + +RSDriverParam中包括RSDecoderParam和RSInputParam。 + +```c++ +typedef struct RSDriverParam +{ + LidarType lidar_type = LidarType::RS16; ///< Lidar type + InputType input_type = InputType::ONLINE_LIDAR; ///< Input type + RSInputParam input_param; + RSDecoderParam decoder_param; +} RSDriverParam; +``` + ++ 成员lidar_type - 指定雷达的类型。 + + 雷达有两个大类,一是机械式雷达,二是MEMS雷达。RSDecoderParam中的部分参数只针对机械式雷达使用。 + +```c++ +enum LidarType +{ + RS16 = 1, + RS32, + RSBP, + RS128, + RS80, + RSHELIOS, + RSROCK, + RSM1 +}; +``` + ++ 成员input_type - 指定雷达的数据从哪里来。 + + ONLINE_LIDAR是在线雷达;PCAP_FILE是PCAP文件,使用第三方工具抓包得到;RAW_PACKET用于Packet录制与回放。 + +```c++ +enum InputType +{ + ONLINE_LIDAR = 1, + PCAP_FILE, + RAW_PACKET +}; +``` + + +## 3 RSDecoderParam + +RSDecoderParam指定雷达的Packet解析器如何工作。 + +```c++ +typedef struct RSDecoderParam +{ + bool use_lidar_clock = false; + bool dense_points = false; + bool wait_for_difop = true; + RSTransformParam transform_param; + bool config_from_file = false; + std::string angle_path = ""; + float min_distance = 0.2f; + float max_distance = 200.0f; + + // The following parameters are only for mechanical Lidars. + SplitFrameMode split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; + float split_angle = 0.0f; + uint16_t num_blks_split = 1; + float start_angle = 0.0f; + float end_angle = 360.0f; + +} RSDecoderParam; ``` -typedef struct RSTransformParam ///< The Point transform parameter + +如下参数针对所有雷达。 ++ use_lidar_clock - 指定使用雷达还是主机的时间戳。 + + 如果`use_lidar_clock`=`true`,则使用雷达写入Packet中的时间戳;如果`use_lidar_clock`=`false`,则使用rs_driver在主机端产生的时间戳。 ++ dense_points - 指定点云是否是dense的。 + + 如果`dense_points`=`false`, 则点云中包含NAN点;如果`dense_points`=`true`,则去除点云中的NAN点。 ++ wait_for_difop - 解析MSOP Packet之前,是否等待DIFOP Packet。 + + DIFOP Packet中包含角度校准等参数数据。如果没有这个数据,rs_driver输出的点云将是扁平的。 + + 在rs_driver不输出点云时,设置`wait_for_difop`=`false`,有助于定位问题的位置。 ++ transform_param - 指定点的坐标转换参数。这个选项只有在CMake选项`ENABLE_TRANSFORM`=`ON`时才有效。 + +```c++ +typedef struct RSTransformParam { float x = 0.0f; ///< unit, m float y = 0.0f; ///< unit, m @@ -12,45 +96,60 @@ typedef struct RSTransformParam ///< The Point transform parameter float pitch = 0.0f; ///< unit, radian float yaw = 0.0f; ///< unit, radian } RSTransformParam; +``` + ++ config_from_file - 指定雷达本身的配置参数是从文件中读入,还是从DIFOP Packet中得到。仅内部调试使用。 ++ angle_path - 雷达的角度校准参数文件。仅内部调试使用。 ++ min_distance、max_distance - 测距的最大、最小值。仅内部调试使用。 + +如下参数仅针对机械式雷达。 ++ split_frame_mode - 指定分帧模式. + + `SPLIT_BY_ANGLE`是按`用户指定的角度`分帧;`SPLIT_BY_FIXED_BLKS`是按`理论上的每圈BLOCK数`分帧;`SPLIT_BY_CUSTOM_BLKS`按`用户指定的BLOCK数`分帧。默认值是`SPLIT_BY_ANGLE`。一般不建议使用其他两种模式。 -typedef struct RSDecoderParam ///< LiDAR decoder parameter +```c++ +enum SplitFrameMode { - bool config_from_file = false;///< Internal use only for debugging - std::string angle_path = ""; ///< Internal use only for debugging - bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet - float min_distance = 0.2f; ///< Minimum distance of point cloud range - float max_distance = 200.0f; ///< Max distance of point cloud range - float start_angle = 0.0f; ///< Start angle of point cloud - float end_angle = 360.0f; ///< End angle of point cloud - SplitFrameMode split_frame_mode = - SplitFrameMode::SPLIT_BY_ANGLE; ///< 1: Split frames by split_angle; - ///< 2: Split frames by fixed number of blocks; - ///< 3: Split frames by custom number of blocks (num_blks_split) - float split_angle = 0.0f; ///< Split angle(degree) used to split frame, only be used when split_frame_mode=1 - uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 - bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp - bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points - RSTransformParam transform_param; ///< Used to transform points -} RSDecoderParam; + SPLIT_BY_ANGLE = 1, + SPLIT_BY_FIXED_BLKS, + SPLIT_BY_CUSTOM_BLKS +}; +``` ++ split_angle - 如果`split_frame_mode`=`SPLIT_BY_ANGLE`, 则`split_angle`指定分帧的角度 ++ num_blks_split - 如果`split_frame_mode`=`SPLIT_BY_CUSTOM_BLKS`,则`num_blks_split`指定每帧的BLOCK数。 -typedef struct RSInputParam ///< The LiDAR input parameter ++ start_angle、end_angle - 机械式雷达一般输出的点云的水平角在[`0`, `360`]之间,这里可以指定一个更小的范围[`start_angle`, `end_angle`)。 + +## 4 RSInputParam + +RSInputParam指定rs_driver得到有关雷达的Packet源的参数。 + +如下参数针对`ONLINE_LIDAR`和`PCAP_FILE`。 ++ msop_port - 指定主机上的本地UDP端口,接收MSOP Packet ++ difop_port - 指定主机上的本地UDP端口,接收DIFOP Packet + +如下雷达仅针对ONLINE_LIDAR。 ++ host_address - 指定本地的IP地址,接收MSOP/DIFOP Packet ++ group_address - 指定一个组播组。rs_driver将`host_address`指定的网卡加入这个组播组,以便接收MSOP/DIFOP Packet。 + +如下雷达仅针对PCAP_FILE。 ++ pcap_path - PCAP文件的全路径 ++ pcap_repeat - 指定是否重复播放PCAP文件 ++ pcap_rate - rs_driver按`理论上的雷达帧率`播放PCAP文件。`pcap_rate`可以在这个速度上指定一个比例值,加快/放慢播放速度。 ++ use_vlan - 如果PCAP文件中的Packet包含VLAN层,可以指定`use_vlan`=`true`,跳过这一层。 + +```c++ +typedef struct RSInputParam { - uint16_t msop_port = 6699; ///< MSOP packet port number - uint16_t difop_port = 7788; ///< DIFOP packet port number - std::string host_address = "0.0.0.0"; ///< Address of host - std::string group_address = "0.0.0.0"; ///< Address of multicast group - std::string pcap_path = ""; ///< Absolute path of pcap file - bool pcap_repeat = true; ///< true: The pcap bag will repeat play - float pcap_rate = 1.0; ///< Rate to read the pcap file - bool use_vlan = false; ///< Vlan on-off - bool use_someip = false; ///< SOME/IP layer on-off + uint16_t msop_port = 6699; + uint16_t difop_port = 7788; + std::string host_address = "0.0.0.0"; + std::string group_address = "0.0.0.0"; + + // The following parameters are only for PCAP_FILE + std::string pcap_path = ""; + bool pcap_repeat = true; + float pcap_rate = 1.0; + bool use_vlan = false; } RSInputParam; -typedef struct RSDriverParam ///< The LiDAR driver parameter -{ - LidarType lidar_type = LidarType::RS16; ///< Lidar type - InputType input_type = InputType::ONLINE_LIDAR; ///< Input type - RSInputParam input_param; ///< Input parameter - RSDecoderParam decoder_param; ///< Decoder parameter -} RSDriverParam; ``` From 9cb9ce3c1e506dc1bf641d0f4593db760e95d533 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 11 Mar 2022 18:39:41 +0800 Subject: [PATCH 187/379] feat: update docs --- doc/intro/parameter_intro_cn.md | 4 +- doc/intro/parameter_intro_en.md | 178 +++++++++++++++++++++++++------- 2 files changed, 141 insertions(+), 41 deletions(-) diff --git a/doc/intro/parameter_intro_cn.md b/doc/intro/parameter_intro_cn.md index abf8e69a..d759b9c4 100644 --- a/doc/intro/parameter_intro_cn.md +++ b/doc/intro/parameter_intro_cn.md @@ -127,11 +127,11 @@ RSInputParam指定rs_driver得到有关雷达的Packet源的参数。 + msop_port - 指定主机上的本地UDP端口,接收MSOP Packet + difop_port - 指定主机上的本地UDP端口,接收DIFOP Packet -如下雷达仅针对ONLINE_LIDAR。 +如下参数仅针对ONLINE_LIDAR。 + host_address - 指定本地的IP地址,接收MSOP/DIFOP Packet + group_address - 指定一个组播组。rs_driver将`host_address`指定的网卡加入这个组播组,以便接收MSOP/DIFOP Packet。 -如下雷达仅针对PCAP_FILE。 +如下参数仅针对PCAP_FILE。 + pcap_path - PCAP文件的全路径 + pcap_repeat - 指定是否重复播放PCAP文件 + pcap_rate - rs_driver按`理论上的雷达帧率`播放PCAP文件。`pcap_rate`可以在这个速度上指定一个比例值,加快/放慢播放速度。 diff --git a/doc/intro/parameter_intro_en.md b/doc/intro/parameter_intro_en.md index 5d370514..38882de2 100644 --- a/doc/intro/parameter_intro_en.md +++ b/doc/intro/parameter_intro_en.md @@ -1,9 +1,94 @@ -# Parameters Intorduction -## 1 Parameter Definition -The detail parameters are defined in `rs_driver/src/rs_driver/driver_param.h` file. +# Introduction to rs_driver's Parameters + +## 1 Parameter File + +The parameters are defined in the file `rs_driver/src/rs_driver/driver_param.h`. + +Basically, there are 3 structures: RSDriverParam, RSDecoderParam, and RSInputParam. + +## 2 RSDriverParam + +RSDriverParam contains RSDecoderParam and RSInputParam. + +```c++ +typedef struct RSDriverParam +{ + LidarType lidar_type = LidarType::RS16; ///< Lidar type + InputType input_type = InputType::ONLINE_LIDAR; ///< Input type + RSInputParam input_param; + RSDecoderParam decoder_param; +} RSDriverParam; ``` -typedef struct RSTransformParam ///< The Point transform parameter + ++ lidar_type - Lidar Type + + There are two classes of Lidars: Mechanical Lidar and MEMS Lidar. Some paramters of RSDecoderParam is only for mechanical Lidars. + +```c++ +enum LidarType +{ + RS16 = 1, + RS32, + RSBP, + RS128, + RS80, + RSHELIOS, + RSROCK, + RSM1 +}; +``` + ++ input_type - Where the Lidar packets is from. + + ONLINE_LIDAR means from online Lidar; PCAP_FILE means from PCAP file, which is captured with 3rd party tool; RAW_PACKET is used for recording/replaying packets. + +```c++ +enum InputType +{ + ONLINE_LIDAR = 1, + PCAP_FILE, + RAW_PACKET +}; +``` + + +## 3 RSDecoderParam + +RSDecoderParam specifies how rs_driver decode Lidar's packets. + +```c++ +typedef struct RSDecoderParam +{ + bool use_lidar_clock = false; + bool dense_points = false; + bool wait_for_difop = true; + RSTransformParam transform_param; + bool config_from_file = false; + std::string angle_path = ""; + float min_distance = 0.2f; + float max_distance = 200.0f; + + // The following parameters are only for mechanical Lidars. + SplitFrameMode split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; + float split_angle = 0.0f; + uint16_t num_blks_split = 1; + float start_angle = 0.0f; + float end_angle = 360.0f; + +} RSDecoderParam; +``` + +The following parameters are for all Lidars。 ++ use_lidar_clock - Where the point cloud's timestamp is from. From the lidar, or from rs_driver on the host? + + If `use_lidar_clock`=`true`,use the Lidar timestamp, else use the host one. ++ dense_points - Whether the point cloud is dense. + + If `dense_points`=`false`, then point cloud contains NAN points, else discard them. ++ wait_for_difop - Whether wait for DIFOP Packet, before parse MSOP packets. + + DIFOP Packet contains angle calibration parameters. If it is unavailable, the point cloud is flat. + + If you get no point cloud, try `wait_for_difop`=`false`. It might help to locate the problem. ++ transform_param - paramters of coordinate transformation. It is only valid when the CMake option `ENABLE_TRANSFORM`=`ON`. + +```c++ +typedef struct RSTransformParam { float x = 0.0f; ///< unit, m float y = 0.0f; ///< unit, m @@ -12,45 +97,60 @@ typedef struct RSTransformParam ///< The Point transform parameter float pitch = 0.0f; ///< unit, radian float yaw = 0.0f; ///< unit, radian } RSTransformParam; +``` + ++ config_from_file - Where to get Lidar config parameters. From extern files, or from DIFOP packet. Internal use only. ++ angle_path - File of angle calibration. Internal use only. ++ min_distance、max_distance - Measurement Range. Internal use only. + +The following paramters are only for mechanical Lidars. ++ split_frame_mode - How to split frame. + + `SPLIT_BY_ANGLE` is by user requested angle;`SPLIT_BY_FIXED_BLKS` is by blocks/round theologically; `SPLIT_BY_CUSTOM_BLKS` is by user requested blocks/frame. `SPLIT_BY_ANGLE` is default, and the other two values are not suggested. -typedef struct RSDecoderParam ///< LiDAR decoder parameter +```c++ +enum SplitFrameMode { - bool config_from_file = false;///< Internal use only for debugging - std::string angle_path = ""; ///< Internal use only for debugging - bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet - float min_distance = 0.2f; ///< Minimum distance of point cloud range - float max_distance = 200.0f; ///< Max distance of point cloud range - float start_angle = 0.0f; ///< Start angle of point cloud - float end_angle = 360.0f; ///< End angle of point cloud - SplitFrameMode split_frame_mode = - SplitFrameMode::SPLIT_BY_ANGLE; ///< 1: Split frames by split_angle; - ///< 2: Split frames by fixed number of blocks; - ///< 3: Split frames by custom number of blocks (num_blks_split) - float split_angle = 0.0f; ///< Split angle(degree) used to split frame, only be used when split_frame_mode=1 - uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 - bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp - bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points - RSTransformParam transform_param; ///< Used to transform points -} RSDecoderParam; + SPLIT_BY_ANGLE = 1, + SPLIT_BY_FIXED_BLKS, + SPLIT_BY_CUSTOM_BLKS +}; +``` ++ split_angle - If `split_frame_mode`=`SPLIT_BY_ANGLE`, then `split_angle` is the requested angle to split. ++ num_blks_split - If `split_frame_mode`=`SPLIT_BY_CUSTOM_BLKS`,then `num_blks_split` is blocks/frame. -typedef struct RSInputParam ///< The LiDAR input parameter ++ start_angle、end_angle - Generally, mechanical Lidars's point cloud's azimuths are in the range of [`0`, `360`]. Here you may assign a smaller range of [`start_angle`, `end_angle`). + +## 4 RSInputParam + +RSInputParam specifies the detail paramters of packet source. + +The following parameters are for `ONLINE_LIDAR` and `PCAP_FILE`. ++ msop_port - The UDP port on the host, to receive MSOP packets. ++ difop_port - The UDP port on the host, to receive DIFOP Packets. + +The following parameters are only for ONLINE_LIDAR. ++ host_address - The host's IP, to receive MSOP/DIFOP Packets ++ group_address - A multicast group to receive MSOP/DIFOP packts. rs_driver make `host_address` join it. + +The following parameters are only for PCAP_FILE. ++ pcap_path - Full path of the PCAP file. ++ pcap_repeat - Whether to replay PCAP file repeatly ++ pcap_rate - rs_driver replay the PCAP file by the theological frame rate. `pcap_rate` gives a rate to it, so as to speed up or slow down. ++ use_vlan - If the PCAP file contains VLAN layer, use `use_vlan`=`true` to skip it. + +```c++ +typedef struct RSInputParam { - uint16_t msop_port = 6699; ///< MSOP packet port number - uint16_t difop_port = 7788; ///< DIFOP packet port number - std::string host_address = "0.0.0.0"; ///< Address of host - std::string group_address = "0.0.0.0"; ///< Address of multicast group - std::string pcap_path = ""; ///< Absolute path of pcap file - bool pcap_repeat = true; ///< true: The pcap bag will repeat play - float pcap_rate = 1.0; ///< Rate to read the pcap file - bool use_vlan = false; ///< Vlan on-off - bool use_someip = false; ///< SOME/IP layer on-off + uint16_t msop_port = 6699; + uint16_t difop_port = 7788; + std::string host_address = "0.0.0.0"; + std::string group_address = "0.0.0.0"; + + // The following parameters are only for PCAP_FILE + std::string pcap_path = ""; + bool pcap_repeat = true; + float pcap_rate = 1.0; + bool use_vlan = false; } RSInputParam; -typedef struct RSDriverParam ///< The LiDAR driver parameter -{ - LidarType lidar_type = LidarType::RS16; ///< Lidar type - InputType input_type = InputType::ONLINE_LIDAR; ///< Input type - RSInputParam input_param; ///< Input parameter - RSDecoderParam decoder_param; ///< Decoder parameter -} RSDriverParam; ``` From b460e464579afe05f66e2f662d205e737ce11771 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 16 Mar 2022 20:23:25 +0800 Subject: [PATCH 188/379] feat: update docs --- doc/howto/online_lidar_advanced_topics.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/doc/howto/online_lidar_advanced_topics.md b/doc/howto/online_lidar_advanced_topics.md index 2b776493..092e6a62 100644 --- a/doc/howto/online_lidar_advanced_topics.md +++ b/doc/howto/online_lidar_advanced_topics.md @@ -1,8 +1,8 @@ -# Online Lidar - Adavanced Topics +# Online Lidar - Advanced Topics ## 1 Introduction - The RoboSense Lidars may work in unicast/multicast/broadcast mode, with VLAN layer and with user layers. + The RoboSense Lidar may work in unicast/multicast/broadcast mode, with VLAN layer and with user layers. This document illustrates how to configure the driver in each case. @@ -51,7 +51,7 @@ param.lidar_type = LidarType::RS32; ///< Set the lidar type. The Lidar may also works in multicast mode. + The lidar sends to `224.1.1.1`:`6699` -+ The host binds to port 6699. And it makes local NIC (Network Interface Card) join the multicast group `224.1.1.1`. The local NIC's IP is `192.168.1.102`. ++ The host binds to port `6699`. And it makes local NIC (Network Interface Card) join the multicast group `224.1.1.1`. The local NIC's IP is `192.168.1.102`. ![](../img/12_multicast.png) From 47d5d1c52a1d4e8c0c76595435da440a71e39ad7 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 17 Mar 2022 17:16:30 +0800 Subject: [PATCH 189/379] feat: update docs --- README.md | 5 +++-- README_CN.md | 6 +++--- doc/intro/parameter_intro_cn.md | 1 - 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/README.md b/README.md index 664a0a93..0ffb13a7 100644 --- a/README.md +++ b/README.md @@ -20,11 +20,12 @@ **rs_driver** is compatible with the following platforms and compilers: +- Ubuntu (16.04, 18.04) + - gcc (4.8+) + - Windows - MSVC ( tested with VC2017 and VC2019) - Mingw-w64 (tested with x86_64-8.1.0-posix-seh-rt_v6-rev0 ) -- Ubuntu (16.04, 18.04) - - gcc (4.8+) ## 4 Dependency Libraries diff --git a/README_CN.md b/README_CN.md index 661dd0f4..2b2f98dd 100644 --- a/README_CN.md +++ b/README_CN.md @@ -20,13 +20,13 @@ ## 3 支持的操作系统 支持的操作系统及编译器如下。 +- Ubuntu (16.04, 18.04, 20.04) + - gcc (4.8+) + - Windows - MSVC (VS2017 & VS2019 已测试) - Mingw-w64 (x86_64-8.1.0-posix-seh-rt_v6-rev0 已测试) -- Ubuntu (16.04, 18.04, 20.04) - - gcc (4.8+) - ## 4 依赖的第三方库 依赖的第三方库如下。 diff --git a/doc/intro/parameter_intro_cn.md b/doc/intro/parameter_intro_cn.md index d759b9c4..42dab4e0 100644 --- a/doc/intro/parameter_intro_cn.md +++ b/doc/intro/parameter_intro_cn.md @@ -72,7 +72,6 @@ typedef struct RSDecoderParam uint16_t num_blks_split = 1; float start_angle = 0.0f; float end_angle = 360.0f; - } RSDecoderParam; ``` From 70be6a9e2f291abdfcbefe7f712a4aacd32c2a23 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 18 Mar 2022 20:25:32 +0800 Subject: [PATCH 190/379] feat: format --- CMakeLists.txt | 87 +++++++++++++++++++++++++++++--------------------- 1 file changed, 50 insertions(+), 37 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a2ab50d3..589895f6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -8,12 +8,12 @@ endif(WIN32) project(rs_driver VERSION 1.5.0) -#============================= -# Compile Demos&Tools -#============================= -option(COMPILE_DEMOS "Build rs_driver demos" OFF) -option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) -option(COMPILE_TESTS "Build rs_driver unit tests" OFF) +#======================== +# Project setup +#======================== +if (CMAKE_BUILD_TYPE STREQUAL "") + set(CMAKE_BUILD_TYPE Release) +endif() #============================= # Compile Features @@ -21,17 +21,18 @@ option(COMPILE_TESTS "Build rs_driver unit tests" OFF) option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) option(ENABLE_TRANSFORM "Enable transform functions" OFF) -#======================== -# Project setup -#======================== -if (CMAKE_BUILD_TYPE STREQUAL "") - set(CMAKE_BUILD_TYPE Release) -endif() +#============================= +# Compile Demos, Tools, Tests +#============================= +option(COMPILE_DEMOS "Build rs_driver demos" OFF) +option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) +option(COMPILE_TESTS "Build rs_driver unit tests" OFF) #======================== # Platform cross setup #======================== if(MSVC) + set(COMPILER "MSVC Compiler") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /Wall") set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} /Od /Zi") @@ -40,14 +41,16 @@ if(MSVC) CMAKE_CXX_FLAGS CMAKE_C_FLAGS CMAKE_CXX_FLAGS_DEBUG CMAKE_C_FLAGS_DEBUG CMAKE_CXX_FLAGS_RELEASE CMAKE_C_FLAGS_RELEASE - CMAKE_CXX_FLAGS_MINSIZEREL CMAKE_C_FLAGS_MINSIZEREL - CMAKE_CXX_FLAGS_RELWITHDEBINFO CMAKE_C_FLAGS_RELWITHDEBINFO - ) + CMAKE_CXX_FLAGS_MINSIZEREL CMAKE_C_FLAGS_MINSIZEREL + CMAKE_CXX_FLAGS_RELWITHDEBINFO CMAKE_C_FLAGS_RELWITHDEBINFO) + foreach(CompilerFlag ${CompilerFlags}) string(REPLACE "/MT" "/MD" ${CompilerFlag} "${${CompilerFlag}}") endforeach() + add_compile_definitions(_DISABLE_EXTENDED_ALIGNED_STORAGE) # to disable a msvc error set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} /STACK:100000000") + elseif(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") if(UNIX) @@ -86,37 +89,47 @@ endif(WIN32) # PCAP #======================== if(WIN32) + set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/cmake) find_package(PCAP REQUIRED) include_directories(${PCAP_INCLUDE_DIR}) list(APPEND EXTERNAL_LIBS ${PCAP_LIBRARY}) + else() - list(APPEND EXTERNAL_LIBS pcap) -endif(WIN32) -if(${ENABLE_TRANSFORM}) - add_definitions("-DENABLE_TRANSFORM") + list(APPEND EXTERNAL_LIBS pcap) - #======================== - # Eigen - #======================== - find_package(Eigen3 REQUIRED) - include_directories(${EIGEN3_INCLUDE_DIR}) - message(=============================================================) - message("-- Enable Transform Fucntions") - message(=============================================================) -endif(${ENABLE_TRANSFORM}) +endif(WIN32) #======================== # Build Features #======================== if(${ENABLE_HIGH_PRIORITY_THREAD}) + + message(=============================================================) + message("-- Enable High Priority Thread") + message(=============================================================) + add_definitions("-DENABLE_HIGH_PRIORITY_THREAD") endif(${ENABLE_HIGH_PRIORITY_THREAD}) -#======================== -# Build Demos -#======================== +if(${ENABLE_TRANSFORM}) + + message(=============================================================) + message("-- Enable Transform Fucntions") + message(=============================================================) + + add_definitions("-DENABLE_TRANSFORM") + + # Eigen + find_package(Eigen3 REQUIRED) + include_directories(${EIGEN3_INCLUDE_DIR}) + +endif(${ENABLE_TRANSFORM}) + +#============================ +# Build Demos, Tools, Tests +#============================ if(${COMPILE_DEMOS}) add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/demo) endif(${COMPILE_DEMOS}) @@ -135,20 +148,17 @@ endif(${COMPILE_TESTS}) configure_file( ${DRIVER_CMAKE_ROOT}/rs_driverConfig.cmake.in ${DRIVER_CMAKE_ROOT}/rs_driverConfig.cmake - @ONLY -) + @ONLY) configure_file( ${DRIVER_CMAKE_ROOT}/rs_driverConfigVersion.cmake.in ${DRIVER_CMAKE_ROOT}/rs_driverConfigVersion.cmake - @ONLY -) + @ONLY) configure_file ( ${CMAKE_CURRENT_LIST_DIR}/src/rs_driver/macro/version.hpp.in ${CMAKE_CURRENT_LIST_DIR}/src/rs_driver/macro/version.hpp - @ONLY -) + @ONLY) if(NOT ${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_CURRENT_SOURCE_DIR}) set(rs_driver_DIR ${DRIVER_CMAKE_ROOT} PARENT_SCOPE) @@ -158,6 +168,7 @@ endif() # Install & Uninstall #======================== if(UNIX AND ${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_CURRENT_SOURCE_DIR}) + install(FILES ${DRIVER_CMAKE_ROOT}/rs_driverConfig.cmake ${DRIVER_CMAKE_ROOT}/rs_driverConfigVersion.cmake DESTINATION ${INSTALL_CMAKE_DIR}/${CMAKE_PROJECT_NAME}) @@ -177,4 +188,6 @@ if(UNIX AND ${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_CURRENT_SOURCE_DIR}) add_custom_target(uninstall COMMAND ${CMAKE_COMMAND} -P ${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake) endif(NOT TARGET uninstall) + endif(UNIX AND ${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_CURRENT_SOURCE_DIR}) + From 1f0ef3e6af53b194913dfa2ae7083ea9180d6edc Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sun, 20 Mar 2022 11:39:57 +0800 Subject: [PATCH 191/379] feat: cals cur block's time_diff --- src/rs_driver/driver/decoder/block_diff.hpp | 56 +++++++++---------- .../driver/decoder/decoder_RS128.hpp | 7 ++- src/rs_driver/driver/decoder/decoder_RS16.hpp | 7 ++- src/rs_driver/driver/decoder/decoder_RS32.hpp | 7 ++- src/rs_driver/driver/decoder/decoder_RS80.hpp | 7 ++- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 7 ++- .../driver/decoder/decoder_RSHELIOS.hpp | 7 ++- src/rs_driver/driver/decoder/decoder_mech.hpp | 8 +-- test/ab_dual_return_block_diff_test.cpp | 8 +-- test/dual_return_block_diff_test.cpp | 4 +- test/single_return_block_diff_test.cpp | 2 +- 11 files changed, 60 insertions(+), 60 deletions(-) diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index 70cc43e8..d2ff37c3 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -43,34 +43,28 @@ class SingleReturnBlockDiff float ts(uint16_t blk) { - float ret = 0.0f; - if (blk > 0) - { - ret = BLOCK_DURATION; - } - - return ret; + return BLOCK_DURATION; } int32_t azimuth(uint16_t blk) { - int32_t azi= 0; + int32_t az = 0; if (blk < (BLOCKS_PER_PKT - 1)) { - azi = ntohs(this->pkt_.blocks[blk+1].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); + az = ntohs(this->pkt_.blocks[blk+1].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); } else { - azi = ntohs(this->pkt_.blocks[blk].azimuth) - ntohs(this->pkt_.blocks[blk-1].azimuth); + az = ntohs(this->pkt_.blocks[blk].azimuth) - ntohs(this->pkt_.blocks[blk-1].azimuth); } - if (azi < 0) + if (az < 0) { - azi += 36000; + az += 36000; } - return azi; + return az; } SingleReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration) @@ -91,35 +85,35 @@ class DualReturnBlockDiff float ts(uint16_t blk) { - float ret = 0.0f; - - if ((blk % 2 == 0) && (blk != 0)) + if ((blk % 2) == 0) { - ret = BLOCK_DURATION; + return 0.0f; + } + else + { + return BLOCK_DURATION; } - - return ret; } int32_t azimuth(uint16_t blk) { - int32_t azi = 0; + int32_t az = 0; if (blk >= (BLOCKS_PER_PKT - 2)) { - azi = ntohs(this->pkt_.blocks[blk].azimuth) - ntohs(this->pkt_.blocks[blk-2].azimuth); + az = ntohs(this->pkt_.blocks[blk].azimuth) - ntohs(this->pkt_.blocks[blk-2].azimuth); } else { - azi = ntohs(this->pkt_.blocks[blk+2].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); + az = ntohs(this->pkt_.blocks[blk+2].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); } - if (azi < 0) + if (az < 0) { - azi += 36000; + az += 36000; } - return azi; + return az; } DualReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration) @@ -144,14 +138,14 @@ class ABDualReturnBlockDiff if (ntohs(pkt_.blocks[0].azimuth) == ntohs(pkt_.blocks[1].azimuth)) // AAB { - if (blk == 2) + if (blk == 1) { ret = BLOCK_DURATION; } } else // ABB { - if (blk == 1) + if (blk == 0) { ret = BLOCK_DURATION; } @@ -162,15 +156,15 @@ class ABDualReturnBlockDiff int32_t azimuth(uint16_t blk) { - int32_t azi = + int32_t az = ntohs(pkt_.blocks[2].azimuth) - ntohs(pkt_.blocks[0].azimuth); - if (azi < 0) + if (az < 0) { - azi += 36000; + az += 36000; } - return azi; + return az; } ABDualReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 1bce5ec6..25de351c 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -246,8 +246,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe } int32_t block_az = ntohs(block.azimuth); - block_ts += diff.ts(blk); - int32_t block_azi_diff = diff.azimuth(blk); + int32_t block_az_diff = diff.azimuth(blk); if (this->split_strategy_->newBlock(block_az)) { @@ -261,7 +260,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + - (int32_t)((float)block_azi_diff * this->mech_const_param_.CHAN_AZIS[chan]); + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -299,6 +298,8 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe this->prev_point_ts_ = chan_ts; } + + block_ts += diff.ts(blk); } this->prev_pkt_ts_ = pkt_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 51716a6c..243f9701 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -269,8 +269,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az = ntohs(block.azimuth); - block_ts += diff.ts(blk); - int32_t block_azi_diff = diff.azimuth(blk); + int32_t block_az_diff = diff.azimuth(blk); if (this->split_strategy_->newBlock(block_az)) { @@ -284,7 +283,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + - (int32_t)((float)block_azi_diff * this->mech_const_param_.CHAN_AZIS[chan]); + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -322,6 +321,8 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet this->prev_point_ts_ = chan_ts; } + + block_ts += diff.ts(blk); } this->prev_pkt_ts_ = pkt_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index ade84e2f..c3f18612 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -265,8 +265,7 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az = ntohs(block.azimuth); - block_ts += diff.ts(blk); - int32_t block_azi_diff = diff.azimuth(blk); + int32_t block_az_diff = diff.azimuth(blk); if (this->split_strategy_->newBlock(block_az)) { @@ -280,7 +279,7 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + - (int32_t)((float)block_azi_diff * this->mech_const_param_.CHAN_AZIS[chan]); + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -318,6 +317,8 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet this->prev_point_ts_ = chan_ts; } + + block_ts += diff.ts(blk); } this->prev_pkt_ts_ = pkt_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 247ee896..b2c853b6 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -242,8 +242,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az = ntohs(block.azimuth); - block_ts += diff.ts(blk); - int32_t block_azi_diff = diff.azimuth(blk); + int32_t block_az_diff = diff.azimuth(blk); if (this->split_strategy_->newBlock(block_az)) { @@ -257,7 +256,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + - (int32_t)((float)block_azi_diff * this->mech_const_param_.CHAN_AZIS[chan]); + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -295,6 +294,8 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet this->prev_point_ts_ = chan_ts; } + + block_ts += diff.ts(blk); } this->prev_pkt_ts_ = pkt_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 65610715..49ed84d1 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -236,8 +236,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az = ntohs(block.azimuth); - block_ts += diff.ts(blk); - int32_t block_azi_diff = diff.azimuth(blk); + int32_t block_az_diff = diff.azimuth(blk); if (this->split_strategy_->newBlock(block_az)) { @@ -251,7 +250,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + - (int32_t)((float)block_azi_diff * this->mech_const_param_.CHAN_AZIS[chan]); + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -290,6 +289,8 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet this->prev_point_ts_ = chan_ts; } + + block_ts += diff.ts(blk); } this->prev_pkt_ts_ = pkt_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index b372a000..9ab65c13 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -248,8 +248,7 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa } int32_t block_az = ntohs(block.azimuth); - block_ts += diff.ts(blk); - int32_t block_azi_diff = diff.azimuth(blk); + int32_t block_az_diff = diff.azimuth(blk); if (this->split_strategy_->newBlock(block_az)) { @@ -263,7 +262,7 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + - (int32_t)((float)block_azi_diff * this->mech_const_param_.CHAN_AZIS[chan]); + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); int32_t angle_vert = this->chan_angles_.vertAdjust(chan); int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); @@ -301,6 +300,8 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa this->prev_point_ts_ = chan_ts; } + + block_ts += diff.ts(blk); } this->prev_pkt_ts_ = pkt_ts; diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index b1d916ed..b60b0e4a 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -92,7 +92,7 @@ class DecoderMech : public Decoder uint16_t rps_; // rounds per second uint16_t blks_per_frame_; // blocks per frame/round uint16_t split_blks_per_frame_; // blocks in msop pkt per frame/round. - uint16_t block_azi_diff_; // azimuth difference between adjacent blocks. + uint16_t block_az_diff_; // azimuth difference between adjacent blocks. float fov_blind_ts_diff_; // timestamp difference across blind section(defined by fov) int lidar_alph0_; // lens center related @@ -110,7 +110,7 @@ inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& con , rps_(10) , blks_per_frame_(1/(10*this->mech_const_param_.BLOCK_DURATION)) , split_blks_per_frame_(blks_per_frame_) - , block_azi_diff_(20) + , block_az_diff_(20) , fov_blind_ts_diff_(0) { this->height_ = this->const_param_.CHANNELS_PER_BLOCK; @@ -162,7 +162,7 @@ inline void DecoderMech::print() << "echo_mode:\t\t" << this->echo_mode_ << std::endl << "blks_per_frame:\t\t" << this->blks_per_frame_ << std::endl << "split_blks_per_frame:\t" << this->split_blks_per_frame_ << std::endl - << "block_azi_diff:\t\t" << this->block_azi_diff_ << std::endl + << "block_az_diff:\t\t" << this->block_az_diff_ << std::endl << "fov_blind_ts_diff:\t" << this->fov_blind_ts_diff_ << std::endl << "angle_from_file:\t" << this->param_.config_from_file << std::endl << "angles_ready:\t\t" << this->angles_ready_ << std::endl; @@ -186,7 +186,7 @@ inline void DecoderMech::decodeDifopCommon(const T_Difop& pkt) this->blks_per_frame_ = 1 / (this->rps_ * this->mech_const_param_.BLOCK_DURATION); // block diff of azimuth - this->block_azi_diff_ = + this->block_az_diff_ = std::round(RS_ONE_ROUND * this->rps_ * this->mech_const_param_.BLOCK_DURATION); // fov related diff --git a/test/ab_dual_return_block_diff_test.cpp b/test/ab_dual_return_block_diff_test.cpp index b01afc53..7068bff5 100644 --- a/test/ab_dual_return_block_diff_test.cpp +++ b/test/ab_dual_return_block_diff_test.cpp @@ -67,9 +67,9 @@ TEST(TestDualPacketTraverser, toNext) // first block ASSERT_EQ(diff.ts(0), 0.0f); // still first block - ASSERT_EQ(diff.ts(1), 0.0f); + ASSERT_EQ(diff.ts(1), 0.5f); // last block - ASSERT_EQ(diff.ts(2), 0.5f); + ASSERT_EQ(diff.ts(2), 0.0f); // first block. ASSERT_EQ(diff.azimuth(0), 20); @@ -92,9 +92,9 @@ TEST(TestDualPacketTraverser, toNext) const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); // first block - ASSERT_EQ(diff.ts(0), 0.0f); + ASSERT_EQ(diff.ts(0), 0.5f); // still first block - ASSERT_EQ(diff.ts(1), 0.5f); + ASSERT_EQ(diff.ts(1), 0.0f); // last block ASSERT_EQ(diff.ts(2), 0.5f); diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_diff_test.cpp index c6a6d9a0..7352d950 100644 --- a/test/dual_return_block_diff_test.cpp +++ b/test/dual_return_block_diff_test.cpp @@ -68,9 +68,9 @@ TEST(TestDualPacketTraverser, toNext) // first block ASSERT_EQ(diff.ts(0), 0.0f); // still first block - ASSERT_EQ(diff.ts(1), 0.0f); + ASSERT_EQ(diff.ts(1), 0.5f); // second block - ASSERT_EQ(diff.ts(2), 0.5f); + ASSERT_EQ(diff.ts(2), 0.0f); // first block ASSERT_EQ(diff.azimuth(0), 20); diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_diff_test.cpp index ba021d4b..98fb5bef 100644 --- a/test/single_return_block_diff_test.cpp +++ b/test/single_return_block_diff_test.cpp @@ -63,7 +63,7 @@ TEST(TestSingleReturnBlockDiff, ctor) const_param.base.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); // first block - ASSERT_EQ(diff.ts(0), 0.0f); + ASSERT_EQ(diff.ts(0), 0.5f); // second block ASSERT_EQ(diff.ts(1), 0.5f); From f4a88064eded1678db277d912365cf538781605e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 21 Mar 2022 14:15:05 +0800 Subject: [PATCH 192/379] feat: support fov --- src/rs_driver/driver/decoder/basic_attr.hpp | 2 - src/rs_driver/driver/decoder/block_diff.hpp | 181 +++++++++--------- .../driver/decoder/decoder_RS128.hpp | 12 +- src/rs_driver/driver/decoder/decoder_RS16.hpp | 11 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 11 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 11 +- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 11 +- .../driver/decoder/decoder_RSHELIOS.hpp | 11 +- test/CMakeLists.txt | 2 +- test/ab_dual_return_block_diff_test.cpp | 128 ++++++++----- test/dual_return_block_diff_test.cpp | 116 +++++++---- test/single_return_block_diff_test.cpp | 84 ++++---- 12 files changed, 331 insertions(+), 249 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index 2abd6a70..e4623a9a 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -98,8 +98,6 @@ inline void createTimeUTCWithNs(uint64_t us, RSTimestampUTC* tsUtc) uint64_t sec = us / 1000000; uint64_t nsec = (us % 1000000) * 1000; - std::cout << std::hex << "usec:" << nsec << std::endl; - for (int i = 5; i >= 0; i--) { tsUtc->sec[i] = sec & 0xFF; diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_diff.hpp index d2ff37c3..548f36cf 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_diff.hpp @@ -37,38 +37,20 @@ namespace lidar { template -class SingleReturnBlockDiff +class BlockDiff { public: - float ts(uint16_t blk) + void getDiff(uint16_t blk, int32_t& az_diff, float& ts) { - return BLOCK_DURATION; + az_diff = az_diffs[blk]; + ts = tss[blk]; } - int32_t azimuth(uint16_t blk) - { - int32_t az = 0; - - if (blk < (BLOCKS_PER_PKT - 1)) - { - az = ntohs(this->pkt_.blocks[blk+1].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); - } - else - { - az = ntohs(this->pkt_.blocks[blk].azimuth) - ntohs(this->pkt_.blocks[blk-1].azimuth); - } - - if (az < 0) - { - az += 36000; - } - - return az; - } - - SingleReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration) - : pkt_(pkt), BLOCKS_PER_PKT(blocks_per_pkt), BLOCK_DURATION(block_duration) + BlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, + uint16_t block_az_duration, float fov_blind_duration) + : pkt_(pkt), BLOCKS_PER_PKT(blocks_per_pkt), BLOCK_DURATION(block_duration), + BLOCK_AZ_DURATION(block_az_duration), FOV_BLIND_DURATION(fov_blind_duration) { } @@ -76,106 +58,123 @@ class SingleReturnBlockDiff const T_Packet& pkt_; const uint16_t BLOCKS_PER_PKT; const double BLOCK_DURATION; + const uint16_t BLOCK_AZ_DURATION; + const float FOV_BLIND_DURATION; + int32_t az_diffs[128]; + float tss[128]; }; template -class DualReturnBlockDiff +class SingleReturnBlockDiff : public BlockDiff { public: - float ts(uint16_t blk) + SingleReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, + uint16_t block_az_duration, float fov_blind_duration) + : BlockDiff(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) { - if ((blk % 2) == 0) + float tss = 0; + uint16_t blk = 0; + for (; blk < (this->BLOCKS_PER_PKT - 1); blk++) { - return 0.0f; - } - else - { - return BLOCK_DURATION; - } - } + float ts_diff = this->BLOCK_DURATION; + int32_t az_diff = ntohs(this->pkt_.blocks[blk+1].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); + if (az_diff < 0) { az_diff += 36000; } - int32_t azimuth(uint16_t blk) - { - int32_t az = 0; + // Skip FOV blind zone + if (az_diff > 100) + { + az_diff = this->BLOCK_AZ_DURATION; + ts_diff = this->FOV_BLIND_DURATION; + } - if (blk >= (BLOCKS_PER_PKT - 2)) - { - az = ntohs(this->pkt_.blocks[blk].azimuth) - ntohs(this->pkt_.blocks[blk-2].azimuth); - } - else - { - az = ntohs(this->pkt_.blocks[blk+2].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); - } + this->az_diffs[blk] = az_diff; + this->tss[blk] = tss; - if (az < 0) - { - az += 36000; + tss += ts_diff; } - return az; + this->az_diffs[blk] = this->BLOCK_AZ_DURATION; + this->tss[blk] = tss; } - - DualReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration) - : pkt_(pkt), BLOCKS_PER_PKT(blocks_per_pkt), BLOCK_DURATION(block_duration) - { - } - -protected: - const T_Packet& pkt_; - const uint16_t BLOCKS_PER_PKT; - const double BLOCK_DURATION; }; template -class ABDualReturnBlockDiff +class DualReturnBlockDiff : public BlockDiff { public: - float ts(uint16_t blk) + DualReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, + uint16_t block_az_duration, float fov_blind_duration) + : BlockDiff(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) { - float ret = 0.0f; - - if (ntohs(pkt_.blocks[0].azimuth) == ntohs(pkt_.blocks[1].azimuth)) // AAB - { - if (blk == 1) - { - ret = BLOCK_DURATION; - } - } - else // ABB + float tss = 0; + uint16_t blk = 0; + for (; blk < (this->BLOCKS_PER_PKT - 2); blk = blk + 2) { - if (blk == 0) + float ts_diff = this->BLOCK_DURATION; + int32_t az_diff = ntohs(this->pkt_.blocks[blk+2].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); + if (az_diff < 0) { az_diff += 36000; } + + // Skip FOV blind zone + if (az_diff > 100) { - ret = BLOCK_DURATION; + az_diff = this->BLOCK_AZ_DURATION; + ts_diff = this->FOV_BLIND_DURATION; } + + this->az_diffs[blk] = this->az_diffs[blk+1] = az_diff; + this->tss[blk] = this->tss[blk+1] = tss; + + tss += ts_diff; } - return ret; + this->az_diffs[blk] = this->az_diffs[blk+1] = this->BLOCK_AZ_DURATION; + this->tss[blk] = this->tss[blk+1] = tss; } +}; + +template +class ABDualReturnBlockDiff : public BlockDiff +{ +public: - int32_t azimuth(uint16_t blk) + ABDualReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, + uint16_t block_az_duration, float fov_blind_duration) + : BlockDiff(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) { - int32_t az = - ntohs(pkt_.blocks[2].azimuth) - ntohs(pkt_.blocks[0].azimuth); + float ts_diff = this->BLOCK_DURATION; + int32_t az_diff = ntohs(this->pkt_.blocks[2].azimuth) - ntohs(this->pkt_.blocks[0].azimuth); + if (az_diff < 0) { az_diff += 36000; } - if (az < 0) + // Skip FOV blind zone + if (az_diff > 100) { - az += 36000; + az_diff = this->BLOCK_AZ_DURATION; + ts_diff = this->FOV_BLIND_DURATION; } - return az; - } + if (ntohs(this->pkt_.blocks[0].azimuth) == ntohs(this->pkt_.blocks[1].azimuth)) // AAB + { + float tss = 0; + this->az_diffs[0] = this->az_diffs[1] = az_diff; + this->tss[0] = this->tss[1] = tss; - ABDualReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration) - : pkt_(pkt), BLOCKS_PER_PKT(blocks_per_pkt), BLOCK_DURATION(block_duration) - { - } + tss += ts_diff; + this->az_diffs[2] = this->BLOCK_AZ_DURATION; + this->tss[2] = tss; + } + else // ABB + { + float tss = 0; + this->az_diffs[0] = az_diff; + this->tss[0] = tss; -protected: - const T_Packet& pkt_; - const uint16_t BLOCKS_PER_PKT; - const double BLOCK_DURATION; + tss += ts_diff; + this->az_diffs[1] = this->az_diffs[2] = this->BLOCK_AZ_DURATION; + this->tss[1] = this->tss[2] = tss; + } + } }; } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 25de351c..789c6afd 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -232,7 +232,8 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe } } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) @@ -246,7 +247,10 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe } int32_t block_az = ntohs(block.azimuth); - int32_t block_az_diff = diff.azimuth(blk); + + int32_t block_az_diff; + float block_ts_off; + diff.getDiff(blk, block_az_diff, block_ts_off); if (this->split_strategy_->newBlock(block_az)) { @@ -258,7 +262,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); @@ -298,8 +302,6 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe this->prev_point_ts_ = chan_ts; } - - block_ts += diff.ts(blk); } this->prev_pkt_ts_ = pkt_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 243f9701..9bbf1443 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -255,7 +255,8 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet } } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) @@ -269,7 +270,9 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az = ntohs(block.azimuth); - int32_t block_az_diff = diff.azimuth(blk); + int32_t block_az_diff; + float block_ts_off; + diff.getDiff(blk, block_az_diff, block_ts_off); if (this->split_strategy_->newBlock(block_az)) { @@ -281,7 +284,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); @@ -321,8 +324,6 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet this->prev_point_ts_ = chan_ts; } - - block_ts += diff.ts(blk); } this->prev_pkt_ts_ = pkt_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index c3f18612..ca4ef5b2 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -251,7 +251,8 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet } } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) @@ -265,7 +266,9 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az = ntohs(block.azimuth); - int32_t block_az_diff = diff.azimuth(blk); + int32_t block_az_diff; + float block_ts_off; + diff.getDiff(blk, block_az_diff, block_ts_off); if (this->split_strategy_->newBlock(block_az)) { @@ -277,7 +280,7 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); @@ -317,8 +320,6 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet this->prev_point_ts_ = chan_ts; } - - block_ts += diff.ts(blk); } this->prev_pkt_ts_ = pkt_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index b2c853b6..2c1e5569 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -228,7 +228,8 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet } } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) @@ -242,7 +243,9 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az = ntohs(block.azimuth); - int32_t block_az_diff = diff.azimuth(blk); + int32_t block_az_diff; + float block_ts_off; + diff.getDiff(blk, block_az_diff, block_ts_off); if (this->split_strategy_->newBlock(block_az)) { @@ -254,7 +257,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); @@ -294,8 +297,6 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet this->prev_point_ts_ = chan_ts; } - - block_ts += diff.ts(blk); } this->prev_pkt_ts_ = pkt_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 49ed84d1..3ab2558a 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -222,7 +222,8 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet } } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) @@ -236,7 +237,9 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az = ntohs(block.azimuth); - int32_t block_az_diff = diff.azimuth(blk); + int32_t block_az_diff; + float block_ts_off; + diff.getDiff(blk, block_az_diff, block_ts_off); if (this->split_strategy_->newBlock(block_az)) { @@ -248,7 +251,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); @@ -289,8 +292,6 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet this->prev_point_ts_ = chan_ts; } - - block_ts += diff.ts(blk); } this->prev_pkt_ts_ = pkt_ts; diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 9ab65c13..afd33f4d 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -234,7 +234,8 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa } } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION); + T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) @@ -248,7 +249,9 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa } int32_t block_az = ntohs(block.azimuth); - int32_t block_az_diff = diff.azimuth(blk); + int32_t block_az_diff; + float block_ts_off; + diff.getDiff(blk, block_az_diff, block_ts_off); if (this->split_strategy_->newBlock(block_az)) { @@ -260,7 +263,7 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); @@ -300,8 +303,6 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa this->prev_point_ts_ = chan_ts; } - - block_ts += diff.ts(blk); } this->prev_pkt_ts_ = pkt_ts; diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index ba648846..10eabc47 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -20,10 +20,10 @@ add_executable(rs_driver_test split_strategy_test.cpp single_return_block_diff_test.cpp dual_return_block_diff_test.cpp + ab_dual_return_block_diff_test.cpp decoder_test.cpp decoder_rsbp_test.cpp decoder_rs32_test.cpp) - target_link_libraries(rs_driver_test ${GTEST_LIBRARIES} diff --git a/test/ab_dual_return_block_diff_test.cpp b/test/ab_dual_return_block_diff_test.cpp index 7068bff5..c51efb00 100644 --- a/test/ab_dual_return_block_diff_test.cpp +++ b/test/ab_dual_return_block_diff_test.cpp @@ -23,35 +23,8 @@ typedef struct MyBlock blocks[3]; } MyPacket; -TEST(TestDualPacketTraverser, toNext) +TEST(TestABDualPacketTraverser, ctor) { - RSDecoderConstParam const_param = - { - 0 - , 0 - , 0 - , 0 - , {0x00} // msop id - , {0x00} // difop id - , {0x00} // block id - , 3 // blocks per packet - , 2 // channels per block - , 0.0f // distance min - , 0.0f // distance max - , 0.0 // distance resolution - , 0.0 // temperature resolution - - // lens center - , 0 // RX - , 0 // RY - , 0 // RZ - - // firing_ts - , 0.50 // block_duration - , {0.0, 0.25} // chan_tss - , {0.0} // chan_azis - }; - { // AAB MyPacket pkt = @@ -62,21 +35,28 @@ TEST(TestDualPacketTraverser, toNext) }; ABDualReturnBlockDiff diff(pkt, - const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); + 3, // blocks per packet + 0.5f, // block_duration + 25, // block_az_duraton + 2.0f); // fov_blind_duration + + int32_t az_diff; + float ts; // first block - ASSERT_EQ(diff.ts(0), 0.0f); - // still first block - ASSERT_EQ(diff.ts(1), 0.5f); - // last block - ASSERT_EQ(diff.ts(2), 0.0f); + diff.getDiff (0, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); + + // second block + diff.getDiff (1, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); - // first block. - ASSERT_EQ(diff.azimuth(0), 20); // last block - ASSERT_EQ(diff.azimuth(1), 20); - // still last block - ASSERT_EQ(diff.azimuth(2), 20); + diff.getDiff (2, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 0.5f); } { @@ -89,22 +69,68 @@ TEST(TestDualPacketTraverser, toNext) }; ABDualReturnBlockDiff diff(pkt, - const_param.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); + 3, // blocks per packet + 0.5f, // block_duration + 25, // block_az_duraton + 2.0f); // fov_blind_duration + + int32_t az_diff; + float ts; // first block - ASSERT_EQ(diff.ts(0), 0.5f); - // still first block - ASSERT_EQ(diff.ts(1), 0.0f); + diff.getDiff (0, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); + + // second block + diff.getDiff (1, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 0.5f); + // last block - ASSERT_EQ(diff.ts(2), 0.5f); - - // first block. - ASSERT_EQ(diff.azimuth(0), 20); - // second block = prev block - ASSERT_EQ(diff.azimuth(1), 20); - // (last - 1) block = - ASSERT_EQ(diff.azimuth(2), 20); + diff.getDiff (2, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 0.5f); } } +TEST(TestABDualPacketTraverser, ctor_fov) +{ + { + // AAB + MyPacket pkt = + { + htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(121), 0x00, 0x00, 0x00, 0x00 + }; + + ABDualReturnBlockDiff diff(pkt, + 3, // blocks per packet + 0.5f, // block_duration + 25, // block_az_duraton + 2.0f); // fov_blind_duration + + int32_t az_diff; + float ts; + + // first block + diff.getDiff (0, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 0.0f); + + // second block + diff.getDiff (1, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 0.0f); + + // last block + diff.getDiff (2, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 2.0f); + } + +} + + diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_diff_test.cpp index 7352d950..39ef83a7 100644 --- a/test/dual_return_block_diff_test.cpp +++ b/test/dual_return_block_diff_test.cpp @@ -23,35 +23,8 @@ typedef struct MyBlock blocks[6]; } MyPacket; -TEST(TestDualPacketTraverser, toNext) +TEST(TestDualPacketTraverser, ctor) { - RSDecoderMechConstParam const_param = - { - 0 - , 0 - , 0 - , 0 - , {0x00} // msop id - , {0x00} // difop id - , {0x00} // block id - , 6 // blocks per packet - , 2 // channels per block - , 0.0f // distance min - , 0.0f // distance max - , 0.25 // distance resolution - , 0.0 // temperature resolution - - // lens center - , 0 // RX - , 0 // RY - , 0 // RZ - - // firing_ts - , 0.50 // block_duration - , {0.0, 0.25} // chan_tss - , {0.0} // chan_azis - }; - MyPacket pkt = { htons(1), 0x00, 0x00, 0x00, 0x00 @@ -63,22 +36,89 @@ TEST(TestDualPacketTraverser, toNext) }; DualReturnBlockDiff diff(pkt, - const_param.base.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); + 6, // blocks per packet + 0.5f, // block_duration + 25, // block_az_duraton + 2.0f); // fov_blind_duration + + int32_t az_diff; + float ts; // first block - ASSERT_EQ(diff.ts(0), 0.0f); - // still first block - ASSERT_EQ(diff.ts(1), 0.5f); + diff.getDiff (0, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); + // second block - ASSERT_EQ(diff.ts(2), 0.0f); + diff.getDiff (1, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); + + // third block + diff.getDiff (2, az_diff, ts); + ASSERT_EQ(az_diff, 30); + ASSERT_EQ(ts, 0.5f); + + // last block + diff.getDiff (4, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 1.0f); + + // last block + diff.getDiff (5, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 1.0f); +} + +TEST(TestDualPacketTraverser, ctor_fov) +{ + MyPacket pkt = + { + htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + , htons(141), 0x00, 0x00, 0x00, 0x00 + , htons(141), 0x00, 0x00, 0x00, 0x00 + }; + + DualReturnBlockDiff diff(pkt, + 6, // blocks per packet + 0.5f, // block_duration + 25, // block_az_duraton + 2.0f); // fov_blind_duration + + int32_t az_diff; + float ts; // first block - ASSERT_EQ(diff.azimuth(0), 20); - // still frist block - ASSERT_EQ(diff.azimuth(1), 20); + diff.getDiff (0, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); + + // second block + diff.getDiff (1, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); + + // third block + diff.getDiff (2, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 0.5f); + + // fourth block + diff.getDiff (2, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 0.5f); + // last block - ASSERT_EQ(diff.azimuth(4), 30); + diff.getDiff (4, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 2.5f); + // last block - ASSERT_EQ(diff.azimuth(5), 30); + diff.getDiff (5, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 2.5f); } diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_diff_test.cpp index 98fb5bef..909a91fa 100644 --- a/test/single_return_block_diff_test.cpp +++ b/test/single_return_block_diff_test.cpp @@ -25,33 +25,6 @@ typedef struct TEST(TestSingleReturnBlockDiff, ctor) { - RSDecoderMechConstParam const_param = - { - 0 // msop len - , 0 // difop len - , 0 - , 0 - , {0x00} // msop id - , {0x00} // difop id - , {0x00} // block id - , 3 // blocks per packet - , 2 // channels per block - , 0.0f // distance min - , 0.0f // distance max - , 0.25 // distance resolution - , 0.0 // temperature resolution - - // lens center - , 0 // RX - , 0 // RY - , 0 // RZ - - // firing_ts - , 0.50 // block_duration - , {0.0, 0.25} // chan_tss - , {0.0} // chan_azis - }; - MyPacket pkt = { htons(1), 0x00, 0x00, 0x00, 0x00 @@ -60,18 +33,57 @@ TEST(TestSingleReturnBlockDiff, ctor) }; SingleReturnBlockDiff diff(pkt, - const_param.base.BLOCKS_PER_PKT, const_param.BLOCK_DURATION); + 3, // blocks per packet + 0.5f, // block_duration + 25, // block_az_duraton + 2.0f); // fov_blind_duration + + int32_t az_diff; + float ts; // first block - ASSERT_EQ(diff.ts(0), 0.5f); - // second block - ASSERT_EQ(diff.ts(1), 0.5f); + diff.getDiff (0, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); + + diff.getDiff (1, az_diff, ts); + ASSERT_EQ(az_diff, 30); + ASSERT_EQ(ts, 0.5f); + + diff.getDiff (2, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 1.0f); +} + +TEST(TestSingleReturnBlockDiff, ctor_fov) +{ + MyPacket pkt = + { + htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + , htons(141), 0x00, 0x00, 0x00, 0x00 + }; + + SingleReturnBlockDiff diff(pkt, + 3, // blocks per packet + 0.5f, // block_duration + 25, // block_az_duraton + 2.0f); // fov_blind_duration + + int32_t az_diff; + float ts; // first block - ASSERT_EQ(diff.azimuth(0), 20); - // second block. - ASSERT_EQ(diff.azimuth(1), 30); - // last block - ASSERT_EQ(diff.azimuth(2), 30); + diff.getDiff (0, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); + + diff.getDiff (1, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 0.5f); + + diff.getDiff (2, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 2.5f); } From 86df515253c2a7c6887828b8df38e843bbb2975d Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 21 Mar 2022 15:35:53 +0800 Subject: [PATCH 193/379] feat: support fov --- test/decoder_test.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 035159e7..16db8b56 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -156,8 +156,9 @@ TEST(TestDecoder, processDifopPkt) ASSERT_EQ(decoder.rps_, 10); ASSERT_EQ(decoder.blks_per_frame_, 1801); + ASSERT_EQ(decoder.block_az_diff_, 20); ASSERT_EQ(decoder.split_blks_per_frame_, 1801); - ASSERT_EQ(decoder.fov_blind_ts_diff_, 0.075f); + ASSERT_EQ(decoder.fov_blind_ts_diff_, 0.075f); // 0.1 * 3/4 ASSERT_FALSE(decoder.angles_ready_); ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); ASSERT_EQ(decoder.chan_angles_.vert_angles_[0], 0); @@ -171,8 +172,8 @@ TEST(TestDecoder, processDifopPkt) { 0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55 // difop id , 0x02, 0x58 // rpm - , 0x23, 0x28 // start angle = 9000 - , 0x46, 0x50 // end angle = 18000 + , 0x00, 0x00 // start angle = 0 + , 0x8C, 0xA0 // end angle = 36000 , 0x00, 0x00, 0x10 // vert angles , 0x01, 0x00, 0x20 , 0x00, 0x00, 0x01 // horiz angles @@ -185,6 +186,8 @@ TEST(TestDecoder, processDifopPkt) decoder.processDifopPkt(pkt, sizeof(MyDifopPkt)); ASSERT_EQ(errCode, ERRCODE_SUCCESS); + ASSERT_EQ(decoder.rps_, 10); + ASSERT_EQ(decoder.fov_blind_ts_diff_, 0.0f); // 0.1 * 3/4 ASSERT_TRUE(decoder.angles_ready_); ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); ASSERT_EQ(decoder.chan_angles_.vert_angles_[0], 16); From 212816d86bf41bd2e90ec1a970cd4c91f39095d7 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 21 Mar 2022 16:26:04 +0800 Subject: [PATCH 194/379] feat: support fov --- .../{block_diff.hpp => block_iterator.hpp} | 24 ++++++++-------- src/rs_driver/driver/decoder/decoder.hpp | 4 --- .../driver/decoder/decoder_RS128.hpp | 12 ++++---- src/rs_driver/driver/decoder/decoder_RS16.hpp | 12 ++++---- src/rs_driver/driver/decoder/decoder_RS32.hpp | 12 ++++---- src/rs_driver/driver/decoder/decoder_RS80.hpp | 12 ++++---- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 12 ++++---- .../driver/decoder/decoder_RSHELIOS.hpp | 12 ++++---- src/rs_driver/driver/decoder/decoder_mech.hpp | 3 ++ test/CMakeLists.txt | 6 ++-- ...=> ab_dual_return_block_iterator_test.cpp} | 26 ++++++++--------- ...pp => dual_return_block_iterator_test.cpp} | 28 +++++++++---------- ... => single_return_block_iterator_test.cpp} | 22 +++++++-------- 13 files changed, 92 insertions(+), 93 deletions(-) rename src/rs_driver/driver/decoder/{block_diff.hpp => block_iterator.hpp} (84%) rename test/{ab_dual_return_block_diff_test.cpp => ab_dual_return_block_iterator_test.cpp} (80%) rename test/{dual_return_block_diff_test.cpp => dual_return_block_iterator_test.cpp} (80%) rename test/{single_return_block_diff_test.cpp => single_return_block_iterator_test.cpp} (75%) diff --git a/src/rs_driver/driver/decoder/block_diff.hpp b/src/rs_driver/driver/decoder/block_iterator.hpp similarity index 84% rename from src/rs_driver/driver/decoder/block_diff.hpp rename to src/rs_driver/driver/decoder/block_iterator.hpp index 548f36cf..31e6a5cb 100644 --- a/src/rs_driver/driver/decoder/block_diff.hpp +++ b/src/rs_driver/driver/decoder/block_iterator.hpp @@ -37,17 +37,17 @@ namespace lidar { template -class BlockDiff +class BlockIterator { public: - void getDiff(uint16_t blk, int32_t& az_diff, float& ts) + void get(uint16_t blk, int32_t& az_diff, float& ts) { az_diff = az_diffs[blk]; ts = tss[blk]; } - BlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, + BlockIterator(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, uint16_t block_az_duration, float fov_blind_duration) : pkt_(pkt), BLOCKS_PER_PKT(blocks_per_pkt), BLOCK_DURATION(block_duration), BLOCK_AZ_DURATION(block_az_duration), FOV_BLIND_DURATION(fov_blind_duration) @@ -65,13 +65,13 @@ class BlockDiff }; template -class SingleReturnBlockDiff : public BlockDiff +class SingleReturnBlockIterator : public BlockIterator { public: - SingleReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, + SingleReturnBlockIterator(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, uint16_t block_az_duration, float fov_blind_duration) - : BlockDiff(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) + : BlockIterator(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) { float tss = 0; uint16_t blk = 0; @@ -100,13 +100,13 @@ class SingleReturnBlockDiff : public BlockDiff }; template -class DualReturnBlockDiff : public BlockDiff +class DualReturnBlockIterator : public BlockIterator { public: - DualReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, + DualReturnBlockIterator(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, uint16_t block_az_duration, float fov_blind_duration) - : BlockDiff(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) + : BlockIterator(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) { float tss = 0; uint16_t blk = 0; @@ -135,13 +135,13 @@ class DualReturnBlockDiff : public BlockDiff }; template -class ABDualReturnBlockDiff : public BlockDiff +class ABDualReturnBlockIterator : public BlockIterator { public: - ABDualReturnBlockDiff(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, + ABDualReturnBlockIterator(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, uint16_t block_az_duration, float fov_blind_duration) - : BlockDiff(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) + : BlockIterator(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) { float ts_diff = this->BLOCK_DURATION; int32_t az_diff = ntohs(this->pkt_.blocks[2].azimuth) - ntohs(this->pkt_.blocks[0].azimuth); diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index b0714527..8829a48c 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -37,11 +37,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include -#include #include -#include -#include #ifndef _USE_MATH_DEFINES #define _USE_MATH_DEFINES // for VC++, required to use const M_IP in diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 789c6afd..6c316da1 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -97,7 +97,7 @@ class DecoderRS128 : public DecoderMech static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); - template + template bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; @@ -197,16 +197,16 @@ inline bool DecoderRS128::decodeMsopPkt(const uint8_t* pkt, size_t { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template -template +template inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS128MsopPkt& pkt = *(const RS128MsopPkt*)(packet); @@ -232,7 +232,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe } } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; @@ -250,7 +250,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe int32_t block_az_diff; float block_ts_off; - diff.getDiff(blk, block_az_diff, block_ts_off); + iter.get(blk, block_az_diff, block_ts_off); if (this->split_strategy_->newBlock(block_az)) { diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 9bbf1443..fa84585f 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -129,7 +129,7 @@ class DecoderRS16 : public DecoderMech static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); - template + template bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; @@ -220,16 +220,16 @@ inline bool DecoderRS16::decodeMsopPkt(const uint8_t* pkt, size_t { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template -template +template inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS16MsopPkt& pkt = *(const RS16MsopPkt*)(packet); @@ -255,7 +255,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet } } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; @@ -272,7 +272,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); int32_t block_az_diff; float block_ts_off; - diff.getDiff(blk, block_az_diff, block_ts_off); + iter.get(blk, block_az_diff, block_ts_off); if (this->split_strategy_->newBlock(block_az)) { diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index ca4ef5b2..0532ab07 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -126,7 +126,7 @@ class DecoderRS32 : public DecoderMech static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); - template + template bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; @@ -216,16 +216,16 @@ inline bool DecoderRS32::decodeMsopPkt(const uint8_t* pkt, size_t { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template -template +template inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS32MsopPkt& pkt = *(const RS32MsopPkt*)(packet); @@ -251,7 +251,7 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet } } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; @@ -268,7 +268,7 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); int32_t block_az_diff; float block_ts_off; - diff.getDiff(blk, block_az_diff, block_ts_off); + iter.get(blk, block_az_diff, block_ts_off); if (this->split_strategy_->newBlock(block_az)) { diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 2c1e5569..26eddf34 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -99,7 +99,7 @@ class DecoderRS80 : public DecoderMech static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); - template + template bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; @@ -193,16 +193,16 @@ inline bool DecoderRS80::decodeMsopPkt(const uint8_t* pkt, size_t { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template -template +template inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RS80MsopPkt& pkt = *(const RS80MsopPkt*)(packet); @@ -228,7 +228,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet } } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; @@ -245,7 +245,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); int32_t block_az_diff; float block_ts_off; - diff.getDiff(blk, block_az_diff, block_ts_off); + iter.get(blk, block_az_diff, block_ts_off); if (this->split_strategy_->newBlock(block_az)) { diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 3ab2558a..9f79af98 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -100,7 +100,7 @@ class DecoderRSBP : public DecoderMech static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); - template + template bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; @@ -187,16 +187,16 @@ inline bool DecoderRSBP::decodeMsopPkt(const uint8_t* pkt, size_t { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template -template +template inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RSBPMsopPkt& pkt = *(const RSBPMsopPkt*)(packet); @@ -222,7 +222,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet } } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; @@ -239,7 +239,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); int32_t block_az_diff; float block_ts_off; - diff.getDiff(blk, block_az_diff, block_ts_off); + iter.get(blk, block_az_diff, block_ts_off); if (this->split_strategy_->newBlock(block_az)) { diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index afd33f4d..c52b3bff 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -111,7 +111,7 @@ class DecoderRSHELIOS : public DecoderMech static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); - template + template bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; @@ -199,16 +199,16 @@ inline bool DecoderRSHELIOS::decodeMsopPkt(const uint8_t* pkt, siz { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template -template +template inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* packet, size_t size) { const RSHELIOSMsopPkt& pkt = *(const RSHELIOSMsopPkt*)(packet); @@ -234,7 +234,7 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa } } - T_BlockDiff diff(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; @@ -251,7 +251,7 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa int32_t block_az = ntohs(block.azimuth); int32_t block_az_diff; float block_ts_off; - diff.getDiff(blk, block_az_diff, block_ts_off); + iter.get(blk, block_az_diff, block_ts_off); if (this->split_strategy_->newBlock(block_az)) { diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index b60b0e4a..feba8fba 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -32,6 +32,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include +#include +#include +#include namespace robosense { diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 10eabc47..dfba6ba3 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -18,9 +18,9 @@ add_executable(rs_driver_test section_test.cpp chan_angles_test.cpp split_strategy_test.cpp - single_return_block_diff_test.cpp - dual_return_block_diff_test.cpp - ab_dual_return_block_diff_test.cpp + single_return_block_iterator_test.cpp + dual_return_block_iterator_test.cpp + ab_dual_return_block_iterator_test.cpp decoder_test.cpp decoder_rsbp_test.cpp decoder_rs32_test.cpp) diff --git a/test/ab_dual_return_block_diff_test.cpp b/test/ab_dual_return_block_iterator_test.cpp similarity index 80% rename from test/ab_dual_return_block_diff_test.cpp rename to test/ab_dual_return_block_iterator_test.cpp index c51efb00..32a6fce5 100644 --- a/test/ab_dual_return_block_diff_test.cpp +++ b/test/ab_dual_return_block_iterator_test.cpp @@ -2,7 +2,7 @@ #include #include -#include +#include using namespace robosense::lidar; @@ -34,7 +34,7 @@ TEST(TestABDualPacketTraverser, ctor) , htons(21), 0x00, 0x00, 0x00, 0x00 }; - ABDualReturnBlockDiff diff(pkt, + ABDualReturnBlockIterator iter(pkt, 3, // blocks per packet 0.5f, // block_duration 25, // block_az_duraton @@ -44,17 +44,17 @@ TEST(TestABDualPacketTraverser, ctor) float ts; // first block - diff.getDiff (0, az_diff, ts); + iter.get (0, az_diff, ts); ASSERT_EQ(az_diff, 20); ASSERT_EQ(ts, 0.0f); // second block - diff.getDiff (1, az_diff, ts); + iter.get (1, az_diff, ts); ASSERT_EQ(az_diff, 20); ASSERT_EQ(ts, 0.0f); // last block - diff.getDiff (2, az_diff, ts); + iter.get (2, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 0.5f); } @@ -68,7 +68,7 @@ TEST(TestABDualPacketTraverser, ctor) , htons(21), 0x00, 0x00, 0x00, 0x00 }; - ABDualReturnBlockDiff diff(pkt, + ABDualReturnBlockIterator iter(pkt, 3, // blocks per packet 0.5f, // block_duration 25, // block_az_duraton @@ -78,17 +78,17 @@ TEST(TestABDualPacketTraverser, ctor) float ts; // first block - diff.getDiff (0, az_diff, ts); + iter.get (0, az_diff, ts); ASSERT_EQ(az_diff, 20); ASSERT_EQ(ts, 0.0f); // second block - diff.getDiff (1, az_diff, ts); + iter.get (1, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 0.5f); // last block - diff.getDiff (2, az_diff, ts); + iter.get (2, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 0.5f); } @@ -106,7 +106,7 @@ TEST(TestABDualPacketTraverser, ctor_fov) , htons(121), 0x00, 0x00, 0x00, 0x00 }; - ABDualReturnBlockDiff diff(pkt, + ABDualReturnBlockIterator iter(pkt, 3, // blocks per packet 0.5f, // block_duration 25, // block_az_duraton @@ -116,17 +116,17 @@ TEST(TestABDualPacketTraverser, ctor_fov) float ts; // first block - diff.getDiff (0, az_diff, ts); + iter.get (0, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 0.0f); // second block - diff.getDiff (1, az_diff, ts); + iter.get (1, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 0.0f); // last block - diff.getDiff (2, az_diff, ts); + iter.get (2, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 2.0f); } diff --git a/test/dual_return_block_diff_test.cpp b/test/dual_return_block_iterator_test.cpp similarity index 80% rename from test/dual_return_block_diff_test.cpp rename to test/dual_return_block_iterator_test.cpp index 39ef83a7..8b64d95f 100644 --- a/test/dual_return_block_diff_test.cpp +++ b/test/dual_return_block_iterator_test.cpp @@ -2,7 +2,7 @@ #include #include -#include +#include using namespace robosense::lidar; @@ -35,7 +35,7 @@ TEST(TestDualPacketTraverser, ctor) , htons(51), 0x00, 0x00, 0x00, 0x00 }; - DualReturnBlockDiff diff(pkt, + DualReturnBlockIterator iter(pkt, 6, // blocks per packet 0.5f, // block_duration 25, // block_az_duraton @@ -45,27 +45,27 @@ TEST(TestDualPacketTraverser, ctor) float ts; // first block - diff.getDiff (0, az_diff, ts); + iter.get (0, az_diff, ts); ASSERT_EQ(az_diff, 20); ASSERT_EQ(ts, 0.0f); // second block - diff.getDiff (1, az_diff, ts); + iter.get (1, az_diff, ts); ASSERT_EQ(az_diff, 20); ASSERT_EQ(ts, 0.0f); // third block - diff.getDiff (2, az_diff, ts); + iter.get (2, az_diff, ts); ASSERT_EQ(az_diff, 30); ASSERT_EQ(ts, 0.5f); // last block - diff.getDiff (4, az_diff, ts); + iter.get (4, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 1.0f); // last block - diff.getDiff (5, az_diff, ts); + iter.get (5, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 1.0f); } @@ -82,7 +82,7 @@ TEST(TestDualPacketTraverser, ctor_fov) , htons(141), 0x00, 0x00, 0x00, 0x00 }; - DualReturnBlockDiff diff(pkt, + DualReturnBlockIterator iter(pkt, 6, // blocks per packet 0.5f, // block_duration 25, // block_az_duraton @@ -92,32 +92,32 @@ TEST(TestDualPacketTraverser, ctor_fov) float ts; // first block - diff.getDiff (0, az_diff, ts); + iter.get (0, az_diff, ts); ASSERT_EQ(az_diff, 20); ASSERT_EQ(ts, 0.0f); // second block - diff.getDiff (1, az_diff, ts); + iter.get (1, az_diff, ts); ASSERT_EQ(az_diff, 20); ASSERT_EQ(ts, 0.0f); // third block - diff.getDiff (2, az_diff, ts); + iter.get (2, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 0.5f); // fourth block - diff.getDiff (2, az_diff, ts); + iter.get (2, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 0.5f); // last block - diff.getDiff (4, az_diff, ts); + iter.get (4, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 2.5f); // last block - diff.getDiff (5, az_diff, ts); + iter.get (5, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 2.5f); } diff --git a/test/single_return_block_diff_test.cpp b/test/single_return_block_iterator_test.cpp similarity index 75% rename from test/single_return_block_diff_test.cpp rename to test/single_return_block_iterator_test.cpp index 909a91fa..417574e8 100644 --- a/test/single_return_block_diff_test.cpp +++ b/test/single_return_block_iterator_test.cpp @@ -2,7 +2,7 @@ #include #include -#include +#include using namespace robosense::lidar; @@ -23,7 +23,7 @@ typedef struct MyBlock blocks[3]; } MyPacket; -TEST(TestSingleReturnBlockDiff, ctor) +TEST(TestSingleReturnBlockIterator, ctor) { MyPacket pkt = { @@ -32,7 +32,7 @@ TEST(TestSingleReturnBlockDiff, ctor) , htons(51), 0x00, 0x00, 0x00, 0x00 }; - SingleReturnBlockDiff diff(pkt, + SingleReturnBlockIterator iter(pkt, 3, // blocks per packet 0.5f, // block_duration 25, // block_az_duraton @@ -42,20 +42,20 @@ TEST(TestSingleReturnBlockDiff, ctor) float ts; // first block - diff.getDiff (0, az_diff, ts); + iter.get (0, az_diff, ts); ASSERT_EQ(az_diff, 20); ASSERT_EQ(ts, 0.0f); - diff.getDiff (1, az_diff, ts); + iter.get (1, az_diff, ts); ASSERT_EQ(az_diff, 30); ASSERT_EQ(ts, 0.5f); - diff.getDiff (2, az_diff, ts); + iter.get (2, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 1.0f); } -TEST(TestSingleReturnBlockDiff, ctor_fov) +TEST(TestSingleReturnBlockIterator, ctor_fov) { MyPacket pkt = { @@ -64,7 +64,7 @@ TEST(TestSingleReturnBlockDiff, ctor_fov) , htons(141), 0x00, 0x00, 0x00, 0x00 }; - SingleReturnBlockDiff diff(pkt, + SingleReturnBlockIterator iter(pkt, 3, // blocks per packet 0.5f, // block_duration 25, // block_az_duraton @@ -74,15 +74,15 @@ TEST(TestSingleReturnBlockDiff, ctor_fov) float ts; // first block - diff.getDiff (0, az_diff, ts); + iter.get (0, az_diff, ts); ASSERT_EQ(az_diff, 20); ASSERT_EQ(ts, 0.0f); - diff.getDiff (1, az_diff, ts); + iter.get (1, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 0.5f); - diff.getDiff (2, az_diff, ts); + iter.get (2, az_diff, ts); ASSERT_EQ(az_diff, 25); ASSERT_EQ(ts, 2.5f); } From dca0a38216b3f3866ae33ba1da13ccb3b5703c0f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 22 Mar 2022 10:07:38 +0800 Subject: [PATCH 195/379] feat: add tests for rs32 --- test/decoder_rs32_test.cpp | 35 +++++++++++++++++++++++++++++++++++ 1 file changed, 35 insertions(+) diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index 9eaa75d2..385e3374 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -23,6 +23,41 @@ TEST(TestDecoderRS32, getEchoMode) ASSERT_TRUE(DecoderRS32::getEchoMode(2) == RSEchoMode::ECHO_SINGLE); } +TEST(TestDecoderRS32, RS32DifopPkt2Adapter) +{ + RSCalibrationAngle v_angle_cali[32] = + { + 0x01, htons(0x2829), // -10.281 + 0x00, htons(0x091d) // 2.333 + }; + + RSCalibrationAngle h_angle_cali[32] = + { + 0x00, htons(0x01f4), // 0.5 + 0x01, htons(0x01c2) // -0.45 + }; + + RS32DifopPkt src; + src.rpm = 0; + src.fov = {0}; + src.return_mode = 0; + memcpy (src.vert_angle_cali, v_angle_cali, 32*sizeof(RSCalibrationAngle)); + memcpy (src.horiz_angle_cali, h_angle_cali, 32*sizeof(RSCalibrationAngle)); + + AdapterDifopPkt dst; + RS32DifopPkt2Adapter(src, dst); + + ASSERT_EQ(dst.vert_angle_cali[0].sign, 1); + ASSERT_EQ(ntohs(dst.vert_angle_cali[0].value), 1028); + ASSERT_EQ(dst.vert_angle_cali[1].sign, 0); + ASSERT_EQ(ntohs(dst.vert_angle_cali[1].value), 233); + + ASSERT_EQ(dst.horiz_angle_cali[0].sign, 0); + ASSERT_EQ(ntohs(dst.horiz_angle_cali[0].value), 50); + ASSERT_EQ(dst.horiz_angle_cali[1].sign, 1); + ASSERT_EQ(ntohs(dst.horiz_angle_cali[1].value), 45); +} + TEST(TestDecoderRS32, decodeDifopPkt) { // const_param From efc63a6351d37d137a05c17daa147d136f343478 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 22 Mar 2022 11:19:06 +0800 Subject: [PATCH 196/379] feat: add tests for rs16 --- test/CMakeLists.txt | 3 +- test/decoder_rs16_test.cpp | 207 +++++++++++++++++++++++++++++++++++++ 2 files changed, 209 insertions(+), 1 deletion(-) create mode 100644 test/decoder_rs16_test.cpp diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index dfba6ba3..d5e0d4d2 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -23,7 +23,8 @@ add_executable(rs_driver_test ab_dual_return_block_iterator_test.cpp decoder_test.cpp decoder_rsbp_test.cpp - decoder_rs32_test.cpp) + decoder_rs32_test.cpp + decoder_rs16_test.cpp) target_link_libraries(rs_driver_test ${GTEST_LIBRARIES} diff --git a/test/decoder_rs16_test.cpp b/test/decoder_rs16_test.cpp new file mode 100644 index 00000000..536e00eb --- /dev/null +++ b/test/decoder_rs16_test.cpp @@ -0,0 +1,207 @@ + +#include + +#include +#include +#include + +using namespace robosense::lidar; + +typedef PointXYZIRT PointT; +typedef PointCloudT PointCloud; + +TEST(TestDecoderRS16, getEchoMode) +{ + ASSERT_TRUE(DecoderRS16::getEchoMode(0) == RSEchoMode::ECHO_DUAL); + ASSERT_TRUE(DecoderRS16::getEchoMode(1) == RSEchoMode::ECHO_SINGLE); + ASSERT_TRUE(DecoderRS16::getEchoMode(2) == RSEchoMode::ECHO_SINGLE); +} + +TEST(TestDecoderRS16, RS16DifopPkt2Adapter) +{ + uint8_t pitch_cali[48] = + { + 0x00, 0x3a, 0x98, // 15.000 + 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, + 0x00, 0x3a, 0x98, // 15.000 + }; + + RS16DifopPkt src; + src.rpm = 0; + src.fov = {0}; + src.return_mode = 0; + memcpy (src.pitch_cali, pitch_cali, 48); + + AdapterDifopPkt dst; + RS16DifopPkt2Adapter(src, dst); + + ASSERT_EQ(dst.vert_angle_cali[0].sign, 1); + ASSERT_EQ(ntohs(dst.vert_angle_cali[0].value), 150); + ASSERT_EQ(dst.vert_angle_cali[8].sign, 0); + ASSERT_EQ(ntohs(dst.vert_angle_cali[8].value), 150); + + ASSERT_EQ(dst.horiz_angle_cali[0].sign, 0); + ASSERT_EQ(ntohs(dst.horiz_angle_cali[0].value), 0); +} + +#if 0 + +static ErrCode errCode = ERRCODE_SUCCESS; +static void errCallback(const Error& err) +{ + errCode = err.error_code; +} + + +TEST(TestDecoderRS16, decodeDifopPkt) +{ + // const_param + RSDecoderParam param; + DecoderRS16 decoder(param, errCallback); + ASSERT_EQ(decoder.blks_per_frame_, 1801); + ASSERT_EQ(decoder.split_blks_per_frame_, 1801); + + // rpm = 600, dual return + RS32DifopPkt pkt; + pkt.rpm = htons(600); + pkt.return_mode = 0; + decoder.decodeDifopPkt((uint8_t*)&pkt, sizeof(pkt)); + ASSERT_EQ(decoder.rps_, 10); + ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_DUAL); + ASSERT_EQ(decoder.blks_per_frame_, 1801); + ASSERT_EQ(decoder.split_blks_per_frame_, 3602); + + // rpm = 1200, single return + pkt.rpm = htons(1200); + pkt.return_mode = 1; + decoder.decodeDifopPkt((uint8_t*)&pkt, sizeof(pkt)); + ASSERT_EQ(decoder.rps_, 20); + ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_SINGLE); + ASSERT_EQ(decoder.blks_per_frame_, 900); + ASSERT_EQ(decoder.split_blks_per_frame_, 900); +} + +static void splitFrame(uint16_t height, double ts) +{ +} + +TEST(TestDecoderRS16, decodeMsopPkt) +{ + uint8_t pkt[] = + { + // + // header + // + 0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0, // msop id + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // reserved_1 + 0x15, 0x0a, 0x01, 0x01, 0x02, 0x03, 0x11, 0x22, 0x33, 0x44, // ts_YMD + 0x00, // lidar type + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // reserved_2 + 0x18, 0x01, // temprature + 0x00, 0x00, // reserved_3 + + // + // block_01 + // + 0xFF, 0xEE, // block id + 0x00, 0x00, // azimuth + 0x03, 0xE8, // chan_00, distance + 0x01, // chan_00, intensity + 0x00, 0x00, // chan_01, distance + 0x00, // chan_01, intensity + 0x00, 0x00, // chan_02, distance + 0x00, // chan_02, intensity + 0x00, 0x00, // chan_03, distance + 0x00, // chan_03, intensity + 0x00, 0x00, // chan_04, distance + 0x00, // chan_04, intensity + 0x00, 0x00, // chan_05, distance + 0x00, // chan_05, intensity + 0x00, 0x00, // chan_06, distance + 0x00, // chan_06, intensity + 0x00, 0x00, // chan_07, distance + 0x00, // chan_07, intensity + 0x00, 0x00, // chan_08, distance + 0x00, // chan_08, intensity + 0x00, 0x00, // chan_09, distance + 0x00, // chan_09, intensity + 0x00, 0x00, // chan_10, distance + 0x00, // chan_10, intensity + 0x00, 0x00, // chan_11, distance + 0x00, // chan_11, intensity + 0x00, 0x00, // chan_12, distance + 0x00, // chan_12, intensity + 0x00, 0x00, // chan_13, distance + 0x00, // chan_13, intensity + 0x00, 0x00, // chan_14, distance + 0x00, // chan_14, intensity + 0x00, 0x00, // chan_15, distance + 0x00, // chan_15, intensity + 0x00, 0x00, // chan_16, distance + 0x00, // chan_16, intensity + 0x00, 0x00, // chan_17, distance + 0x00, // chan_17, intensity + 0x00, 0x00, // chan_18, distance + 0x00, // chan_18, intensity + 0x00, 0x00, // chan_19, distance + 0x00, // chan_19, intensity + 0x00, 0x00, // chan_20, distance + 0x00, // chan_20, intensity + 0x00, 0x00, // chan_21, distance + 0x00, // chan_21, intensity + 0x00, 0x00, // chan_22, distance + 0x00, // chan_22, intensity + 0x00, 0x00, // chan_23, distance + 0x00, // chan_23, intensity + 0x00, 0x00, // chan_24, distance + 0x00, // chan_24, intensity + 0x00, 0x00, // chan_25, distance + 0x00, // chan_25, intensity + 0x00, 0x00, // chan_26, distance + 0x00, // chan_26, intensity + 0x00, 0x00, // chan_27, distance + 0x00, // chan_27, intensity + 0x00, 0x00, // chan_28, distance + 0x00, // chan_28, intensity + 0x00, 0x00, // chan_29, distance + 0x00, // chan_29, intensity + 0x00, 0x00, // chan_30, distance + 0x00, // chan_30, intensity + 0x00, 0x00, // chan_31, distance + 0x00, // chan_31, intensity + + // + // block_02 + // + 0x00, 0x00, // block id + }; + + // dense_points = false, use_lidar_clock = true + RSDecoderParam param; + DecoderRS16 decoder(param, errCallback); + ASSERT_EQ(decoder.chan_angles_.user_chans_.size(), 32); + decoder.chan_angles_.user_chans_[0] = 2; + decoder.chan_angles_.user_chans_[1] = 1; + decoder.param_.dense_points = false; + decoder.param_.use_lidar_clock = true; + + decoder.point_cloud_ = std::make_shared(); + decoder.setSplitCallback(splitFrame); + + decoder.decodeMsopPkt(pkt, sizeof(pkt)); + ASSERT_EQ(decoder.getTemperature(), 2.1875); + ASSERT_EQ(decoder.point_cloud_->points.size(), 32); + + PointT& point = decoder.point_cloud_->points[0]; + ASSERT_EQ(point.intensity, 1); + ASSERT_NE(point.timestamp, 0); + ASSERT_EQ(point.ring, 2); +} +#endif + From 0c326b382dd9fb251dc13352e691530aa7021b0b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 22 Mar 2022 17:41:23 +0800 Subject: [PATCH 197/379] feat: add laser_num param --- src/rs_driver/driver/decoder/chan_angles.hpp | 21 +++++++-------- src/rs_driver/driver/decoder/decoder.hpp | 1 + .../driver/decoder/decoder_RS128.hpp | 1 + src/rs_driver/driver/decoder/decoder_RS16.hpp | 1 + src/rs_driver/driver/decoder/decoder_RS32.hpp | 1 + src/rs_driver/driver/decoder/decoder_RS80.hpp | 1 + src/rs_driver/driver/decoder/decoder_RSBP.hpp | 1 + .../driver/decoder/decoder_RSHELIOS.hpp | 1 + src/rs_driver/driver/decoder/decoder_RSM1.hpp | 1 + src/rs_driver/driver/decoder/decoder_mech.hpp | 5 ++-- test/chan_angles_test.cpp | 27 +++++-------------- test/decoder_test.cpp | 6 +++-- 12 files changed, 31 insertions(+), 36 deletions(-) diff --git a/src/rs_driver/driver/decoder/chan_angles.hpp b/src/rs_driver/driver/decoder/chan_angles.hpp index 141cf176..f4a906f5 100644 --- a/src/rs_driver/driver/decoder/chan_angles.hpp +++ b/src/rs_driver/driver/decoder/chan_angles.hpp @@ -65,7 +65,7 @@ class ChanAngles { std::vector vert_angles; std::vector horiz_angles; - int ret = loadFromFile (angle_path, vert_angles, horiz_angles); + int ret = loadFromFile (angle_path, chan_num_, vert_angles, horiz_angles); if (ret < 0) return ret; @@ -81,20 +81,15 @@ class ChanAngles } int loadFromDifop(const RSCalibrationAngle vert_angle_arr[], - const RSCalibrationAngle horiz_angle_arr[], size_t size) + const RSCalibrationAngle horiz_angle_arr[]) { std::vector vert_angles; std::vector horiz_angles; int ret = - loadFromDifop (vert_angle_arr, horiz_angle_arr, size, vert_angles, horiz_angles); + loadFromDifop (vert_angle_arr, horiz_angle_arr, chan_num_, vert_angles, horiz_angles); if (ret < 0) return ret; - if (vert_angles.size() != chan_num_) - { - return -1; - } - vert_angles_.swap(vert_angles); horiz_angles_.swap(horiz_angles); genUserChan(vert_angles_, user_chans_); @@ -157,7 +152,7 @@ class ChanAngles } } - static int loadFromFile(const std::string& angle_path, + static int loadFromFile(const std::string& angle_path, size_t size, std::vector& vert_angles, std::vector& horiz_angles) { vert_angles.clear(); @@ -171,8 +166,12 @@ class ChanAngles } std::string line; - while (std::getline(fd, line)) + for (size_t i = 0; i < size; i++) + //while (std::getline(fd, line)) { + if (!std::getline(fd, line)) + return -1; + size_t pos_comma = 0; float vert = std::stof(line, &pos_comma); float horiz = std::stof(line.substr(pos_comma+1)); @@ -199,7 +198,7 @@ class ChanAngles int32_t v; if (vert.sign == 0xFF) - break; + return -1; v = ntohs(vert.value); if (vert.sign != 0) v = -v; diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 8829a48c..7f91f77f 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -227,6 +227,7 @@ struct RSDecoderConstParam uint8_t BLOCK_ID[2]; // packet structure + uint16_t LASER_NUM; uint16_t BLOCKS_PER_PKT; uint16_t CHANNELS_PER_BLOCK; diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 6c316da1..7009b3d8 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -113,6 +113,7 @@ inline RSDecoderMechConstParam& DecoderRS128::getConstParam() , {0x55, 0xAA, 0x05, 0x5A} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFE} // block id + , 128 // laser number , 3 // blocks per packet , 128 // channels per block , 1.0f // distance min diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index fa84585f..f547619f 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -145,6 +145,7 @@ inline RSDecoderMechConstParam& DecoderRS16::getConstParam() , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id + , 16 // laser number , 12 // blocks per packet , 32 // channels per block. how many channels in the msop block. , 0.2f // distance min diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 0532ab07..4b199ba6 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -142,6 +142,7 @@ inline RSDecoderMechConstParam& DecoderRS32::getConstParam() , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id + , 32 // laser number , 12 // blocks per packet , 32 // channels per block , 0.4f // distance min diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 26eddf34..f42577f3 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -115,6 +115,7 @@ inline RSDecoderMechConstParam& DecoderRS80::getConstParam() , {0x55, 0xAA, 0x05, 0x5A} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFE} // block id + , 80 // laser number , 4 // blocks per packet , 80 // channels per block , 1.0f // distance min diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 9f79af98..531dd3f9 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -116,6 +116,7 @@ inline RSDecoderMechConstParam& DecoderRSBP::getConstParam() , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id + , 32 // laser number , 12 // blocks per packet , 32 // channels per block , 0.1f // distance min diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index c52b3bff..bbcf32ea 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -127,6 +127,7 @@ inline RSDecoderMechConstParam& DecoderRSHELIOS::getConstParam() , {0x55, 0xAA, 0x05, 0x5A} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id + , 32 // laser number , 12 // blocks per packet , 32 // channels per block , 0.4f // distance min diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 90785d61..80133e98 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -171,6 +171,7 @@ inline RSDecoderConstParam& DecoderRSM1::getConstParam() , {0x55, 0xAA, 0x5A, 0xA5} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0x00, 0x00} + , 0 // no meaning for M1 , 25 // blocks per packet , 5 // channels per block , 0.2f // distance min diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index feba8fba..01c3d5d5 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -108,7 +108,7 @@ inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& con const std::function& excb) : Decoder(const_param.base, param, excb) , mech_const_param_(const_param) - , chan_angles_(this->const_param_.CHANNELS_PER_BLOCK) + , chan_angles_(this->const_param_.LASER_NUM) , scan_section_(this->param_.start_angle * 100, this->param_.end_angle * 100) , rps_(10) , blks_per_frame_(1/(10*this->mech_const_param_.BLOCK_DURATION)) @@ -206,8 +206,7 @@ inline void DecoderMech::decodeDifopCommon(const T_Difop& pkt) // load angles if (!this->param_.config_from_file && !this->angles_ready_) { - int ret = this->chan_angles_.loadFromDifop(pkt.vert_angle_cali, pkt.horiz_angle_cali, - this->const_param_.CHANNELS_PER_BLOCK); + int ret = this->chan_angles_.loadFromDifop(pkt.vert_angle_cali, pkt.horiz_angle_cali); this->angles_ready_ = (ret == 0); } } diff --git a/test/chan_angles_test.cpp b/test/chan_angles_test.cpp index f227d2dc..e1beb052 100644 --- a/test/chan_angles_test.cpp +++ b/test/chan_angles_test.cpp @@ -28,7 +28,7 @@ TEST(TestChanAngles, loadFromFile) std::vector vert_angles, horiz_angles; // load - ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); + ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", 4, vert_angles, horiz_angles), 0); ASSERT_EQ(vert_angles.size(), 4); ASSERT_EQ(horiz_angles.size(), 4); ASSERT_EQ(vert_angles[0], 500); @@ -42,12 +42,12 @@ TEST(TestChanAngles, loadFromFile) ASSERT_EQ(horiz_angles[3], -100); // load again - ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", vert_angles, horiz_angles), 0); + ASSERT_EQ(ChanAngles::loadFromFile ("../rs_driver/test/res/angle.csv", 4, vert_angles, horiz_angles), 0); ASSERT_EQ(vert_angles.size(), 4); ASSERT_EQ(horiz_angles.size(), 4); // load non-existing file - ASSERT_LT(ChanAngles::loadFromFile ("../rs_driver/test/res/non_exist.csv", vert_angles, horiz_angles), 0); + ASSERT_LT(ChanAngles::loadFromFile ("../rs_driver/test/res/non_exist.csv", 4, vert_angles, horiz_angles), 0); ASSERT_EQ(vert_angles.size(), 0); ASSERT_EQ(horiz_angles.size(), 0); } @@ -98,7 +98,6 @@ TEST(TestChanAngles, loadFromDifop) TEST(TestChanAngles, memberLoadFromFile) { - ChanAngles angles(4); // not loading yet @@ -142,10 +141,7 @@ TEST(TestChanAngles, memberLoadFromDifop) ASSERT_EQ(angles.chan_num_, 4); // load - ASSERT_EQ(angles.loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4), 0); + ASSERT_EQ(angles.loadFromDifop((const RSCalibrationAngle*)vert_angle_arr, (const RSCalibrationAngle*)horiz_angle_arr), 0); ASSERT_EQ(angles.vert_angles_.size(), 4); ASSERT_EQ(angles.vert_angles_[0], 258); @@ -180,10 +176,7 @@ TEST(TestChanAngles, memberLoadFromDifop_fail) ASSERT_EQ(angles.chan_num_, 4); // load invalid difop - ASSERT_LT(angles.loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4), 0); + ASSERT_LT(angles.loadFromDifop((const RSCalibrationAngle*)vert_angle_arr, (const RSCalibrationAngle*)horiz_angle_arr), 0); ASSERT_EQ(angles.vert_angles_.size(), 4); ASSERT_EQ(angles.vert_angles_[0], 0); } @@ -210,10 +203,7 @@ TEST(TestChanAngles, memberLoadFromDifop_fail_angle) }; // load - ASSERT_LT(angles.loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4), 0); + ASSERT_LT(angles.loadFromDifop((const RSCalibrationAngle*)vert_angle_arr, (const RSCalibrationAngle*)horiz_angle_arr), 0); } { @@ -227,10 +217,7 @@ TEST(TestChanAngles, memberLoadFromDifop_fail_angle) }; // load - ASSERT_LT(angles.loadFromDifop( - (const RSCalibrationAngle*)vert_angle_arr, - (const RSCalibrationAngle*)horiz_angle_arr, - 4), 0); + ASSERT_LT(angles.loadFromDifop((const RSCalibrationAngle*)vert_angle_arr, (const RSCalibrationAngle*)horiz_angle_arr), 0); } } diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 16db8b56..3f7c1a01 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -59,7 +59,7 @@ static void errCallback(const Error& err) TEST(TestDecoder, angles_from_file) { RSDecoderMechConstParam const_param; - const_param.base.CHANNELS_PER_BLOCK = 4; + const_param.base.LASER_NUM = 4; RSDecoderParam param; param.config_from_file = true; @@ -75,7 +75,7 @@ TEST(TestDecoder, angles_from_file) TEST(TestDecoder, angles_from_file_fail) { RSDecoderMechConstParam const_param; - const_param.base.CHANNELS_PER_BLOCK = 4; + const_param.base.LASER_NUM = 4; RSDecoderParam param; param.config_from_file = true; @@ -123,6 +123,7 @@ TEST(TestDecoder, processDifopPkt) , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id + , 2 // laser number , 1000 // blocks per packet , 2 // channels per block }; @@ -206,6 +207,7 @@ TEST(TestDecoder, processDifopPkt_invalid_rpm) , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id + , 32 // laser number , 12 // blocks per packet , 32 // channels per block }; From 708a1566bdba0072f9731f8f06146e0c26cd04f7 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 22 Mar 2022 17:54:39 +0800 Subject: [PATCH 198/379] feat: fix dual mode of rs16 --- .../driver/decoder/block_iterator.hpp | 97 ++++++++++++++++++- src/rs_driver/driver/decoder/chan_angles.hpp | 1 - src/rs_driver/driver/decoder/decoder_RS16.hpp | 48 +++++---- 3 files changed, 124 insertions(+), 22 deletions(-) diff --git a/src/rs_driver/driver/decoder/block_iterator.hpp b/src/rs_driver/driver/decoder/block_iterator.hpp index 31e6a5cb..c450a391 100644 --- a/src/rs_driver/driver/decoder/block_iterator.hpp +++ b/src/rs_driver/driver/decoder/block_iterator.hpp @@ -41,6 +41,8 @@ class BlockIterator { public: + static const int MAX_BLOCKS_PER_PKT = 12; + void get(uint16_t blk, int32_t& az_diff, float& ts) { az_diff = az_diffs[blk]; @@ -52,6 +54,7 @@ class BlockIterator : pkt_(pkt), BLOCKS_PER_PKT(blocks_per_pkt), BLOCK_DURATION(block_duration), BLOCK_AZ_DURATION(block_az_duration), FOV_BLIND_DURATION(fov_blind_duration) { + // assert(BLOCKS_PER_PKT <= MAX_BLOCKS_PER_PKT); } protected: @@ -60,8 +63,8 @@ class BlockIterator const double BLOCK_DURATION; const uint16_t BLOCK_AZ_DURATION; const float FOV_BLIND_DURATION; - int32_t az_diffs[128]; - float tss[128]; + int32_t az_diffs[MAX_BLOCKS_PER_PKT]; + float tss[MAX_BLOCKS_PER_PKT]; }; template @@ -177,5 +180,95 @@ class ABDualReturnBlockIterator : public BlockIterator } }; +template +class Rs16SingleReturnBlockIterator : public BlockIterator +{ +public: + + static + void calcChannel(const float blk_ts, const float firing_tss[], float az_percents[], double ts_diffs[]) + { + for (uint16_t chan = 0; chan < 32; chan++) + { + az_percents[chan] = firing_tss[chan] / (blk_ts * 2); + ts_diffs[chan] = firing_tss[chan] / 1000000; + } + } + + Rs16SingleReturnBlockIterator(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, + uint16_t block_az_duration, float fov_blind_duration) + : BlockIterator(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) + { + float tss = 0; + uint16_t blk = 0; + for (; blk < (this->BLOCKS_PER_PKT - 1); blk++) + { + float ts_diff = this->BLOCK_DURATION * 2; + int32_t az_diff = ntohs(this->pkt_.blocks[blk+1].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); + if (az_diff < 0) { az_diff += 36000; } + + // Skip FOV blind zone + if (az_diff > 100) + { + az_diff = this->BLOCK_AZ_DURATION * 2; + ts_diff = this->FOV_BLIND_DURATION; + } + + this->az_diffs[blk] = az_diff; + this->tss[blk] = tss; + + tss += ts_diff; + } + + this->az_diffs[blk] = this->BLOCK_AZ_DURATION * 2; + this->tss[blk] = tss; + } +}; + +template +class Rs16DualReturnBlockIterator : public BlockIterator +{ +public: + + static + void calcChannel(const float blk_ts, const float firing_tss[], float az_percents[], double ts_diffs[]) + { + for (uint16_t chan = 0; chan < 32; chan++) + { + az_percents[chan] = firing_tss[chan%16] / blk_ts; + ts_diffs[chan] = firing_tss[chan%16] / 1000000; + } + } + + Rs16DualReturnBlockIterator(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, + uint16_t block_az_duration, float fov_blind_duration) + : BlockIterator(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) + { + float tss = 0; + uint16_t blk = 0; + for (; blk < (this->BLOCKS_PER_PKT - 1); blk++) + { + float ts_diff = this->BLOCK_DURATION; + int32_t az_diff = ntohs(this->pkt_.blocks[blk+1].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); + if (az_diff < 0) { az_diff += 36000; } + + // Skip FOV blind zone + if (az_diff > 100) + { + az_diff = this->BLOCK_AZ_DURATION; + ts_diff = this->FOV_BLIND_DURATION; + } + + this->az_diffs[blk] = az_diff; + this->tss[blk] = tss; + + tss += ts_diff; + } + + this->az_diffs[blk] = this->BLOCK_AZ_DURATION; + this->tss[blk] = tss; + } +}; + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/chan_angles.hpp b/src/rs_driver/driver/decoder/chan_angles.hpp index f4a906f5..ff9fa687 100644 --- a/src/rs_driver/driver/decoder/chan_angles.hpp +++ b/src/rs_driver/driver/decoder/chan_angles.hpp @@ -167,7 +167,6 @@ class ChanAngles std::string line; for (size_t i = 0; i < size; i++) - //while (std::getline(fd, line)) { if (!std::getline(fd, line)) return -1; diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index f547619f..3eb02d82 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -87,7 +87,7 @@ inline void RS16DifopPkt2Adapter (const RS16DifopPkt& src, AdapterDifopPkt& dst) dst.fov = src.fov; dst.return_mode = src.return_mode; - for (uint16_t i = 0, j = 16; i < 16; i++, j++) + for (uint16_t i = 0; i < 16; i++) { uint32_t v = 0; v += src.pitch_cali[i*3]; @@ -102,11 +102,6 @@ inline void RS16DifopPkt2Adapter (const RS16DifopPkt& src, AdapterDifopPkt& dst) dst.vert_angle_cali[i].value = htons(v2); dst.horiz_angle_cali[i].sign = 0; dst.horiz_angle_cali[i].value = 0; - - dst.vert_angle_cali[j].sign = dst.vert_angle_cali[i].sign; - dst.vert_angle_cali[j].value = dst.vert_angle_cali[i].value; - dst.horiz_angle_cali[j].sign = 0; - dst.horiz_angle_cali[j].value = 0; } } @@ -129,6 +124,7 @@ class DecoderRS16 : public DecoderMech static RSDecoderMechConstParam& getConstParam(); static RSEchoMode getEchoMode(uint8_t mode); + void calcParam(); template bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); }; @@ -159,9 +155,13 @@ inline RSDecoderMechConstParam& DecoderRS16::getConstParam() , 0.0f // RZ }; - INIT_ONLY_ONCE(); + return param; +} - float blk_ts = 55.5f * 2; +template +inline void DecoderRS16::calcParam() +{ + float blk_ts = 55.50f; float firing_tss[] = { 0.00f, 2.80f, 5.60f, 8.40f, 11.20f, 14.00f, 16.80f, 19.60f, @@ -170,14 +170,16 @@ inline RSDecoderMechConstParam& DecoderRS16::getConstParam() 77.90f, 80.70f, 83.50f, 86.30f, 89.10f, 91.90f, 94.70f, 97.50f }; - param.BLOCK_DURATION = blk_ts / 1000000; - for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; - param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; + Rs16SingleReturnBlockIterator::calcChannel(blk_ts, firing_tss, + this->mech_const_param_.CHAN_AZIS, this->mech_const_param_.CHAN_TSS); + } + else + { + Rs16DualReturnBlockIterator::calcChannel(blk_ts, firing_tss, + this->mech_const_param_.CHAN_AZIS, this->mech_const_param_.CHAN_TSS); } - - return param; } template @@ -200,6 +202,8 @@ inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, : DecoderMech(getConstParam(), param, excb) { this->height_ = 16; + + calcParam(); } template @@ -211,9 +215,15 @@ inline void DecoderRS16::decodeDifopPkt(const uint8_t* packet, siz this->template decodeDifopCommon(adapter); - this->echo_mode_ = getEchoMode (adapter.return_mode); - this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? - (this->blks_per_frame_ << 1) : this->blks_per_frame_; + RSEchoMode echo_mode = getEchoMode (adapter.return_mode); + if (this->echo_mode_ != echo_mode) + { + this->echo_mode_ = echo_mode; + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; + + calcParam(); + } } template @@ -221,11 +231,11 @@ inline bool DecoderRS16::decodeMsopPkt(const uint8_t* pkt, size_t { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } From a7bfc5e59f3aeba47e7d2d8905a76803c6ac1302 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 22 Mar 2022 19:06:24 +0800 Subject: [PATCH 199/379] fix: fix packet duration for rs16 --- src/rs_driver/driver/decoder/decoder_RS16.hpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 3eb02d82..3c566b50 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -155,6 +155,9 @@ inline RSDecoderMechConstParam& DecoderRS16::getConstParam() , 0.0f // RZ }; + float blk_ts = 55.50f; + param.BLOCK_DURATION = blk_ts / 1000000; + return param; } @@ -202,6 +205,8 @@ inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, : DecoderMech(getConstParam(), param, excb) { this->height_ = 16; + this->packet_duration_ = + this->mech_const_param_.BLOCK_DURATION * this->const_param_.BLOCKS_PER_PKT * 2; calcParam(); } From 7b5c991c8a35b87ce02eb7d69d891bbd2a128e32 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 22 Mar 2022 19:48:41 +0800 Subject: [PATCH 200/379] feat: add tests for rs16 --- test/CMakeLists.txt | 2 + test/rs16_dual_return_block_iterator_test.cpp | 92 ++++++++++++++++++ ...rs16_single_return_block_iterator_test.cpp | 93 +++++++++++++++++++ 3 files changed, 187 insertions(+) create mode 100644 test/rs16_dual_return_block_iterator_test.cpp create mode 100644 test/rs16_single_return_block_iterator_test.cpp diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index d5e0d4d2..b32cb327 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -21,6 +21,8 @@ add_executable(rs_driver_test single_return_block_iterator_test.cpp dual_return_block_iterator_test.cpp ab_dual_return_block_iterator_test.cpp + rs16_single_return_block_iterator_test.cpp + rs16_dual_return_block_iterator_test.cpp decoder_test.cpp decoder_rsbp_test.cpp decoder_rs32_test.cpp diff --git a/test/rs16_dual_return_block_iterator_test.cpp b/test/rs16_dual_return_block_iterator_test.cpp new file mode 100644 index 00000000..8ae25a72 --- /dev/null +++ b/test/rs16_dual_return_block_iterator_test.cpp @@ -0,0 +1,92 @@ + +#include + +#include +#include + +using namespace robosense::lidar; + +typedef struct +{ + uint16_t distance; + uint8_t intensity; +} MyChannel; + +typedef struct +{ + uint16_t azimuth; + MyChannel channels[2]; +} MyBlock; + +typedef struct +{ + MyBlock blocks[3]; +} MyPacket; + +TEST(TestRs16DualReturnBlockIterator, ctor) +{ + MyPacket pkt = + { + htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + , htons(51), 0x00, 0x00, 0x00, 0x00 + }; + + Rs16DualReturnBlockIterator iter(pkt, + 3, // blocks per packet + 0.5f, // block_duration + 25, // block_az_duraton + 2.0f); // fov_blind_duration + + int32_t az_diff; + float ts; + + // first block + iter.get (0, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); + + // second block + iter.get (1, az_diff, ts); + ASSERT_EQ(az_diff, 30); + ASSERT_EQ(ts, 0.5f); + + // third block + iter.get (2, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 1.0f); +} + +TEST(TestRs16DualReturnBlockIterator, ctor_fov) +{ + MyPacket pkt = + { + htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + , htons(141), 0x00, 0x00, 0x00, 0x00 + }; + + Rs16DualReturnBlockIterator iter(pkt, + 3, // blocks per packet + 0.5f, // block_duration 25, // block_az_duraton + 25, // block_az_duraton + 2.0f); // fov_blind_duration + + int32_t az_diff; + float ts; + + // first block + iter.get (0, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); + + // second block + iter.get (1, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 0.5f); + + // third block + iter.get (2, az_diff, ts); + ASSERT_EQ(az_diff, 25); + ASSERT_EQ(ts, 2.5f); +} diff --git a/test/rs16_single_return_block_iterator_test.cpp b/test/rs16_single_return_block_iterator_test.cpp new file mode 100644 index 00000000..eac5eaf2 --- /dev/null +++ b/test/rs16_single_return_block_iterator_test.cpp @@ -0,0 +1,93 @@ + +#include + +#include +#include + +using namespace robosense::lidar; + +typedef struct +{ + uint16_t distance; + uint8_t intensity; +} MyChannel; + +typedef struct +{ + uint16_t azimuth; + MyChannel channels[2]; +} MyBlock; + +typedef struct +{ + MyBlock blocks[3]; +} MyPacket; + +TEST(TestRs16SingleReturnBlockIterator, ctor) +{ + MyPacket pkt = + { + htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + , htons(51), 0x00, 0x00, 0x00, 0x00 + }; + + Rs16SingleReturnBlockIterator iter(pkt, + 3, // blocks per packet + 0.5f, // block_duration + 25, // block_az_duraton + 2.0f); // fov_blind_duration + + int32_t az_diff; + float ts; + + // first block + iter.get (0, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); + + // second block + iter.get (1, az_diff, ts); + ASSERT_EQ(az_diff, 30); + ASSERT_EQ(ts, 1.0f); + + // third block + iter.get (2, az_diff, ts); + ASSERT_EQ(az_diff, 50); + ASSERT_EQ(ts, 2.0f); +} + +TEST(TestRs16SingleReturnBlockIterator, ctor_fov) +{ + MyPacket pkt = + { + htons(1), 0x00, 0x00, 0x00, 0x00 + , htons(21), 0x00, 0x00, 0x00, 0x00 + , htons(141), 0x00, 0x00, 0x00, 0x00 + }; + + Rs16SingleReturnBlockIterator iter(pkt, + 3, // blocks per packet + 0.5f, // block_duration 25, // block_az_duraton + 25, // block_az_duraton + 2.0f); // fov_blind_duration + + int32_t az_diff; + float ts; + + // first block + iter.get (0, az_diff, ts); + ASSERT_EQ(az_diff, 20); + ASSERT_EQ(ts, 0.0f); + + // second block + iter.get (1, az_diff, ts); + ASSERT_EQ(az_diff, 50); + ASSERT_EQ(ts, 1.0f); + + // third block + iter.get (2, az_diff, ts); + ASSERT_EQ(az_diff, 50); + ASSERT_EQ(ts, 3.0f); +} + From 6ee57342de01a09485e837a1dc5d2d927c40cc30 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 22 Mar 2022 19:52:58 +0800 Subject: [PATCH 201/379] format: format decoders --- src/rs_driver/driver/decoder/decoder_RS128.hpp | 9 ++++----- src/rs_driver/driver/decoder/decoder_RS16.hpp | 8 ++++---- src/rs_driver/driver/decoder/decoder_RS32.hpp | 8 ++++---- src/rs_driver/driver/decoder/decoder_RS80.hpp | 8 ++++---- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 8 ++++---- src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp | 8 ++++---- 6 files changed, 24 insertions(+), 25 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 7009b3d8..7e9a4401 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -248,17 +248,16 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe } int32_t block_az = ntohs(block.azimuth); - - int32_t block_az_diff; - float block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); ret = true; } + int32_t block_az_diff; + float block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 3c566b50..b8c0e67c 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -286,16 +286,16 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az = ntohs(block.azimuth); - int32_t block_az_diff; - float block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); ret = true; } + int32_t block_az_diff; + float block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 4b199ba6..90fc9728 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -267,16 +267,16 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az = ntohs(block.azimuth); - int32_t block_az_diff; - float block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); ret = true; } + int32_t block_az_diff; + float block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index f42577f3..6ab71d2d 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -244,16 +244,16 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az = ntohs(block.azimuth); - int32_t block_az_diff; - float block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); ret = true; } + int32_t block_az_diff; + float block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 531dd3f9..65825db9 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -238,16 +238,16 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az = ntohs(block.azimuth); - int32_t block_az_diff; - float block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); ret = true; } + int32_t block_az_diff; + float block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index bbcf32ea..a1f5a883 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -250,16 +250,16 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa } int32_t block_az = ntohs(block.azimuth); - int32_t block_az_diff; - float block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->height_, this->prev_point_ts_); ret = true; } + int32_t block_az_diff; + float block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; From 2524d7a0f52c87d65ae966cfcfd2a06ee9a7988d Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 23 Mar 2022 10:07:02 +0800 Subject: [PATCH 202/379] fix: fix rs16 channel --- src/rs_driver/driver/decoder/decoder_RS16.hpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index b8c0e67c..9aecb516 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -304,8 +304,9 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); - int32_t angle_vert = this->chan_angles_.vertAdjust(chan); - int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + uint16_t laser = chan % 16; + int32_t angle_vert = this->chan_angles_.vertAdjust(laser); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(laser, angle_horiz); float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) @@ -321,7 +322,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet setZ(point, z); setIntensity(point, channel.intensity); setTimestamp(point, chan_ts); - setRing(point, (this->chan_angles_.toUserChan(chan) >> 1)); + setRing(point, (this->chan_angles_.toUserChan(laser))); this->point_cloud_->points.emplace_back(point); } @@ -333,7 +334,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet setZ(point, NAN); setIntensity(point, 0); setTimestamp(point, chan_ts); - setRing(point, (this->chan_angles_.toUserChan(chan) >> 1)); + setRing(point, (this->chan_angles_.toUserChan(laser))); this->point_cloud_->points.emplace_back(point); } From 8f5f62b21ef342dda037ccd18412bc3e0634d305 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 23 Mar 2022 16:13:58 +0800 Subject: [PATCH 203/379] feat: add tag v1.4.5 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b5ebe9fa..9f787fe2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.4.4) +project(rs_driver VERSION 1.4.5) #============================= # Compile Demos&Tools From 825fdd5b587884f71d67fdafe6f8e8a6c2d6332f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 23 Mar 2022 17:10:10 +0800 Subject: [PATCH 204/379] feat: add source introductions --- doc/src_intro/img/.xdp_01_components.QEQTH1 | Bin 0 -> 16757 bytes doc/src_intro/img/.xdp_components.8OXVH1 | Bin 0 -> 16674 bytes doc/src_intro/img/class_azimuth_section.png | Bin 0 -> 5618 bytes doc/src_intro/img/class_chan_angles.png | Bin 0 -> 21809 bytes doc/src_intro/img/class_decoder.png | Bin 0 -> 37670 bytes doc/src_intro/img/class_decoder_factory.png | Bin 0 -> 5466 bytes doc/src_intro/img/class_decoder_mech.png | Bin 0 -> 24579 bytes doc/src_intro/img/class_decoder_rsbp.png | Bin 0 -> 13120 bytes doc/src_intro/img/class_decoder_rsm1.png | Bin 0 -> 14074 bytes doc/src_intro/img/class_distance_section.png | Bin 0 -> 5535 bytes doc/src_intro/img/class_input.png | Bin 0 -> 14447 bytes doc/src_intro/img/class_input_factory.png | Bin 0 -> 7171 bytes doc/src_intro/img/class_input_pcap.png | Bin 0 -> 11257 bytes doc/src_intro/img/class_input_raw.png | Bin 0 -> 6317 bytes doc/src_intro/img/class_input_sock.png | Bin 0 -> 9638 bytes doc/src_intro/img/class_lidar_driver_impl.png | Bin 0 -> 64595 bytes doc/src_intro/img/class_trigon.png | Bin 0 -> 9436 bytes doc/src_intro/img/classes_block_iterator.png | Bin 0 -> 24135 bytes doc/src_intro/img/classes_decoder.png | Bin 0 -> 29753 bytes doc/src_intro/img/classes_input.png | Bin 0 -> 17065 bytes .../img/classes_rs16_block_iterator.png | Bin 0 -> 34523 bytes doc/src_intro/img/classes_split_strategy.png | Bin 0 -> 15437 bytes .../img/classes_split_strategy_by_seq.png | Bin 0 -> 9567 bytes doc/src_intro/img/components.png | Bin 0 -> 18552 bytes doc/src_intro/img/fov.png | Bin 0 -> 9712 bytes doc/src_intro/img/msop_dual_return.png | Bin 0 -> 281751 bytes doc/src_intro/img/msop_ruby128.png | Bin 0 -> 28558 bytes doc/src_intro/img/msop_single_return.png | Bin 0 -> 268522 bytes doc/src_intro/img/packet_layers.png | Bin 0 -> 5941 bytes doc/src_intro/img/packet_layers_full.png | Bin 0 -> 10547 bytes doc/src_intro/img/packet_record_replay.png | Bin 0 -> 10314 bytes doc/src_intro/img/rs16_msop_dual_return.png | Bin 0 -> 36497 bytes doc/src_intro/img/rs16_msop_single_return.png | Bin 0 -> 35964 bytes doc/src_intro/img/safe_range.png | Bin 0 -> 5158 bytes doc/src_intro/img/split_angle.png | Bin 0 -> 6448 bytes doc/src_intro/img/split_position.png | Bin 0 -> 6181 bytes doc/src_intro/img/trigon_sinss.png | Bin 0 -> 4681 bytes doc/src_intro/rs_driver_intro.md | 1523 +++++++++++++++++ 38 files changed, 1523 insertions(+) create mode 100644 doc/src_intro/img/.xdp_01_components.QEQTH1 create mode 100644 doc/src_intro/img/.xdp_components.8OXVH1 create mode 100644 doc/src_intro/img/class_azimuth_section.png create mode 100644 doc/src_intro/img/class_chan_angles.png create mode 100644 doc/src_intro/img/class_decoder.png create mode 100644 doc/src_intro/img/class_decoder_factory.png create mode 100644 doc/src_intro/img/class_decoder_mech.png create mode 100644 doc/src_intro/img/class_decoder_rsbp.png create mode 100644 doc/src_intro/img/class_decoder_rsm1.png create mode 100644 doc/src_intro/img/class_distance_section.png create mode 100644 doc/src_intro/img/class_input.png create mode 100644 doc/src_intro/img/class_input_factory.png create mode 100644 doc/src_intro/img/class_input_pcap.png create mode 100644 doc/src_intro/img/class_input_raw.png create mode 100644 doc/src_intro/img/class_input_sock.png create mode 100644 doc/src_intro/img/class_lidar_driver_impl.png create mode 100644 doc/src_intro/img/class_trigon.png create mode 100644 doc/src_intro/img/classes_block_iterator.png create mode 100644 doc/src_intro/img/classes_decoder.png create mode 100644 doc/src_intro/img/classes_input.png create mode 100644 doc/src_intro/img/classes_rs16_block_iterator.png create mode 100644 doc/src_intro/img/classes_split_strategy.png create mode 100644 doc/src_intro/img/classes_split_strategy_by_seq.png create mode 100644 doc/src_intro/img/components.png create mode 100644 doc/src_intro/img/fov.png create mode 100644 doc/src_intro/img/msop_dual_return.png create mode 100644 doc/src_intro/img/msop_ruby128.png create mode 100644 doc/src_intro/img/msop_single_return.png create mode 100644 doc/src_intro/img/packet_layers.png create mode 100644 doc/src_intro/img/packet_layers_full.png create mode 100644 doc/src_intro/img/packet_record_replay.png create mode 100644 doc/src_intro/img/rs16_msop_dual_return.png create mode 100644 doc/src_intro/img/rs16_msop_single_return.png create mode 100644 doc/src_intro/img/safe_range.png create mode 100644 doc/src_intro/img/split_angle.png create mode 100644 doc/src_intro/img/split_position.png create mode 100644 doc/src_intro/img/trigon_sinss.png create mode 100644 doc/src_intro/rs_driver_intro.md diff --git a/doc/src_intro/img/.xdp_01_components.QEQTH1 b/doc/src_intro/img/.xdp_01_components.QEQTH1 new file mode 100644 index 0000000000000000000000000000000000000000..6d487375aea02fd97402daf0bb19b43439015291 GIT binary patch literal 16757 zcmch<1yCH(x-QySu;37ayIXK~ch?XIAq0ou4k1`@5AJTkU4y$5++}cQumSGm>~qiF z=bdxkef3`5M-4Sa_f)T*UcLVQ>?c%BMHUT(5Cs4LGif z^~d8+vvRqiQ&N#r)Zolw_DXrK(5Z#o{x@E{VGEd8xLQ@;ty>B)&7 zA%4DJlNM7zd#B*V6c$-534kIHa|@@X0Zt5wB5;jc$rt+Oju=lSfkd(PdnW`_;)mP2 z`@f$d`9HKvR&5z3dkMtvWo;YsEoQB?NhG^LQp_HRCxZnR9xD9)ZY4$4t8e|g^;MBD zmITrTI<06RrbJu75C-(j&OTmBB2n}TCPOg)SG(Nf1xtBc4n>UHY{@9J(3O0P1wI%q z8M#e4U1VI&Yw2yA{BdXPxN4{bD0)%(PD20Bf9wDD3Ws58EVE}D?D2aY{jq;4Gg9p; zUDdA4Z_yfIk|>UY)j8?-dvWr_?8W|Gvj?~HyU{RQ zZ-{m|*{$8_jv^RKIV?@&aJ@WTgm>=up{Bb&>#3gm`2kA;^8NNc$4U#+X>%gp%_!gC zM5q}2_E;v!Sf$S5Cq6dwk>FYn7sWoL;D-{&4c@DzZXX_t}sqQf!wUT;=4T?1NV(NI)n&$Nz@eeW$<*X zx!o7u6TwNE+y46)c&FP~Qr8xk*LM1t-Yspg1=2q-r>*%eCFkV!cKGWmf*d$2k*Pf2 z)1(_*+#G9%bk8JOGAv^7Jh}g#w%&4o>#d^;xgG$JL6_CC^Aknk$E)kT)#NdmEgNYPSi-qK2f*N!(l>RkmZX zQsaX;F27Um{iJHL=g>Z`N*-OJCPZLT&4&=Ka!h-i82 z2CSsC(y%@_8)vC|1WbvW*D7AQhtfz4_f^j7IOaX!@4@}nFmm9Nry>Mp7yM`;hBHDH z7m4(S5M4nSV3KF8jJGKxwFY8Hm}99>pq1zd3g}&%+8STHN`VJv30Yu(kMI#P1r%bq z_X^$BHr4J?y)h^#2}BeUaxc*JJtr4`vEjW?TlXj~?x4?Kt!qzXCS%x%m81&KB5J_R z|>cIAdrDHyZEOIHbI+!dZ4DU9NqOyZN3%ss)*gftR+Ca^4O#c6pu3 z<9y)KLp!`p)Vb`)RIzXp*bOFQJ0<0}9^Ego=0WV(0D$CvpT|^^=YG+Tea2G}W)DwC z46M>y7gl>(;{F;`Qb-4E5P2#sTTx3bEEVl++`-RE7t-2xo>8Z7qjLLRA+*xAzc}km zhBZV;F*5p~#24cc`fEug)ilR8C(IyGW7bVRc_nSr(Q)Pa7o#TBDJfJl_q;3U(=_s* zPOW;!;823L^>={w01#wSP%_-CM&r%mLRssxN4}FV4UIDiU-GWrPt*MA8qU`=abd#? zD{lR2bXeaEMru|@@&pyA<6(h!FROKGT$zq233KpkFVOPZ4ZZt_W~R;mc$2MiQ-g+v zY)QPCw|)s*?M{v6Lq?bt?VfAm$_J82(;i*7Nc)&hh-v2jPQrxArKAgn*_M#S9&bRY zUTBKqiz?{4GV{mZTfyl3`#&pYMp%)su(`btqC<9L@O&~w;AC3qEPtn)BZ-hF5loru zyekqCMZVwHC7l0fwfny->l>8<*@s&5nS22l(BhYf0==id;3qZAf4DaE1}V?C_0gJD zc$DdW!z_LI_i;7`F>+dhEVLPn`88qLk@^zEl!lZDaIBXGQ`sB7Fq0tgjKdO{FLl8d zU;1s5QfQGvpLTQnfu^A?z$^j)@DDBFPxYZpzWO2|%c~x*l1rN*ttCl zCtoqAF`!?r)ak9FY=3X?&lELShuy|$A+)iDcg$Y5_+3_3tUQ5-i0NRdV!IspPe(!X z#%$QyB1vieyM>lB+uZWET=E!o^09`#uKHpNr540$-k2|Q%*9CU7WIxli5Ax%?VmEXFr2$2%eJBg4Ec>7n@vTq0W zIMGoEo7#+q3i}FKT}SxuDjqiRgb;qH$wP~9ab}DwL57!2-;p#AUBSjM_&d|GWlCtV z8Ck3(qW=eLlb%0yqxo+Fq>7`upyw@YGHK432CmzXxiAlRLf{`>mQ84k#%1N$14{_% zis$`_XeKeWQ6|!7f3-)Rph3w_gSoB5u!a10(r|Fck|T_IlDP(jUo`nOGi<)VrlkN_ zMT#ZjVHR7jcCp=Syx4S^d0^p ztUC~7^+|Hhp|OrZ^#@~TgQR3J7`lFnGfhVc6~=<)1Yg4dZa0WE$WyqUWf_i~#SkR+hAWO5;qP>lOmAixvpR*J+grUtj(dSm$QE0#@j+9gL zw=g2B&Qk?m!>&z+{c{Qa7pQhknntI)VcNC^sPFF3ue+M^unDR@*8DWQX|-Ghe6QF-I++g(4ii$_oJDdS8sESDaTJ`QRJ zQA&Rpcywv_B$k2g`K(f^A)YS$sv*8W*03{mb5j1Tt5AaLOIKwc0$NvL;Ir3Li9#GD z+o&COkthL7{>c6j4FZe9NdOw*JnHqn3@s{W)>>Qz4aux6QRrojkQT@ zmS=OdDZgvM4NO}G?#%)LOWJR7UmY+WGj+JQuMPd+|IqU0{+q_XV=@+ve!Op9zLqxvw?pCm0!T2~$M-7# zYakXDzS>ULujOciQBi$s_e*)4_M?tE%*bI@VA+reJOC^;MHbm(=t{U?vV<#wJbBaV zzU1)Z`0=vJW~S#i5Y86*llQDPhA>$enmpCoMBX=WPpqJGVZoeCcBC92tg@o5Hq-St z)sSf9ufFav5*Fa)h&bf8>Gq;jKIipuK8kJK4^F^yDJussJry4^APE@HV~fIyZfGo= zCK0w4Gp}H+&Hd|ZyZZGfi@9w->b%FgT=wHM#Z|5*tSEl0S>I!Rpv}J8{M~71G{r_o zC9In+3jl!)=x8XUB}zG8|0sPtnv98LdC`zq<@hIj92#DhA|Q*WwxMG60x3DpaM*f7 zWIcYsWS@)M+DIc<=|zGml&1pW03JcenNPJZOvQ12691|L9s({!pmIbwB2i17@66|X zv!!dl8FY_1yUh{C3Q|f8!CPZF8;ukg^6Q_6%XM_RF?sU7`C;h87!RDFjYa|@*#hrn z0b8?)W8qp<2{7~#QcptOi3tmj)HTASfnpcL=so{La%bLJb`&j)Q+GPWB6v6Kgbvgl zFeG^0%2a~w4g>jYF)CemNmCCJa%|gl?Y|0go832a!2(>$B?+Y(d;Qels5fronG@7N z_8$vm0HFHF#fS!zJE)6YWn<;;FtX;(0t|JuzYO9i)1b^&S)EC0+*MX7NPMee_Zwfy zIS|aQXDCv4lJ=b|t}+uh#SaNdVl&4EKJrJI)x&?ogavYG$MIYS%Np~fT3dp`=B_3R zSXwC5(F@?esU_~;4pzq1m9Q_(zU>?9bb6c9ByF!hKNZ&?!WPY^&aGJx93(Ur-H4=m zXhsGhXP|oCTbwHb z=n!|MQkBu@$Ot(*MdR>sg^lhwStSE*&*_LzobSSd$k_1B*OB{DNnKtO@$%9m-*U`vX( z^2R8IjVY;Dfi<5-U9t6!&>KUuHS{Oadt_!38av-?b$^+@lFQ~cXCB^2`W-yGV)>S= z`?OB~fq{PCa0jG2bah-Rc18ih94QX@%@-&I(T|E%K)p4wIiCCQA~fCX9fRG1PHb4G zq(Al}pOWWr9XsuD{Ow`y4{A!F{-;@U5~6Q{94!LiUawlz$Dv<+ILxeO5YxdKEHF39 zf*Hi3RgIyDrb-?Q3rv2pOwo-{rwoM$vJ;ZPrIN!|Dq7FW+PRt2lGDi9Z(2y^c%h|C zO1U*G)s>|o&LRQ29&A75(_Z+~vTMXUXBA&6tO|*qW2nSh3xE-Q$X@0Usp-I^2OFkX zZYSzY(O+nBfq!E|S-EDJ=_@+AVY*BF3Z>Yt{1t6pi3dG| zH{+>gnyXRQ@xFAO8tM|ERqECzd4Hz6>*V-&sEkN($|Ly7!qBM=675W&>#~3(J=QZcGbYIAO;cnjDEa zQq$(Xnj^hyL>-MOQB1liemNr^{yEMS4gvhjQedc({BtMeaWS+2$S=ce z{V}S`k!F#B^0IxB4c$v7>UVB2u5WXZM8TeDQ>6*F;|ymRaA9wFtXS%t@VKm4YV4^j z7Q(QJWy2b68nvA-Hm~T%`qZ6})P?tlfk-^Nv9!DLW|{Z_m=bcG zA1|50uyEJNUmO8Bq_nhtv(61iO??l-q%;Msd#MUa!l21&(-RpeV&1PXxn#nZX7B$K zQSD+o;19jN0vAu|f7MS?D1rJHNG$|{{&f>U%fd*_6YkY4#ZH+LT2h}8P%+ec-zTYU z@cBFlvlJB4etdX(2j!y@NOPR9RMv`p9Ya}mEmQ{rw&3KSF;|d-jFI`%9sUQUl!rw` zk_zju6BD!uBzJb>!vUojsw(9pLzSm8I?F#8>57g)nc8pCk}`@an%+tvX_F~@nraKt z)pbg>Td?ltdl@2AdS7L6b-x|bVfoeLbitSEIbyJ~xgkZSy+7i}OdaH;n1NBH6VsNw zO6HDci1VSKtw6c8**iV$W$LxY2M3BkH8Xal>ZjI0-@&cUKQ~$#FLsAD@554UQge$_ z%R3A<>de)t>73W4uVQ4m7Jxq}*r1YLIAl6cQnTugjHzx$!!rmiYrnQhez`|-OYID_3x&pIF}w2b`p z`cK}iqr9s`s^!a2);<3a&=m0lZW%V-UpZ0{zwR9UuDG%12$2dTD)PL1@yJMl5d0lf zZdX>o{d;#{Riqgt=N+QzMF;8F)bpQs;C>!k8)F!f@XUfVtt`ZhguWTOl=yDuGvJj> z3!l-68*8~GVj)L|`f8!Bs>@onCSkfkWUW71#n7j`{(z$@1n2R5rG)MasmKSyHz!As zkY(78I|3O88A$&0hV z)8Lly%KYO(F@ujw&FDv7+hfL4^IUYuG`zw#Pn_buFg!9>U%h9_;y%{IAW*ynXU zo=c3GdeI3>ws^9PITr{b+jH}|WJpXUVmW@rdVO0G@?g(Addlp}agr>CvIQ;dU}vrG ze$7tv`;IG~B1b#cb2%@UdbEV4z{+>Dcl+SEvT=gfT)5Y+7W61XgFXX-io&A()RzmI zOdXl+hidLE94s`CzYEFO^gNY`?aBBYwwB&$uSE3`W!94l<$C?LkKfDWu^2}9wRHV0 zPCX%(e6xD^mw0I2YdFwpM)_aO^l)AeDg9r00dB&w+FjT;4brZ$Ei)jc8^g z&zT{&9RS~!1EZF#l(Hg~-f6L%+QqPm<5KClKBIZyr}@)`$+g?lli~SGCpoUqm zW$tjBpDj+om?TE@YjgiVe1YYz_GapfY=CYGO8bH)+av%DKOx4z2 z490AW)2HtktDTS&OSE#0iR5n63;IkjTQPa?Ha6LaUMCr&?CQ7Czo>QHsPo<90?ekT ziW=w2Rx~_uK5lLC=cp>e*g`U2Kv_O*ds(6)Ze9bD?80RC>ix=I&UT;Q&N(dv-b$rz z*gy2XRg5~x;Rdgb)ywNXufY1e*mh06Gr3h4Es5n6Nhvg}VwnN709%h`Tz=Lvi9 zU8ll>u+)Pv)$hPff&5M5DU*wr@zx<)M5bTtlwkgtQj$}IspNaYg=A}8jRK#86&rrw zTlh<1z&2V&P?t!%JL{UA1djUV8%hwCqB$J?i?teYb#=8jw^hu|`M%xP4TVXcv9Cpn zbZ5xvMeR!^8nByX62~*sX+X9`a3Q@ZXP$w8u%2iKXAqq{7lCC8&(qUiwBJQ`8STfH zCpH8NASqRh!T?J?=l<^9Q5&QzbtEG1ifwkeq~qsrM-u*EVtOnzci#3rAk@{w8|^LR zH@R2k96jF~<@Mo69cZ>cZ@Ojv}JNfy*RUfkr73CIBmj1YnZG z%kiTq{wGAwcNNMgZLuuz@uWAII~Q$~p``}&TwlVjzg+m) zj#xRNnVXQb6mg+QkcU)`i{yMP5G(=om-?gOJ6uC*=aY(J$~QPo9GCh#utJ|fy}~zT zH--v#B;w(JWR3%3-s@L_Eo@wM8k!>CJ5ku$naS@41qn|kSX7nMTKQELgNC99O)J+F zh9jDMsaUg+41DXXEcUQFSwF}|-h)lbV2rZLv$~$&<<>6$xLBv-J+l#qQR5N8L99PL zJ<;lq3bI`2D7d`qKjX=4!vqU)Q&I~EZ$JM<=U$DZQb~(3ZjWEaa39Tmn<2LYy^tyY z$O*)9;*4s?t-zEcKj94WK_BmJ2l126DLD*1Z--v1XS^etMjM?~>#FCJv0=Hg$`|ge zn!K+c2lNDf)>a%|)JJ5=e!WjQW7N}{$4XR?{I+d$<}=H{%cDfb|DwJe)cMTU0)qzB zeemn#xgN_BegE}YK1wJ4Y3F*lejY8Ah!f4H-z8~v{c26>@R*jKJa8N7 zt3gA=opoxas+UIpc;3rv;wP)An)UgjPv&^^2pj}(z@*Q^Z&^(|1p`K(jN{Kf^W|o! z_I~QSg`i^RX>956Nai-(HKZw|e9DJf3Nrj(nXQjQh5$g{N-@up^uRzLny^_IF^g32 zsb!-22Y~_}6;`)%u!&alLCHZM5eL?sR7kdGK(3`E>e8gd$7PL`rLwOi>Vw=9WENXg z2^g#vnJeUmu}{HJ%%Q8}r}J=d z%L}yc%3MvfBrd@Zg$Zt!QNl*xX^D()b zH#4%m_W$+X@ioP!neLc6L}D z9eMXTgGMHFgzt0-JPbU}gsRwz(x7M;t0D|LfxRsHPU3h{@T1Y$H;+X61FkP42eB`T z%1TAdC*`k=%;Eb>=esl9I))XLOjwSY&Dd^rU>*O}_Ywf@ndFznM%v(9$JBS${GW%$DHKbO5ITb%k|2zcmIs{H9jZQ7Q2o~SBjbsX z;gW}Yf8o?&h%SmQc978SGEbaN=9ViQ4a=h%cHR;i_5ou5WJ|RP!x2MhiqH0R*z!`6 z4)I$!CRuX;$V|{w{GVBXcMQ+BHL1nIP=t&$hgxIzTnPp1nA(|?kYq~8TO_GZpi|0$ zsP8frL9V|dQb_iHa~5HG%0lh?{Pp}3#M*$&-Aug?5DbHQMgcWE61^rV#mJyYLj>0f z0#wBQg?znNmQ@?3w zfvlIsa}&-OlMzwHi&Cp{@>L9cO>+~JwReyf>nJ`WT+RkPg^L*F-3rDA!M26)oj@31aVp}_!me{3R@lV#}Z zk1Khxkjn`u`-mNS911NuLqjsPWr}m8aToHxi3Vb*YrWTer!qIMrAPza|K@Kn!1n16 zRIwLB$_YELyxis>TXRppIJ}+n=doWK>w_)&3e6vAhh@^fUYhJTy8Jp*e%n5v`Y5bp zWpA2a#0C#V)hv_q=@c9;7J|L41aPqP{s97fZ|8g2daOvZ1l|-@G!aY8MURb)&%l1u z$^2R3TOU_Ey=@wI+3eWBg!osUFT;I}sjc#>C3kvm-mZk5T#MzJ`yT3{!oC9Fzo*`- zFRWB?xzyp#01oWUz$7zRv%kweOoRl-kXs0 z{Razp>c8K1c~_bcLk7F@VC$R5xYn_%VcJzmRm$^_4hbU<12s7c?c?=X}|(QKAz75ePoXltDYeUtlQ%` zV^^Z-A}(`@HhtT|GkXwMUQXxbTSa`5&~CW#MlHCWq&Ve4yc^pj`l`dpyc8G&fSjah z?@vxF5AL_EhX$W=Yql&JeAiKn=YB-*gd9^|UZO)5&qJ4Ylxb0GCpL_?wX**RAJ}Lw zv2ec%ELCoo_cf6Awc0<;iXwjSxze|dF1ZR$HC{ho%pLInq)6RB$7?r7=x57yHyj6C zmpw+WDAJ1D{XF&&WC^%0t{Wow9X7{N(JjKkJ+h6l#(WOkMl=ot!hWAo{YOuFJi?Ri z>t|<1zFX;{y*3V`xJ>Su@mUqYnAVbQbAe04_B=iJ-+oz3!U2F>Z!Cw0yVX%hGU|KP zHIIw^^$bKf(>h>jXVNeFMDTn*N07k)nEWDb%ujl~bI~kJ#7o?ApF0~>KpzIH)@!uz zI1(LVS5Tb|Wfvac*&HgmvoFxYx)?}pY${eG>tfhFtc#iu7>0iQmTN2uuYAwEe+M>p zB}N~kFR1k4Pn%tHxay@(P4X)D@?#p8&g_D@eU!xYyX%06B z?O`t!uIHDq;5+in&Dm-b;`I3acOFE624mhkseB>F` zccPNq`ez73D1Co{rS{FbE8#m&z36mhssS>E7&=3}*01BkaGN%!j}Za!KJ&r!3Kd!L zvTHx$>Kw+Fgw1~MZs5Umer|odOHN0HG`BAFnVHO+eOUJx)_ zoc=Y^lCIoUvtlZ<>blMG+UsV2W$;}osH%E2V~ls^yUS6v1&`&J#FehPne-|n6LdkB zu0=rBkZi3?#KQ~XmZI{EN=r6ThgfQXp-7DILHngvFU62O=>g)FrX9)fpN3B71pLKb z!VMT`r*P3|A}!}ds<(j%@7 zJxE~y%q0OX`oY+vbWywo0j|$;yT-Bdnp~Sr$LF1XXroS6W^^=$)#6Y?A}K{p=iR^M zX6&BxAawT=_ZK0Rh(ELL!x|q;ky~ax^;U})@)cZ=BXh!*bzSRg>?AMu^mxE>LWyJ%=)vAf_bt6g%&P0U(TC2tQ&w~aYxG%exvo*AH= zj>cxUNK}bHzSww6=Am(!&ZMl#SP+(Ale9mokyIWMdGA!HqLm<7Lh@bBWfEkmTCag7 zmVkl>Lx2EuIjs1#qC^JM5EnVgjo|IP`T9`_Zs%1dItSVP6{Zu)Hy&QzqARksNXQvR40hH;VV2vW!8Yvfqn3=_lYE@nasM%+a&oi8P!yF2Z<_kI`Qx1NgWO^ z`tc*Tn%HQ+r284|LWC6+kx{~|7Y7`ATg-0v?Cwf_ixuq*_K$!((=_D8c1-9RPL$Y{ z+U(muej(f5a*1yXOf#9#vAz3I>KL{;c0waWc`42C{dC}ToWWTBxvM~5#r{TJO zzr6Pg3w{LBhe8}B=Ul~&cF+*@-DbXgS+L6UVC6{VIIEp6>U4a5Q`%!nMtNJg%R-9~Rw}lVns_8ERe^S4(Ea;!xhc2}VrNSX@5; zHLqE|3_ae=VbrohslPPx-aKrs}fnRlVA|!1IIEogD_`0Py`M&K?_ha0qkB_bzDsLey;fvDFmInA$9q zXdxw>E6jI0f2&)4t!_qKa+*F(hIX#eZQDPUxI=6T7Mh0(`ez=FnBR6kceitt_|9td zVrXYvr=`c`f9v8Yb@~YxyvRcD%}IiAKJH)HVmE#~^ndx8+Ef8of*g2V-umZ1GHTsI zUHwL@HxpDD`lbr|hk~ZXno|M@*bD%`@-u9m@~r{07xy%4S+l~}&;40VPb~pE@IOU_r74h6?*H~N3mu`e*Agzn*?E$0>)EX3>yn!m)P zN2r5(k^+tU|08^7uyh{Ow!kh-?g92g7%tV!!I~@`-I64uLdC&SXX1uMhG%hpS=+rE zLXNZ`KZK=WiPt#x%W-7PsFrI+P$2j?*DV&fBgEf)(iLeq;G2gC6~KS%|6WpKS(mzI zJvbOVL&GZ2kVi@@BL5iC8tj%M6U-KaU-S{}nMv(Sh6WbVjs1Zne5@3F_MaN&+soo; z?4f)B5Rh-#*UL|bb@@y#k-~?OdOw!!woEVK8HG3${dq;O@KW81q0n}hlj)gPRQ)bo3~Px!9tSAYp6%LcI}o_^yF5rq&-r7&JEUZ zxFSICjq<~%sc|ole8Nvs#e2}in2^*+`SQbqGp^?MJtHaszGNgt2CCzhEfx2LN}v3` zmoBbD?k|Rwyu{4v*x`G^Z7r!Y&OJsr{r9TRAD6yMr%jNFUMmNTI1PY_F3hET35b3Y z^uNbR5vU{CT8)75Kk5=EA&!vNu8eCq5CZ3Ik~okeA3%d=KZ@vO#9;c~DW$|a*J;r* zY@C=mNfpsZHe{5xKXriWfI*R1-=R zOnnw=flN$o6Rhg^txD=NF}_?}tVgZuA~U?h6*4!*n-#%WYJ7Rajw2lH{h9CUnwF~I zt8XLGtv-$uv3KZMV3j+co@&^v8*4~f;u5+ouj}F98LRzT^HDcsJRmaMe!qP`FW61B z?R9`+^Yc~V2?aq!`{R!Ow!pGlipitj;#)>yA)f|gQ}%B>EXNyQ#oNr@j_hJrc30Q!MVtkn%zlpi zHCx)4Y-z`yT>Doh49rC2n1t4gke?iO&N&O8pK;7bi76IE&HhX|!&1}z!+!yjEjApb z_UGitWyZb-m%LM7KK)P-Lxe?Gz|xWPPWaGs($8d)XO$L=jhOYs+t-qah9;KM=m67P zG11lk31GeGJ!bpWcy~R5*I7ZzCM4i935h?*-;(>0OU`?E{(?@t)bXUJ!TD0)w9boU zz;SR@IlspBmdoX$@dIarckQ{@D;V<2CPDMtU&e0k>xC6b@rh)CC}AHp{UOaQaP zi^YVW_aGHWnld0p@?dX}g=H%ZWFs$DiA*HQI98VzQLl3Xr0{$)k9{e$a% zY=sy4njA>$uzQ4qAvK3#cww{{o36Vq<-jqj+Rj2TsUb(@EdVIhV)VBcHQ&vPG7!`M zA{jg2@6LP$fDh`KN;Hr&(pV;je&RRX*$XsT2Der@#;S24;I=_pW4 z>q_2B>(gFh8Rf4K`V?AWVM9ijdt_U|ueoO!nr_75H`d<%H_7J8Fu>Q#W8ydE?{97# zil5;OH2Tw7{=vE2$1x75h@rZnBFW9;t$A(u$%&;ClOiJ<^Ra)So+WsSjk74jIsIYR ztAP@55BFO6SKp#w^{YC{aMQZ1B;kti`N&~e4TW$dsxF5PnoZM>JWy6UX;AE6Gvku5 z{V3|+Nm5&!Kb2MzG|wtjpv|C9&Rpcx9DLXp6oeX}v_z;0WY1aoR~fLtWdHXvz04Io zBu67NGgVbAgU}a*P^3oBAGQ4rGm5Iq(#0G;RH1;P%b^k{PGGk`_yFo9TeY6glgaYB zdtg`J1q+z8QM!_CuQU3-(A553?Pb%Qa(#MQn&kC+w)uTe$8Vqvj-O$gH{!LhQ%WR6 zE>5%pavKyi8-@mH`o8kLTVw=Hh~%@#Wjw_mE&!M;cBf)a z|LrNd3)vBFt}=bB^tZ}Ieq1kRm`@$F_&9f2mt6HDWRZ0}Sa0TVrz)=%eSOLbfv$nr z3GMB4_r-R7XWv*lw_EZfn1>~OnY$=bNjXl%9y#ru8^}Wx3e1*Bxqzo}x zjmv!1$8>x^J|oiUu`zqfvPn1zZ*R~ZdI*9S7oVuNoL41nwFQ}xw%&GqNTfa5AuIA6 zKcr}DKC|H}Q{k_Dv?`ktJ}v-&mD--8J=!`8vqW#2ANQW?x~pg~O{0TUt>E=(t2vO{ z^EUXRis#RqI~;`s_jgLOF%Z=nG>7GK)c9Oa5+w5RY6jb=>P-|+H^h6Xx9WV6{%|xO zcYJzWL&=|UTc37j^3OHND4Z24ie8G6p*MG0Qfjh_{*peyY?lLz{F9e+Z9%T`yx+}V z1kKZcz3p>S317bCvSd3?28sw6bmRi^2n#P%H**h{KdP zLtop8`WsLA|I|nEzwey;&)pZDJI^W}<7*GDL`G00y*+j|tkL(LW-c0C9BJ<7p}a4l zhX4&GN`AkX`kY1%dhX~rMPcD|>0I~TmtDoNh$FFIolSM^r@5dl!4~T-zq>Fv2 z>Y^ATMCs-93!NS*5!hA42`PBp6LV00(wJA0zw_n*}SDqAw*(&iF@jCe)}%hBT#W zq=G2Se+kQvVAX+rI?F1=;;~%rk86W{Y)K(Lv{N3lMLxyWk5MbHZbNZe)68T)v?PBz zD}62CV7w*rr&CrEMyz^Fo5Ag+J>hhRwatM(@RZ-u8()zy>^eu@vl@2#u~KC2`FV|X zYw46E@UDWk5=?CfdB(eUz)CleZ{ihL;kKA-RfG!%`{J~Hkm}l9X~$(am=!siXE)9o zOA-~Tq2AawTedG?(1_!t@-uQ?8n!ty8wjH)OlyXlC>VJK%2 zt$bQYzI|^I?|68UPIv45Vs8Awg;3y&(%H^gFdO=4>|)y5%lfq679UlSD?&)e9g7w! z;cAq@n>lEwhN2{Q{Znpf6jW(?aC0D$jR23nn03|p)sVi3_^Mch=WL7Y$JY*fT}Qc_ z=^XnPWHCS7&{{4v-=V9uHd!jfDAK{!QD&F8 z@7b95Yw2_>ZXibl=wW&Mhhf!avk3(!_T z2&CNtXDCzD(q$XQwr+@@1-8M*d|U|4FOEi4X|T=9)Ft9E_RFX2G-qdSQC*fwXm&Xe zVt?-xt;kX!#*Pl|=K|CyW0C3rfU^1rEHG9t>U!X+^|R_bYzn;1wO6K|lj+RayA1`Z z;9!PFNm=B)&a=4Li{yADiz19dm-jr6jb6{;f?TmdE;lD9R&VF)r{V^FJ*}n&l(wIb zno7@5kenzfBSv1Fuw2Kj@V))Y=lrfdXMYc)f6UUFPU-gTpE9a~10?HDHM8F-eUcdt z^~!+*&E<^mn4T4$aaqb)$UHu@xX;FkZ^%R%iHdY^S>JpS0m#dPEy_4@vn^A<25s|( z<-!15B@6^;h^k2E*l=A%0Mzaoj1tC>RkmE$^Gr3}{*>v@QnCJc9>!owN`oROH|&$r zCm7c5R|J85P|bLYpH=x827v#9#;n~qGwnp(Obnn&c*!n9q?*U2_>^ZVUu3HZS4Ya= z!BLS51Er%Yjyy&5(B|8%ndIhn3;$HFYNQ-qou`@1PfQ_iYTd#|ZOXJzl{FO#;s6+O zHTMI07>REH(6$u$BbA$1=;F$_+5m`iv7PtV6jgnZKe_Q0FfA>yGmvm!#nNKt z%gIED0>FARJe7v-(_(Ijtgr!yr9r-55>JX3Yo=n-Lu?Z7eiUc*TRq;po^I)n?**m( zoC#qQZLAcXL&`DGr2;{emffB8h-{YqO2xihx^lmBC0S;OE;qcJd7jC+7;^i5T2Qct z){;i(_t^i`nq()U*y+W-Z^?>Pm)7w|)JNPLgf5IY-ag-7q*%6x&|0W^=eZ5{$>FRr zYb(V2Mg3v=**A;D&~K~c-L3d!UYlprI#!EcN1Od!#F|Ka=l#JaSVW+U>w?h6;e7iy z&KKKAY`vnO4=Q%r`FXFJTC~)%3#xLz90`c0P57n$dg^GcwZ5fb!g=4^NYH7bIgm}W zej?~_-pHh^TS-c-h>q-=fbR#=`DAc>a~^o@rQ2hiztZU|%JK|O9PkL-S$X!FX%P1N z#lQG*X!@D9;kl28SFVHLfs2in3nG1)!GuL{u}Lw+0xfSvmU`8&p-V|whwGL3vqwjj znA3>df+Ui9%Hsjn`flST8rxba6GZMRH3xzvHOr-VR{mOs4z7C%_X__0%5!i&hPZR}W8KE)H7%&)2~?y?-yZ9owaUCn%zJFYwV zibG+9<9iZYo1Cn+VfHKc@il`Fyv@3&$ZY?}cZ=(fm~Cu5&ledV*ZepWM5X4K^5Yy% zTxk0)Qhr@T_(Ze71J&U%{{CM83awfza4a1z6_@R{$x{EeZ3CV>lbbRz3wunv5vBqZ zTGi>%dgw>$F~R`Fa4D6q@LYcyl+8J^VSJ%iH>pH=_S%#dDBXg+fuV_$A9>G;I^xJY zf|Adn-aMC>`;XzELmYNpb+{Mq)DDMLc#MRk#Ev4Glj*mw2YH<jyJ_Xy<$@kPG~C25sL34s2{ NORGrzlKA-je*oV-uCM?A literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/.xdp_components.8OXVH1 b/doc/src_intro/img/.xdp_components.8OXVH1 new file mode 100644 index 0000000000000000000000000000000000000000..c50b6274eabd18af100fda907516e49a5af4fc0d GIT binary patch literal 16674 zcmcJ%1yo$owk>#oK#<@T96|^V!QGwU?i$>J6s`%b!GpWI2Pe3@yE_!_@+XUo}Zt~uvAAqsL5$cXre001CMNs1}~0JJRR^F2H?$5jD_}aEuhtVa4d) zH@{~yVr5D$WJ;cI4#B@n7L9!$L2r57n)3k%4INEI0V+EC$|0_#`O>??!3hhEGvjp( z^>p=kxTb4`pQonT1&izrnlL;Wz1SQGfG6`;pzq`jLKBuuF-#YMC(9lAJVxe^Hfj26 z5Ar1omSIQ8S8DNgx%|LV?PH0}qO? zK|ZKLUoOA3d4$gR$H8Hjk=4HkQTFK3|9AfIE|s&m-2J+cj{iOqjRxwHuoy}`!DU*< zNgH49JXsp4WeL9_Zv)))7M`pu;4V>xdgs1wl{utuH>W3_X0-!@K`}P-fm|_e%!LGOSzv)?(ME z=}P&IE(}J53<2InrT*+`)2+c+HzS9DkyWwMhX_9QuAze?Kvi}o80}%*AYFt_*x9NN zYBnozkGWl!MVpCDl{U}rXrhM8JbYKuw%@03(~>UwgMTdvzd%rN#phXY2FnKH!C7C zR9s!5$1C1f2_N#>cA=-sAw6whLq!m`cNdYkszHxiPL)NyY)4n_f6vMuz0c*0wZ`Ma zQy{kHcjM-l_#HDMO`?f?=AFT}l+H{?Y-}o8VSj}mKeo73yfCyIvLZh{(63O2@7pA} zI?voX&JrRF{VXWh*I%-S}PKqJ|nfO%0g*RlX z##Y_cdt)t{u8<98{;a=c6FQGv6rN3x6EdoylXe@Ebs@GYV}_XgIECN6_c2Qtxf`R@ zG~H^IDD{_G<&Bvrf_$m-8q4%p_T(b2kXHiTocC_ASGm|I{KS0tVRC$m$2nuU;k@`hTeDoHGh$s-Q%BUPCS(nS@{8Z;o_=Nb zLOI1}*_pDn+t~dnGK291oy%i*-{PqLp?w_yewlhb;uAgo>2sNBp9r_;{h?iS)3a%B zXQ3_S$NYCL>F%0&Ny?KSbkhgFg$i@Ye=wA0pt)dnV3RP#qMxQ-W;uv0sDV-AV*XH- zdCVo59arRP1f|=%>)vZ5*Mlk4VYHWVET5J%?hltu7dM5$)KmSgD-K&;40h16vpaK| z=<|M8K>N@X>H0O7%944Os8a6-0vF@4i9UQ6Rwd6MzaN^BCS2ll3<60C&{dhKBdw+= zb=Uya4Bb#GuTRb!3?=}$+(q!)JXcZ3Z25F%2;+~BHSAaz`PqiojPYt(N5sK+^mu>U z0>kIhUVAP94ts51!~HTb{;NRaL-%|M(k-XZ>a@5@4f+Rvd{Rim)y#Lta3c?f3T(7Y z)!^5iIgHnr0Y z@ZtaI|AQEE=K)&?H{Ad>`%`ft1m6k?H#6b1Lp+uYP4vhxk9Z zs83j^Pk`?%6AtJK!{r8No_mWFH470kfByI%%SlVlcGHK~0?n-Pi^H3B=Qc=Hd>{d} zu+2cm<~zz#~xojVW-i+zI(W!I-uc5d)?@m!d-t>wmbTELvkBnFI73P1FbTuc7R zUBuD^#t-gy7+Ktq9V#nOwqT5v{n^6MV4z}h7twLYC29yv%&7G>yzEYv$W?ZcsaF=y z%Ta4Ae1ZwC?H2|-bvjxBcQg(JZzyz$PlW&32Zamew0vn-`>Z}-N>QyDf@WVHj_=wj zE+9}g@*chT%imt!QAy8TYAfDG-Dam^xs`hmWA`4Meo|z4(ZXvY|Ec?IZQ7dFJ>6629(>{oxi;G9bbYhcYMYE9z+HBiJ3*A;Hbp2(>yqSo3Utc z0^nPbJiQ?u1F2n|lpyT3(iuhSdQN!Wx#Aw4o-0R>+uWI(VK%L6jz_$~qfM+mSy>SW zGUX5&aR^f=b{3jZL1^7?RwZk!=~3I>Qyeo7HaAl!H(ea>$C&87=;0?m_Jg%F(iMZs zKlwSf-6Q`CPEcRhkyyL`dX4xc+?!byB05%;bGLfG#6|yrQags!f|Y81%sV;5O1(Zg z6HEuQCnVDJYaBL&V@y>g(<%764V5}H8~AGP{m3Ye*c5epYT4_{%(kuMnye#!tn=3S z=U36?rf7?m01|f^f9IF!<{AX#j{HEKwrdqK>3Ezxn$UdxG=iZF)p0V|DCawzXRbge z>IH^)TwG83fm{>sZ$ERvuIgQ)BkrLAUnS!afvkog2$CU>YaENTO>Q;38|jF5_mr@Os*C|J$XxRGXuk%V4X1M9+QBxntjup;22ra>4oA%4TB; zYCzRUDKo14jTQ+VttQ97mn&_3XS|q1G@e-Eu~00P3Nga z$L&nwA|KCsW=R?g>$7itO7eG$OQcs6pUNFv0p;6}t+FRdIUSPXd?y;}@%4ww zLXzBQKgH}Dlm(9hh9(9WcI$XBm}@jW9S+yarztu1d428rQvC$gZ`OwSMn)5-@J)=f z=fTBNy&n17`4Z*OJv@*~4^g)9?cvx&xPHruu*LF%>e`s5<3~D?^z`J*N)5hHBeDS+ zcp$6T>gN_0gTRjw>HItBP|DmpBk8$cn+QkTg{Y|=xw>y@?Oi2q)9FF!pjsX5wZ)Y` zC~+uHzVlAyM2+pn8@7GOIr;B)riwk9ISM$5>u~@Z7F*9mwvw$t?R|nqZFO;u`H|PXzZ{SO>)+JQt6T+97*7n(aZ_ht+Z?J4k zioU=AXRw|MFaW&2XK2_`Gvlm+lLJXv^@Vw!+yI$@iYC-la)wyR2>%-Z&}wf@NeqL@ z;zm&GHv879EvMBm|4ZsOZU(Kalv*;f_ZfxO1|0D)Z#GRqG?N#uX*<$@G&NoJ({xn)8!J< zkN`?-%M~4x{68=!)dL($eKmAlsoLYueDh8yAO-Vg&5zS=tzNcgj&o!J0~U+SUp7=8 zKx!)WRyN5u)4cLoLUEh1ov@8pMU4*B^TfnR(XoYW9J5Lo6Rz)u0fr=E5oQ4=+N;rweAi33O|i_o7(9&Xt1pMS^)4)vLa zTbRl<+r3>&2Ctl;@_0~!dye|fp=jvGD<6JtQ?8WPqAhCZa2PP->_!%r9 zPbL)gNmh%+=^_r1+uuUxYR{ZGSMl5#%p0z@CN=8rPWySaDp59t+A2`aRd=ijDy9aX z%*MOT``Y}qf(_bLiL)jCO`pp?y`orwSzhDFf}UNwf7|Cf!4S70noSOi0uEQd$~syF zau{MB7a1Hs4DKf+6-jtY|i)x0gP#A`XptNbp;oP4E`K8#j+ZJUKZA5)~k( zCtki=8J-=$9pLc^n^swlMLH=|g0@=Pw%p8!lvKJgl=8c8sc1~*F<0V9bN3Z86OKOhK^5Mr%nQsRBR+kak0ZdUPlI}PmKR2yj+;*;99Q~Q(qeFGi%=dA z|6LjD+dZDO9(S}9?TSMD6X}sW3DMlxb!*~g$0=Vnm3XeYXSfi;$L#FaD!RUELUJ5j zqVoCQ1Rjz6v%meKHhJC=>a@tXjlg$9vmZJX{Ub3kdGi6vS81erc}ST@niL%dXyNvp z5)R1~1?}Ka(Mnb%iP%`}x&6q-DP9ON3GBlRfdb64elHU=Qu#@~0Tg=6TMvI;Bx9;P z?a`>pFOXThQFyx&Su6Bo*zr5g3M_q7qK1@;14yfsn_4OUN+BMrNZMNv>)ymxZ~c{n za)^cS(NTnC#sVgWz$L@!f;FW5{&$(x7Z^lei!CmXEVFZFCNpO&T4le?}ff z1RtY*X9nL;S_YUJE}Xn}rv<@lH_wXYO2U{JaG1}c{wUVXm$t!MxP5i7eYKoZUYk~V zCC$yNr5uYFod_?An4cD3_Ig)9ry_ojyUL&G`t9KQ=%Tsrp1x_~J0e(80-kKT!@@3o zN)YK|HVTZJ8p;8_Tlwd^Ou8%oN|0Uj7GTKZqBWO`0!dEERKD;B^Q!xsS<|1gisCq5 zT;pe}^@H`}*4p8*M(idd*QWjEa??7B`6}$Sr3;mVvLN`en3_Z(9R~Puo&sMICy~l{ z551ux61A5{W#M!}F|(Q-QI_8nf=)Mc_=J*UFn z76Mkg)@=egna+ye44fL?`Xn>FOQj*%LMN#_VF$gySRntTbvm7U=tI2rKcKO zShJ}}rC}8Z?%30g*p(n>Z3la)qe&Gy!C`haa>R`SIWlwYrZ`b&!D61lqX=2yeS zwl8Ba9P)dO{$l_6_+)Wcm$Grso~~Trb!}mGsl~fqGXNFjo!b0Rxmm-4d8D0QqCYVW zBO0Be{et^l6+0y(wxYb{y)gU?q4d|u!JgJ;CRvVCHpA4hZTSL5t?KK^B60!NCU!gP zcJx}I8}8?@8ebZmAB<#$!yc_2Fg` z$ibq>vDp;biqv!NxaqMWQZlwiqmmzw1D1HlSkBAXZeq7 zC}8>^E67E!l?3zld-Y{97f6FAEs?AE^ULxL=Iy1VoKchE>wv!7k~HvpI9P<|N!eF6 zY;3*m<}7V;>ESvN2A7xXdavj$B0p?X%U-Ezi3!^u?Cv$b8nCNy0iy@yOWncOti4_k zKfTrCg`voZqmG`=S>4Cjg!?~2F>PDA$e1t;x)J@%--uar!w_Js-3wnwepxrpPfUrt zo*xj%Pvfk>HO*H?F{DQ@Ib0vl{&sD^;a%K#9I^WxIz=!U@b7qETy^^Ae@6VDbA4rz z8$FMTgyU$Q&w3sHC%^nsZ?$R|dokNGMLeA}Ek+b9gUAcjgE?vB)!UIeTVrrFVi9Y~ z8-~N{=#d_R{rRa01(VGjx{r9JM;lebU$p40%bvYd!QOCKM$7dQ6Zd3^KI%E%mCU!j zM4^1F0R$bU3%joC_K_2+==5JJUQY##kq^(y)OU|i1h53RrN<_~WaYKUr|b5!lMr%D zEkppZlLJLJn%QnCinv$h^hB)upu+aMA9KptW*=PIe53P-Sejo`%j#?d?4Kkz@P@&{ zXL+&^*3;u+@LnkwMgp0<{D|A{e+T@*YjsXjHO@aIuBe_ICtDo3={aB7w2754LMOK< z_!U`gR1TMg`pPA6S;!@B6`zyO{bI%8#6uQ&zJk-5_T3EwkORstp85I~rl!`j!Sd=R zA5ZQkcN%P3#ZfBN3p{;8P*h{Jq_*9xovWGoWr*F{)^|@^Vrgq$U+BE*hQi!#@LmZ% z@U`g>+ecDe9C0f^_=vz>ch+d^ZA?J*EI%STfqpyM<;Rb7_~R3&NrqFNL=oSJ<=P9U z=CK0Mbe1pkS!$K#Xt3VMui&-WQ(V-iV`E5Im;|#LXW_2BCX&d1#WXN(D0`6Q`{piS zjPJ|5f4s1CtSU|2jPSYAC1tz-IcoNGe($J)U*F{lT#>fgWl&-mxkvSk!=Rh8FMdtP zzG3V~vmeA?^^hI=XdWLgK?}OL_NfGip!KTmq_M)5 zv=UF*+Um$qkDo%?8`@14kVpKILg=*jWK&PCOlRwzj)k;?^K=?$EERF8wikz_8;8va4eAj z2C%gFHJ%}shMCJ`#>3BOjK^6t3Zl!12`nQXO^YlYQjQLqpY4|BrkdtGB;r$&@j%<|Ro`J#0EoXNpMAOwvHpu8Z_*d%g6=F7gNj^Dk!+bW4p!*$+nV8<%X666&Z5nF)B#xS_ zpH2O%#%ANHUGJQTF*-GgWG|lu*TeGc4SZuutf7U=8OaiOou|+*;$9(zDTdxUJ1P9=+h_P zJib^jAOC~&2LShB&L`Jo8M&~Yip%6&aMQK*gfT^EOSn#eI9#@QR(eR^VTS>>JY8lx z{)OAbp__;CE)*bmkIZG=yeKao(*2GDlpD&3GwCHKJ{(8;9-YMW^Shk>A;}@Cg`a+z z?A&iGkVEr9vgW#&=_Uk*Jh#~((NC&;K84c3KLxIod){D_&yxwqV^Q_$FtO^{Zydg-JPDo5DV*R$?cs!^zb`w~E5*)sgC{WfcU_1fVznXvJ ziBu3GV5c#w{1zzvRQ^bLzmz1v_`2QU;0LPE^eM|Q9vVNJDPOtJq%|EGC0babyWUmZ z=p?^%KTrnZM)rHAN>S>+$v{Wk+W6yrK3A?7RaINZtfs+H>696b`p+C!S50C!Iqz4DO2)mg?OR5S zy6>CuEc8+QSi(oEZI>R8qZPtZOH50n5l{MBN^mBN(=vOY4+g{T^s7WKy3R^8R+G~z z7Z>I|R)=h_mAEOdn~f@ycd;S(eV@H!p^i`*8D-@?|0K_AoFTPo8D!EHW+LRUizJ*7 zSC{5H{|>GFG^UC-)$4d8EN^28?Tf*VzLOK=3lr;MJpkkGT-vkdvwebFGw z;ef=}aN?W8tE51VEK(KXzdvAI8(GzMt8|HN2xshrQ-2zuAN5@UfzvMJCwnI79mS|I z`FB6YPF}AL{uV z`k)$|f5=sldkQ1pAQpgUHZ~;$2(pJz;FcXXu>2q*XkqyHGQ%A%h9kxG*kSed3*=h+ zlBi?ZZ->|rGejf4T1+O0zEm`-e)y%^`01*Bvs(?v9huhqZxW;pGlU5(V%0}ROpmwD z^^S0QK&zeIyH@3T`*=VBw6lX&>}KsP*M<*FPhQdOl*EfhN28_abf{M9!UlifP}eIn z@TGFNjEj#iZ*(3Chstu9?YJNWfDuT{>?=uIqa8ug<*+aF`Bc>MQJC#ZnzzReCuIg^ z(wnci>c~$|qBKx|+dQL{%Zf*(*=Ax2Nmcx;BJ@Di%45-E2WY}BjYjWnjwJHS!d%hX zY(w$p$`U;b+!JTErG>9s`TGwZ-nW}KVrykwX&8>1a}@&TcwBBZKGG8#z9ZgFTWcnl z>^h$4O~xmQB3`{RtF9MSgn;Dg)R%U;=Vi0in{PP3htJ5halP4%7n6^;swp4y$DS|s z)cPYc5*WFN0}7(Sg*b2&c_}{!Yftw3SdO+Qm4cuFG*lgzy?#j~M8SVE8?;_G66IN4 zM#sWlqwrmGzyGIlp!#@1{4arl`y>GmMtEj&{4!Nb?I%w4?cA2c%c8r`3A4?M!j^VQ zo0bDTiLc~V7vu5T?~Qps`lX6!26BO;Jj@nQabJUk-nTeCM-J4f`6=%WM$SxGZWNLg zy+fA=@$bT41>86KXCW%S*=1t+ne9}i?PL+9rJ;fnbaXFq%ErzW$hY{@W*N!+^v|$9 zl(eQNL1_R8eiG|$RKBf7Gt>()~NJZ&98-KJuy}1Bb`^M+MME z={m~|Zd1`qjDyD-q1jY`X6o9@nh%!)Wg4uBWq%TqSrnmwBV!N%P)(6PMd?O-X|Z=5 zdW{S;b;$b;73%$bVsK#wRp9*6cBCO`iWh2o^+b{eP=Zv`zw0T{5YBR|0;fAObKgj>&E}XnQh7gl@Wq(> zN-mz~4cRTZM-UoR$VFoSCJ$XODZAxJ!&nPV$RO4Uy90hh{}Otl2AiA7=6V=$RL6l8 zW{0O}QH$)ghaN|D5=7$^O%vku<2rr~HPh!*R_4#r)2n12;AyeB?`roi>08GK7T+dr z3rd&)x0@e6b7T5-0&lb$2Ig5z7Rqul{L3X}OfV<>n+RZxW>G~XQ9 z)E{kk70}I3kM^{p5~kog+|McpP+ebVe!Q@RKRC@NXxfsw3uCQW35qWl(X}ax`)T#3 zN>eGl^>I8BhZp4Rv>w4aG<&fgrr61l)6%S+aJLnwxW1E-@=vqNSfPk|YzNoc6I>2w zYZkd4@z*fe1mayE^8BAn=GGr39FM8mTwa{z!rEX?E}BFv8&Mtf;+JL>qG> zVWghyrbrRmnb}PL?Rah9Z3=&JtlIsRoCr|KCOLxa{~PCx^?CGQpu{dVE|oErGLf~C zC-i406Ba}rTT}6L)(ikRqc0=C-j!x62VKyW5!4KZfY(0tMf z$$}^miSZhGpNogD=)$5r#qVVbwOBY z;>j;^ED(P{vF+j&Agz(kkUOnR?Vk4+>mXtUU0+pc zlR2l(6%ASL{xg;N-i4yv`1KwkP{^WG6t&E4`EDgH|RIXm|)nUOLcQs231I7IZiz<|S5sc%YJ1Mr`~ZXPam)!;)AY z1kpMY#8u)zNkrern=O4W6Qmn4eEUrhp)n8v->u&q60q^16odu#*@M`-*bbTUFxwF3 z@H6rK5}GlhFFQMXJ`(Xtn7VuY$8)GT67+FKx^3UdXi33@Bt=P${?R!W_Pb2EH^qK` zm7=g>WNCl=A2EA*a1{2~@1$9gJ{ND-yb@pC{5twrR4C>qY|Y%>TG`p5l60Vn^Xw(w zhzQm3);A)u@V8)u(J^Hi9-qZ-H-eC@u4_mOFZbD>n%z0#+)oF~;o-3>$X*HQ_-JTr z`B5Xm$h46`yaCi!wAwH0Zzy=MDT)l+McGYnDteu4H3YaiqsW~a3Mq^3OQ z-lY|4qNbTZL=!MbB_*RmpKtNiD&l=Q7K$CkpK~I2b!6JHqKq|uCueZ|XY9i7^`$GF zBs+Ya5BE39E?=!*8b$UVWlw1Y+QAM@-1oB^m{BKz4XgmLo=&v%nXw9_T@!Z%HGKQF z?I;Tg5X5VgPpRLkQSEAeFC_bTfU5N0GkK^%(_KX6vI$pSBn0E(=K&K~oEAyO!!=aa$fr_gz}?4zo&N^o0D& zCx*{H{64NYyYM}6j#42!nx^0Mu92ZN)Um?!u(<=z)TDlhseDN z9x&Jr*6jIi(R{rTo{h1V5s{+%SEP9-s5t`C$A2$#-VKePsnQI*-bFEJ87sFCecfk7F6&TVsiA$RL+}kzw95;ksrA#MZ&WTze1~qy;O8Jj)KxTl^2G1K2B#MgO zu^l$`JT9~d_rXYM^1$K~T;ZLp!DgHtb~BG3uNdwzH*5O|L$KPmuRP`9#%3bB5D(e4 zPf8WeOSh<|6Urz~1Pl$8dSNC-cD9hzf0o%2*{H}Eokz}OlP>cG-9QlaODkH{K``gP z5!k#iX$r>Q8>(nzh8rpqy^pNM0qaqa5V%1RVy`acYhE0_N1 zoP(r+9zX71-aRTbM^lL`Zm_H$V%&VahRA|^IX~0QVJDy5Pma2x*%}J$+V5z^KD8WU zil0!rb}R7J<_t4KRk^8(iWHGdzOKCvH9nW?6lEtDCk4PKd)h zYf-^Ay(>uguh|AQr=>DK@G=$qAEZz;gZE9{+Xf^(J z;mAMeZT%E}ne=pUCHAFWj~lcdBtEwral)~g5&YeOosJ{i<oH^t%+D238P5fftOLRYKpy&C)f=9bIP}2vh z%d8egeQD$J7jW$*1e*#2Aou-^G<9%acWdTxi>VyZtXvQc55`Dskz^QrlhZ{fd9#K7 z!t!#4poTkGCACG!KjTu=;4Gb zq9-aD*R&n@6kezeW!ITW&!0U1<-OB}L$RAS5=4ivwL?|JP33VeXGokKKQ)9RzZ&QYhCi^w{fj~ z>EqY;xxR18@$orP`QwjZY+fpXsVT%y-MCSuYt@cdjt-{~SgtQ?qx|jsYKIUS82mYO z;3dw92nb@gSQzJ;Ah~U?tY=a}d+?;yhCPn%2(F~8g>Vd z$~a`5Yug89bpI!&gXd#gmmglLu%?soM==&w zu>*nw)s5_UZd#E+rrikogKG9^co@Lf;{M=wl&bm*U-F>e@ova+I(ex%V34uelKu&2 z!i{Tknb0Dubu6Jv+m!pV1P4J(S@6%$9P9@u7%bIkDhezFDchSPCQ>n|9^A9gP{hB< zXKxR`XQ&$r8=9*ZO4h|Uydn!ijYPKFLK)s>&l4%Hj6BHt@8>yhZ?@BK{IIE3nQE~* zHPa^T5-^?sL+Sp^Ycn^%2{!dEJ@Ryf;O^Mn?P`P7`icV3NJe#x!zWz}5ll=is@@~V z!mN&SLSY~?{NbnoiHic|xV9>ZI-UgoK|wW}_3`djb82i}=JCe(3lz}ORbzZSrJI6E zfroNuDBM?_Zc7D|w`Mo^Q~Va?x$P$KtEBvMc6_)dITFKWcb-{ApV~*Beb2&LwG2~Z zmZ?dxw5En)qjmThw!ixhMB33Lr7Lj54cH7=+w6gYi+sQW3TG@yOSNPH^Dj~Iss2%@ zFSX?2P=K}R(-beHlts0OIEXLi3(F)TJk?ZZr~WtQq|_}=6!;BJ=u|C7=_o2J8fd~> z?prEl7><$mjb~L`n*!c=EBiaJ?J)$F{^z0NZsGDv{y)?s;Cw!MHip_Rt~K*{JvLO} z=!OocmN*!Vmg)I?DTwD+HT{?wM++6KlTQi&gng}26aM6HG_Hpv=C~r`-jCV`xCMxL zCG7bybhvKgiiA@GKxefW8<~pTMhnG*!Oy4n?Yca#XX+TL`>*1%tqVHBFeP#MeSzY< zgH`%y)^fDU!t%#lIOS@Wa&|li>pZ!2|4TBR+i-i`v;fs>^!JQuucxoiPM`Wr!5P=G-;w1hhK7b!@Hww^oK4EiJi4-}zr+xMEMt2E zS70Z4x~Qb7JLV&AK*%u>-&`-NOpe>0ELNWJ!n|Lz`#!B}bILxsbycTxQ_vn;&?^eG zd+i^u+8EL(z}jdw2OOFqK|zhp95jrkwk%DraN53Rc_6CZB(;y-q@HxPd#wwzmdNn6 z--<6yFsK;;!0AF2@+G7!hwV!vafheRdNXkoprf{Z&i58vI5YUAIf~nhzqHj2ng3Ui zLPVCNTkM(S62yM>wuVncyzs!&G^Ptj<7su<5r+VMaPpp1^YPBL*CNjXTUY7=L2 zkFdG2Y)1FDB>w9eQ4Q|jaS;A`&z$-ogp3IRHVXHWyU&=9#xifOm|A@9)_3L?TVpY^ zwEQ4tW?2{ifz3!&kRj;fzapy^{#&6-NEKMQh#&-q1&oD2EHaa(5bpf{r)s?aTP)_c zhUt=0)A|sP)mS~zkY6keUwppX-S9zJD+dn3O8-bz{D?z$y&A>6 z5z1ggNm)8MNQZ4yNvi1l5tJZma3C#2EfE5yWFs4OyiFE9}IrRg2frh#Np`rC|lyx8<1tG#O}moMowEQgB$W)Y8C zyiZ`yn3Y1tM+FX4!gi!lOv;R z%V+b;RetA;SFMe&rb62#M0iIsiU6!UgDszz{64e&lf-TuD|-jyM2qZ8-BApg@^bjr zno}@Wjwi7b8I_ot3}m@8hhW!82#wPlb)F^> z?o4~<)p3=xApe3dz>#}BZl7^8pu5H7uKt~u=XCsnG2zKxY_Ul`c3qRaeg0)UGYIJx z>>q$TnVzouxPv?N+Ss+oKD5j<>GekzPuuzu-RI#%=WM3BOlWA`bVxC|_%$Z1vh6P&}=INSwc%#UIdMv5^o zKxZ*mUAE=*1gq@tY_D7@d`O95&~_l8a7jI>%8ms#Fh}W>L>Z0m)h+iMUh^PW6^~ij#Aqud91Pn zI~VQ=XMitG@RH|kMy|yXjoq1p1UvvmDz+l7ce-2hOgljqH2T86rJnalNffS;7egLr zb7UHwSe}mw7-%M_mK^D~Pa`TiYELZ{j22)5*($~Gf6FK15GkOPG!!H`6X>t?KEz{p zgnaS0RBjz{Y`M{YFt2V^h~+(nBV1TgA2<$WNJN9sg+vCxA*5WVXsZ;THw>> zaf{iuE=!-1jkQbU5nB4;mgQ)D)N~{%Nd(m28R^c9>v~$9D;;ld%U8VEnD-o99#_fE;*yP?7m@A;r5MS`EM2ipu; zJUrxHHs)wUAOh;tvRCE6#@Ji=U#)zhX6eN4^m#T_n`ci)EPlL%~5OEAyX5g>O zTX`%b@c{$zpGBD!Ejte1&R>tF7;VM6<#pXYgshKzR5nR*ynyDCmrzIsO#AF+kIj6PdK0%nCM#gpZq{2}51gghSQ5RibT*BHsZ3X!(0z00l!3#l#09sep;#qx04T01%vTchh28UKLCG=t|1u7*o%R@Dy(hAe^EgZUvPpv8zQ2q*K zMM=Es?QPXz+q_K@sX@uTcLImotAqPp&6>~_G|v=zs+!6OG1q6E#x?Ry_NW;Hr77x{ zVN+|OTEW5ochcspZXup{604cLlYWm7#I*)T3R}OcG)Lz z@iVR2Y~MC+<_?T$yIMLrI=0rhF4AU#Y4C!n{W`t>{``Nw2hW^*$IyZTE(Qh$cT7ut zy<~~M+-T-KXO{M-uKCuLjMqv`Fm$P@sVO3M?>;>d&!9R!KCbmS2rosyC65><9z_0fFeN`4d7rU94l+a}TOWxy?lj^whM?*tH zwmk{lI!~VDd4OYo{`~o4XXir%;-4tH;JthF5)u+A5^kI`-m82JjEqk=XBr*8p%C&f zUI@L5kH7nT><$!IRP_AADIp#VLMkZ0rhomq3nFif@gOrbHQn0UYJPX?vCHv}HA+#@ zlRLhq<{q7ZDJe8j>&h;BdFCeOywsoWwLhwN*XO|D41gGoMnjO7msjBTIg8QHPxLFS zh^VNjnwNIr3=D*~Z{LQRn=a3tzZlh!lhE^{o;~Ay;pSHE@<#z`&U>6J=y&3tl9DpJ z^{0(8vV)M2uo>XkWouR*oKA^@%DC1A2f)OB=b4SoT;ILlueAzM#>ULS!NHW&)FJpJ zbOq;*A9HfRKY>#aiefRLVRHV6e+>kL6co2*Gu7+r>U4~aRkZWfZasedSa;a4)?=Nq zsBV9MAC)_U+qLilhTPcLK%sQBv=pE&kRddhh8Q2`CMzrJ)h;&?Z=#|&poFwE6;%5H z6iLU2Kzs}fyG9j(60slQsxtdC-yPrG+#Co|wh7L!ud9ZJhN4hb&d%y#VPPX9BPbNA zH(B6zm_%_r#h~7v)mLHPk{!v=e}dl zT<1FBZGt-5+HE~7baW3FuAka9k*i^g0Y;5OYYGTsk>9Vd<8B_JaWm%*bE?r8Y9t zHZwD`b#M@-RoGtIbn(Wy>71^-yqu7n{Gq))kMiTk+eh1$x=G;Dl<+ri-e?#bf8pE& z+1jpYI#*>+-I%V!g%|+ZKRmOx4xOGhP5^MX<2xp8Yo3^>RTM*&Ho%00gfz6Yf(HjR zsz0bJE4OCJhm<-0maU#1%6lC5;X|b3RJEN|tX=T8Z?b`lPxzr)ztif6`wU@r_s%h! z-`du&UtKRR`~V;T$jrw}Oa{lt75)8XA>9ad4rhG4_Lkuw zJ691YD-*n9+Q1;qLh;pR;2Pw+-9az@YKH?<{`U5F)|^kD!V>edvY?y-LPQ~aUf;d1YN`}u{1KW!9pR+%~Dc88%eIO|wQR8-W;$_hnJPVU&_JW&<| z4Q9yrEcXgDIS3O&$f~NU^+`x5H42Rev@!CKl#GlFFR-DZ0gYY;SOJ{+h>PZ3WF*Ng zPEIO_n2hWe;^W7Uh>Dt;+kk|LNk}Yz=a>bYi}L2{-{CCR|KT4K5y7UXr^hJmB^ZH1 zyl`>JdQzmTX<~8%4hLb>^zsrnFfxh{3c_jJ>EU%hSTm@;2*M@k!eUcNNl9(@mVeSP zG4(DMn>M}&+=!i+(2$px|DcKV_Li)}VB)j0*|3w7LlxG&1t1t`C3dXQ;K;SXNw(K$ z@qj>^z`Z?phv`~45H`)n&N39u#rVtOX|Vsly!nJ}-)rdUg#!jMU!Sb<=i>57IKG?F@<$R(%&!Cfk6q%w-gi<1RW*>Q{KOC9UrF$ z6v0^K3K&k>_ef)P$xBPjamDF_pK2*@Gxn>ErmpU%r0Q3@&!U;>0b`Z>pL-wdR@x2E zZfwN(9B!~lNio^Qk znyEDkZxb9b=b5O>i^C>+yX@?2^qV&@2oE2h4M?!?vmb%^`L{W!h$<>7wm_wW63hDX zg_J4+57>uxP@r%)97i^jf`o)bB~=K2ywr>UQb`ks|MuM_`|;z4pzYwzqtjF1BbZEj z4mU8H2st@ctwI_C3Koa>%k#tE_YraCKT__-DsdcvZzsES_4U!g!LWwyPNuS|s?e$` zQ4pPpUC~G1%yHh(>eq@VwzvOH)FjZmXr)j$9KbifKB5cL6wC0ifk!}q3-R#q#Ky(p1RHnrLakjEsx~NkeFPb!UrfX6&_}^(OIkb#)DPZC40`Ixu%~ib-8D~7&!`(x zbaIzx!oawczg*RA@93}_T^xQ`voxh*U8z^+0BM1YhKZlBUU8X|MD5#xq9QX)2|2+i2o7=xU@w8!SmuXs7jrk|T)%|O##mIv9| z+uLWS>)e2?=hrPZ#E(;YJu#sVUb83rt7SDcist4w0neieo6ZlIfE#6t?}i{ybXU9i z{7y)q@$&KU#QOXCN(U}RyaTtX?#>jpA^%cb>q$ZPfC6TbRTgmVdf&(GUaGoc%f=3!)(?BGRtN>X$pF?ap!99e;a!yy=3LlamvA zA7Um;;?moqKKK;lw5+mB}HhDk_4ncC5sR3zhQ}baWC7 z+lOPec6Jm12!SC*69Q*5s{bjUsD^p^jf~I1>|);sa4njLG0YJ_gOEIl9^9v(yPREJ zB>`v?7Z-2t>nrXZpF##kQXQmyv`Y{yp2Mv~EzUC>Ri@DozGvwmU|7C@a2+MY1q3KI zn=bvsk1x-bM(9UpD~kzqoeE2e7D#Nh(hOUB5ILu>Yy38 z*vpsu159rtH_Ky9O*liCMfzhY1dt}yfHT+3u0iweBlaALyy6aX}+8 z7KdPG59#ae=?TVQq}JBg|12+~`##+BNqmZ}um+)TUH+Lfda&dO z99%r7YU@O~B~I4xvf2CkP)vP2LROZ=+uM6xvZ1rH^Xb||IS{xMK?_)kX(MsgG0kuy zuin8UXDk~nEp6@!Egb%Hoy%fzanXIQlMG=WBepm{4_brU>KPnvZf^B%OXP6T%n$dh zx+uN3W^uS_h=s(&K2=tVAP_wK{GaH}eB&A~(Qx+3$_J=DVE1AHt$-g?-2>u#VB8c* zFYpd|Gi!3v5P^8%?w$*TquR;lXOm>43mq$~x|o>Q-fRo5y@NyUtKCI7bhTw`s{#xO zte^YhkLyBr?`EH!`63XKpmuB1YBeRzE*K?A+6k;NaNg?}q~g9Jp}2VyZBU2|^pd^e%30tFGW&u)t!(n43(@3{u6H`-i+04?# z)?ZKdO8ciO_+r%z2z{sl<2_lOS-eb9u}JYS^T$^H5)^0X4{ z1z2awH~Vn&_xCc3HXvD2KUR6KTMJ#MqNX-rQlJjkfEXm*3nnju0LOdulCjD%yDk1$ z8G2sZ^f79GN*ZZs$moN20=)X{-@ht_`f5>c>7Lr`%}fJ_8H2#|oV&!2e;ba>i3JFAVHPWD!m zl$6YAbIZyoLG{{DBwq{M*?9rTd2ee)Bxl?w5RkW+ovNy8%3aHApu=`q9pfWqk!FxP z+rour_s7k?gWmFHqVms?5j-%@V3zTwxgSoB51s7|s~>>{XJjOnk&*dg*2F@6TWyWj zAUZnws=|QrxX&4HG2a#EuvZF__BY*gM&8|BBr*Z2&I5xKFsX>S5xPe(kgiu&O?q7j@APm}5s8HQ)1}7Ou}IJ)-Z7}a z%gD%p0^`^f?JM)v9wiBw#Q=xeIxtXbB;-zzt_Njd$?a03SBYfOJDy|XCo-4Mc#-3O zXprCkXZ@Tc{L$0%_W)lS*S1~&S#$(}E+j99?=PP`vlQqY>}h|76#YIw2?`1VXSBB~ z_9S@z(iEvTGB$QFRxEy!lC%q}+`zeVHJU0os&uM`B4rqteV=^)#}v)igZ^Wvs8-5< z&F*QMh^Xj(7y8e?Lnpryf^Km DLr9>M literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/class_chan_angles.png b/doc/src_intro/img/class_chan_angles.png new file mode 100644 index 0000000000000000000000000000000000000000..e965bd922fed46d15c682f947819626a1ad3fe23 GIT binary patch literal 21809 zcmZ|%cOaJi|2K}GW<)}=BcswFl1TPSB@#ulm54&f$jshNGg%ecBH6N)5oML^k|-m| z*7tE-*Y&;c&;7ft6BV zOjOn4TAA~!BTwDrd81ZcGaTDjE8ZP-AG$U4&C}S9mCs*+JRl%oq9esmFzfx#?|+0*0nb@)qv?!h7ODBOa3D5bfM6zs#a;5+AQ6n z`I|Ry7UX=du8qI)I3TT=cwOsNdjE%?7vKFUS`A1Q%G{n3A+4&dyI+aR8J~IH|Ns0< zjuU$Hn>XKn^vJN%MfdDkrGI`Gm$FK2TYcl}$$b3-cc)Gse$qKK#OvVTz%J+ETDe~p z-_>oRq(n}=h0|ZcrYG1?YgB8pE@*2|Qj&@C)IWb+7cXHmyF7oTV5(E@|Lc4I&wCN% zSy#e`O60wNf7WAdNqhK3@wNWj4d#lO`T2~a#=CayGAW(xdKJld`)B{FG?$sdGiT2D z+`GqIVkpAT&mZetQBm>Qyuf~OdSG|f@$=_dFI~EX|IWYp^OKtJ>eAepX@P!Ug_~nq z^eOGySx#rggT}Xn1x~2tJ$l3~7;cmoI7hmqtI(=F-NzSt)*XWo=tSA}& zm7K(~eS1w^9mT$V`_Aa<`d3!U4pz8Pkfc18MD-7_7TXO)-W52mq^L-?zOqnve~;GE zTLxNM-06d`(D}cl1$&++eO^R+WLCIm3KUkWN)z!4i1ts&I}ztd2;h^t;gYF7LCc*`inib?9B_$&lksv0)@^=m+K@=nrg zzfD_7q%6HWHS8_RcaJ0X>O3R96VKG6U-OX^Q+s>+?81U7o_g#x-%PFV@87?l7^;>Z zth^O8QWrFa9hi}kF}z>d#DuqcV`V??jeh_B{S~(s87^G7P~x$CsLEscHix*S>DtoV z?BZfjaq$rn4gI;zw6u!-#n%chyt#LIorm&2+ExuY|NOL_)KThqg=BiY)uhsW zyO)=jx|Y`Q%a?cI%WJdi(z3GXk~8oA>`0*~yoNuG+;J=rOZ$7#^#?UmHMmrq*u^zxD`yZLjo zo*uRnmFJ}J-o3tIVRWIPp|dLsHrUgOc&MY&hNU;C>;@}p)|Tg)cI=3ln6Oe&RrPJN z9BaNS!2GcDxy~NaIRPtI<0_B6PM)VvpDwZ+;z8kP7$|p{n;lV>@myh%b^oo9aO7IP z=ju%s7M9_joQw7@E=@RR_LE(EL!v@b1r_C=>qKZ?yvT+7S37ft(S2bu;Kcpiikg}X zDJdzg3zOSDJUtttwa=dqMCE!A9nCK+yal&>93MOT=jTNkuQmN2e=4fx-R8$@UcdHP zmW^p?c&?M~AGwgz{`T!=)R|k0)2cIrl@3!q!oEXtuFo{$$mQkb{R0Ed(HQiry<|_G zIz`;zu2a#b_&MSrIXOASUS~5C;1J5Jn%Lur%ut~ z{Kd+7mi3`z+C@1}^^CN{9L#_9>Ug?lV!qqFC9c*SHHQC{u!xA-rAvb05fRIrP9%1T zt1O{mVY^oRv!6c?k^j3!6hobKO;zmo1H!^&G#fWZ#>V^_!q_Zu7V`@Wm5q&g&gUA2 z9J%(1IO+J4Iy_%d`(Xv##OUIXchf{?T0@Ut>ZH=>i9@$1*G=ae~jwdrh95bs7~j=wADHpv|2#UbY*<+&7$mK!(ABgY){=lTCfyY9ec zpeI`wtI0}9#fFG&|At!Zx;VXK-ce1B8b=|P<7VcqrCC0-HthAzmo|DTYHBBoqP~2& zRCOX`*WJX#Ev#X?w2w%tYIpT^SVg#-oAbXYEZk-6{p-scDbJN6m8o3)g4@4#AoFRNVO=9w5vF%90 zZ#EK6>T;l>nyP9|Yb(7%clu0$MH6{O{L{vs9@a2c;o5w&y4NH2`OZ`4Nw3i+XMcPY z@B8#=6gPv`tN?5<#C>1pTYI8%Q{)aY$8iny6DMlg+ZoVHn2&AxQsz8m|9e7vX=UY5 zVYi;%*|WDx9lt5*>9KKga-t&h?c2XU?rXYMQsDFFdmlV_Fg!lqc;J+lR?x$T+kgN5 zot%>sfdeIGv5p^!#7?Yx^M=+?gl+fk-N8{&Y%cM4@7^VIb91BIw5hJKk^0%QXZFs{ zRD6_Lk7b@qxG58-?bnwRBp;Maq8VJgcyZ$U_nPkR?YLgQoE%{(?#R~`=|YqJ@A=Pi zezZL@Iy#CD879B6MDga$8+K_YA)>O4HAVTgSqdCE!phAM^l|+AhxC_kOFdVQNO3cK z9vEQa<=rYFA%SJCZERHgvJrFO!tD>~S{9RC&tt_b)N;NmDk`c223)>0)W8sxFlWMP$8(%jMR(Xa^50sCU&s5d<({6ih zS;)l78hG*5^%Tc%?Mv&6LnF9Ye}Bq?Z<%=PXb~k&-h7M>O`6nvEEBSQ|9J(}&>J^ysH>~{WM?0k-}(A;sUzR6T~yA_&Q4Q3Tk?!6$68J0R{|w6RvT(+$Uc7j*xcUUh|)wX-j5$Yq$MXv z$r%|-fA=qVZ!tp`OME-gS0I3rCuaJZ1RSgpf0%Y>Biqq4v!%V=(lUCJ55o@W z**4p}?Ce%O7voA?_2yf*Zqc)gl2}<;)lZ%rohp9r*6Mt8aOL{NbtVgI>+c5gy$g?Y zSh`;vwq6V?DmrXp+#0l%H~xmpu)S1pM8wzC9ek9wN6HnyW&b<78z`>UE|W->fpM-=P&9xb=tFiZ|Kzv@lNV#fDb%!9yH1O6n_AE zIEyF)PXUs+{@tkTbKb$tO`KN$fB>?L$&Kdb<~vpsPf&O|JP9m%>(7rGoT}OHANGXr zIL6Av#KhmS|G)v23l}(67H77SfwkWHw7+qqcDTkb<;fHOnd-kh=yW+crGUitH*W?;L~H>b)YjJzereNtoAEZ< z=WfMcUt41Eyz0;)MX$7Tx5i7*xx2duhlgKU$x(H1a;gU=o5e@a}QpbaVoMEV149$)}e# zL9bscNJ&X4ptpOj{-KI#d1|zeWr4SLpO6q^LOK@K(2L_yJR?A%jAb6(nde&DTE}lL&6?SMF43O&Re0sy zk>xveIL>J$CHliJP({u0L#NBULsKVbRtOktAZ;JiZ)Y57K;342nMpl*u7F|eKn2PjYZ$G1_ zM|6ABD_4SW)=w2h#WPi%PLX4(ig+$^w{d}}fPd+Sdpc_c0ZI?~b6UAl6muD+hq+S;0E10Eh8K!#gTNBjEvhTq)ZL-OHM4m1VLI|G25 z&=%>_) z;Ugd@+qZAe)-O=HYSWu5Dk<3%!6jMW6PKD1{WB}Vi)p*WEqpsT<3sC` zi12Wd?&a9e)!w|Fot>bd;w01hU?z{RjrH}zt25PX<=$pYRixp`$<2`Zs ztVknR1w~_HBMlv$AD*G3#d8Zk0GP4H=<{rl;5_#Mog25KN!k-9n!I*RDkE+N}bMbF!t6ts0)ew|Bm znZm9BmPLtq^6c3tItj723bQLJxN$tyTwSG@w{7dh$qeMC_Q?#4W23w|T2E`4?TQTz zw3(8g-c*6LUY_O!0qwC#T8J2Ld-v{J7&&Xt0)OVTrKM$XaPVsY7*lie+rAW=Mp0fC zq#2;tM6yagnZu3umAf3=#+#Lw7ZoRdgHMjPmSr$VyIQC=a8+=+?VBq{mIU~#)p=*pj>U^OG~SEvn2=+`J{1dhi; zN`3Ky8U0Sm{kPD{pPzIjVzc8}+J9+gYQ_<+*y_Mk1ysN;WxtbE#E^!Iiwk6ylyTCI ze(TmNob9MAb)B6|_*iE51NZ7FB?aSSTD}rUaHoHAe*T^1K<)b(Wk3bI;B7(&4-!p7 z9)l4RV@{xD3g{r&v|0X{n3zpn*>u^(^c@DB=7R#m0qX4nLR+gIgz zj6@v$60db>(6!j_U%~$GBqbfZ!P_n1;U;NhbHl+wQD2{Z$YKSDo`#;DP*H%!e*F9? zX4%S4pcYe($jHdq`T4O`!Gr1xR>t70f_wH@px*WsU*l3zR#v^v#mML*X*Z| z-!~`7TzG(<1p@V~U`oAP2b{A#Nj|EtPag;bc-8{Erp-tgq(k4@`gw=QC#+1*!}LLB zew!?twg|VluRH{^7d{xA{AF?(DRW3k;+tBqKCq0@>rv z(?TLy7PgXk0-GYfu7W z^lQ0li~bCFdG`K8J4;JyXh`U(L_gUf?ZhbU@gOzhnPQp?mp0a<=;h114<9yMDqidT zF<8k3V1bqJRZ+Bo>?gumd9e-X*v!n#S2Iz1PIbU*V~xXcyww*K1JFYB#uxSR{u*>q zF&ysk2q6Ih3eZ7pCZhHxKYiLzfgM2{{E+rNpW!@A=~!U_VuxYG%NvP#M!Y) zUjMA{cVpe`(xrMC!EWYiw=*o~`t_!CzNyYk_Z3j|<{H&S$#2k@n3$lK4!`!LAP@`y zn(3uWlv}rM#UJ`G-o|qC;oOfkMo^sDUfG|ecktQgGL;!}1zXz#_ovS4XlT%zTUZd} z4t4F>DIrl&#wZ?HrGIf-N4geoNogrr2Iq8KY-})?MsGZ~MMtut>-vg>akW=OeZ30U z!W`9oT1SvpLih6iyDkaoBgA2>kx&C$-NK=Q0SkhbM5P^%GRFoM+Pk-Asy7e17(r#m z&;YP&>Vd{68-JCRmMQ`nfiTsyB}g){u>}DnK~bu#oco|9&xf8&TpcJ(j-)N>+-~Ce zbv@VVOi|thv5B7J5G8@%NkqRwFMx&Nd9EZE6|sPN5Oe{1;{G0Sa7y20spaKmf)Yg^ zxIoSt768%Me7rTTRg(SMwQKlten@0cFKTLPCI-r138voxm{Uu0$%0EOYy|}$m4&6HIf3)p`o3fo)TVf*plpH7>c+{L^3|4t2XXz69~nd$?ck&Z9@+08Q#eMs4cGB=YJlbC0t@ z?7ZXD2Yd5O#?aD9J`j8@7ACt1VolV`@9%g07^*f&l|IALU16Y-HpranqUvC8|9WG6 zb?$2m8|gI!Juu0(#gGg5cy6Fgi+7J@$>qi9?xRfrM-$>O`aoZq^ZvIjEph8~;#M6y zWjvM`xAMwSo^k%5+p$IS^5x6=7cUY8lax6qG3=$JKJZxIfkNQA^3Zh@(D)ymG%wx&Epx^D*tubs6 zQ8BR^Ald>H6{nfO9Te2`jHNq*>J(84!O}W#axPg~rs5;Xt50ytd9VX264lPvm+bmL z85IsXde&&KiFX5`PkVZLvU70w){Uqi{#E?%Z~Cx=p0|hK3QGi3vOh@!s&% zjJ&7aU!K1znlRF?Z|Hw4d#l*^>#xSOzrR`z5*uOl&rc>!PJ@|{f~@<3C)sg=KjxXp z1BUPm2>5ZhpU~E=`yZ9}AH!x+KKNgYM!isC5?hyf@l{WFYg==(57dwOOIMtU#}U&K zkebR5nKTr_e#oD@@Nf2)f4xWu)~aEw5-t)XlHE`h6}B^W6l8RIpkYNdwLrIw5Y*(} zC!OV~8joc-!1SW61}5*8K7al^zo4K7Y|SPIatt|0ED-E=Dk>_XF_KeIG{_ZE=*n^q z8Ag<4l=$0qR{z}y!-gM2O+It>?A7VXGhN;%K^mlw9h)C8j0g?A9T&&plc_aS5fY=? z@CJ8q?q6LLFB$P>~a9b zC*(YkV^LAj*P!ch>SWq;#o#LhE_VMt;R{?Jmd$%+;Tf^AAVGBi@dPv~%!c}b7LIa^ zqOa)TAycTK?{5cGj04ET%}oy=g9cFB-Tlz*#&3v%{%CN7@QkCtxlKWPD44Y~U1XnT zvE`*)5bCb3F3M=f)j!u@qu}f)10P^--m!X?1Z6fEi%mmA^BN6zQg;#CgTO5~UCQq6 z(kKxq?PS4`uO7lo0onu+t&Yk9VZzKv6T3N8l10_i z(?r5ukHyU4h4b9T`Ypo>S0;4S8YtQM@DsrGQ`*0F1>nx^-M{Yuw8g^4X7TaGWk}#` zTy`zy1)@$9XJCf~4>UniP0q~RY-3|X@&RfEgOA;F{O6A!rna{9r2H2z%=!HqRF}w2 zZ;U``-ukZ?qlBWGnVH#Fcx5XXS_%|9DD=DCW5JT9veafm`44Coi%8%6L38TVDMBuR zYIA@0>DyIRascB~hP)@%e}B*-aQep5*j9pXfFabQT{SfJlaC7Aa)ac#%Xw0epWmcLUuAzAF@L|a3+$vDE4hXY92Flsc=aj%Z zyq3SR$+-VkAN>i^!~>p=#S$0Ghi;?s*VU+N*P&i$PQ-=)KK04uioYk9DFPzt#G4vv zfezVv8s>%S#MG1@Bmben;@s?<97q{K#N$*r$N%i%!-sv60V`@t&z?LPhU{md#tk5l zd^+LCVXqhm`2g>eZ_N+V%Lbdd)KJA(|mnK=Y;95rPQfSz_-K)&TldZ|O9)q|xEkfUAdbSX9v= z=U@+yKg)!;hsLP#P3ma|b?Qd~cK%hocRGGK;=bUK=*6A7j!Wmw{TjOGQL0HkUh6An z06tLGG9|8{qMyz}^$jz>di7K4{Bg*xV1|RAyBSa2bAO-koTb}I@QqH)cNpw_x3LBj zys)ly#qU3SNH}$rB59ug*z1h{+3O*84~*f9ZES3uzQ7hbFgJ4K|IGrV3Y`pwp!)k~ zzupgbXU=t{RYLbSI1<9O0DJF4P!w=;JnhVgfP+=i|9`Lj?(S<{P-EV<#_Vm+H7cjv z*nmt5N4eGGQA9&i(kSkn)+kSp= z2bL!PM%QPa%M!izspwgzd*YOU24JM_xpOsNZ*VzPLV5yOXCNNH^)6cY;_%p*z|DRb8&Il`oIf{t8E6N%`rEB;8J^^6ogXJg z0S;gO8K}JF@?XQqb#z1TYXV@-M-5lYv#|(^j3oA)1GEcwUOOE^ZvK!FcF6s=6=1=s zwUL0-c!Phf1$2w8OJ0)y$vz~)#r^-4?~lXVJaFK^9YA3eVj1rZ!!KSpfAo>T&S2-_ zB8t0SuAy0UqP#axrTYSa7!N2O1CLDefpX_5Rv2_t0QTWLvYdd1%)ALfL7P~G4g7gz z-Ay;vmiedtvj$KzH=RF!o*DNs<)CEh{sofq@Xw!HEG#Ty zV`E>#V!*z=9G$0MK#nI9fXG4Lyg4Lw*lTq#MaIX+Arv*Ywo;P*>scM$-Ov>qpjW5l zu3p`Y4gk6!HeV@XQpFAC zv3-fpC$&nNpA2XFSHE3#h+$JrjV~I)-5D1&(o4&~zWOsN$;irvL`E{aX=~f%&&bTe zq7q2Yp+v*?Wwaqo1&eQ5`YuU+4@n(Da48(>e1{$N9UIb$CZ~5A@@(N{+ z? z`CQ!kn0DK45{cNQ@K~gzr4Pwhd#%UY4MCQ8`A2w?M+ta`u#a}E@DXyK=K0#OA3s_(BJ|eF468girl+Ux+`D%h`csF-3Y19b38KB8P?Jz7q5PC} zSY*&?H|?iII)J2rDsBo#2qGb@$-0|hL#TOHlf8MokL5h~6+I$MMNnw)$%&pEE)@5M z1BFFJwnbx4GXky7JT8Ou$j!}7A`!?VCPpvE?PQjYuI{A`;a$7VecSjBmV}Zszpe=| z2Q)^?EF(b=jLU0y`t)f=cJ`$*1J^A(?8<@1Mdi10OEF^mD=p^0cyf>>iEg=5ROFPC zWW(dK@O?;-VD<=|95AVRWamwIPcZl5<2i>`YTN0e@~7@4B}GB_5Nq*wu7m_WhBH^< zI>$d>4);%ODw5H;!oa}5{8gS8A*`4V7Ue><-NJQb7?~@qmJ-ahK!zRrinu|~#)l;S z{w2I47!{gLs@l%olfSykoxa!h+LJ55s)q|l#0e1F8Xj*;06ZcRARq4h+F&25yw!BL z9p?`+c~1SRWr03(_m~Yt$k$MD<0QM{Gkec@#U3cl zy;o0Hwki;z3^PCq;zNBhzfTi7W%A@Uiv_Lb)b=nbX!?6JACdSd5x0ZnyshMMTABdy zDAoRgJ=i-rU7GAYlNzbV3^#PsneODIV=fFmJv~DI+xJSoYGsa{AhAi?; za51Y&1gRyY{f4}^Fj%aWB-hc^<&W}^nwl!=I&11XMI2+OjfAI+Tvu{-b~tWS8ATE* zB+ZsBR6%vVU~!0$jKIi*R%BS_L<`0jD`CTW#BLBx%>8v++v!yMM`b-@HsL<{FD}tS zyYGY?ggT`FMhelFlL`u?&!0ahBhZ6YEh#AxU47pE{ynp= zuP^c+P3UVoK{$AMlcYVjWzNitT!!aykQ_~R{;Q2{Sgu5xRJf9Xqd$m=5pU{XArf!s6*6wWzGOMqX#bV1c+dzj zWV7L5YMDt!BT)y}Hdbc0J^T6b(^VtcEZvW+7U__|ko37(eTGGKeG?HdA<~we z+|r7%$U6= z%FJ}EGyfiRzWlG2N*IF3FTmYkm-njZ`x(hA&*11dul8KoXk(-5S@g{aR4-FYOPqaa zQ}D+Hk-U_qbLY=fi^PPX)VlYQS=Dnrg@r^|dnU>yms?mv0`JYGx_GaAPjAfBObiL5 z9eyrXpH~3&l$``2#7HpVV=0z*~e>e$Osq{Cv!h=c6Rpl!Roc!5L+Zl z4kS;0CiW~&UL6`9*VESM-0{CbIIrVx-oy8(L*j!(#H$M4Q60WnDY(9B^Yf~4+N8W* zwHj*f)ef)!RN*f|-P;q|)X=={M;i=neR$YikK6>38TJd#xf(JEH>W>`;Bk8NON_~%`^jL&UJv|v6s8^RM9VohLTX8ii(OLYzKfE`81f1VCynn zWHXzq_nED>PR<;8B=0SUwIfOax4aiO*a5ln+T^zW1G(2F{#x1?7Y3F%j8Qvop{J+M zH?1MZ0VC=w8sUGMdF*`7)2C2(sCMgW={_g|?&IFEV-AjFZ}shaDst~92J(0-ZES5d zimwlxq~TN1(~CL!3WlAaw6uY(Y<)xf2I%=Ev~++Rh=nHrJ(f~0l^TkCth^=Z_IE?} zJF*iY!NEKI8Sg!QtVsYHoCBaZ$ZG=sF z@&wj+>))5aG2}i=%gbVO>DY^Vut_c6;+b%9NM3)`w~oii3CbV?)!Oq0x_?)*u1|k1y@b8+BsEpZ)>EZnTi8m1oY$HZ@HZch z&MvV1OCa--&A{44j99*KiA1J2~$S z4H+4kW?aNlWLDYV^%-wOE#gWwM^m4S0Y8_Ox#z6oY1j$5>oEeqRf*=5J>JS=R!|6A z!gQ4V$X=!vL~lRY3c`VV1f0_Yy9u>fRYmvui3$2ZnJxSSPQBXPhZd1N>5-8<*K zF*+I&uzuPEm=82k6~vgZ`VSsF==)Vtu=s-Rz}1bmo(jt?gmeVZj6HyGr+}0cd*!V~ z){^V^G9oGo#b$TSdBX?4lNJ47GYAy-D#cPuOhWcUx6pV3;DWnJ!{?C)T{Gc=vA8=>g-@C4%w}vjGL*l&Q|f1< z;tL9q9kVFT;ZgWHIY}t5Xu~@X9H2+EP9yp>ltqNoVtb*^Em`tpdR?F7M-u$Qv(t6p z-lnj&@Q_2pDXBB7dV0et0k1kfe8@UiCFq=IH$b_=(es`1X$b)@-^{V-FYaNPbr8G6 zu6;VpE#t}vTa>x`>tuHp+V_=qWe9L-O-F))g653`PFN%~bmxqhT4hfaB3b);dVuTk zIMn*=~I^(MSzGCbp^t#k1zM0dnfWLc=9nVyBn>6Y7-sQfC zPUni)L5|%vi4$kHDi##VbVt1b-$t5B1?nks&NbojfP)IKyd3^+c&035%%tnEv9Wmo z=14h=QX;6{lWWxS`%UOsab|X(*LI%wx+<%jw>h<*-ch;#%>wKBAP^nkk=MxD!G(&p z^4=1%=lW!y<%!Aj^M;3e7OaP=WY6arM|5ZDjiC{-AG>*ge#@3PWAevzY$B$}o0cG8 zH`JzcBJBxPx86M&=jUjB3ZJv&Ome1ftIeDTF{4XOOB1txFG%Da%;le-`sYp*eg?z5 z;p>MQ`H!2PqJQB6aR3kiry>#IQsgCA+{Lp*?!H7#fVR(zdjW?C#nuVo_uYg!2Q;5U zlJ@}fciOXGFq#@V{9p6)4jXH3q;qzcK*u!nl7z74Li_gBf*c7B zCY89FYeNkq@)dx5y64Z2!YL&0&9bv~RG!=&0$6f<*y`#3a8gLfETeUFy=8j~m{4AR z4A~x?sf$lagua7nAv&&U`at}kmQhDoud(E(i5T?B&_@gE4<;e)ue{GZKFG<%C9rd+ z&q4Q?Uf0E+{cPwm7W|fQ+i$~xft5@&KVUp03@#>?dka24?g?N;B%2eZoo|Cp<5BL{ zZVVM%7;b3)Gua&$l1P=w*%<%rQ$qt4&=f*k)Cq0WXSy##rtw1z2)a0t>L7Ltgifj+ zYm5>=GYkaQ?VATvGk_KJx~q!?+_wqx*PZzIP=q)`K1bG#>=Y8Bxq0*EM0XY&!bWf+ zqYRR4Ck+-GGZF-e5en0q+tPOFfX{>=3UdIhyb;Zok)2(rQ$3A{He<7h9y(-R_2;;% zYRKn6$rovewTg<1E8nzol zk)q7?^ZENpbnI|g556spkvqc9Wu5QNG6ay|1~jT(`$Y#Csk6%S78-buwUe?=caAh_ zI%w+yji3r%KEY8C)za;`WNuz7gAo_!h#?OE7w}^CTbK7}#%kV;jCq{o5c;yb!07a(y0Yro{Ngo{Fl z=vw{tmaxIEBfFk|9Umt$e(_2 z^rJ}=O%Wx4Jf`I`zplLZMmRDhgk7qprpA8shT#0qWXmV%Pv#P2pezQUE&Ak%9uNp5LPNrD2ZzTvXKj?J}QCpJaRtiIHcU!Mq2-@WCJbP-JunB|J8K z4Ho6jg9o*KlwMVTlq+R2zXC036k`EPQ+d^bxxA_`DNS;;5&;0vZI9jj@fy16EF9a~ z-rg9F$H-~~?$LVu8c-T?CW264`Vh~QotzHO3w|L4uYd9uv9augBV@kly|&~)B9a$K zSsk!X#Gez{=VQmXP-`?|&X}6+1oQTXk3_5>j<&s{BLxX;j!#UC2?V|gitqAUE>saB zdjTz60Dq34k4F?mQ&W>NkO`4>gYb+7+vp@-iD(>>PndvdB2pojF9(2I>AnBZ28**% zOMaaQ>JWMx&JYqYiaGzZ5zvI%`g;H87eVEr0o{pTo*TL0| zV4(>_56Vl@UFRi6o&K+o$K472s__N00)0Z~Xy2ylx!=I{_cY9JLIl9shg59V8Y}j) z=Oc`NB)re2%g|{P4;8J|r_Iu$`3@hU68dBY_hUjyltT(PQ*!esCoy*z`kRHNnpRi# zPR*?fedrO8bO|qrq$`mLeBDYRfxyeQ1S)~xCt@kxX|BGRt{uqP5yL51YQkB*FCZ{! z*e$84$855?qHkbul7;M)w(yCth{5izE)~SoU>-WGuQ*p}l>lAG%HARpd3R%Do7tZC zGfD_(xh-UIxV=3k{bkp9$gK(0Gi&3Jp&c;3Lj-`4Q-(KPON1;icSbr#W+)MrWoei% zC>TMT!_knCnApaaxbNV>cP{JxiCHU+-%pO(81p7i@}imLmsQAtP(%h%g?0KI8y zY7$Bk>|QJxX6}LkB}P%!&zwJ>>#U=vU-bezz{GnMe;n&QZ?2?+g!H%e9U#^rGuvF8 zyQ9)9{r({6iRVo#tH}ev1zUFK(W4yD8<~gduLnOXkz-lNxwr4Y0soSiC!UWN&dIv# zK|aGc9TDchFa<<;e{|JUuoRLHDkwi5{qaa{CaL}iQ9KF6GNPqei={Vh+Jp=VFEBaT z8Hs}#Ks7_@nu`7ncFaooP{j>ASCJxz79oS|$tKiPT#?wkIu48O#21E7pFU~OU%P(& zKewAU$4&04+MFhMItG#cn=}K<-QB7FEKsFq1L3Mxhb~nMlcdQOs)nSqx{f1XpVPU| zeVS5h(Xq>(7=S@C4AqF390O{E$%Cd#4QT4GjRPnkHhyrHI`97dZE({t#^s9)q&dhD;5Y#n z5YD5zd5#EC5rqb`Yhtjgi10r&O@0d{o5xY{+7(BR9MLbmu?zY>!4BZrfWz!Ck1FN6 z`x3CvV_V3n%!0hF?}ohpwz(wvrp6~=MCkD9SFWe&=|PB1^sYt}J%etnpry4HPZ7}N z>Vrd5`yh;=jxe8I>FA>2BO)_s7NTBjOXIl=s+~V#da@CMg3NausS>Un4MIn{@Pe{> z{m;d;hZpqlXw1`RR}FALFgMUd4~^PRHLFzI>3@dNdu-HAPtA|iZ9^aTY4r{!jZR3(bff5<2=FMsu^sh?2ES={T2 zQm_HI4!hXcfTW#vG|8}I{ppqRKW39VCI-}^iD-%iWd`TX^e0d1{q1QTfs%n0N#{Pa z&G9_XBW7>`q<^i$Z(ty}opd7CnTHQ8u3sNa_Uu&=xVAU*dnZ2U?1c-oN;H3FhD@@w z4+;x6ppFo>-EL|HW|Y-NoF^{bJQ#Cx5|g}g9zK{D#6;+??mcAB?iRCj|F-%q;&Ztr z+6+#@%bstZEmHQwq}J9}G%Ip!WXzsyBF(NXJ0c{?%5}un2Rn|4f8ora#jp(y4r*Kg zptv0nKn1pr>_yXJ<2@Mk+G%QvL=a>X!lN42k4}eqsR}O=N#DpM)A*{{v%277d}> z;U^Nd`Lg*9s7q0BGZe9VfL@~QgC|u9zwi8q90ns?c29e>y@Fa5Y`~@Vb8w87ccH1 zp~DCn;l|2uYv0xN@99a+z@!a4M4uy507o*g`3Pwz7?1H^?+rGU3XUq$`daFk14Gts zH_o8|j6xt0m+AczuC-=cu-$h)ucEldZIEY7g zK<(~O(Xlcr(OjtVIEo>5vtob`u8`2s(X0d*v(K}$1u-|Y8};N11UbROhaX@N`aaMh ze&wjkG`Csd=Qv4g5{adScrU=mFMuUj6Mt~Kdw>pb^XBH}u!93jiy@F*LMz2IO*j@e zF>%M-!ouZ0-)CmDFizKCbO@Qa3zhB?7m#|xS}`w;zEnKy&ZYpYVg|KEBZhVR_5eck z2iigu77)!e()xc{U((`%AG^EHO}LJuo>h1(-*fwgJWm`kVqLffHF60vC_6Dg1p=#) zDE+d1p%+vgMYSAJ1}+GBXncVPG{IlKjawNHv~CL?SgD_i zkBcLw#jwTwki?>9;10%oMYq90q#01#TIF1u&d8cW5)QBqw^17)|0}{0dNlsSy zauY{MztD0E6t2)GPXrCCy(%?B;t+36WbMp&pC@GB$o4PKtv%krnJ; z?%ZLt{D{3vWO;x6x&ht)BEy&$s1cMxRO<-@bPo7nFy57L=H7q!(D};FuYNJ~s&qtj`XFbji;PCb4d#IELrF zY0SokPFPqN_A;)N$XTGVwQ@DX19kY(Cq{aW;1BYR^gDL!AQGyOF~+9e$=&!ugOfsu zCB@esCvIu4k9#EbjJ`6FYVC6f`5w%KqC_h|WZA|wJ$qH?%mW;HE(|6We(Q$+IU$>HMS z2_sltwu2RMc1so(m=LIkdNDFOdK+8UvpfBy^%G%L30Y!>nPp*1^1#38rvF~x5uc-- zcPiVqt@$%rEd(iAkCk7D6JbN+b5tO**)+6o7C3N-jgi}Ae=90u9An`mPCNy??~u0{ zVR+KS;5Qb;55-s7WjY)^@lc8d2~Dk5W#{2y+?E*_KYy=vDEkmf6_K+8wzKZKv3K&~ zKN--jUFVD4FI~qFDzFn}q@xIC?J+b#p#R&q$!+_Kw_rmsuaD4$wtjuiVbae$+xS8& z?hqBCEU)4FV)`Nqi{~OZxhcjh{Q7~s|J$y4U%?{`YS}KY-(zy0IOaTqNumP2tFmdv#H$t(D zB%l8?CZw*Rp#p>hC6Sn*#*Gq|4UAlZ2`oph0&Ae;DBw^orP_b^@Bw-O6@n60HZ~Tp zFk3%l)Q;YBBj5wF97@393S&)6mX|IO?mOIF(>&&sL?2pW)G**(;bH zGyi$DR5?+xQ|H_KG7$j0O+`nTs7YQcwAi<*Ha7eJ9r?v%3V|k>Lo}|7L6!+p;a5bI z1p3s-w{JxHv~XG1zp(WVp+FT})0v_D<=YnnMEI4BQQ!oT6jS*RP^L9=N6=M>LXHg_YtM@(Z3n!Z-Cxf?D?w(Bc(Vn1w^ClO0Ol3Y9Xx*YevbgA zszrgFshDRV5#z0Zk%JZs*{b|ZMFzsaDg;F&-YbJZn}ciJI5b)YsSB z2f5F>${;pDFq_Y-FP(m_qt-!DKm*E&>8Newafz}?yBRB4G|(k0{pYfYjRw5H8m*-bQLKnWB@yxNV(3xgovS-dULTw z8O-d%6wb)W2|yo)-_X`phPm1XYcKf2q3BeO4v8-2km|W`#3yf1K4yA&G60YC_lhw+ zH3iFNDkR&8SAO7w>w0^8Zx1Og8d9GfYq^hpiyHgYKq!L^4YJKyHj4C7dwEGg!xo*LQW;# zVFA$m8b1T{Cgr^$6MfKxffS6$rOS}#req7&eXL=MDumGn{Ql4T7LY`%1eNK2x?vrAs*21+K@6)s3F z+ha^Rp{+p&ti|xBK~D7kFN72iNqu;9lpLdwk7V5LO${xoz~mz=BVxpxcze$8-~PsV zLFcn1E_Nj*Cf>bshlI&2jkrSrEn``ERkg?`yGJZ6E;a!ZmU%G#dD-|1AK9z#W9`8a zetcx0%CkRvRrTpv#hr|zi*#vpSeE*GyG~*7Rea}IZ%Ta8um=^{xobb zWCvu8*)|6Z&$;IFNL+pJk!{=Nfc)314X*7-mnfrTJ~+9{Uui^#S03Ut+@b7b@yA?* z1;NFYz>~)jV63cG+0O-z<2qBhsA2pU-g;@o8TyvEBiA?~nFMZ?TOz?hanH11!+UCw zwD2r@5mLjxS%yt@02AXao0-*y%sz+zF1p+D^-jxIibF^I#9}#Ej-BM7r}pcV%uj7M z6=hcrR=m)KF-DCtyyxpI7&@ipiQ1H?+561`jE)l<2EeX{?qCJ! zxh`h=={0}6L{Y~;^0RkMRMI`3)hm-(Qea?$%x|{+WUv%vr)ctd?s97kmqtTR|KonI z`+3paA$dfm*GG-GIM|vCJ9-1#njy<6tOM(8Lgy5r8I! zSkR-5my%C&jy7cPBEIkJa~3d@J13uhj?}g=1{?6z-KPpw)y1a)165Io2=WUG`uBIo zVdM&X!W>6~cy9sV7T^6h7@!S;gW#C=@zbZ!j*c@GYrk6Vs0$kX0`k~zXlOW$z&v7o zRxb@mZIUc9~u$y6hXO8 zgtmf%)t{d21d$I3&H$ICBv*Vj2Vz7+G6MC7ac>3ogJkJ0e*Vnd+-DHgI&nWI(mFd3 zRz8vbfr+UT(CH*N@)NiKosc}#I{uSb-*bSP{uQU=zw{1buDRF`Gof( zVax3Vxl}lw=ZX0n+40m)E8?v(ZLSvP=2Bu0jy@GOH4w9*RZ3xm8Hf~jJ@&#*=8)MY zUT*~<7UH#I2<&|={t@Kw@6$9kf|Lny+6xQEqQ`L!DV3E2{E64??M0EhBRT!}arhJG zI$m#KWYl)8nU;ZJI`uu3MwTtclHOgvI34#Xy2iD5LT_OjwEb>ELKyCpFt>4Z@rmMD zc@pNfFWD0Z8k44I{c1W?SKp4!fi+Q*SodB#{oN=hJG;!vGy?G-G7?rA=raHn^K+Rq z9kSH7^$(0Q6caPjT~{R}b0Kn~*4BOPy71Hn(`|A|c6T*5=R~MuUyLpbQ|51b@$Z|PMe?F?Ykbt4%0UA%k zr`N8a_e1f;i)rW*HHlZO;n?CWaKL*E0M+Eq4qF5zU*P?9q;!3aw}p9L^U zMj`?=nB2j^aOc)~dN!q`gdJobF_&5#3xeXd0xT347h4X@LJr0@2FO>0zh1TW>r~OJ zR~Ma@Zfb4P6n!b|H)q?KH))idmXXzc^?-3j?0$7{r0H`eHvUaxe6XP43A%oLsE1i? z($lja)2j6N?EHBzaPk zh>#wDIA%L23iRoLu5sec@p>qXs1a|4_;TZ@ATurgNr;e40&2gdqHzWx_ShpoM3D8T zF~+sWc|HA?mRxOzss?OxdA--fh~N&o0cY*)MhE(kp2=KO;ic0m~zIp+YS8q0@&_aIGFVn0Go5}l#*o1;G@6aX0L zSL1p}U;BzEdpMte!_OETKn!*MxgtXRji|3$nr}=@%*Uics}lkw0;QAtCO6qM3eQ(| z_VhHC>OZDreK&eRCd_+q3~rC<mDQOcf0NLC0TGb?+QRjCM}j6x(bitHlUBW0ISq7+JI8I_Du85P+o zAqt8A`@FCFdG6=={eJ)ZbziURQoiFn&*S)f-s^Kjo9@%2r`tkD5Cpw}zP33*P_W}4 z>-9AFld)y$Mqn4)o@bjp+Tl|1`NALK^3GW|DC)Ka(X;Tv&H&wNsocrEs z^yxYxH__zvHvX?){GUJMmKI-rcjqwG&YgF4vuqC@Y<_)m{K3!biz`A#DZwqnyC3sv z=or0tnXsilwEkoNyYPXf_wJtDRb>9rpXfju5NkmcK7Z5e9xXeD=b!~ z37t(j{Lq#CSZ&}^-$I!ZJ56Ygd76d2G?!TT|KkVCN6Sri(nr+T+1dS8SE>gbPWM$5 z9ojmD3m^WZzxI*o#ful&MMb@Z-kb03KX*?4)TvWdzcVs2%I@E9jO4ozH8J5lF*Q}| zbKP$bum7)a(GN~`)Gj>Q9IF>^QB+)P?pONkVxf`zotoEU3Ojf1Tv_8))@40@@?_*@ z*%O14Z*J@F+t=Lp&@DbGDNOd{Yq@9#mrcjZxdPP!#5~00Dt-xdwF|P5Xs5O zR<(gj-@bk8yk)}e7Z5OfaqSP^Azv>qnSqZVyB?iBYIXRqeRIra(H%P|2qxwfNgFx` z2L~>0?&0emwM7qmRMgaXap%=49zGoU_ASQZ_C5-NcaI;z8y6YPDssF&n8Ney*+6cs z=YFBmx96@l4$n%Te9c2>7#h+MgAY2?nqDM}?{a# zW~`oo>rK!6SUcA&tgVe>g@lD8@bP^UKR4ggJ9vw z9Mn)&R<=BFKu249BZmY(Z=BxJ($dJpg#M8uM=TE>)YaBbm9o8+bzwQ0ZsSIm<@rhK z;Hz6zntMK0d!PI=>t}i7h+(3zi2!kSW$}!FfdBjiGe!1I)c_Xeu93FH4TO`UBNKC1 zSDxMmLP${1^w=?83jPp{8QqqsoXlkLL)`<_-jlfPDSynvD%R{u)PG1HK75!UEG#St z4R?3RV>Nya?e}W@7wELZzI{72GBQ$MUmtwk)A!uDhzAd3gQxV^2&~R8Q;*8Z>U&BK z%}#V}-*aKb>eg0SS=sdS%x&8bey$B_7@pk7Z>Q4K z)SUQGzMbF~5us&ZU?773{QeQzG2YbJNEs0kK?K*->`_!!77!7M^yW!erm*|*=_wOk z_`o;~4Go?*K@=7hJ&m@vlcPAbZ*(hujW+Azs#40%qcl=dQr|w;@s*aArtLW|Lkteb zsp}dTZ1^%fOkUTkjNKdG+%loc>S)1+Fgteas*?BEApVm}_Qa;#yu2;5N zt18cJS9w)0qqYn-$8vKixbt9L@3N~W2n}Q7O?ZG2g@vN&(S331t6W5x_xQdjZ2@w7 z@deE@YYTMs^9eRz*ZU-Ere*IfW^%=GpU#}Qg~fI^H@6HGUrE)AtC`}5ur_c%gp7=g zy1Tn`c~$*Q{r#1hnGaZ6nw~u?ho=~S>y~i!lP7P|WlvUl$MLEfy1TpQ=jCZ(=d!W0 z>l73eXls)T&&cz<|n-=UmM5p zt`Uaz`_K^z+5YDbNy0v2-14W0td7W(6pr6A^775C@!Op$vH_fJnxFQR^M`?xzf2_3w5j9yPq z&)LN#2e0PZ<0p;nP_acPJ8g+SUD(zEq9mXF z`i}nCv13&z&)jYo`yZW_d9hTl?y&Ub`Nn50EyJjbTGrOqp;HGQ-OCXwckarqoU%MJ z_u=X8+jBjKY=_Vd3}2?FrSVHh7?0KcT=@Eamvbk7h5N@X8V@;Kj~^E}c=w1o}%X<@#s|VrLXVrQ4z0is%~UtWL!^8SyffVucmfWWqhb9l1t8+>D8-Ob|+7Y zc&9!%|MP^Rl9DDrQ#Njm;+ZehzNf}t-zatKgk&Jv1_wGrZJ$tq@M~fB>co3aqsKVjL z=eoG;Y<@*WMGbx?yQ#ND16%vUHn2+jPFru{Q{%aL^Cot`zL60Xfy%^1MYAaw>-p5_ z)8wU&jE_5f?|b;+!AV9AsbjB-ei${4{~Q_{i$KL3PPM&2VfwW9%s|zdvPX|13JQd1 z7+008U`G1{htP?1(OT_}AHRg}&c?=8^N#C=k~a`gx)N9wT8(p|?K@J;g`azM!?F5wSyS8;V zQ7oPnH5gU-%?eOtqgTCiJ;cw{iK;gV$UznsS_U3|f!tTGjJw~w$#Z*O%FJw*r55Bo z`{lVH$Cb&k_UmsS`?x(u%Pz>zzZM_Qtm-!t997KTdDh3LsI2T7uUeq~mMvS(uCAOH z5HK`07Tmpi_vI^BwhIXG@$p@bisCP~GVaJy7xDG=?Yr-^k@JnqOM_x>uBGz4O~bGhBI5VPOdqVPR=) zXwWQr+FfY4^gUKN`R||KiRI2C*pe z8XNagYB2Jtja)tbx%P%p9y2fR>%aQZQ72w!8lZ^Zb&HCg$V%ewR=@wF_Rm$6#wz84 z)2jaSqCQwMQBkOFdx0pDl9B|s?=r~$P!#q2IEoO@<}F*iI4|nxgul}H)q66_45*ix z`FTrAVt9DC@!#jq$(3CFyRWa$`Y}U@hQ@{s8wPf5+_+IWa8dgAr_Ro6t1CY{jyUWJ zT0Tq1$T`LXpQQ2DB5V$X`-dL8@@F^I(< zb@eKV>9MKvJ0mhPdD7C;H3eC=0VDx743wjjp&)sAt709FUo~L+^7H4 zFI-R)6BDzuvorn5MU?K_zkmO<75beCr*RG*ec?E?Q65czuG7&wMGuYIc0ELTz zYT5$vF^08g>j*n+Vtsx6LAGDwVq%VOe-%_-EGa7L@t5+rfUn;cD1~POx-!OF&Mm8p zHraGCD=1=S#uI?nZe?-S>Z!j^UU!+Htr40*6V@RGQB+j4_~nX}sku3&T2`Ej?{s~C z|8;S3)pMvdEx9^ZP^l=uO;GS&#Bk4ad@#7rtY7C*d_Mie!+Z&*^-R3HS6$xRI+Haz zI%*FHEHg?rGpCm+L%0x8aq*G|wcucbDCz4rZ3;_I->mF2MI!8JA(rTw&ugok&CSgO zzxUAJh4;3il9Cb8(b2EQ2~$&35}HqZ{rWzmCQ*?UAe*QU-^f|@3sq8dn7V*{{O`&N z&~x~aNm;_KJ!7}xxo=#*wNfAH9XASE&&b$9l3Tqv-W+s~G}VA}H=J|?n6YuptgU0v z*1dbzQ`n(Ak?>kZM#l5kx5McUyZ`v08juJt;Mcc?-UlboEYG`0iVuCYJ9SDzmVvw< zH&lF&xyAH7I(-G4;>+CVOR^i7o12%N?ti4)E0XR&8JwFdz_n#dZeij2hK2@UntFh4 zlE8ZX+{cpNA}K6PbEwq10c;C5HstQnO8FNll_n3o#E7!9ljZ}DeKw-R(U{&S3m_lY zlXE*cRS#QPMa6O}G&VJbZak56tEPqr2tgMMndFwZGmDFh{8CbkdRKWUh@_O15k3QRSmvQhzr#dG}i z)|I94EFu`2HoL5hiO9ZpFYdzMWmmoJ+d z!#B?2l})c-Gk}}S{QA|5hDTxf*#-4!D=N|f9Y7o*wo+yo|m-K0U7u`ZE=CYNx1ZFq-6@J9j{-n7O$(^2QxHxwI^Uy&)(p zEFde(3Qi9uS--OMlUr36Qp3cjrz)k^)s$%duR1%Kw5ipy7^z-&a=qN%XhwiA6Zf&e&nHRcqlF7i_DVSw`n0w zRCs*mC8ZV=oN~X}kRTQA+b$%}SZer8w~)v2+sZwo5q%-q};cNN^YSaS2? z{y%#3Nb%z89ze3M-~N=^JdqCgbxPt$#rj*fZjo<{ih?B%N?ieJh=CEZf;j%Vm7@VqUV<1v}@Ncu3g8&y8Q{eg{hu2^^0nm znVC$0?)U0ew^Vw3PI(fje(HlXXh_qiPrSH}(7e3ujg5`c=e}7D)SQ2C?0Z|&`}dqE zYav-#e1Ol_($m|N5}IS;BO+)xB(0;s7aE(JY0#OyQ6KGCVP@$-wow;Ii^wd^%^VV z>T3-FKb}ScbI1kOe-fzq^5x6>cj8tLPSDHk-hDVpX4v-M8kFhb!@XbbOO~PnU`^oq zY6pfuvcaz6)W1bD1HQtvWVPe659|^X!HepcV}ldnqk3dWkp3(4GrSGp3dLsxHu6L6O+eY zqjb#7?dh^4(wX@6yL>*Dq0|YN>)}@K_Mag#hD># zw6#Z>RP{?g$8)eHR8>_gT;9+?7P+LsUk|3xp4hf`O{lKZ$aMygBkI_vH1iP6}eJU zQi%G8SvPNzTl7P3Zv(0e!9*^XB~EtsA>5QS1rJ`l64xRPptVmivSqlTzn>eoHpxwa zc?d;?`{1&K-%; zSVr{~Ce$-XG14+Jdp$j+gQx6NgMxzg_|NN?p2ilPnVBI>w+^^CIE22ry99uRNUM)$` zb`y8A=+kxj>vAV3=2pSs(-#s`)JQQm*mW{=e*P?|VWzl9yqc$v&)v#-O`S~wy?k0_g!>`-gLQ+!?h4!D)zsR+dRye3LCZ92>i${=_$UfO|Q{UJ)%vAIl zl#N;N&BkZX@*7Ue=c~u0P{kGc)6e_lCZ$5c5;)#XyGDtU9F7&UT~+mIk%@gFm%*i9 zkfK^ukNpsJnw0nv+rD@V3V6XayP7|yvUF(e#84zVjAoXY>cmu1j9Vk7QTA<<{Rn={5bWV@XLVtNb@wSN7*w~nfjV%l)n`Fr({`vC! z$}R}c-#$L!!~!3CU1Zcv>X4|1A0E1K1_lKUjf{kW@4v5Z6uNhM1E-|5MyjNZougw| zaB%REqXVO}P=7aZNfYRGP(q$(Ylc>tQh>gYAAq{4h2LhvnycKWprC**djB1l=<(KT z+sOUJAz>A~ZX-vHnbJBP8MYXXt2LdY5#3gkp^J-tUOqmfpSZcX-vHsgei|1OlMnjM zYUVRH1+~%3ejday2kjl?+tpPpJtM<>-#&%|2M%;WDRKT#X0I)HJunbuZ)9@PKs(>G zTO(n`AMg>R(cFCRR^_wV!!2>|r&4nt-Mw?C@X)tiUw^%}0Hj)G8u~3^C<9;_yI1X6N z{b*=UXJ|9z*qt~L0WIm&r<%PHcK(;X;`qW_|JZ^hcLT(UCV563#&Mo40Q*@%X*~j!r;QBkEtgpo26K z3egZEkmI-bR(2SI4R7AC9({BQ(j)yLTN{~;3lH(VcF6TBv4bSk_{~y+Ttd5wkBMSs zwuj)w1*|&#@ku0jwEdr7-v?~8KtaI~LLeUvzrLX|(f3fC^UOf;0ddj>T%2iQj8934 z0BIu&{KM|szb4<%l7P|Flqq#s*T`t2$i7U{__+JA2$wo4a4s<+!SS2Yg%!mVDch^i z_`U$pMa9NG#~m=Ww6ydH;EG9U=)ZJOD0^Ps z>g+VFE;<;;r+#&pLvwJ)xR$Lg-*&yLN#(aC)5G7F;|5)o3z!Ve$oXBb9$yC_HE^;! zZp&^bdcmJ^3C>?K5@&7kk`9|Wse%}>NV6F%^v$xcooh3{L-*1*ld6@0o!m zMoFL)M?k&sY$0pr>3;d7)Ksd%n}Xlp-^(%|x|JcPEmMyNiv_ukc?fzz=C9~yya!q( zq`7v6R6feDxwv*Ax##)#&vHO`?aJrAwch3Jd48E)oQZ>jMqFGR%0DSu42WH=c(wPy0rvTY1#Y1S z^>!81M=It+tR%+9_#qMiXCD%O_^dx4n(EP6p!b#tdTxjfU5>w`x#)*%rGl84n1a!y zh@KKnC<*S}Ez!H(-em*Zg7oU?=&S>(dd};?wPu)+tb1AuO_NI4B!e2QyTY}H4n=U> z^7Hjeq}L9Kht%COGPd~to{oKfg;U{iEw_SutAx>e$ECSZ8KoGmn6bTAdMub>ORB|< zXgl0pz?@DjuA?I( z^(`%W?$1c$W@vJ9gN=>N*{Qb%ITaytAizGtN?BNGxw*Mh2jb*VAk)Q%dUdXFoY^;ur9ZQ<@SK(}(6q$*@Zrq> z_E7+UIba_6zI(CrDh>9Lh23I_@qKqU%lY%?O%Gjsx-_R?&mG!jm0`JT_biH8Cg3Ow zE9)$_BUNGTpKEvAMH6V()6+jkr68?%{3{n^jRfYDl$5T$q#Ds!Ur)f(rp)Tl1J`<; zrGD>h!ukKWG%+v@TX$L@e)l0&#lm^EHB9{NUgfsoHBt z$DmJ>H)-zYPv$LKUhHTrfQ^L`slK)%>;Ca^I5vjE%wPi?>1#?C*H-_cvpy>@O7(=# z!J~e``h@IOf($9VFSThxG=U6lKoEI)?9nbRkHiz=L8hz+TB-H~EwiNd63&~JXP*5*KAd0qec*aY`L~n_+7%cq97`Jx!icSH6mC&)c_-zbc`q*L3}Y_vI!O zBqD(QG8OyK1)Us#?G!RF?{>MIr`GA-uu0b_*I=B)9cTV7`w$vXj}_FrnV|IIJ5C9i zF+tKsSvhl`8hR*%x}x{pK3a}U`J3fWaiOg!io_=;hub$rJH{Qb zddUrdGEsJ_SBCU~$yy*Lb_u>OfF#;6c z--I76jIJNt4B|uf5FlK8505y&PXSTU^+2~Wqq?zM*8O9m`uX{hfRvcx2saPM8oZvZ zW5ieErho4jxrJX*_s8JN(%M z

z0IP#yOGxvJ3XysSG2ipI|@BR?izQ#;$24izmJzmJ7b51Px)?2Nh9pd6taV^8b zp$FPX&EoIJ%;vP&UoMZjX=5J8r}+DEi$3|@4n%=n@O!o7UTq`fgU=O*V@?<*8uCHh zv_q-~>5;uC{%6R<$MAIpkBG!XR%%KLSQ=Ns0|)|J<$#-o6t=^W)TkKf)pR0gheE$Pi;q^+ukDj3I%tJ_nVD(tBl_R)pvIq~uwU7k*XMthZubHqABQpOFzqvXUTdHZ(;F+h=}H+kiLIA|ry@ z_^kLq2|=KMT9qGPcVX?X@5tB~xJ1=K?)3C@5E9YawbcNWIjtP)y(UGpIy{P=1X;r% zDPIEYQV_jn@!vp77+BowBp>|cSQO*>4wwl9#Sb$ zEVL6{CKB~+_-&B|m->YjHz$5OIY#sjejrxB9%_U-9zBwW+R$<%0LCS5C;9M*!SV4( zy!5?FuHU~o9w{*aG4Vs%KA4VzWSpgT<9cw$ZZ{4F9!1mJHF?htW-DLSH$VCRl&;=4 z1F(a^Qo!tiUTTlFW_<%{Cl}1Q+LbvY$(Wp4uMICq=`fgrs%l~kp4GcQ)&^{q(A2us z-sxy+Qmi5*MwUU6Jmj%09NMDVOF8R^v;{TAhS(R$4HZ`bQn2fh{9dgjlh%*4#h7%Yfs z+4Hy@vY0`O{(bD`iF*Pt>8k437s@3C4JHd5N(4XWgk>af7{AULeS`J6yu2)aUGbAEOAr_l&Y{&z76iBq2S z*}1cKJGcxxszs+9Z1j1aoLv+8ylwbnfx!(!_}k?tJ9y#JqQSHp3r76M!ZB6Vg8@b9 z;o*^%k+Ijt=0>6k9QM%{24uho;Vp)8s~FPFL4kPK#|S_I2fQk}2}{oI*SB7uKJlUl z#l>`_k$>nUo-G0tQ29KubH4Rg#`SB+{hxlzwZog4*HbT!B<}BgaB{!#%{`lgk5`99 z=&R08f8?%PncE12uc0lIA-S+w%Y|*h3<3vA`a?k(NT@^KzsF(^07G}enN^7Z2zz@@ z_ho@W0pr0tRw0NhLWawMl|hy_-#`789=3?T)PMfWhun<#!8`Q`C}rQi9f?-PFE7ur zZQC}oZ$Z`=oSbaCarD4}a0DRz&Yy39GqQ(wzx&8&&H10558V!7S+bK!73_R9tX}0m zolkr{$X{%3*1h!_7Kp>@%95v-*ItArYFC%t2H+brGykhABI$)aNQ-6Xc;bYYx{S*s z_m7vMd=4R$Vf8$k5A`D;rVvKNX%8hNzjSRwx1r|DiVM$$$zk&9F_d0iPU&1Y1ahDZ>?W_Xf!M zgRrl?;!vfAAc}hQ3iOl({C2-%TUYyf7^YuHdV25Cil{E8G>amUcC)A>38vp|9A2gE zLR`<-;(CL#;I~;=4~1;ENaa$|GUs-q$NSQ)3U1;{PjaN%4o*khw{N1ESqens*R-%; zg$P!U8Ud1W(bEZN3(H|@Kv@cb#5{wRp*?>ez+Xl9ja&kJ7gs{SLGrS*2|#^Vi49N|VG(lM zco-U9j@HyZ*^iJ1faz*nYa?s{c(4dP^ zU_V44e1(J{>HhzNqn`mak|{>SoSNRf;|Qgp-wV_KU8&6#l4B#$LwZcXt_>ov&B!(j zWDfIfqz|{N30GkYl^_rJZDxL68{tx%n!_F4*M3q7#VF3jNPSA#M4gO$271(oy^V94aH{QqGSN{5#!PRg- zq~TOn){9GXLL~SK(I9{TsA*^f#KkviEC_4BxzyItA$K#0txk&cX|C-*b7t4>l(aN1 zq+W^|Ww3vfGBYK9_9B30fE#<~fV`Ac9MK7H9m#n81GPm*p|Qu1;U2W0s3-(P^-%$N)h`%pYeRdzbm!ERcyOJF7Va0@bGnjXK%1B4Qy?*P>-XcCde;}3RmwL5$UwvaQWWgOgEE7@tBH%|p;uKtN1Xlz;p7?aI(#{yX$l{o^w8!F%iO-dePRF0|hZd+MW`|ZcJ2EU|=9#eF<_W8M;N1-31b~*PrdNxo)~EQ={bh`~-&T&vh5o)s{wBNxFhnOcHD4tm3e7n~>bTa20lK91lEitQJt+$l2RU|#}GuM zC9JHh>^ieGW$sh@ESP1$@PR2rm8Tm^X{s8@!o_7(k_n20cPR7udXVfHC@G48i)8~# z70;e&-?6S{(ePP`D=8^?HDGSzMeEb1jX?7M?LHO=9MJgq?|sE~2H+3r>Ui$N9Tv9+ zfffgRP;1-U>&PC4|H)|H{6S|T7G%l^WQ3r?LwPbn#SS`4rn`YlLqO~thMQx(@-8DE z7=lVV-BpmAyZ3~9Ug@=fczsKwFB)^_vFJc{svVr1oS;&SetLr1(cVr^%pd@Ms`vgn z((!}C&HiFDcHfJNw(+0Iw~n`Wblf}84B<{#v`pLQC+f$YT)v)!-+&?Ol zPW8WY;n0jMOI|}B4McF5oQ6Q29Qhf?F(K$Po6yF_U15xW01Pw2#`7y z31qAreKtVMY6i$BbH*P&e9(~K5RW-}?ba|<%||>bl}}@z$@bn zxed@R5FVjXTU+slMe@>k(J(h2!eg=N>wigrqN4RMX*Ojqzw5^@6UyslLQ+&*P1Hw<_ zFwOMUojZ1Hz;BfP{_rv}8i^Ubx(k2FMMDI`MFD}CN^U4Gb<;ge)|<=uBA^fdExNw5 znuh55YU_)-5cs7;Fo+o|21h!(yD#C!kaGqoh1Fg4m><~z`fumtwC?E9qmGV_o}ADB zQ7A%z((IsR4#X9Jl|lE>wzA@CzPj}a9=%wFH=<+%bS6kD4MpG5$dZQ z#0+TeC@Tco1yQ`)f#iKqh%}&BLn0z$(bp0ZE-`FX7EO``!O=jV{P^+Xh>gX-t0Hw1 z(?f^!kTyi_rnB5ZFa4+!k^n2nN?O(U?ScqEvxzGhzv-S_SPM7f8$4t@kV}A$WHuUc z{v(y6_~eNpO-77bxp-^h4&FT>NDVLI$Fc#@Dyy_veeB-=3&R)StH;dCIm#4DzkbzMHq4+8$(zK)~swgpqoR;y1C6 zkk0}@AxSNsa3pf2+hk9Vw-J{Zx0lA>pCpEIB)CVn*a z4nYh&4d8?o3|aGOjB(@tCBZz=veZU`3qB$s9R;K}6hu;KfYgLdPmA1ERT^)$|L-E; zjnu3O1Y!otQJfnAcJX24goeXi{i~O{v|BgYxQiAislhN4LbzxP9@Xz&bfva|fy{UJ zZ1+R2$_0{0_r}bKKEW0d|9kRHBt{I30oU9=)fgb*cne_@uY`5L!$JbNwio{7A;peiXxA`Cvbx8o#o&A0`r{dzi1 z>}_-qn&xI_b6_kL7ZxJ?h`Z_xzJ@y2g#{g5c*HyxA|u<@tv2I|Mp6HN0VZuZ1eG%| z0maPxKO^~32>cjAHn+60(nrKv5X4m(c{*lhjJYMi>pT#T>o@*qC0^Ua%K z8OC!{Z#PheXz1Sb1acxh6EcE^J4QwTvjXP~?v|ZF`YC;BGdZyc6fY_vp^ZzvWpbT{ zH;xui95F-h4b3Q;yO5P8f`P|@?!%GF^oR9X4+*f`p@o5{M{UZ<%cBDEn6Aq8PcmRc z8p;mias%$oNO}xGeDxZ4WlO$mbWo!a<1(G4HY%iT^VEN#5t1!}wZZDEi&Sv6s7-h7 z*mYrL(Z8ckzi~5B-_^y8N002?z#lYH%EFXQ>lqlv65bls4kJbc1l53SAuL!TcyQ28 zvfebEXI-9)U*0~9+ff6G;QydWjqv*sVrle;1>HvoPBQEEJYhzBl6!1Ntwzj`+?Ig;?7kE zcJB63VC%6+oe!plC=Z*Y9)uqxdS-T36PC@$>-{^#j>;z4q6M6Yal0Clzec!*|9t=L zqK&@C*Mk-oB@4$`Z1YbA=C|nj2j-9dlQ!sC@@w@|kt-2$3egBgegKYL>>mkq`;-bz zXr<*?i`La%1;@nqCwTfy@-<;4A26aW7G6l^L@U>YL^BK1P+-@t@^=gdIt%(njQZDV zsh}G)!R3#?aijeyZpNr)EZ?^$|1iC4KZ#ia8|H1;M7KD&! z%(1Y*2Y_BM@$T+*Yauz8Edo+AZ6aBA@Dh>CEiLHCDdctPrXrsN(sv3<{v)l-uWqUy zEq!|V#XBMK?De?$7;W{AZv;GqGNJOjDn|_M7-^(!`|PFwPc$(u2$nqrs|3W?lg=NJ zp`mGQwl*{AjH{K8Oh}_=K@5~%g+##s|IbO;@t?>nBpq^M2h1%DQ)!5)I$4fUESV)C zC{*S1m4lRFp(3+mDiZCz5ndB!j&e=uGzFx{Nm!WeP`RG&J0C(C3>aj^^}BhhqG2|I zmX$-wI6FPC84Bk>-x}1P8O&pl$QcnJ1o4W!-5%%O@4in7NeVZI8}MeuOkO@)~Tw+}KiNxB}rVMWxI8)&F8F zh8duY3qFmAUW4;wJRrbv1*#9*)zIA99jNYx_H+kmv@U7y*WrC}e}~~p%h5L$MLU8# zq1=K~y!%1u`5!7h_^{in)EF_b2%+ru{;aWSIo&wk_P=+FYiIrTkfSla@t410b+&PT zybVY4UjsNj>J{LuttLT75+Cm!5~4T>&Eo%>EqT)L%OIZ;W5m@R`A+MmxF0jNz7W%Q zr_I`Po)X0zFkVnZ#Jj~71KFw(6oV{zCHFmce?8zx8=7O7F*>H8lQV;Rht|}LrBN+t zw9r;0&WI{2arl0ici_Dy2msY}LR)qq6LdV^jgtv}AOJpig8s zZAR>|x&`?FMXc8*j2a-Dj)Vv$)ISQ#{jV9g<&8^UyJ;<-aCN1_P~5(8O!6f^Nlet! z!W}ync|s(J5KW~^gJT2fj?}YB;)aSy+S{at3=xg2>f~?=5VK>7If@${h$_G_KiZ4t zeaaUku0+Tt3d17gQ~dyPOpsx)^73-h$sy;+b8}tUkquZ3vn6X(f8D~%|D!h>paoy|@ zhb8(?>|Gs!_uI!h?B3F1LRzDJQ~1tk*iv?A(umCtZ@r|t`maMQ{+Wk1nX&|Rh(zF` zsOH!KeNnkEg`T*|kS9-6Q11WSk`J9_n0=RNh@e+LODSbic$O@e3H=(GsbRP@@*|>l zDp9EH)_h19rl(0e0L~vmGh+$56!mDXNTO1sXCp8*Oaj?mI^F9pTUEMmMG}o9f`<+r z0udw#?6mB=cVj{98Zd=`F1_$vf*}pK{i(}3?z|r>ky&@ic{2Z3!rEsenqMA&p0GX&s1j))mHTjnNaco zs=LuWAw^nG12O?47^pZnB;Qu*!Suotsv^f-= zg#2ji45)}kM%%Hl{Z|%usRk}y!%W-+aIm&^Qd*im)E_oZPCfXcxfrUB*T=8tq6l_( zb>$%cB>pgN)_vx+J|7ug1mV^Uy1R@~AI~q(HoUs7z=+y~_(7VS3(K$R zj~j_Hgkl>)Y0qHVi-g43ReM2SlCC;vIc~xz$n0PP6&YA224Pd-yKjS#4ZE03I6;6X zFnFETA1c7Ko>U01_X*OC;%B47>dSwtMx&J>oT_#$B{iv)7E=+_Xv%QvWt>1B;P?p& zujT{b(Y>=JX9vj~FfJ#cqQZ?;Uszg7llqdqPZ!$w(or0Z!NU+4tvvR}oPcv(Wp-@y zYGynRx%hb`C`c9efr5Z7L5|1V+IQnJ22GKAvFj;5fC)jCe)sJ2TS7q;1)yRtxnm6s zdQ~Ge#<|Quq&=e0Kw209jYuH!L7=EK#WT6j&Xt$R<+pRz&92!~e6pjQVK{qcITY+l z_%mw@yfx21zfO}%2;!Ss2o(SiNtDOp18C}>oETZNF*W6%k7Ed4>ZyZDpC|a8`0-5y zBXpQV@|zi?0Q3Plt zqB4;n0wTJkbyYB)VD$In_AdI@@BQm^hT+>EG4PSMY3Aq8CiKAc2XP3Q=G?!}f(dx0 z5?v-eB*P%zXWzON0quhvM=HE`Pw({UyB|7m073)00J4(*@N(o0VjsQf>T&wm}OAwmXr|UAbc$3whQ6 z4+Aac$rTau^uEQvFSe5nw0=E?Ffk^Nr(6!~fvHeZ^8?&Em6(;7nyLo{pVTzTGh_gU z>%kvQZEQX|_mi#{f?(3Scdv_V3c=PR1A#(9LK0SG1RAa$VrO`-!J(lLsO$>2xhbOF zbCF3|2!3$9Nc9WGDiGbSGheh(i5zhE$l{C0&(PPe8*!OA{cqt0eR$$41!B|x4U2}j zvz&d{v)a1#<KI}bc;b+Y^i(&@?jWmXGd3!p3J|=} zq;Jl?XT3yw_|p{t*7zOYvQe!BEIyTJjzY)*8gV*bI?zkQIkpY#8PE;;Go# z)fF$Ad^s*I5+c%GEv+t$MZo_gkAe`W#JLKjN_`cH-l(Yc*o%9=G}c2@2PMYIJY9%H zP^Z4sfpQNo6I75PARr*VBhZN&OnG-Wj|bDZN40i!3VIfp8r;RF2gO zuX{bVxdtwR7{qr(RyquO@xu?;(ZTRvHbeUfg``GGuDCohr0Dzv;{FO!ucXNeh>yEw zhN{*zjR46W(rdE4up}hB|7HwG^0u8j>7j>`5+&B<8L(~Kd4o59CHO=Gvo4DY-U$EM z!ng!sX_xrW;zfnu4UBCbQGyGafKBke$cw>23SSVLa#R!F7sOAGEk%Mza-C!N2gYDt zmpmDx#Qezvb5ERBfS8YqdFC?@@%k(EW2rlEk`QKD$U{tsXC)i3;X|Q_=3tchUnf5S zmdcD?MgTl)>GpK*0}&h!bp|toV}DVx_yq(g(JMibQ*%=@bTQzx|K^?s#COeb3JuI! zoP1QO<8;4f4MvbAG_Db?0WM-im{&= zTh{mmT@yr7J)on3l0{E7GYwq zEPuVXQ!;gQ__hgW-R@1#r6eU!ta98|8ywdY7C7Nv0A<*@Kf-XG8FM8XnH8kR;lTK? z!5ZW9=c`TAyNfpv{L<1)WZoY+Asjj|o3*xbyLaJ=YZCx1nVBO~GjOcUlXo!S(2lAn zPx5MOd0{F%he@2z`}VM!P2YUV96D%xTH1Qa)GIh1B`4n+r2`}(6a(g~zw6d02mr+` z8#2gTSzq4~R7yc%;l}p%yJmkup>=`tAxaQ4DVYczK56?k_j1Hj5xQGls|>}gD`oIW z>nF&lotqx$z0*^S(;XBMn;>rf!0}e5tr{mm58y|DV@IZ|!_98Qc_Ia3wx0cHn&5u9 z__iQJ$X?i6Jh`v0bG?|693#LI)4+qrcWlD2Rhr87gtz37OBiN-k*b}+c@ho1z3J)t zs3W94fXNEKtABm^rav}s5KS@Vh4##%^XiF$g@9Ffq8ae4?&y|{{N2c;&5s9p`On-MU8K{YrvMTho49*TpYl?FC6AXrD{Xmlf} z1CnJ8sEuSM-@3++8BBuQ#4yBu{rD{9a}@X9Y9SgNgOsYwQlht)!ZUalHh#+HA5#}OPGQHF=1 zq8$J9wZBpd-^a|#YCS|N(o6!p$Fm}bL81!dmo<3kD}&}nHed$O{=^9ym=%!v9=u#q zchYt`?IDTsnS-e3m5!_)tPSv5mkuihFCLHvFeJkq(t?E6gtM~)@F*7@zIFW$I_7_Qb zFpq?Uy-4m^9zALV0ayS}|JDE&Eo3iV3wH}h9LW?3UC4y!E`mplv>_sT7Bfs9mfEi~Y{dm<1k%$XQnVp~SP zu&^Moo0&dTVhN+rvKL>zd|BzoOCD8&V%>sy=U^BVFy*PR=bX#mgcmFf{jt=Z)s%RX z8onId(O=9+MkX;~I)+0Ax<=HsynARbjbf9qVbpJ3y#*gxqhY+IMlWkv+dkv~{CAiL<;UniET?0abWLYC_hRKTNC#A73XcWKG&hwfFL9X`GF{cbE|FD2<&%>#Y} zFXi`5vPK->3#6W+BFHmBz{>$@C?Fw0m^RP-_ITT+sZiMD`cF@j**}0^GK>s_K%Sxo zE_3~W!pjyapfQ$%LG^RxO~s6T!H?7mJiaa;w#pBQHNUXm@BLKh7{9m)<;&X}R0{Rm zB1_er8SZxrmIY?~@9k}Pon8zIUKk4a&uah){;&5dzGJIfTU8-(cy4av9vq24o{4g( zc-i-RpHR}Ly*y|l%>Jtg9-u<)h20EvM9R=uwdr=x#*#krjCEwi0dvcCK!EbZEJ6DF z?RR-|F%~d2^1}o`gHTec7S`JSDJ3H4dAEN>`ZAfmCz%Vl9@Z*taAnPnwJqxIx-7_+ z;668Cb&)d|mzF1(UFMvXRh)|)V zXT*di2$5&pbr%@T&W#$82fhJr#}|1Gp*oSlcp>-Hn>Rmw(F`9Q&NJzuy{`>IinIwC z)*&r30&Eq?LzWywL0KbpHLVJdW>nz#+-15-ylbi&OR^UAZ{?aED0TIC1Kf zByLdI=a+l{Dj;^{97&9n(~?4P^yy$qAehc}4+rB(lHeCMxA>{ECr_9V2un;Rj5&uR zS_oQk@0UD`x>dg|F{Iza@YC>|)6#8GQGvqDf%uj^K0UZiY;Q{d3SnHt0xF(Ha61Xx z;J}x9o0Ol6n2JPXz&;F|GSbS*Dycd50OBg;hROvvH)p~X1WOm7gw4qn#@(SyH5_oZ zC`{N9@uV~bq*eIwiA(v#;ytC_f?&K=rZbKQoR*fh{A=AnpKqV$PCM(>2c@Mr2jQn>_#vc z5fPz3vFXjf)(sI6rB#%^8Ll^k{NniKE(fKrn9Kt@W$=D_6NPT=vL(D1WE(DyyT>Lv z+kf}dk>kg=1cI>Do$l_Q9MRfOXX1}}*7_+es9T!B7;ik~%{7+P|1{WfRAt=ZPsMaU z_Vd4LEY(2J=A7x9mFb>$SHIarbDmgSy2-QYHEq{aS9%-ni8xmLsr1sYn&e}Rd5)Cl zqdFNj;Nlg#Ev)?jiA&@a0yK$MnEBm%!Vx;k(Q)JbL6r}0*gZLScGZ*m?w}ot5_j#| zgPY;TV}JTv^|tnBYr9Q~%5UMHwuUZCv1Z}4D-Y%19=&W;;i=SLMyTw{JI!I=64WRE zndH0e=s0 zc1uk0lUsMabM&+e9la|L#+dq!piFEGo!d$iA9K+5J~u_cUH0mg8GE9z3?N9-i%4KE zTZ1$iT$c!mQAP}i%3f78=?U$2DA=zg5?-vUd3^)*Iwp(3pIcAly#ySWTp-Lg#>fQ~ z=cq%gt`07i7aRbMh@A@n30o)rh0XVGijk-scBT9WK?bN5{ZMLP^7YSp;*33$?&?&8 z+TN7Ut1Sjm&8^?ak%xPa5`V@U(_zh;>2Q$fwLQ?+KOt?!!nln+lNDl+&g{y3pBPFNCa@%V2 zcF!fv5s=4W)2+f+J-6OUXDb;6J4_uSp1W@!cGZhu+T6=D;H%_p3DEW6!AT3xFQks` zPD;v+pLGMM4405ZxQzVLue;%FL?$yVbKP_DuGFW2-BQ8G8o66P1;fq52E8pR?NLe79szNC_pf3TbYsi!n~w z%sxHrw=zFA=TcA(d`10W@Pg`G0C~lnNv-{N+~@z%T>KSvVxykMD=-D|Yd}MM;U2Cl zTK_NPr^sMaE-#lvj*4ScGI!RZrC8gcp9;zn4z}aDJv@~`REn-hX#ttn6?hr6;Hc)C z@UL7T%LpDOH!rVsd2a<0+)xk`3gejO;ty@8n097mTZkKg{Gc5>x{x{<{r)Tw90V9l zFV}gyZ0xq_-{_`Cad2@4=X(IvxNS5a#pa$m^Xx?y6uHoUig8tpWRM~Wd82E2%cUeT zK=+7NX%Xt%@K@Rh$0N3H&;OYKLp_n~mX{kYEnLs4l$Fhc&CSg{N5ix2!1!q^#XPMG zRX}N%&4DZ-1AsRTOTGs7rIJK#skFD(Bo#U4V|GGGt9$8q$;8Je#i&^P`89-MZMosT zdJh$^C|G##1+O^(C2pD1NZf8e|M6FIF`1A80aNdVbygC=z@1x9SREEnUs_O*zGdsy z)o@J>C=CKrQy0cL>hb9%hbsDQTP>|cC_Lzbq=f(|Zj00F%IF%7M%XSDNqae7?9;o( zEBbq2l0dnXKNpVtdPVYQMn9x8D`izICv;nONCK=eM#S->I6fr~P3jAJji*>*TyAg0 zWGqreM49^OT~aKzC6u8$`uj?Ji=Yz(<1`;kIXMb$(j-I|WrO&5^sKR33nB;q!R?8b&6MZ*&rj5xc7~nT-lR z)*bqmEB%rZ{+|{g*dZ{?x|iN+aMCAe`$wUOr})ax@ZsFSq@zpVexy-{lCcKg&?w1) z6g)!*Jaty74oJ5gB2@7&zTyEF8_*EaW#i0jTZ11hrx%BwS_4TYvQFTWu?u|Jyns5o zft->Oeu4`-_1mipLxRTI+LlmVRcF0?`t*HK*$Z)4Hweu-4^4%oIj7cA`@-?~!CO$;qnHqjFRG1fsx*r^7uzV=p}KbMig?|)C}Tw+ z57YHRP*X+x_|I6#iVS`YGT3Tubbc=w9V7xmngE=s>|Ox27pwO>7dGQ*P#)OWp6_pfvW) zT8ehHg6b*U6v-bQb?;4PS&cjz~LCTI@ z&@gQL`SW8c-}vov2)fSp%tqjk@POwl`c3|(`STqZ3u#&B|MmE2NR3K;i*!aONaR1s z#h>rqlz?D_L2~fn2GSeQe$kN5V#{GcfUoAi=I_%DwJ-dE=ftTMRq(R-h3&WL1uu?o zYht{sf0zoAv=AjO#_xm zKQ;vb$bc))_n=v@T5~qOy7fOe)|Jr^H0MnGsLR?gUnEmk99`-JWeC0WDXg5|Y?Ei^tvUN2X`I~j*3(+)u z2QAf5K`4UOxA*k)@lT;VquwyC;_!swRR!v`dBK<=g}keqMM8OP5-J48>(0*thQjG3!D41)!C& zDJhQ+WUicitZ?^YLPR4UG?h(-or#mq+B>D3N|azSXOK#2jad$ZIi*UGdD)f={w7{p z>3}(;rMM#4O13Pmt;5?}5dK0t6$nDoZ|`lzLJcc!go}rV0Ddrot2-MD@JijxxC~b) z*CtJxv|8~);I0|swnLYi#R8I)#QDP@8^oZ=0TlwHAwPxIqe02nx;_Y!M};)^M~cUD ziT0mO*Dv;EDn7}G)^rtq<6Ec=2=V*hUp!HtONTH1B1xRZ1?7a7o<3={bwEz}#!s zgnkhk$iw6H=npMfu+kYq7>OwlRa z{bb<2Zqa&Ne}avW;1D_Gj4}wiD&vlt7R%8#rvLLDi7B2fDpJPo3VuGFChJdBTfC=v zvlEQYonG5^`yU>CBs_;5bb!aABDMPfCTDi1O;|0NU@>L$7Z^VJ*c9b6dwJT@0YT12 zz5*euzm}5SB_epdMJ69I|3IJmiWehlZSMYR;k3VHk2^-M>y#1@$8x)T%*V@ezf&#v zDcbhXf`Wq46<@Jn0Zsj}SMw-;Hxz^*Zlo~tP}*(CKwnd2>P|3mH^DsQ-XP8<>Lm>GAUIyJSdhW;yj?eWNg~`VqZafzEdzphlHC z*UiIY7OT$IX`6bnT6S->?8t}+1@9BRST{XA^Q3kB$`1Ik!987|YDttco@);kC=n=Z z!9DlQ}mc*IUcxI^&h3QpE8&=JD-;W-CR_7;mCeMgZ?2SGjk`Il?KCy z?^tmaHU%@XHT7sCKTd7xT#H72n}3{QKCSPT2Mb7wRw}D$DL0(E2R(-a#CqH~^g`eW z1#F)v8bLy+cgi4Al}ZzsdC7n8l(uPRJ$FAW>xmuP+^e#(0uIV#g5U8^DUsm=##6+V z6F~LhF%6F!#%aRySR<&vUCZ6}Wr7SvQjk18;YFf4rJa?TnLqW7jZ%qtT&ru>aa%$dJjCZ$WOq0@iK) zaE_asC8=|e8i+FKRZNIS(bGd1*=6XEAtvRcxL@eCXN~Zs*sfz>hZsA1eFVQmzi?^Q z97$+j^1}ATCw?KxLhDi7g@?JJ+9UaGlv0UY|GCKn6dB9+Cu%hj?v-K+ra;7w z#;IF2Z8{HEk6W!x$F3@s*W#y6@CO1{!5lIFVY7`fHSx1k3{y4}iIsBuT_seVkny-wwE z_oNY0Rxde|SHEEGot!f;s2 z*brV^u#Dj3WcM{~n~1ue?AEySrbh@GXBkQZj^2J!l$WQ*`rcORK`f*!*mR*xmoGnY ze^8io{bu!!&C@rR|vrL=A0nOXbRd!mlwf=ev|;gD_Hw*9l#BxD-b z`+$yHqN8)ae3<9vCWMWoTq}yY9Ac5oqQp=vuM0%RhYMMq-hs=sz`cL}_jKiPT}!@v z16mHG@MPoz9!d+jcJI%F6g!_vK!LKyCKVT4hDj+YsFBVCV-#EaONy_+Bb337&kb7u z_uXM&V$#f-&4#TMQitSM8RSZI0QY2osV-7)w)+LYm6nW}tjl|&Nu7x0d=wQtQYS6- ztSwrZM&pJSXki2vFAv&h4deu~=g!T_$q7FB@EBnn5+B1e1TYdNVadfbJkX;ZJn=ZN z&|Q(5xITQ)`my;akxH?eC^9CLEv4rEM>7?Qj9+Rj!l3}RY!XI_ZkG*}p0c@cHr?m; zlv-R+cb>r*?ui5_;~ND0Q)LhAKN*DE>+$TP-@A_J@1^_iO81rG+>_%(4PKF0tScR|c#j{*l(mHi`}KP9;@ zx2o*h!Pr>=SqS@WbZaFjLVV`NEj=sNsK9&8`4s+|UD$T4F=t#;%Ywwm4Wk55^mg`$cH4z@_lmB|oQx|Q_{-UaT8KAqO8ePLhE zCiS5K&Pitx!_noba} zLr^I~vs@fCNuCUaj8x2cdXRo?_1CUdRaN+jWSBN2dK?{LM~(5@q37ws=WoTHVO414F;?3(IRw|z+9g`e{K`Ge5~07Lq9Hf z1C0x%1j1?rW6=>`63xF7cGXlt>X4IV+w;CVboTXq_s9QFE1*=8S`M*l61$Q<%^I7MGma?oDqqupu2n z)}6~+@AcKyoc2#@XOJ^`=c@(cJ0PecVkHFtP=}q&cVY=^YNtq@c^OswlXbi;~uNmaWsROT(W3hPnPj0InaFL27#sr_ek-t$7k zaBNLll34SnXN1)`F?6wveP*Y{fPpOoTSRD5b_Z!%mS8rZMQ8Wg6!xXp2+ zc>C{m!we4{X4+Rn} z>0Wr=;gMGN;bQw9}sjk;&^G-|8BSlpft!#JiUVuzV0p7e%%sS?a zprWXF-{l`(XuvVveX-U5W8@^KL?Z*Mc0Ew>!EA{wCvHSZ=*2OkMaGUfDy7sTj9FEasHu=C7vH{n_b26>3klPd zU>9KIE;dSd`{1Y=G1YzmGZg<&OZ_Njy0snoZ>s9J^z?QT-2k@1yC&`)p*B5Ff>bVf zID>DMk)5=NOZJZG{4`TdK`}%`TwB0Q>ZBaN_@K4RZnnncg<1eHiHLGRm4aD4GB}i{ z{e(h_X{|$-{NB{^xRLO&(&GX^$yCR%!f}h_ik&#QHYo;NL+4PEe zCvavln|=^YlYBgag&sa~dY}3J^7dq;e~0Jx(x|2Q&_4NVaZkwm{9>K*Ogp&t<)`Z> zgbo*obWq+D}LFt-6cFCZmIS8sRn?A+Zjl3Ld+v;BCc%T_hmD}s8zXRyXWz?M=F!i zI{AgQf4(mv!Gd;jZr+nIM-%t%jUuo|JWF9=?A|tPX4Sy3bCNY1X|^w)>FB6bxRI-o z{d{qFST2=*__UPd zo3@xfnyww^Ldj`Dokca+U2o?#SAlqL|KfkHc=G>5GHj0>IW|w#E9~`T`%6}^#5E)` z0CR``9c(3DEdXZzCRVeX_wMaQKdbk&i#V8>|1&(?b4Bqd-8~y8I5#N}*ZIva++cH{*jw#>9m4 z&(ppqqq?Z5eCNUfk$OY6i1J3pov|mnI6M0RA#ygU5*jWi9OYhRU5$rSzU=zuo-La; zb-AW1`JA-POicQ7#ms4+p4Ls6b~fxOJw`1?-A<~*4>GJ5u1_{S<(zF;Lk%gPw0p*h z`~KPU6`^}L*yLe-JTa}WBu}AaZ1Q-+=63FN6C=cU$(GD=X{;c2t_ilC{C>mc-8SHp z_Vbp(r+@tMS^snSgm@HiilC>qwXv1FA8q!VMoe0#t8NwhZPnKXXAguFD!#qes8N%7 zITX}DiRcS*gYuETKcOQL$sLuM*Q=X7C0!E!PVOq}NTEO*ltltp6=B;nVQP4lT^HBA zk729i%OSvQ0@4V0Q?aJ^Oov@*j{Xw)s2np!23MMIX%UdIPQ|QKTELL_SCdCj4_*W| zkz6Baa_n(0x#_WAKXFfEKb=oh(Knq~_+|5v-QOa8jotBM-O;hcFclnchasYw?;(#Q zjgose?0iM-&5Q+Uvgu3AyM6dhK($ev`;IeQ;(?1tO6Ctk%qskNZi1eRKmjF3r=Aw~ z(7d6F_hJk+D84I!sOvIkPIzupev~#JeNh$Zyxj&5o@`Kgu-ny%x|aJVwF-^*QC*(5 zRx%OLH<`C+Pj)!6pJs2b^Qro;h|2L!9lvRijw6hG)+0l)fN_4aCpHCf6?X>hs$zM^ z`^+p9@lx`gCVL_V-JS^wfi2AWodee;{_&yDb^cSs)E@ATnLEN2q3_X9$Z-!{wCMHS zK3}N6WX$e>+t^L$1(Ji zQ6)cqr`hs@h8I+Ky#K?Rr0~rz-lyB=F?2dVdnfNHIs`uLsI~Tjb>ct2bj0NLi5nS}=?Hc}v{;^cd_PIqxJJB4-AXJgFE9=MI zeqZ&$IHV3ALhB?erJ3W0I4pu~G-W;}CbL@r&=R3@JHe)Xq-UFZsb5Na3>&sh5kWP` zM9u!|(cq2%UJ-;#U&%%%E?l!Nfk8ta)s-jt;<7DUaExj_Q zH03Jw3tQL0vE`cw>SRCO^-*)>^>%4zjE+q@EAbil;LMxpJ561N{?M`aZ@-R3&C7)o z#C@xL>DlY676+=^Jbd3*s|nGCcrBvy^P)DB4=CwuoI@!yK7L-?`D^{Ia0*J}-lbcw zAl5ZgBK{2j@!`b_7jCW=b%_waAgapD)WpQQ&*rLLYWbJ#-{8%mKo-{;+fTY`ZN0j^ z=J2}&3;XNTV!()?olMhi14oC*a5NMoR8#H&o5&#NhpP1pI^==rtS8q@;#mbuKPR^L);NZont1m&kUt1mhpV~A5dDAkgS-4ZzDRwA23C#vV4_Z?wVh^YK;1H z2_HImx+{f;%sW6vDnmz4oH$|Jdy#1)?1#

>jQf1VIEs`k4o6w9{Ax;62umW9UN9)Z3W2mV9`;n!->qBC{h^YcMUWM=tjft(@eRf{FL9SO{`1@h#M$#27{O(=7S*_cu&O5p@j%0wdLfLc%6! zTkfAIGHG$fLgZ2PfeH8eFjfmh3H-G3QX=J=1NG{&gX z%DyzdL@*!O2mqQ9$IUW#`SN9u;=6Z5W*9RYEX-hSD%OExmn=ShJmsILv?@1ToyNuD84OuKLsspOSe6V6I%u} zy)IxBGgR01e*)ewA)kp?|2GhJ)a@!+qTqSsNsM#^HKA5mt76u9!|lc!j;U+Zw{sk5 z>B>ZLEhauIl_XL908Ki_*Rs$Q2uG_!2TQ6|C@W5zaO@Sf%6db+?;)%I7o~UQ*en1> z69NH~3xE8xrEAr;AvOMBVIu0Ha8P8_ihfjsO*e9?C*6{`oguzeN~Ul5Fk$Z?CH2Ao zG7q*;pvU`L=5;)u=MYZu8u_6S%{c{?q~r^ePq9iZuZCCJ{2?eugObM~+C=`^4LRF` zkb}Pcs!q|Yb{(;*iOdN&=hvX2WMh$9Z1W=~tmfcIvR(=Exs`sKIL2;U5)<_S#@6d6MymH2+{47oTZg%geg}@P2JRA>;q9Gt=5&85|U}o6g#ejAaRLow&=&K|Ac0 zVQy<`8i^(X%vQudG@ZGsN);5jfHOntNHYSl`!a%MMK0ei5#PVgqh?!jlbA*F*6Ny4%)B#pAspx7gJAsmv7m+ zoo17ua@o4QA%eOriOj?~0?*i;I3=!uR{z&@&Gy%fngW|4inV+Cy98T6D-ggb>VZ?I zeu~`EL&H63TgmZ0-McsBBbD7t)#0mNVB?7yiHSkfXit8*aLLw?msw;OukJ;o0Qt&LvjQCR(M zJ!W%Y(g6A^S>U#R{p8N4%*Y5(TkU-CQOJqYr)A`mq?op7F-PxD8t20#1;keV1>E(b z{p1LMi6=t3?<5OVleR$Yx)JIVrm-kOXjf1+J>@p9D{?xsav+UcDBmJ6S)zl5sS-^& zVsfjAKBFE7u^xB_WF9H#dMWKGe462a!3vXBgUx!5%<2zx5{x|d z@Y@ZIz2*gOeiQmauXeiA5#L5nb{&SQj~Y4%RiF$ynLg+3=7F9*HbcRhXkbLTy5yB! zN}*T`Sl*!SgB2nxv90wP1&r1T0H>~QCAbKKQbS^bkd2uDUc@Z=ixXpjS|Y?dHygwK zr3^9d=s)kdQ#}n zitOOI%Xh%^UoKHf`|9*2{)$o=V^yLsi2|#w8ghcjcDBPGF2?4t*`O(fe9;1 zX8pS!tJD4#c(lTKwK%N&uRPZ?G+cf1waSw#%6KA-knLS5|Pd3QH>Xn>=8=|86vE7U|BOleDcdy$|KXqc` zg6GYKm=TkD>~$iKU8qRzLs}8;Yz%i#8?YwhR%?bKaY9NOF`$L0SuujPRLFc#8EV9> z7b1n*H+R9U8WdD$3&nv&?<$jwg#CcT7$c+<*)j}UZvh8&p6xoi4t`3cS_lb5oqg}h z9^s5R9iD&zB7SUG@;EkzEN~foD_K0(uC-v-qUaNW7O7}4W;Mu^1Jlw5{u7)KJD`^t zh#E=h0>^+ks;6D$szvn*Do*3t5`MB2D&`VZhj_R|@bZ2xrFS(p9s4hT{+r$^>+)r* zvZ=+7A9q>PuFnN7csIWk(DdTutS5`)l%^t*lv%p`v3=XOpAGaN@eHg47e+N4+jgBs z?8(!oDpc#qdDZYZ6cnATqPJdo_-0q4%uYq9OgM)+dK`%6z?g-N{E${zxV_t#;xfy3 zwk-=C1Gznnfmx0XtLl9ADQR{mXGhcHgLc^l{JuHe1^;~qw71AkuGnS|4nTSdLvc;?LFWe&%WkwVCNR0o&vPVIaW5@Qy)@QAvZmtFwB7d(4* z(j+X(&1TO@mo@>E78&=J{h}!9wBuu+cWVFWu9|=MU2JT**lvYWjoGL(BRvke=BUHg zmr{y)zg#*Uud&DtkX040n7%>OXXxZ{ZWpF6P`By*!790Br*hTWj4O6EMC@c=yy!}e z@8J8wvv9(cDd8wk8OM-%xw(Hz_;>e#>Aq*rf4q5PUZ6F)E`G8|-_e_6qz?BXVss(YCRwvO_ovx;Nr-};N@A60O<*T(r7gO$>u%Stcc}X}#tV>pi*mecpql3$Sr=urXTJ``jF)!(i;`tl>tZw!|&16p2 zux;zUdNX$J!X#i_vtn~PVW1%t1W6}O{PJv6VO7bFI!9O*TOMe9O3GL|PtwoL_`lh% zuI5T5o>LRJYCXM`wUymK25-_fy`pd>3a+o?Bw}+&gKKr;Y+xS9aZ|;n&71o_#8zxG zFbUEn60b_ZAOvB+k})rNJR5iH7^}=Uk2*YZg%R5*Wd^q7|EB5IeQThq)|Qyy*#5YO zM=Hu_V%8OA={Ry#q(K4ywaeSR9K2^92Ax|A6!{8EB|4~F^kf9ax`Dr&7w>19iJ@gp zecG~*x|g%PI-fh+sZrxz$|rWC%q&%{mAc1%WuE1PLCS#pt<`TdI}`4B%;Xp|fYKWI z53y*~!7Qc4lbZ#1n+2Er(qr?Z0Y9(*_~^l><%OT#-~M(5pc&u%^I zaJ0edyo?BQ*r;p{obkgtQd3%=ZF48RUT=KD<~=QMYdzf8cj2wUoz~q<*{0j13?Q3f zf#7{}=FUxMtUUSXL!QsQH!Gg|=#*64EPJ!T_fzqM>*IU0=G~jH{qzmDpyG-#Jz6tb zYHebUeY-WPadB~QBN$}V^diF&JLKBx2Ub;iE&qAv_|Fy39-78vrs}lyj<89cRKsu( zzzyB5>r3nEI=y`Pa&=|w0sh+PUURP7T%Q=3nwt8{j2Rc1>OfeZ$@M10T6F8&qV&z1 z=HG?KsvZ(a`t94n-1nRIC*0ZT=reJb!$HStvjrI=4>~yAx%JAV?(^pagP^;2Cz%W$ zy#L_7F523Gx=n7HyngqtFZi}r_uUS^q)eLKzhjRmt5<3CV?d1uQd6^D{pRZ9)Ad}% zMjx|Q@5iN_p4Jyw_guwCo4Adkp=uWU&pg7*iWp?ks#QNOjk$7Xs?&%~#p}aI*sW>0S1(|i)$QD(d#81Jo2<{jt}#^E{H%H7hWbDJ;N|OURFj!q>P4jW zozmmSk4KK%n{e*UUw{2>G1@vM?fC@Nq~UJ8Hg7KRFif>G=yB@tg0YwCR*mQvWBbC} z*VlJu=Z+oiGd61^^}SeH8s|1>Th89Sd-r%Gzpq|tcO~S)LZY`gqnZ(Ojq&gDAKML9 zV~V$%eLQctsp%{a51YfEChJA|T`KKWHw+cdh1WGcE8C4OcDl1GIbuZqoB_04Oe3$l z9(ts4V7H33lwPR!@t;Czudbku=}QkvllJ0`;eYA z&pbB5wKO%gL)WgG)A#S*72Lh8-p#f~hRXQfj~Dnd19qwQPi^dC_ah4av$7bcJZSD5@Lya- BuE_uZ literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/class_decoder_factory.png b/doc/src_intro/img/class_decoder_factory.png new file mode 100644 index 0000000000000000000000000000000000000000..4c9d83b6bfd9b7b2ea8e536ae0e14ee21e9fa7d5 GIT binary patch literal 5466 zcmZvgc{o&W|HqG^>0%#**x0FS1V|WUGPKIhz@&-?v)-{HF2cc>{?DIf@z?ivjn1Tj*fRBr1(PhL&&)i*HUY-_+pn327D_eRQ{ zZf-6tmnA;(b&O&cAF1i$ewa-zcaARhRSbqxu&2c;C{eREL6Rx%(j`d-q@dc1WHr=v z+q)qcqlp}K432Va{rJ!Hb>X6X%t8E#@p8ep@uTB_qrK6iRId5spY^_-OG``p8((QN zicA^;IF!uVDGx}MCo;PeNnlOHp=4yR7m7+GBrg=Xd0;OUx!;INdMZ7B{J4nlu<(+N zjg9|J#db<>9tGE}PoF*wmD%4FEzMO}OF5)e=%tdzxmma1z*y;Quo-I#w06omgAF?BgE)%T6Ej)>gbUZ+TC3|;CQnwV3}@=^~aANc6N3Py9<6%#IFV$ zu3|U?k@hw=14SqXTA8)AwFh-RlAld$URkz9|M?*`*Xd7YWa z$@rSi9T*IDnAMP;4lNHBg;rEZ$;rtbTBU`DKQF1{_=iF@#tW9x`K>#R6mDy4+tSj) zEha`+RaNz%#EM+lq!Pm+>j^;*A3pqI-FZnMP9r`k$#QpPSU^OC6e=q(p9Zfrq^3sp zx{#2V_4j|0<$Vo%{a1#>_K%Kcq#6#WO-xOTeFzSVYe9(VnHdXPTT)qB*_Gi^Qt^bY z#+&$uQIn^;6{1p7p+!X^?j9aQ5Kh?ir54}Ut+`G*dU}|P%ewICQ#nrG6)~tWJ1v01 z+}s@8!Pg%@sC{==-p+nDsd{PM`Mzmlf>Sw^=38?J*ZME~dy1BhQm5z&xyUiENBOqXhQPbnTXJpits;;j7 z$j{F&hHzH&4-*pul&ziOplhb9`$+e6#IcADs&E=@1@Bo#TH0-GtP0VQnTdcsva&*y zmXs{a&Z@AnvE7uA_>!KEaj#0AX^pZpG`z&Xz(9_nWD-W80=7E%NgA)-|FjVyQa@GN zjnss8wzqjvsdC;}=vLsVU%=kDSF*GRpOcf5_e?9bp}syG3Z-Ic-q>)>>v!njQczI1 z#KgqL9u*b!+fG74QgW^(oFM^+YsmgE?G6e0;lkz(Lk%#*LJsKsxxLq7KoA>gq&jVR=~-yR)&89ujh4bYw&w z>*nV6uEVMzFYhC$wjW(xIsFbO?EKFZOB)+LM@L5%Mn+Xg&Sxhl)3+;L41Dv+lP9yU z8LyFH__dR{QSam8SV)57t{JhKC=L$~lQez}rPU;A>gy|wP#EV(NJ#kYfG^0&dF1ae zkJ?(TnB;>#WoMV><-LZOnVAI^W! z6;uiO4?BBbNB&zVr%%qP$o`q^2{qZY&{s&$#DofRb#;ZHcQ{-|ZZ7IOe_2@>2BD#$ zk=|qX$jOO1M2QI6AP_=8xnhzk2+-8hlHj7Jr)TTI_WV6V!&gg74ndym930fCrK4P$ zFk)h!*p5uOrf(5US;>t#_cE%76nu8V zm!+jyAW_?&><}h4mO)TZ(DiQ@OOQuOa`M#dY%mr}4|GiVgYML*OT)LtzHBkj7gStG zb_hIFrizKZ{Z%b3t*Mn2Dp0wQqN?hJ+Pb7kh8p1eK2j!69~OcM@xBYcg8e z^^cwLF020i!}arNft(_>8!#Yup`SkST{o>Ri*UYuMu++q0B&bv0PVs91c-=;sJ*?t zF_@g;i~F1g)c8>~Lf71!76?X3iTJrliHpYHlBB_c>) zkWuj3wPMRQ8o8sD(wu^VmDseqcke+HO-Mwq!>`Vi-cXhQ?dCW&14lqP8iL|EQ4%z_1(e(2tO{vX~rC1Rd zZy0;?YTrQuS{QdfSAQ!DXZBcGIp}GsVg8(^NSz836H{VB!scch*L+7TKME_85}kC@ z>0^HWHAadHCnqNfX=x%IHnz4N(=Fj;U%sU4<$@l%4pt9^1*#Dl6_tg@OLA~<9Go7l z_kI8VItF=|gDBF=U6`9wy>a74G`lo*y>5>ar6CQvfRvmymcjH#djq0F~wQ{Q0lmUaXjyn3}(1 zH&13}=F?)!iCS-x#)XB2QO?pcro$xVH-vI3-^Y(HtG_0|N%lzY-Mcqb<-rd$D#C51 zb==8g4K+PI{m9uln#tU+c+|&o8?Hig+qL_?t}dpi;gr?h-kywtg1%{r<}&Q%RO-A- z;1QeW%Fv5&2L8)JLaWY6+lsu{*DrljXJ@TIrO*7%z2A$bZc4fRKb-JivyO+o31Av$ zDKv}#`kj%4CnI_38&q2>M?ylfQ>mzdMx${h(Sr>=1UM8XNk{VXhy;7`koNYI-+-kw zm3~_{zyAT=!62>T?{ZWCX|UIXH|b>HnSTsHJb_ABSU4;qLK#%g$Bc}up9g=FTtw}A z5zl>m9-iC_UGyg zMly@R%*@QfqN8tCGIw@%ZiXrx6Q!o6ZftHgwMMb^jEqn~&)2Hv;cRRXVwSDkGBT`x z{`}cL-tKl=`hE45tgM&puyTI?;~$BVuFsx@WMuG~`E9B$5PSe9d~I%q1)grFSy);I zZEbCtjSe{A$tWp<^m2nEA}IfMB?JK-0e0OqImrc}V`FPe2^eLO&su-LdZE0Lkr9HQ z|7%AFisE6CluPR?YPR!+0Jbs%6jKen@$(jObc_HCh6>nQ8{gR5yL0azT~}Av##+t# zV_+8>ySuH4l8%Tp7yP75?ECkxj7x2JE? z^4?L((jzROb!Mm_QX2NgSRG_I-f{48Zzjss!{h7bOxwAPY9&gLBaz7cKcQUE*qEqS z)5{C$8XDpbXHI>SbsWmd%HDwYf=b@K`{(fB;F)xVzj;%0vyxejXVk#J!14Y}3<|5N zs>&{IMb>b3>WiH%v+t_}EV)GRIh|KH`=d-N-?Ba5y$w9B43D47(!{AxjPd^hs)fhn zYyA$yNohH|0?&>n5gojDqIHFF+l?=X5gowBJXS~Wzn2M5?CjD(*?X;xp|B=Z?pH!- zxqkNc>S3*njam4$;u`_Lir&0gj-H&EnUQuJxIR(o7DONrb_fJ(2M0k=1mqZUa&j<` z+UP{}vukP3r^#9rJ_jl`Dd#tc zYuBz_#dUhmeP_g4X=+juZ2(Svj7GDiq@-LiMMyte(g#sQjug`-2=JwbDT(Y;e{??5=ibN#D#wy>xf8Wr^$ZHwxGE-of zpQ|hI;K2iRtVxA4htT!w`#`{P2!K@I05NHJ&dtvLYHIorQFk&vTC79F!^;~4=%lQ) zG(+jb)UOZ9_O`Zdbi8VBRt_RiSa4s*UPodW8bmi<;E;7ZsOXu_=OvN8$#pgusV z!p0>kc{O15JUl#d2bUAxzU?U#$+#2q>0#k}a7ArAQuAO~@xd2e~ zIkje5D2jfXH(S}87~w_f=;*AC*BIr=y3dmN`}t*da}dK&&SRBtJ^ps_c;B!~0xtPI z?wX$B!jKebR1>^ITu;C<);^ekxp}$SXp2H`lSms9v^Je(b2s~xM9m0 zmtRnz;^=q{Fy6ff56Gg_h_m#r_B-MqcBLtp``q-IeS0TU=3kC7Fkl2>k9uchXed1| zk3uGe2K0mJ(#YsV3@~-gXN84@dh*cF$cRRuth6+$h6H~!lA^%j^hBq(%+_g?z~Wew zlS5WiyF~%;^AXTL`O8lSQ^mM^O17PMeRWpxeZ`acd3ld)Z3i<%EG#U5hTR72M#CW! z{N@e(0UDiAUtb@wN~>@zs-dZQH0HAU^!M=R3i<3}mq{c$(vR7vjuT4nTg+^bJ+gU{ zEGvu=#C6vAt;L5jOW45+3JdQU8%IXWUw?l;&y_0|TxvHjPWbPc zLXA6%eE?EkG@PBRLzvc9wSou5unQM1oVzWbPHH63x^vBEWVATm-xLrMQnj-aK%VT} z2j~tp0=bSpJoM2@5WfH@b{|08W>Me?CA86VhwDRm`6Wp7>4Gi@KExdz9gwrlS%u4F zG%+d7&Tx_U_TN8sdlSl*mb|QNY@0iMI$lRI?GHx5D~=bnfPvkDfWt+8cA2N@J~497 zHy%mcys4DkH(pM=r_``FVCFS6Jj`O%4FrW7*Xg!8BAL5#FrU^YyIvdg@#E#-;9%zV z_3;{}#vc*8Txa{FHeK-+Ws?%DcZ(*8qtt>xbHbpl?QH=5a5x;3n8*rBv$?;Y5tIqK z!Z}2XZ`qAT(PhT321KGM5ESbs?h?XJ`50?>uUrWcPl%)lc?k~XS5y|Ru3z58+w&_Z zq=7|x>gAQ4l*BezWZpe6V2HJHa}x^+3bJ=`(aF;5koVnHcLzkUv%C8#G?et@`1m>S z*&rDJz}3~&?!acLsHkR-)*E!T{@$3c_1?bqxP=UyIVVs90|SH$(&aO{Vy*lbL`W+Y z6%wGii&ImLIXMF5<>i2Gqr0Ef;ZJ~bx$kfM0h9cFd4V!MElmeB=x5{7SHK2929OA) zW@`ntVMZ9sKbb)L0v_o4{vEqh#?M$}Rwoz-vU0qkp`jKE1tiD9&cdPzz?0^D**qM; z)i;0%zdAa?0RTU7bi6Tg1_CE2=rzws13^Z9ozyOae8Zl;zF3Vc?9tvjKWbob5NKDz zQxA`sp<+v*i%mc+Wn^Twz}|(a-@o#NzkPZqOOIvt*7@-1>D-GRfUZ_oS8IlRjj*p_ zO(_Ub(O=x~XP@x+I6y~ozPknb1Dx;?;vcIekD6XOcY>LT!Jbd%wl+NrO9$X^;W@7> z=O~IY3p{yt9bHbPi4$J+EMG}-sVAqUrHy2h`mD)uBuWkM*N8Wai`LsZT`pAP5W81v}n5fuEMemsJA1W{R0P3>ZDZ|}tdd9blVLP|;-UoVRS z`glp`VQ`A9S94R7MI#|XmZV9(rF`oY+X#%|d;4fS8Qi-B#+8Z1$6obJai$b~c^Ybm+PX5UDjl%MQw1NYO zM*XvhnjW6nklHs~%-+B@3(Onp+qPx9Giw7*WMs_F)QFW_BqSu#KYaM0$y<@He7;q9 pw%pD}Np?B({|EVhH~ppqZO|1TMI>BJ!DcChQq@-Ztn}#Re*kYHkVXIi literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/class_decoder_mech.png b/doc/src_intro/img/class_decoder_mech.png new file mode 100644 index 0000000000000000000000000000000000000000..e6801ff23eb4ab85a601557644c91af51006ba19 GIT binary patch literal 24579 zcmZ_02RxVk+dupjQ6d?YQ52a;Bqck0Rc2)qBBRWVkdo|?63WQlgcL&ABUvGpWM))E zWTblD=XL$=|8xKE=YFo&wdgy}@%bFbdmU$p)@c=5YF26ziA1ZWs;EOEk*VVUXSYz| z-!GpHUBG{~I;k4Cl1SSdiGRpq4{m28k@k_)6i@1TCVoxwGLC%r_ph19!)QI*=Nhk) zjww=SIvf&se$1+^h=qxM#HALX~Q zTr)qHsndKlIjZHir<>VSRp*JfC)_38R(5)^v(wWL--tVGmUih)*1QY<^JJ5*BAd6@ z8QvbOaiylA3|L5LU{$3IsEa1I-^W5jsj$7^hLtcg&50a7>hSRJdu(TQbT+xWFMFJh z|L2WmU;cji(%;{|@a@^BfmNU6>Su#@?%WagT|er*G_Czb6K`#9X$@iI9hskx>Pc65 zJALSBJ-byDyYyr8x|{3mYyoxVK3b-=J_h+e-Z3A*Ppv1FOv4OybZ%18vTn4zvk+zu zU(rxg+v@*dnMZ#@Iw(Ise|+!mcf<#)giTLwH&Sab7iM<%7mLQx@23j9Qi8)CcTIot zgsG{iN$c#{`{JGB3*8mYmLZk}RBH*Ac6QY4QB?SQ=gytXEG!lit#>M}|NTSN)^&69 zwwL1zPWXjKm8qNT>C>kfTFw<3HhrApxW1vCEj2e>!zRT}mw&b}Pgg4Z499?+-~IyQ zN`|mqhi=}z%XszcAQ=@E)lh}=xPnc7bMOmcJ$?PA`4@j9v(KcswCL#QJj%;k-(T9i z8g4;5vAe!6S6AfPPlvA`pYLWne!20>+hP&lbvGd?85wrR_fJkX+@`g#u?gC?Tgb`c z*_BVXpFfv;aLkcfCM7C3c*~YRdD6@LbH&2e?M(6U@p8Jlj5u8Jt6!NtzL{PBz1hab z=BQoYmbtmP*4M9NTi=%3zwNHM=5h2=FGX{6b8tk&WPQi$*A|YB5u3N|dZeAM?729x zmGsE*!&5D7?UODpM@S=UKc-f3SG#L{uZ2{kNMF1C=+VCE*;#oFjcs>%PRVKrxv6}$_7OD+v@G@{e5{^3AdYi+qTh}nUHHMbE8u!*Okr9 z_tpOWb4^i2g`CtJ&JutdLeI#1y0OUQxt5;ZEg9eSkNnPluOBS?3EWy(kas!%*qrQjimaKb z@Hk^#W8*C={j$QsLu8Mpx>DZU+RC_vWK!#s5F8xIF0D@D6A`(?z`(GDq@=9OK(Br2 z5&NYT_wL#DW~eDDT3K5wk@!SKb;tZ9JmxfC#U19gwzh76^(y^j z0Ht=EkO`lJ!~;@y?7?$*(Opt>R1}>@VOg1I`Q?uff`c6#98^tAlGN4JgM+6(zkYZx zF;UaY%ZrJF_}cv9T29V1tXG|MSpWc=`rC;v@I-B8>g1Pyw#a1 zdp2mc51X*Hwbj3>O5(|rC(#KBTS?RJ%6L7c*jH9Jx@7-4U0J80p&{x0oTc2pXA8;r zOcyR%*oW5EEu`-gZH!Xaerk>xE;x~ltA2cb-B2I6jf^Cpy5sN04?2&?+qZ8wE_3?$ z`qHzrN1FMqZElI&t6*i7(I}qDH#goArJ$fd?msd6I6RzYdV1RF)3>i*&24OW?ok71lZW#IXDu<@8d%H}W@cswxVhDuK9<>>X>4p%HR+oAvG9FV;oklGX}CWX zE|b(kX0_pdzt^3ozI#d~ToSF_GsujB^7qe*tfG>V#rKiAcnNm_T+r_gbh0GU?d^N1 zNx@-Z3fKYz1qK0i0aRR)l5E4n!?wfKCoWi8mR$eqr>Lxa0gI!;>j%$+<5#xJ%E}s7 zIFVs#wBY3;Sm!zU`Ibx5J;FzhjG3+$n7v^C@a&3;x;k|n@8QFTaRK-7^KXsfkZr!h zr84s6OPHulXWw)(uKu0m$RPE9j24r%YDmx0@MJAHdEHuT(sPT@AqDC;Zi zTcTo*j*g0ZFYzfy?g^=MopPx;MM+L#3)mQr5;AD??{B^@%Zhz?f0Kob)@J@Y1eVt)S2>jz@#Jf|LX`;(DRx83Dc zRMb0rR@rr`lbex|(XRUu*@+V;wC(H!=;@DBR=P~83z^8Iobi!)5m{ch+TC}RMkiG` zE;ybp23_%(=EGyO>+9=SEBCz(%@1B;rlCyVCCq^)xthjz=+I_Twcl^UG4ZID@m&nT z<}&Eo3rhQES4&hJ(7$uY|I@f1Q{uyfCmuO*zfKUf*}=lHW;Pj!-wYo-S7dzW{2~3l z{X$|^hwac$<3j5xOI4!S9n!?{9S%8dXN$)ki~MhB;6ER#HBUQ{r=R~QBZI=--F+@S zJ39#F)yl@kb;{bxY9Alp7VHz;Hvc?!RZw*Fj@-we{C?45i_z25ySG0qFBjXsM_emgd^YUXEefgYfA;vh{m#wL zZ>X=|gvI&yW#z_|w$4ttXE4)#XLib4q!5{K^=L zPQ0+iCXdr7=nur~Z$Ei*bmH^pF|>;c*QxFG_4NnF1o-&m(0u-^O>x``479+K*g{KN zsPXhKBgz4Zgk?4O>{=4%((0UoRGfR02$Hc_!U}OxC{ky?Pa+>MoMq6oUZ>RqDzWnZ>*gRI)^oM7M zX=rKp@7Qv{JLStjVF3C`K|#UD^mMRp_GxDeY?Pt<=@u3iI@gj`*VpUu=BH1e#*5l) zw;^razP)*A=1tF2N28+DD_EWA2H`c=R$QE!cJJom<_`Q&N+Q`jdsB{~arNsK4GoRK!9nxo*?wc6O*crge^$AwtE+LSeDpTh6dp;Hl_#=JCxtF9x~%^C zHIBkVG;VqMn|i z)){TkdA=_#DXOY&sk-`&8c4?BU1{L9xN~RZCeQBa>FF8yv8Jl2NkIa5QP{WRWn&}7 z_U+p%eAZl&zLXC~+YA?mXb*LDMMZMR3OPGWw#Oze7${!6$b+jCcJt=V3QIHJ<(&&_ zK87V1Hh-*e4!}x0P*mynTY~J-*w}?!x59z~TU4E;v8HXkJw2%z83#By)z6&aJ#^?$ z71lL9{ql5AK<%$NNe1e`rMG6+0rn!MQIOrn8n^cL_h$kwFltW<`8{~>;9gvu%9&)T z{bFKb>*GjKiEOu#cr?pQdmQ=KR#G_FU6^Rnanbz8>>T>mJR(-uZC+CAB*3_FRDH-T{ zP?uU?zVttGWX1-#VcI88lEucx-pS8DsHCX4gT7~D?MK_2H+QiE zXHf1@X;iS}(>FGJ?A|}&-+RL4R&X%!F-l>(j7O(9w~{m2w+-Nyf=3fpwjmlhX|_%Xjc#7^%BCf-NN2_V1tH8F_i?Mo%5~ zbEY*mDwaNZa&KK4XDsf_X<%T`1Kh64#}t#E&IMQ=85$ajpL9Mvb-eVp$fSSZPIc+7 zNk@PLJs|OfgoKRDOeNmaiO~rh&N5cN`8kDzBC)@w$C|J3r_)nTV1|V07R~I&9mPZD8JvN(j^c;sZ;DG-aGpA+&<35g@w_l{)LA3 z(>AsR%FkT`fty*Jd^Nb5tD(>pg3i_cgzBJ^Ydrcrf5CD2(k!{CfJhb=7GW{5$$GE>Q2eflh-3Bx;oBI$mB!t@OMdX+!4Pq@-pItnJt!k5 z@l66Wq}|zJVcT|}H8t%FB#*U>)W3wr1Be=0Q6a9GC{FJ&H*|7-xTbP1xsr2GP>>~> z@Q?^CEiE=XP^%H=3tF~g_XgL_7#ThMWuT@O!uA3E|9-`FZIh{qiAUJ^IxBp&lBu31 zAuW}c-tZ9pI361h8$sB6$yU&$ib-9)RK*@$xH4tUM`qVy({L<)vK-?tFHn=Ky_czR zE>Hwyz-M`$2|japcN2SfPNWR$YD`;yVukVBExtb{J)UtDyS1>LXP?)#BGveVyZxcEmZg{ zf~GkA`stYaL($R=uyW{C^z}b$R1y*r-EZHjoIV}dw}zGLxjY-&Cs&?harEd>3KAfQ z{_JkWTh)c~E#WNW0QpBR4>9AO2Zn}P^{}zBUI2<2lI3tlNjR|hYkk??>f*)v-d>%H zhKoh7+S*Qfc~#c`Dvm@&H(wZQI$!N6f=Yku&+lL8Y^v4%j96)Gz~nkDKYsiWF@H%S z#Esv-R;aWpU!{tVSyzH+`2797LU5Rlj*fjy)PH~M-D0n+l2&^E8Q}aX^XwV+H0ds- ziK!_90g2`DE_j=OGhhB#6$m(U5|k}BHJ(t~$0Z<;r+mfw+qZ8$PcG>e7(LsLz8gcmva+J0sY!GE z^$fmz_4C6kBvJq+tvq;C@0&OKnWzaxsN;cH{`;d;w5+!PTbOq4OwGyJf{Uo4qr))t z@#CG8lqeK1QqEBR`pX;S#$Bh`!E>D4+!~=!fGKamhTG106J-)x4mT;x?#E`mp9RCU zzG0DjB{z`(r(eFl8m)w)fapA(IRIOlcjr$u@Z*21Nv5rl4%Y0sc)!I6e?2q08 zIgjkzxwnRIb@7IR!a^W`8|dE!24$3!laoVFw{Sd=5Q|2Uj`gm-ukA91uu5GE>7QBhla`-ZwYvb?-JfasLQa=<99bLUjbF1`jU3CYxm8+$%qJ3c1u zG(rN0ra⁢`m_~*7M`CGUzdbCFCCS!<$pOP!y=r($jkY^p?K9W8Ah&&_6D2H!$yG z+aAsh?4s`8-kZ6({GhtzsB-{=V<^K;?(UOSi)aB2xRgN4=9e!=0)Q&yO>squST@U@ zIYWod7EAr`ge%Y2Z{IAgT%o%m=Z|vY{7e6ur>8kK#&m!FZa{5<(7Jya(0@3bc*3lE90BcpWv{Ik=8C0y7T6poIL8)!?bbI<3^t*rymWG&lbxToKj=hv_H_4Ntcbnc

`L14oV}7)717w7))uV+9W4R*8ARz7 zDJUrXyQT>GgT?6|5kadQ&U^znX6VKB7w?y5$(7s>6c>D{Z!x}(Mx%^%g?mQN#B?jg zZ+$D+B=wh>;un8nLV2a6_Usli_6M#?%Wt%O(TNpO$g$Vo3ZKgNy;Vsix)BwxT`oO==kpl0YIE=OrusyfX_QY9 zZv!PnJz5|zerM-)J3Bku{=A)I1uh<0jCsF#^ zSx!2(V-9joPQuDj>=D39>bLlHP6AEPfJ)sC3E66FYzz)ZjxCU|QfvKc*JXxc)Q)Ty zM(RM&%Rsq(a=7ONVS^T#;GBrs4}u^pEbI@2_{^Is$5?j`7PCxbib=A|$%L4dydbmbXP*9MNEJI3nY@v8u zUf%TVlixNE508WkmP&S2uOA+FWlSq9EG&T~VE3cLyxL>J;P9}%2k_BxT$KCuU-ES2 z_IV3#|i}O zK5QC|mwG@5+z@49X6}aMbP4y`%GOpDk}DTy8r0DH#wI2qITyWia&q`MIlY%>cb41s z+&rBumHSvGIQYJxfxJnTTPk{(_phIa2vQ}lpb!$wCnJ*#d42{B0WccGnt;*ZQ|+y- z`}Fno*FnPZqGQMIvmUj5IWwxMsX4v6Fizd?rlh0fl3mtM)A!fU*h?-KglFX) z-EGR}PV#VbpM=DPeI|}7hEv#aZPdvjYGA?JN=qyVE}uqGz~%#*bEc~G#T z`8d2ZQ)Ko+Dhh;(uBWFrGB+ngUyPc2oYMZvl_*dLqP-4Px;`!~9UIWY=dfc#=`5s3 zc`=}%L*w79RoVC0?1dkg@hynI=tT5vY+*0{{$YbZF^F2$A+|=-d_5$zI^v0jy1MwG zXz~7;PQ0vA_Va9XwtwE~0PZuB6eK8r1XlA~o7_$Mdwl%w^}oM3j<=`{FR!hwG2CbO zihBF*-8*r=4RO%x&b`-ue5NfeD}xb52Z`0<_xduin*|RYD!I@^y;bP}-}Z$k*h&YO z&MvlR@p$toO>%)9xph1|PDjTfa|=Bc?}lq~==kYJItgaw9iCFjxBO0T_)X@{;C)U% zzZ#%aH@tbn*xuewXe`Z99A=KSEaC4tSwH8mZ;ERfcYaPDoKsF$DuI<62o7smcXKnt zU7>>l0^j@3nOXe&`i?=UA+Jv{fIA8b-9A}a4iM28Edg5Aqgxgh7MPD;POSe@{^W_4 zmexz(>#N^WJAR-i5rR^I$@8-pE6^OJq@=V=O(TJmU%q{NPW_C&zO|C#>W?njOsQCX zFEj5Pi-y~&sJN=Cs-&ovhTcq#%;u}s+T|Uj)~_W{ZQAwUkP#)RBKZ&Y7v+^JS0L-W z92oeyckXsw^chE==w+GLHV})u`}%Hygb`{qNY)4%OZ}sh0ZzEAcE|Jb3Mn-baSZ!} zg|*t-n3siHGFjlX&oCO?0!2daQzccD5K2zzwf5<4~&o*+coUG>%w!MFTZSxXGsq4XE9==#}czir_*xd#tyBUOe6cza8 zOF06j0AZg!dzP>d}yHLFa<~2G~LK^?kX9z;-wY85tRH zL^pT8dD8$NAUZKokh{0A9Vd7Qj0G6!CUm{eok?MkUdG`m7G0%M144q_U-#hy8?b=_ zB%}9F9S`bX4()Thdi5&GDb=36do3K5$vEn=f0|FYTI#~j=J>usy!=X!#qkW*=z<^c8RXcHQExYrVj=dO6N$4VV z5Zs6kPxz5o)JKjV&ObD-YuRMpM=>B53W&Miwfej32+G&|p*b>gO7oZgWXtUHt#`OY zTqat*qvGmv_`lLWB!umk|Jv0J*X;M1ReO?=laoU?>R)}ZlF4NB!cTgo>|X_W-^$P- zqoGtGKw3t>qAd3e+Hc{LeKSo4E+=-3V|K_7jnJxnm;wh2C`(IgrgkY@8 z3oxUZ#q93&3GCwH;+jh@ER0Z&U?t1>Y8`Ta_vKHuduzOxGKy+}YZ^IHbhyUyZ z$b{wc%-gaxdOyPtFw^39C9VReBW@e_&6xd%3TWXVG!|MWX-;UAZ%K)vsi)=tsW8?p?dI__Xfdm8uI0GF2 z0745rJ=9LEu4L&GgjM;oC09To~ zb@cQ-I4cbjp?%&2fenkG9>|zekJK;Jhk*m@NxRcqIIc{K4d>yYfq)C z%>iCsjV3Y3gGU_(cl?;@ic7d}tHw%#Z2$88dsYyZp%vaU$$iIukpx;uU?7mQ<_rPBLE+SA-)b(GRkGDjw9<34`OxviywqPqVH%`F1dgu5(E&Y zoD+19aCT`!3sb^rcOGwcwkw7g1PAg4qg?BoaQ&viL1rj}4Pc1~QG}wDr2%_Um)p(f ziR<3tbWh+sW$eCw+#nHq5L#_wM5D>Z8!Av+3*tNkSA$PR0 z`;R(0E6$bz7{3I_xOnm6>P&V@#iAM-XnSX0-@P}D{OvZUUY*wS8@r$3q5VRHnbYoD zKtUw5H3~{fb-oqg3}VZ|`+8#6PmMK=>cVu)@jZp5<+w*@^%h78TYtQQLOsl%47^!~ z>wfImF_J)FSzTQnVSf4j{q5m4KfIUZv^=XHB72cuf9FMPH@?G%gOZbzhmI~UFLM{Q zy?(u!gqE)w-lb36-^b7d1Wl`%;fKpZi2?m)vg;q#cRss!vClg6sB=h2Ncq4E{X>$E zN;edbSWqhLDqlD$fNRE7Dl>n zkWQJ!9|nM}#a%%>2cmUA@W1DmwMA+6h|&Xbr8PaM@dj6kJWf~F)W8i{@1-qN+xO%= z`*g5*Dx`w0bT->g@_cqB10kfW`T^QQ0RxWIogD%sq1h|JL{3Tb5-|!V$Xy{NX&P}t zHLfzXf7b1BTZx|t%>z*EZ9vJhXH?Kg;JCs|WNQBL;_q)djr)Qp<>W{%E-u(SNY-p4 z?0a;MO!I8PXlKWbQ87%If($Si$8u4>7dY1YM6#ZFhEO3r#^bW!pP|84Y)WV zM{Qm|2t;b70bE&;!pO)7$e{e}N^w@!?Gvt_3F{XZaAd&~&R8S#jqXP$$$@Z2;0M+r z=Yl2JdZ}MAv<&)6DvA^Elr+4=AozITVwq>XcI+<_;^NH7%~i{JrTCx%><#~K0Y%4l zs6vGG_+`Q4DQG2x#0N$i0{rEA>5{$uc$}HvNo*lBvPW=|2nYt6I)BfDGF?E^qZv^S z=J>gApoZD4Pxsu=K8QfqL62uDr1KR{`;Wi-Ysr1|C=*cKU6zZsw&xFPXt1PE!A0+* zHZuBP_pE4jFn1<&A7y~_1yN?2+X#iUA$aEEd6?G9@0R#luBDmclZdXH7iLGFr!%l!yQwQvz1Q*<#1lOuVSE=guyem)3)o zuDpa}cq=H#b!O??hdA9#u?}ZMHu$s<-)Qp z5Fv5*w@_>%>QZE6r0S_tn@Qo!BAb8)nT5?su%>CQUAvYbt*yP*CP1gu+8f&@5Qm0I zFi|LXlYc~%{=30CbiYzR_6oZ57CO41*w~$f42EJ+T`fh5jc`1Fo*8BnM7}8GI23?| zQJIJg-`PS#Ztc@PGATx<8qE6+EO}JeDrDpFL$@KXGz#wY__nfWiRt5|EV%gVYS1fZ*US28`5(Qj4sH+pnhilKdy5}9H z@8|DCVdb7{>gWjn_3q=xy#)0HZ4SkHAp)1*fBvM@;(rR#bQ`EqGhG`9EBfBOTM%d( z0KcHXB*l3e!xx)qc|~1TvI?MJ3#4Z(*@mf&d(O#grrX_WO6IBF&FO zLysWYfBotZX#E~e1j;!qOM7-VC8f)2hrRsS zv%8@CMxp)8ori2r&%&}5fDS50YxU`&L+5q-<7_Rxy+TEiGbk#d*tfu`j^qqLLU2@6 zP-Z4Kq6>EAaiRZHj);46P5+QAsa!xosr5~4n|!tAZo%{Zh;5AmB6fFo%OM8>n$G`2 z0`WY8wPGddScJAS<$O(`LmNb$LIUk(Qj&?|l{)rWK`6`-`X zw)PDmHfNqoUcm>8Z^`c`lv(Rn_np0qPyh(;0$>{0GcLcCAypNCMK%Al^Jj?0a8`HF zBaR#b`BpVU)UJ`_6m(fBnF?%PL#QSuTU{N>aSXXsRkk{;WE9|-^ib_AKD zGFK26x58)b2r34@D|M*qvbDYaE3D`jf0b=*b8c~d10NrRwhz~f5H($0T{jk5I1)c! z?@3egTwmfxQy`o&@DH`6Jc>sVy`#L}MZ{$M9WPL@%0y)fs!@!iiiS z5=YgCD6~&V=(L3oaRr@CkPKjfY%XqM(C?C~j+QQDTtS2_S65d@K3sXB1Y?58c5R*f zfc%*-D$U@B4-Lb^>_`<6f(&$jGQFR3Nnpj+)?MZ?<7jNhu)nX*qx%W);5On2&z4_Lmt%?s!e6H$iai#0PC6%&yuw|#$rb5 z_^hkKb0#?)Tjk`w9de+c=v*xxpM0rE1jd3r8Hg_EeC2`c(UhA-9f&dC@3LQ z(9n=o=khOzhlJsA>eMN;=e*{D2YJ+DNEz##nYt_AApTM`NqO6&N5NSN#DcMAkh%|R)FPH&>g{#hNTyL==^ z%8I|QF*k4VJ-jO^X=%bOLQou_1Wu>OL=cn$G@C#@7dzr_ z;IO|U=`T0wQUxiX0SpMKm?PtrNOHqS5q6nSMdJPu913wLSmiTai6&LI2yYh-h1-h#DXd7EW7#Y#Tv72qBwT1n{;lAoR_A)K;r-JXc*mcDL3EjxNZaa+!M& zw50(*EI9kmd7c^$n=8n&wX^$Uru^pxTj|qrUkLCxMy2f2N#axK*k`EnW?we+l#C}g z%e8;z>V2Z0&4W9W!n6D*7~wL(5}G;a)XPb?C=lw=NjuMZGcV6BX?$1QX;QShit(Gz zpae*rL7ctN7)%dsztD9ZHerL#JZ%O*=AVrpXGn4=n#YsR=WFU~Tk_W6;w#g=6@)z?HQ_Z?2bD#GpoT@vI@`xWNUjKd&41zvi3M#5MFtBnfD&ouvP(L>Lbr2>nyiBN7XA23HKJMNEd^2IwJW z;mFPszJ77GFBe%7B}hJc=g;#kc>P{4?_1OK$RfetId5pViG<)~7;2IF)`R})7MBr{ zChqAWvoC3KceC{+y%rC+xw(nc--dUA_0qDuOX(O_k50#XE&ch=6BD-}lQw`291MfB z6k@L!^%=5}Cmh#Jn>JO@RDUq^>_!54qaHg}*bJ)wu%I?I+^WB+(WzlE%^+DaLR^Knh1-ev8N$;hcMv*+; zj|P5z`1%}+d&|2%!d6G1mk9TuUs58mHb+=$gsf!IKuLgSUf%5YZj+b#QI>o1^bZcz z`WnrZ>+f_dKe_Q9!&D>Cmc`v?nUJ@NhQ^J0KOk`$SeBr&&<1>`d_XcI@04h&0F}m`A6nk9rx3{hL>E)?f+?4Hbrjy0X~Ib^Q45 zfq?-6G6Pr$A=@8AX0gP!KO`h7oX1bkfy$`3N8v(jBO%D%eU>=RQ3lKD9~ zau}&1?l^82;lf}kQjdd})*+QhSZ}bIUX*P*m3)?#2n-R#Yd^#hz*9JM$m8T|SC{Wc zgamQJ02nN=gCdEMERcVquVi?C4MmG-f|1poeTD;rEAo)zU}D9TW})SCRYMa<`1k;V z+fmzY|C!D|mhopJ>O8L#6A$m-zefP^rXDjA{oZxCy`U@!^a%Wm*1V;<87mpE@Mp*C zJ4GRMi)H0&J~UOL271|Y+h}Mu&h)Nz=aom5`!Ulv%Y2|Lt#!9qRyxIGTi%~nV=uuG z^Y5R;zYh9urV;s@r2ewkEs$#AhQ9>K;=Zbu?=8EirKddRd^X~*?ieU{cYl9iSlBC~ z)TZvplDu}NN)#XvyY{3~rc3;}4L=zhyHY(j2!+$1UcBh*)yOii^l=dWn6T%g0m#gM za_{jEA6jAuf?uk5drS27_m^D#W=KTRp@e|*-&r5;#2D0#8)R5%nRD4Znn(%|X&3~n zF+F7bZ4Fs#L^qWD{A!1)&jtN|#G9eg7GO*WHpFxQ)&&6f#DM=Roy;~%2xX7+L z6GDV#^vjoR$aN0Be}4hvbSYL*4;RSpWN%*Yb+`Fn3<`m;z`+x{%03 zv(S)`Ty1ui6kbh_v;QuPuOFV#p@{+`2@pmg{0vv*$?2%HPQ2@T^=g|2*ONomFC5&EoJ7MdSNNrR1tS?`_jH)!!{OF5D8KoX;tBJ8O%vK6q zEtE{PoPox3a*)e4e2a5(MiwW>#_A`%5U%6nCOj7 zFWm(29fzo1fu#QFMDZKYi=9WuE`_>TEeBRyq|MPQYzzB~jY`m7+_Q7z)d%H=eOVA@ zMM{$>gDd=ed?Vh4%b5lrUR;+Y=12)!ikR}iC#Pm*o&6$?d@&gb=IrF+FN_r)JCUS) z5I(jt>wimDk}%7JkW8HIsuJyKGz{Wid3daNS8_b+)ggu{NU?{*5a|(I@k17o7}|ks zz{SIprR;UC5mqPW3s8osVfcqVKa5-=M*Ex|l!Et}e2XeHWY|}iYk;K|c1_=|~Wz!des-6%7E$Ac}b1)fp z{SGJ_GAVTME8M2L$$%#?bwfcgc${dzKoRKfC}dQa7XariXg_3!4;OoPiH`pWRB@@= z1DX1prh={O|HZV@$TAUk=}$`)ZkXY*HvHZ~ZB7FqYCt z5QpDO+{MaCUyKvVly;c=F#XemShOk|yHI$LNy9yBfS4oXe%jet1T>NcbsWgAzNJM) zzTmOnZ*M|+$Lprw7IV0`x@L|MRs*h%b+g${B?0089zci|T$x454geS=gmnx{ytdl$ z_8AdULJTKf`r0uf(GQD4%4?AVcdme{ZM9(4+%g*JUm{k6Y2IMi1sA~Ni3AprxStGx zAJ+udjDap1oNdB_@$;*+pq$JnTn?aJ0ODn{N>`!j{CB#YFhvBp(85|fJ8xqo1w!8; z_fBjcr0pu#`XSLC#B(Ibn|tKHmSiE5$7T7X(Z}Y$srN5((bn zNCq9K=$1E0{Bl0O%T&qF>Pz0gdzY(Z&S;5&A8IwKH^cg4G(h#C9~ko?Cb8iNvrgqo z>>MOyN(exfknGA$sS{FC=)h`1ESE3wUl5iNoAovO`d?tWWW76yEatt4cEkDdx_`$I zwy&5hRoI)GlW0c=6cqgW`XU zS;W&C5%hv5e-rErk4)%DmSzJA9V;p?Ev?78>qg)K7D?*+4FR1STLa~3IAr!9p+(3l z<<4#OC{tKHQ>MF!0i_Qfx9e6JEUH9Vsze_xYRd`>?|?r}gm*EY*vMu{j}MlIPL5|b zP+`syacmAqb(=|^|66ukt%*oG;^vv7{`P-9mrN}PCj!V>9^+6p-N(el3iau5_)PW# z1vfB)1K8w@7&y|;r5`C-%mf_{{TrmVC#1XdysmtwcZQ41)U*2TX0Ue+x z7-zdpq)xLpmfMChT?!R``c2Q<`F& zjs54`-)WjAB8W5s@Q7U%Oa1EAs|G9~2t9R<7yhQ6hw*&v(~K}CVi0rI(b)85+rqUR z!#K{ScX-DqjrVwBh;q$rCz0UQ@^yz)?FI#wh{{8$nC;K6e2kk(AZJ`2WJQsn-b_D= zF12Obwg$9=o^tzhA*;~bN56ihAvt+?sJOV48vh;yr%nZ_6PZ~3_Sv=Q^F| zjm1rYeEVGJ6UcT(kx_?Uis27-VIr^o{CoR@KLw9z#Ewc@d7bb)Dt1a#p_l54wb#}s zdcBKR7jq`b6zLm9uIw{4|NUpgf`c;NB6^|Lw5#DqYlo@5uZ{oYaM{YAf}h_Gp6bZe zTw|_4S4W!)N3^J@s0hPb(?jobqEZ($%oNsAtkG^6oOdxYTI$urEM*_8~?Mb1FJH`7{cB;I+18eh%_y=5?De^hd-}PoPv`*x_j2 zVaw*jf6F#7IB_qyj81l=JI9-QMs1~gtn=#pa0FB{NZwTH^(G4P@`Mke|MI0(IB#TF+AX@GpLmEUojlfUo>wAwmFoV@*U;Xx;hUJK&O zEI5N_m-j*-gUn~5_BU4@3mLM9z}87X1>#vN(#Mq(tbEkG2jZpXG&$h#fbDjKvxsWt z_d|gb^_VjzY)x!jxEalF-^Rh0xpV)%G8`JX*%#4U;lvWZK=sWFA3nk)OUcb>g+VEx zKjom=T|0LYS#M}ih(s!9>MZ>EHP6=n^azK~cQORTVH&+b3jlhK2xU6RLB4`{tWxlD z5KhP!`oqtt#A**n+fURC#vG6q{pUYwJQo(lE+rq0(p8Mh9cv}Ld!XaYuI0Ip58sv9 zeDa7OVdNWQZ_j$CklLcq`U1Y)&4qTV_!`&d}K&(Y?g=lxg1}iW*7C4ubR3h+GT8}Ms*vvwLlo@J4Sl?x^rf}N(gDbd+u=Gc0F4D)>K!=2ao@0 zM{es1K={Ja(gZ3(20VbiLZfrMBj?h4oDh{r|FlglhP|4K-D3dm7`I8b!^GR)gXQ+S zp=IMZ$+?4aGiL`1F|Is?2Z&IPOvagIq4Kp4=c;F>VeUfzbR-GZI^hE2z({ynSL$)^ z*ZuwaTfaGetP(@hlZbnV058Ful9Kkav$Nx+ksBKu)b3I%L#`l^Y`@N`#w_j7yGD0J zP%s=&|IvX_Z`>Ek`Idp*Ywog73=iR5?JJXv?!-MpIldSF1oHQ^V%9rk8N@n4roHBC zR#Y`K6f$+3G09%jV}H1IHLY_6Qv-c!?fgj{qt}aHpda0P@n;F`y06&mQ_lJUHE;3c z9LY;GO>Q{SSftIIrn~n;qvsP6Dq51@wd_bdaTkFZ&E|x~1Dgm_lW!|2P}@ zEtnN9kcx|ogF|o#kxbM&qCf@2yj}j<0rI|D#*@9uLuICsM1*>HGQk zf-&y(5GG77L@??P=*`JsCP!Im(e2FF7AGZU#@FG#6MPBA5CMrmn6t0{{nMYP8+L>bB*#i-|Qk~8wQLc_LO9fs$ysElQ?zDR) z`X)58+WAD(ynUp8c%gJj8(Fbu9Ke!|I!bp0L&6ct3aBlWPNSQk8bTAvSN6q*D22|f zo^p^a=prAhBQm%|ls_l3UGV&45~N3Lt$W2#ctkM{K&_^N4>iza_jrn#VhAe`GqChi zm78KQhZZ-ywNy}7C4J}a-E8H%KVni8fH1bWSF8pc)3MYLXR)fu>hTmw9^}3o;W;gQ z|4z^?i4WOXSz~y75kjF@y@Du@UUS%{h&b;=i~!brNMxk)mXnyPM2{xsBTB=_WW)hx#z^Dm#EMS znC=2|Bo!EzQ=_60wG0;2qWDWBix+9RmdwdKa_gRYA1ptZ((3>GiOUW4If4poTmJsn`)#$J3!KQd5v7EZ7&a7_kT`

2n$BzK?-gY_aF&_}2JYiL$-ANHBP&fn zI1-G+#-=7RZhmRtQE%i=OYqP#N*ZQ=&_G~*iMVm*P|<_5Pr%8ddq#J`_-=;44dDVy zl9<;9PLR-0hh$AecW%?L5VY>zhXX-0ENQpC0x8`EHn6gq@O^PvEk<+dMoUs``|H>G zF8ej!4G!XoT$|-^Ct)E@L1zP5cmCYLVomqe&$isq)N^!mQi(bXqs>K!qpbdT1R6%~ zDMoOn)l0n^L|C17_H}1xBqY}#?`%?L4x|$CBs?!h$h5i@eFbY_AlE1+LuD%UqupSJ z8Y7CiJ3GOJkeDqztAV^YfC4cnjL^sqGqX>u5jK3Rg${|x3$kLb=XVbe*0e14*@;;; zhg(3Km555g%n0s1kw6&s`EhD;0a^wEH<$~Lk*dC*(bA#ta37XPk6k&+Fu6aBLvUkd z;CJF7bl@)fJWbHd_-$^c9$@{35|TII3Cr*z`Y9@z>+f~5`RLIG5CJZQx*#P30_TtH%p?*m3&!x2Su0X^fUH^FJnr#2-S7#WpeLV*ZT7#8w~ zi^rq;^g>ZV7%4%@>j*ptC`_SnoZu}R;MoCqBMf|2?GZ;l)VWGezlm4pu~Oud^Y31 zb@esHC0nmSk72JM0BqL&D2QQr=v^kihG^^HdmxHX^-P`nw;jRBkX9K9J6x;v6a}KY z^1M502jRn^O+0UQM=*gN>U8q;KVBGp^@sR?Sftq8iuMDDdgu(rE|Ll_j51$cAfN*p zDJF94ds#DiAGXE$)|g>jBCm&G+nG>I5a^sg--?Wy8Bt*|*{|W|c9eu*FM%Zu%hiR1 zh|o8Z>7zhic|Gxn24HwD9LFA$kN`Tm9fC6CpHPHH`&Y%JsbP6f;h^{J-#=RW3u50z zv}Y1Bn&HG6LtIlgmQQ-KX4Tg(c#26B%IE2vZ?b>a&H(z88eY{x)hzXxH+^J9Uw~nU zZp6J%fV%C{jw79u=+-hE1d=pB@;0D!QTId)!k8JLBm@YGkjfC^6%+`O zLYbK(ni1+it$W0kSd9@dZZ;~+E=t6(N+Fh7G9eOi3nIW7KxRL0f9>Bezsvi3-{<*0 z-{<>$&%7+p`2)&Y1p>-E%r ziQI}!5x@1~S+8{}S)zAvAvH&I4ArS!Jhkvtsv4WpIl z5F3CADv6xL9!_877$rl}AHS^Y=^WZsGu5n@Sr(jZa1vR*krd}-gZupbeS zD)o9jl4!L=euOqQ4wFljl7}Q)YYE11B}3kAiPe!+33=F*Ib{(;%Z5$p0=VBb*6pEY zLrlp1#v3<|P%+JPQ?dm$^jGZJ;!bj#q)Ag!$ob&8;@y}AcBiT%4ZmcnT-IhGORXkc zHy~l=T4fR9i5%-gid$x=4#w$5}4F5 z^=iwN5;^*(BSeffHg2dh|M_cc@v-+GKSQF5iq_mY^lMz7a*n}O9jC_7 zGEIU=!k&l44+x^o6ADQsu}nM|ht3fuAezE1& z-?5XXB~+sskVmfzL|^gdldC$N;P3nPdrD}fKHH*VfC+9-UA z=0Cm*878!nT{^VPVx*bhC+_|1ldP<)>CQTzz8ifSbSbt8=-ALxWQN~t=`DGgXtM40^Nw_<2LvLY@g`CJDQY6U_G&G#Q* zAcagJkUwDxU7Gx7E$`qFu_!8)gpBr4n!#y|3S7dlnkyD}Sy@(sRe+HYnBP2d`)$m( ze&KKt64mT3V!_TZ%fI5cZMzO3c<~>qrJkN~cp5T9blFhDv_skc@`DXW9sHUenI5DW znaH`|bDl(ltt0>O9^4pbww|1W^lr_)U}O6iBO{AWPmh|?PWnU^`FvBc~hPxLJ*kJcT=pGa;)5>EMk9BrnI zqKBNbkG0SDiY@CeK8`kw_7 zjg}{|ngPfdTB%jT=ETLQgc-XQ?OO1HQmu|ixQdb7)YxVH@6;w@nuR`K0v3tfSzuf- zuk_cs-k*-71m+g>KJqsxVhgPaeerxM1T2Fg1;gKpsa}Gdn1R4MZEsRi2TR5x7}E;n zHr&nhbGEH%!f4rDpIF?eiXI!C9e$^M>h=Qs33GkN-|8+p`}ex(U`LeOVOP2r%T9w@ zWqA;$|9*bYHPKI9+ZxM^3A!ex5$js*{aPynmQIY%5-mZ>jLbHL&;D2A|GR!_^X*z> zcx%#KYQhfvlzr;OfYw#Pf($+IoX?Hmb?Y=*XTWmXh2Kil2fY56_DsyfeI#;V**m2V z4LD$aywmH)=CO(=t9I?dUIrTQD>BZ_vh0h2P&le-B}En1ii~?PH3b7M;Th?30n?$& zznKxr4QyZYhkosGTlm)hf$m=RR!fB85L`yyluPbwE1rG&ox)df^|uOG9sEX_{N2O< E1K#l!rT_o{ literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/class_decoder_rsbp.png b/doc/src_intro/img/class_decoder_rsbp.png new file mode 100644 index 0000000000000000000000000000000000000000..257b3ec79ae4e456d779cd08014cfe48dd81bb98 GIT binary patch literal 13120 zcmZ{L2RxSV-}WsPmC>C-16ipMN=6D9MOIQ8HYF+}O2{f%*&{@eWR<;@mAx~v6=f!r znHBGG{hsIfzwh&Zp7-$=YK{2t$9d~dJws%L4p?%7Hrk!Tea)IQvd^=`R~wZk)Hy3=m>boEPwFdQOy{`3*TPJDMt!@_na_!b z80EIh$(@!vvGUjT_#XpiW@GBZicL3DJ}~yREqobmh>{qMnk_oX!66)zoJ=!5K5inA ze3JK5UDizUsvfUE=hPl%n$51$X9k{yhF<9H{^u{b0~tv)no-Yg4qshrx)h~yLy(!~ z43Fz3)_U+bl=gv)v zcoOfo(_D+b=+yr9Qb1T(SQ6{=(0X|}xq-d{Yvz-->32GgGSgI*1kBCdoBPp56)9pC zbht!tti1k}c zN{X*~?3r&1lfBx-oM-(?zkFedh=>^L$>E)toSYsG)62a^AN|S0%WI2_tnBpi{B2Tc zxd(k^PitG7th6*~W@ctBf|J>q_tx#()8p;$82vlGr^(DVas`QmA3Ss@rrT*}Rf$V; z^Z6@Rt_)0l`OsD3ETtMP>1$E)m+{!mCWp>=MU}R@dw1;Ez{|_KoxHX6Dk%*KaS4EynWka zcx_g~_{iFYW9O8VBBQ@k)6*v$zul1?(X@C|$gD?rgY;j)Ubg4pILyl% z>o2tyuB@Vxq?KnrG%|7~K`nZu?rVXy$MTts-7ZC72^>AT7KR@ly&a|_6=3mn9bRXTgX%oA+ z_-_2fBP;8eX7ZIsft+VKBqa8#s;Y*cv^#3vm;Wd+@nB+75<4HCaz&_O@B#Kyr&tah zI+U20SX$x5U~uDxo0{a(#-~r8l3ei0WW5qr$CZWQc>So8c8@*i*&cgZjyAFM<=>_3 z>FH_i>^!@^_LrT9$D{q-7m!mfE?sf`;R)f|r!w{~}@ z*)0R;+2~?>l9iU_M2MA@6<5dL&!0-DdAYd~31d-F(K=K(jw4pzLqT0VaBglcF+P4I z?ZNigw(_a)-4?ztUhE^eJbFa2bt@2ES66pn+SbIxghT=)xoCVoDkw-Ip=Q3j(o2#^ z+8=CaN&3ddRqeO$+@T@WeEL+~mY^nIC!#`CnzJ(KFJ(3R;L@c_W36%Co+%rb zl9ED8I>^VjQwb09b9mS-JUm=;(oE63rLB#@m5RRV_qX!tFAw?+P(a~AMw{=LnPpgy zs=knNW(^DsY;I{ejoWF-v(VcoW=Z-p^@SlRL9fJ#gW?n~@3xhNNm&~k5fnHD$(i&_-YpzuCIQwDDJUqE;zR}p2fG$M{PWmz`>tIms7)I;Z#Jy< zWAXI$twaspUHolu{rYu%)HgueH8)qpW}@p67HA+$&*`+B+(yk*ZLcj12TJ?<*-#;i zCF?6vUESRVjSLL`Ae57TVl_ON6yX93!w?&#{)e%w+VbN zD=!za9FV@#ohkqJ=Xh(}HWBkaPZt-`6F0YSXkP~f1c)lPoa{NS{QT%9;FN-jiv0ci z#~mCUwPP?Epl(-l-z-Jd?)iiV-Cu1-N}?&uhC;ud7S(B`1}q!EQA9IbRo zLxa=8!s5ikg=B@|uC6PYSy`Oi+}xSDx$!I#HkPI(t25hZ_lX5uymU$N^5rl_{%aMD zX`#=awV<`u*3@{uzyI@0R8-Wx>F@HX6Z1bilP;&}zDZ72c5-scwi-USLHeveD>ujM zYJax2#p%H$^t{h0TB3W78Pg1pjxw~YkA!DsWmTpoEWId5NZ_G(_2vy12gg%Czxc03 z4>bT(iMKmbxwccA%#XL@7TRCykpkl54*)l<7xHosyH5XlU1Z&GblWfkxy=Zjn&!|V z4)OVm7oU8RS}&}e>*x?VmO^ys|1X{Rw+4TH`z;rdxHxO+!O+fz24y)pxkA$qAS;6w zYUn07epi?C& z{M#k}2dB8-F#0L_ro=ifE4vl_{M*>rLF)pWqFMjRRU@zwQL5ghYFyTWI(OEe;4SR` zMwQsJSgpg3=zPsqAt;xBOm42G@hM|*bS>diq*qJg-`GDJO)2cyvE%pZlJ)ah^nI3h znkhj^DJfccMC}9H`eG6iJb?J$YJ+*Si_zeT26N`j8I;_kj0_g<|oxXi2A zSXUf2&Qqs!4m>>Z7{G3XqC6V*!RhY_03=>o(Tb<|I5>TM!NPiCV#4x!g_mYqw4~$H zfPn4Hd-ujFg&h$T5jkUNDHw$|71m?s9Y2`36pk8k^Y-56wD`?K^pa?fhM(3HpoJMVgbOvdwm#0xJc=u%8V9-g_-mR#ui09ZI{O zdCwjWF)?NVy@*?zFOohOZk$ip<7;{-hwifB#-VQStPR8*vKu+S>bke0}>9 zY0*G_|Nc!dx#_=u`eO?V_krk?XWjfX@Z*Qq+qZ8;J8Wi!I?thdUdzW zWRDv__Is?qRke60g+Q6$0T1}zF4vmkWLp!=|U~n31kW%1KUe&_@`p!DOUuf}CLRxMWj8xBV=`0|NW3OAG;}8uQ+3?m zKPBtj4|M zFx>PXeDHIUhH1-d`Jtg9xtN%kke4r24jecjeCzYUo(~TMF0bRT5-=!yqi$zY37Ym? zEl+enN(%p$jT<5a4L0mzVzRygHeJ)x69Lj-@;Om`ZtjN$2geTTjoCNq8Lh0XIr;hd z?SB>hA?`pGEao#q{^@Bk<<@yS8hqcIFf4KrJ09S_Or~1Mb=-UtC-~ z^!+=>g_3Ne)STjpFCRqB`iozBdO`r41qHcoYui zke}a-t6j^Mg)&fmd4k)p90W)~P0fF$$#Z&6OWdZnZe4J4Dz0#%*}C;L z3aUB(?qDKX)@M+Px`u`~z%>nj)>Adr)gGY#o}P)x$v!B9A9?*wgA?J90Q^_dr5kQS z7rjBXT(GmV^Y%!0WG}nBuDK!W!v_gM7I^M)9m_UtI|wEPa=V4}1yAU?M@kurVwjsV$Ib_Ss;8$HA#A$ifqByl zac~AXt=u~?I8ol4mO3OG+}zwYx|n}0R20xH1li|5r>c5@rj@9pWi znVwY{Vk;g$Sf0%5C)(@W&$N;Yw{9K&F+ScJd)6N(8!Y2ZeEgYDQKw>8R~;@~y!Zxh zfzrWhDC+7)ZEN`Y^{cSO*ORwQOkM#3)dBa14jgdz^fdkyr4k<>9}*dLd*u)i5O|xM%*F9~7q4c3hX)mz zTv=VsfNS7Bc97Kpx`z%QzHs9PHz8$`Q&N)9Wjs9zX1*yq-e!BwzHtA2;$>gt6ldi2KUBa4dT)dK_iz=pY*VI}Ox{>zsyk9TMBT)KGiJUZO`Sc~h2jB^SKuW-v= zUGQGcYzD7&x@Dn16_DgJG<1FJ=TBKZJvJWI7t+`Quu-VGO(a1fq0{HiZOzQgEFGOC zGckD(Z*OlaadtjwKSzy^Ad#e`q>`Le4{&p{A3R76#xT~AviFE~zRT`o#@XS2U^z55 zH@o1NfwmbK8Bsoxc7gDWdhqU$(9rJ_ z-C1bnWhh1x3D9M`{`XH{c(~`yPf_1imu88&1F=A#4~UH1CLtm5=FJ;@^nctm1u69} zmXiZYS5s5d^6p&<5~%lPcXxM^OHj~`)wwpcEAQ_e!n-eCyeN3PgO7`gi$ua-H`DE- z*3i%(M@lUYP_8cjOtbwxKta;Sc`+a}q+VQH z9Mr@B$4a~VM_U3ghs8mXjdC+hDXNJ?LM;y5vG7F?m$`hI2`qq;1kPgwT<4hWVBk@G z@>ph2G6}%ODJsh3GG~-3o|BV9*fH=$=uz&ZQj}eW`Ii$U7pM+xZSDNK-F<1TKHmUo z8%PAV*V6Ka@~~VV9UZl{L2IUh%a9N9MOXv$^z?vvCeXAUSu4;n+o?B>_2vnX^gEKT zf+lZlUg$D8ha!Yw*E10r60)=5g?RA8shvA^JofRS!Cq`2H8eJU`|)GTs|-EVAN(R} zFoKhg%R32urLImsP@$$VQp=Va03VBs=w1!hSH z+ejN~s`+3ZH8_h@*4EZjV%8%x;Hg!O^2c+oYH96-fCm$O42h{w1fPRorHYDMva_=* zTA!Fvx}efKzut^?ta3c>QYAh-a_>j$rbmw+L08Jd5HkPr-i^$8##5*BwY+z}J%A46 zvTok4?dN#_!gL(O&Y!#&FJ9EF<_aq0xpV1JoAzk7EyuA~yNre9L`AW}U-HAvS?T#f zG*s6Fa<-)DNzMK0XS;g!D#u`El3v{I@-hK2bf%1Tw}mvVJUX1|a@5_ofdQBGwLc{! zm&Qm@@5PHCqh1P9@Fv3}BPj#S?@+fiH3;ubhXI;YO=DvvQCR@OnNnI3sO8<+5f!3xp$FuR zjSql@^d#%4si_T>U&Btle}94*bdZl{JN5Q``+N$lN5A8olU&NmWI*D{6ciNN#V`Z+ zb8u`pa^%PkwsVzLRb^klvH~9jg@vE^`qDc6oxhynfTDTvvdrTSM4U@#C?k-tGS`xk ziK)D_lmyMN^Wpi!`>4w#UVt{p4^j4njMQ5_fra)Ff*;g?nuca*O4= z%lod<9&jpX+`!Dm&22C@)>%TY)JQ&WDAA8!Dj zlz;uI%U1%NyYgz+ntg!r9cseQ@b{-LUK-i!vrqg27r%f2{kL!57J+S*%V)&mX=!Kz zUcThdpk-rYTU=axm6}SY=lu70mG9op@!VnP@WrL2obUs_X>N|3DpGYax1-}an(FKJ z_Um8J(4a({=_|BjAi=oUXl7=%oea9WA2uVCfG){oLK}x8@$K8!&@Xz9^Sb~p=XG@W zL-P)yc~<(dNI*M2f-&L4dg|KunP>6ISF<*ktglHdOnuq*YI@5QAUoZ(?ST2@H=yS4 z_RD(EPeqm7u5od3o<2SmsBkho8q)8Dg);^Q?8WPA4@uJU@|%nsBitq??f?`@%gZU@ z55Z3>1?z7~P-BC?TZWy24*{afN*Wld4YpmH;U-`oCutQNdJ+Fpkf`YP4TOe*78=$B zuy+;O9ecn6a#sPy-!pgm*Vm$$)KtH*F%#uzNgY1N)x~K~FRyQ*+nms#7Keh>#QNDz z+3)=GtN$!|FC10&_FK36Y!3+uu~g~= zwI@WI`QcZ`ukW@t10!&UVlsa^0I#+0TvTX)u=|aVwY6~9wj`#ex~HZd*+5B|VK+OX znFhm>CC{S23N4m`1W#`yG&kqC2toN*Gwu$a0h==%X?VUk`$Qygjv2vpMzQ0e2 zGAt>PvYG0u)wz7{o-mwEj)nRxaft_0ataF6*tl1(UXiG%sLU(ntR;G681?FV{DYcN zRq~)3Ax_NVqUAa-Ov^SksmeEs!TJUU6i{4Ow6u(Hb>ht8Nxq>6 zz-KT7ZbMACynM;xPS56dqdxQ_(gZ*ULw#?En$+K&a4%sZx}rXp7bd;2ib)fYIMqN3 zB4|KoDyylXhQpX|`E3IqAK$B_q%Dwazn2^W<4zKMEU&n=tZc*0rWYR}M?KkP-7V*% z#O`hY;dO&Vu%8>F07Dj&kf0<%ZusMYOYwPLP0brq0jk?ke&@-=mu;GU` zrUS?U9tYp06_>%zGB7vygDC*a3tsWcdGJe@I7jK3nU5jIQgw?C&+D89xq*snjy+4C zkqt@mnlLaRyONWW(`_cN!DHNDQn<1-k@acd=g)0utbHZUY~cH5xe2ddKZY;zvAum4 zAguZG=L+;d_U+V`Q+?uiNRwN)zISC9T`96Z4z5e|VA{PR`lT)uJAQ`VXvlHH9We4; zalyGQ!-)wK(5pfYf~s+Yde2w|(dA14DqizC!Afdgeev6t;i;bUZ5lVVhwot~!fuf83|H#jp~FJwK^VAK6sH^ThUI`10ImMtH@S9s4@d0O87x2XCxw#`Y6Gu;Mj$yS{I(vIMuY5jyoj)@g z#tRxfgTw)q2(B!ZOnp$}TwP%S0X1Wm#QmS*7x8)`ic4i47RIoi`g zJ1QA+*52bf+S--~BuLxqC7jnBh!ZM37o;J zGFgpyWpei!`;`SVpFPL7>U^--)STaljv9NV#Hr}B6Op4Ns>k99sNp0)ba*HY&Mpxo zvZ0}Yur0~d1Yx}OnH%N^mDevF!@n+eSAq%vkI+wU~-by$jFFLG;Q%JNY4dPesWJdxOBAc+~Gs98r;0; zfvnEkhe=UHC0vl=*|TTJA;T~JEwhys4ofo1jGhepd*|Hk%&6(vc=66T^wsX(-Zp@lm**I`%A1%N_DiRv))qN;g9J`~0{Y`vs#_4?`lkdw*jzYeIr=(^=B_-6FwxDXFFcOdBZj~_qOA+8iOG=i}?HLa~d zo}Soi!dQgoSnE~8;6>GoY71NdhgAMYewghEXJKJEBq^yovvND&mvvX^EJ2$#d1VXSsZe%>`NmhTtY_K9~Q9ZVUmvoqq zZ)lts_9sZgQ-A-_RhiERY3N;8PufZ&i#-4zjVxi@5KcI;Jg?U`jlg?tfmex;latfc z{?Ak+p=Nk9qQH?DNT9UeTjQ0Vmu=d?!^5LW^D@|2lZ6_Hyk`t0FS5P-^-X_GA z^3_Ird3hnC$zPqHpC_zJ!WDuxL%;amifDl_gycRS)RlzVCV$}P;~RrWAxs^Vj}qq@ zpMl5yAathR%G^T2!)rE;EG*ALcx`ln=~s}Al5IgW?&)dr@$n|%2UFTdRG7ov1laQ* z{9>gTDDH!NlE-VzW_#%NiAgUkEO3~@Y|XalFBUQ5;2`|lQQ0cJLG0K1-WyVppDta# zbm{K6ZqW5p6n76Pzq%`tB78KABzS-P;ywu*8f=lAw)Tr~Co8Si7?RwOtXq(;Oz%JE zPHA4aeM>+tE4$fJR+0eDCE%gl?1q`jwTsuBH*eZ>w{7>sg$c4&SdXrAE_YsckOSBL zmwaQ9As%L_%r&+vh0lhqWVTd+OCnL-o0OEqVK^=mQMag5?66zHW+LG2TIh8tt!o9% zFXA(!W#ESpfn%V9O!p@YSe(l_D!*uO`&Ju#>uaA&%${Z+4TJqexZ^<2+$IuqfTy2d6=H;f*zD|!6D%%!_Us|a^(U_V{wDkUXQ2DYUnMypE+a~V zJ2bc>8Xr-`=Dhmo$&-!X?N%}xt)Dq-qg94Q+$0H*1U?lMPCoOxQ-8p8$UrO0YkJBc zGn!@pO7}j+%&4FM`H`bAfk3S)OCM2I3fpkE8$lNU<)#dVewC~@P3mvpQgRTf1j8~m zHWs@#ww*KpU%IBDA>=Kqyu3U*a`s{E{vbVsCk0d&6crW0?ahxRDh8c5+Zz3;+JnvM z;LPt#yOqi5n_5fSvr82PNMtb{M$)YQ~RSsHH_*(7usei;bw?!9}1k;%KcyFYEX zvCVXny$z74fZ$WN&=x80gr&mSe-Vr1+xHdtNZu4i4?-pa-fd<*TV1W6;=4s#Vb=192|k- zBe~;>YHB`?Fql(`frXQ_x&$_^o~B!b$GAN7_rb@HAG1wbIGW-|W;?+& z`@GG*^!3SojpTV@bb#Z%-RuFvg@l1Y4y@TXt2dqSn>!H}91#t`lj(D~cbk6w$*-1r zj5oxywLr@F{$qLO$e%qMjA5kb&!4LUxnMVV6@}+;M|yUZm-xLwMytFKJRJr>HZW4_ z>gozo_DG<3@jHvw{GV6cOEnK@$sfTYi4#P{=I}eUajCcby3}q97PySb+66nL2Mfm^ z^gHs1sFa$#9GMAx`KY2o4s%RGLT?_>Y-{kb$%3c&CLy7`qGBU9mztJ#*F&{^vPWf> z6ijs~7UBV~OTe<6a*`1}#)Ha1*|GfVSE(u5^k2 zHi71ow9=MjP0!Rj(Gmu01C$}^~RJ5Qo7Q? z>450ye&esA+^&cCQF?Hch8&DdOgw>$g$_$QT!!v`z98kawlqq;b?dFHFCA6n{fE_h zSXm_b{@}p62`;_o0I@!GlSm zEYCZ!TuWuS*9EmW*x4z79GgiKy?OL-Hp@XSg-n|FL-1K2jckmQ<5tu~o@7|zNoE!` z-v=F6uP9tqS^2TLnhM;77&40B-$vEE_zn3`HM%wYj3ZW^c}U#E#Kk{0HPK?DK+;Z?)as?3he%FM(k(7|fPXK|pxa_Q{Z-GJ`f z5GhKJPe{+mc!U|1yq{`8W(cOrFq}h%(MdtMxfJ$Ea!P!7M1)~&5Vx4!%$qAc=#vIu zeUQ|72iZQ{YCp`Ul}khD59f7B(0gJ`1d|h8y}g`#e94spT^KEshLg^8L_0t+D*L!; zFH&<5IKo&#RUqIV@q=YUECz|IJ_UiLA<~UIj*I;v3u8hhyShIi_6&sF`8!?BrhN+Q zBgb{MIGw*h{@Af&8M&UGhDJsOI$9uA6{E91u+m61pFNX@p$1ZQDEFso(8XcoEQ*&d zJyU%lc3N(|H!cU#pW{|vV|;9^EWC5>*Ht?97^Gpy;+K?+f2Ugjeq$EXfY|htJ zEJ4_`~@}SbKlc2 z;uwIr0`gxqbtuxHlP6D(!K~onnEn!s4`2tLm@`FNQoT%1!*y%>`d$R3E&K{x$e^~GP z_wOfx@8N>qXW(|-{SYa+JjMwXNTn7nDUbZ4%4atv0|NueB`rFDS%YhsTK54V)MO2;Ni1De;Q2Fgz9UtNwh3W$i<3SmmK`{+iJpxw-MVvr6?2BY>P zT>b(*L3Va_SSZr)vSG;y8CFoMYNK?;wR^GIZrB&_V=7WQjA&%C{s7D){$R^rAO1R} zT0;yf!n52M{fVh|7Nm`+U^HT8A;XOvoSYQWug%ItU@B1vKb1u@9YB`PzkFCqij4?O zZwfTq=1H2ia^>ge>tis7KeWEC4mxMM#+68vw9A>CTy!oXsnNcMxw|ud`@9ekz#PiH zlE$U1tQ-&&^f)=04=x70fEWab{3DnHlh@bZ|Jc>FAeYPc6bbtOET-l@3oz=h7TNJ; zMoY);3Edtu)`X(uu46jK+uOyc!hI^T?v6+Tf6_S}oi8Fk&2O(=U2N0r(#6tuMu7!@ zTsJOd9#5(taU!2Pk;}EzrQLcAI`vHvCR{y>V&3rYRtCA{;^7$t4<^i}$jH5-0{pci zB*Vu_@V+>#%YnBZIMx^@A*>CA|KFt6m*~UR<~#KUfwY3hj@@prPVxFJ9OiD;V~)-T z+MB<3@pJe4cT4!$Pz6xr^6o>lcvcd0)*k{?@7IJe*BFpd9XkQ>$7n#=}F!a6lOz zubW(w5~^gPuYjSwy`8j&Es74+fn18V+??rqx|JrIXP~@!3@OcofiWSjBM>>Hm%^c zowr=VLP7>`T>6B`&54cpjExAJrYZ{?hZV8hql{tgib1(%=Map=tG;}S8M@NGK5ed) zl#I)W=@8Kz6K`_f!s1l@A|!;%CbhVj6;9Y9qHfDSQ#$v4cF<;IWFRyAm-m>MmgWIH zOU&hL$zX#^p(1v9z75wkSVUN z4#}JseAmaGuj1l1fmUf3Sh=lOV*0`mots(QitFvWcQJ{Ho^b3CPi%q!6tkZ@D7iGm z&=7TMFBF9sMrpBR=?+U)C!N>!fjsZWJe8Q`I{{qV6SMVVCr-djqK$T1J|tTC8b&!F zRv)^KZ~{Ss1P#hI3K`hGx_g52z=8P6yo*#DHxd*20H`MjF@V^2A-qWeCfE#-3GfO- z1RXHCt1xWAd$f_8A8<#EI)bJ{?Co#$hq<;0PVoDC<+i}QNJKAXppfWLXOU!k%bbF& zk_PSl-6-0>Ur=y6hS$)8iRuUh{$Ry2#7%&B4$D6h!ZA^S=LKyOyf=0p$)Uy&Q#~le zd2MYUZlzFtPy*7PXlG2F7B^;uJ%7H1Skt@;!L^q$q4`0v8qx;XV zeK^Z5b%=zgdpQ4ZU$6MDZ-U$#3%!F$DOkzAvMCAKD;1$U9Mfjl%DI(9A~ERdkc~(rDpma5 zpN1O$&-(Iv7yh92*0J;>kr-QvFRIi%j9erVA4!*d&?F%9%dJ40gwN~k>IDb#S--3Y ziC^Q-E5ECwFZNjG{K=NGTyU?;+m~9R6V!W{`1y! z@UiK$%K6fDA0ND33Oe_yLG`WQ$8Nus%;29ksscIw-$o8vTXR)LrMgU72Aci-XkeH9 z#>GLJBR*{Bi!m9FcB~>~kdFnKMVw1fr zM|z8sGzSCq)B*>+R>VamRqBXddwa(J{Aj|8xL1zbD&)xedetH~cXxLKBO^zzfD>DH z@7_JS7%-fD_b#>C?L^B*r}z~V)=~!h^YwNt1gLJ?zI~v$K0iNyP;R%lcyoXMwx*`0 zj?PXhzM4++dlppM+S;zJt{U3fTXrd*Z7g$Y7n=3)^J6Os`}1qX=7YkSVG^l6>>tm^ z(6wFLwr%SvHZ8HTQyTY+Y8VT37#tk5|I`{Au)ZpJ?6z8hX^9!XygYksY-~?o->?3u z&clZfZ{D`;@7mLVmDvGOcwe7UriwqKb=B#Ec6L1Hzl|iU%)NDbm8mrI;jzNht6OpN z^QR?FJmC)gwcPY)ea*qeWedr`%&e`_Axyb%iz52MDY>{Rz{COtj9!jh7f zw{Lg2xw+Z=Oi$;isj1P>)ZBRG%9X*#{(I9_Cpy_SZQ7)9{5VrkP!J6bP2+fbV(oHE z3{%UiSBy7q+@PVQrMmhuK^e5vr!{`s}tioO#x7ykY6 zmpwC_UXpvV>pJ$fIa@P^L}NB};z@|*yku!%Ax*A!V%wMZ)!BKiBb%R)(_7XrjV%V? zYSg6B7a99W;kXIM&SYWSVbjm0>BYAv!uW-RHj%u)49P8j`^c+*L-yd&qx46Q9+f^j zV<03Vl5^({$e-n^N02IgdA^pPt3d^yY5aN=LUiJFthIN0sB}&!2-0!3y#5 z@rnhTNNIadv?cLtj?THF|u7pbS(>%@!O>bwQVZe2=AVWVc`rqR^YEM+t`H4O*|7#(ejAcf;0 zb8>PHo$kuJc#(=-!lLnA%a0BG0?#`;vx_Y%Tv;S-Y92m6+cw?wy5Kl1>D!XFY*@0+u2BU0gD1GEDa$)lTn;x zCSJ9?nHkp&8vlNFht<@H>fa!f#H6II;9TmHT>t+5X;XLW)-I|$&CQ2670z%|-6=7D zz{=9wnIcL{I;^d292BHX#iw?A@2SU8QJblf6zl8j#pL8tDHL&W@fke#U9;IU;%-@+nx@*= z*r-)lbMVGu36m--2N+07bSSsfvh=NZ1yO@Dq}Kq3hW3X(LetT?xB-FhcKf3v>6 z{yob_)a1x(*S6)|y?c35PF`N?wpwW8^wQ$*pMIop+@*PSQPFPF=(D&TD9BU`%ignN zfmC-q-j??C_mlCvB+|d%OH66niX&zjnlX%HJ=vNI-@k7ly~tEbDY@A`?$8`bTNAh> zGEyH%9OnwR*VHKHrsL{=gv^fH+w(o|>RN2)4I4!X($Ldid$fJ$iLIyae4>k{)KG<~ ztE-d3V`FLiUcX+%^56z#WX7nMUibCcyST(uRLF9x1~A{Zu8yv)RU&yGVxv_SF_$ zPr|B#rna`0hKVVrs!Bd2G&CDabo}^n)xhuMdpzg@Au9vs7FDNreqUN*;ozX4x6E=S zFFtD=S$HCCWNf@Ro~SM$Awi#&m8IxCN*bzgi|`q5qasl=@x%`g+mH_*9-Hh+OIJQ8 zUQIuaHbcdiPEz!nq8B-u9Laj zxPdX8V~a+l>P)ZT z_q8=qTU%Rfa_)sczj`0Jbk{87;wc#!JLS;a?jFrJbRz7J9MxzW1qZmZsp(=#@Y2*v zGI^N8?%PPivr=8fXwm1W1YK+Eo1Aj)#)lP0>eF~s*oCl(ETl~ma&_>GWP1merfR}F>yKLG!S5Tn=n z>X(J(dl*R z1j{;D7*POPvtnRuT(U~$l0V&uO@8)-OV%}M(C9kQG8a6Dw8_hpii(O9Zu|Irwss;9 z4Zv{v)h!1PkFKa~^KT#UW~l~V;yDmx|M5wvYkwijr}1$dnB%luS9sMKafsq~sj#EF z5hwi2a19mOXhziotIDmQRc*h2F4fYU$cg7U!1?;FzNUczbLOpEy`{D)Lc+q?xI?sq z=;~?(yqrXHx9#z{IcgMrdPauB_lZtE0Wg`ykr5s&^G4FP9Xlerr=8lb>>8;0Qsw!6 zbaa%2WmQyEw4Zx(-^L0j+p5BqYRi@_0YO2ZaJFo$oSlX4-M`;7y(AO(-TCb2zRmBe zy&kNF(6>F^&Xc$Wowz9G`t|D?ODQugxz{&u-rS3Zjm1&)zGG2~zG{dAAFFdGWNvKi zAen4vXqb2J-ixBIBErH~QJjDYBR99*RCn4FdE*8`Klcf{4^>*|u@;^-!)r;YKi%G2+XSLfep zlF4dnYTGzDkB~Q`zm@<`ulf?k%>v(#Duee zK+xacN{Y}kIBf$7(Q1Yy3Ss3{B|3z1zO73+S+=@>*JGv<(aD%LidMy8iM_$3Liy8 zY^0~B?qioj!eH*X(Qn@p(Sy*@a@$@pk}4`H{<`%1Q;Gln{X6GC zc1Z~xpr^v)Eu$(A6KHh=x{;J^orzPhcy3Wq=b!uFl8ctEb5V3VMyID^uyjo?UozJkv~{aD7n%{U6$z}MxKm68Jwz$v8c>M3Yd&F|lHnVFgW_)`6mMB2G?C*{hO==^+P ze;jWdwSLyTs%afdH($Q zN{}5tUO-TBk>gqMAO-xpchh>luiD!d*>yyT@bZ;xFTb}H#Mc+19(8@ZLw z(y)mhYpwAaw|8@kjo89;==kvmLrVk|&(6;NvDB^ZF_}))I5fm*TyX60`zp`u+}sE> zd`F0-bVVNl5cP+yy#lRmZHFu^cM{|ujEEW12G43@S@7u5eu7Duo0~JUn3$M6v~SuV z>ovkndU*QXz8^n-X4lkkV7Jo`1k0n&?qp|QTv+g4o_ouLGl)IVx+(AJe$JM@Eo~Fs z>p=}~KfjjNShiaG_y6^s4rtBP!j#(;xA(7o``8Z3UwrgLeSl0g%`c~=-KYKh{ioTF zn2Yf7k>YmjEq%Qt!*QGKM16~&uWvIboLc2hqo3(jC}tFuZkKD%!`l`Ao9yl{X^Epy z!qJ~lx_1f+wkRklv_5;*X?nhu!ji7wmDTz&H9r$jFXP<73}!}%G4vVenu8ZEsFC>g z?>9b^A?Eh`d)MAdsXa_+SQnF%S)tPJl$J6&IXT7e+#hZI)O;6jU)zfQkt16JRC#c~ zg@l@Bb8PqM#SCl`p?xD=#17X?;n{St@2B;glkFK&lzUrJ zM3~Nf8#ypIH1w(D!4uX@or6?Bif2Go2S>*Z8V|Xg28vBV#t)U4-5;Hs+f#Oco_YSD zZJA?~$?k&SwXaPdKi+=-!pqq?65#9fxi7!Qdu#*P)+Itu0o+I=Iy$<0b`6{&A|hxL zTCg>=;yIdhm7(v(21?8!O~Y^AQq{RBx-OY^_Wc1AOa=h`I z2PeAo%}q=iTU$4Y9?MKBNjUi~WW0?5^1HFEjT-bLT{UnYZi&A#u_U<&=*Csw(7?jV zdg;n8mFC`F7W~IL8I^3`H)KjU46a~+^IyKyKKp=P!rJF>_3G7`fs!5Iy|o{tZ~@|U z0am~@;y|ZKeZo!7x}Jy0Wa47SjvXWR9D?m3a0TR-3rC3Mk$=yfgTv}BZS7GLJuM{) zfrZ%Xl3u+eg0oa&i*Xi_3GUB9=lqbm)*6A741s*5{Wu z75eMWd6bux@eAZMMQnKu2~-orE@h(wI1&}e8EFW94Ov)I0TRr7ySo5-lZB-hB&G-^ zgUv741f3ln6jaBAyOX87ijq=qqWWJQGMUhUa-Kuiv=VtF4PzuSim`}B1_pO;?P^E`WSYdH-AK+zXtR)8g z=qTXLM#at56}Z1PQ75nUf&YQ3$^Edtw$|3ho*w4t=x9np!n1IyjrOjt9i7{uNj{(#1fb>!}H3otz@}5JHDCzO%se2X{7Y~9?%DDFz ziYs){rJ6*(?>nTa>GOSpz+w$uU0V1hnRzKZLrgvlb zXu)WT=y7k<1gR0*M)W?&TeJ6V<)@G7>9t@#Yfp*;?QzW0`sLYDi+-(td+KoNR5U8w z*VEP0GXbs!iDXrEns(2gJwif49j`+N9Px7?j{u+?n>_d=RK=>&UHEEZ`}jdPeyBPU z3A9=@>~H4dyT@)RAGEZzoaM@wEt2F(jKN;Fwzq>D`*|gxgG7O`k-R^C8>*xuc|%Bm zAUAe)79A_SWw_Q~qIwM!^7`HrS0LR4RaCg}C|Wu?G_dPlOtPfP^u2jgI>2}K>4iVu zqm5K(vjS>rJh<4x%F6wHPYY#@eSP<7C2&5|RmKt5J=&*B@s96nX^BX2vU+Gwwf3l@ zTqp&sX{|afZ3p0txc+e6IXVa~7GuvW$Z$fq{QVP5Sd~&zQm$`HcU_K)%f5djp9@aC7Dn=`9$AJ__WwCDBf7C;Cr zH~~4Ylb!b|6dJJXMo_XdXU+iPi^{zwQ-?k+2H)6UL^6!pGv!R%U1A1)$;P$W4jLPz(^+CN)`XF zCQ5%h#usazqJ*~k`S}r&4iu1vk@32fme`%2uuOb?37$RLHg)#w+19oRvM2+Ho;2PZ zc7%_Y>yaaUZ$muX-5q}|e+Elt;ZX~r(O58mS2Yf3hcy}n$`C&L-s1X8_$MU3sr0_S zzPzDLCX&XRH5`X4@BR^sYfIpAf`v#htTQ9^vHM+KQ96g?1cn|!zCG*9*DDKNI|GHq z&(D7`cz;Q}MA7}{f40)Jibv9OD>8#!Q4$l|Q3Emo3!}<4?pmRSUW|LCq!{62wBAzj zC(%&9@4lrH0|Ox&Up7xZhW*?1?AbH1y?fiiZAK?2g&)}&?k>Pdi|1Bi1=M}I?&Ey& zBtNVWxYOY`Zdg_J9e;4*DZySE#}^lVEIQ49e0sY?4=oZvhRrz$b%OVa0;Ks(+m$(P zUh`{fY1v39J(e+`DeIL0kPJniPn!sZvKnoc0e>$tCPowGP*qh$3P1CqE*q9|`o5Ew zE#A!zVX;7LA68aQesWh0SRlc=OmpQi%k!#~&(4Gcw|$IUfNaBgOnlxQ z2M-?PQ1W$7?Oo=$%|hl?bK_5dWezV^kZ?8MytxbYPoMzYoU|?{0FmBx34ZXuef#(4 z0+S8R%-C5>54e@Ny%s?OV`1P{OrlUqPdq(_I`6+{xxcTsmmepKQ{}vbLQ)7^VF=6J zkXnYImy16`l!KPVTw1<8{dWvD?!?Rt0U-sgtz>sdDKxWKUq8PhBpZ1J1={ANHrcR( zjUe1RhlXxQNJxM`P;eiy6ft4pDCP6>I`E4oCMOS%jg2{bcmZgwe!*jm7X50$-QWmi<0M;tG<^qSs}- zZ7x)wxK&Z85F^UO&dz=oSwK+Hx-k)K{AqCM=5c>pdduP$yl*#nYn8=>8@7#^dEwxy zX*-ZRPg&Ix{VTbkz~zADavcJCe$&!89h`4(Wo2D~hbbs4TOp-iy8p>F zwQE{{Eoe-iPp!11Mj}E$>T=AWGB0lv1Pl0?Z>m#de0R)VJIP5W8J|z&;aa~f^78Tq zCMIM&uMAvFQaDT(9@T(wRJ+;k3ajm~$6C=;Wc;R%o>^Q@Yn_%dAAndVlgajw=jd)) zXpk)1w{M0X=T^VK-4e|ZfgVo)Yw3$uw^Yhdrs8w)adA$D6KX6+7t`Ty%{g3dM}THX z``?1HB#*vNh*W6k=t{h-i5SkTK5*&oP}IBz!zs6?6Zu={smDJis;V8)HDNl=372!G zFQ4va{z-&tlAWEMib2b+sYk}3S@1ZK$#9LGCG`xAjh(#w@xn(jKulv}V|PyL>&?gv zx&K>cxS-2zr{6pmJGGtRt=L{5U3rcp5VFGWOLO-(i3JDqk)d(wq$Y|I8M9oxjFCI^ky zR%n%qNlFUerE=aLr^Mn(h!QM9A26*Ua~%_P!!A}<){cRJ)cN`Oj_1!W6W%g% zPGBOL)Pb(VR%}!0zTMK=It7VB<(UsRl9Q8bf(|cT-g*&r*auAPgpY<`3nqyhD@zxJ z0((ds-a*=r3;+K9advlq9(txPkM@?L&moC!?5a}J%i>u}L^V4O$5X^)WUdYm4|jmk z!+CUrO>HyM-*19E0WOeWc~#Y2ypx}s`oG`%m6Vl}8yXH&y1kBmm35#iA2Nh6q|tH- z!jE+G3fBKH`5)Vlit1`nbQU7GD)_SkBH0HbQV1(m)}eWm04q)5(9lpaaxu7ZeuniR z&mE9`#N*>G2vx9mZz6>P9(5S?+W#~x4Dv!$?e_5Hce9xWB2X8#GT**8pck|}Wl*f-%JcnzpLdV7GFiU!Z z*EoB59S>2v{cG(TK?Cl>!~y6CqG&%Y{ao%=|JQ>66NqGWNc%xeO*)u;>wz@W4_vUS zMCIhS5w#RS4XJVn{ z8NyY)J$G?)9|ecV^s@m0J2yXgl|ljPX`;6a3S8Xxz5HaCVx@hr0mW3Q9tKK}!p9Iz za=GTIH?s7Cx4Wl#{$dWm$j~rb#;J{&#SjiF*1fMQZLg9F2+(1K3HdmtaR==ClC~%B zmyn1DmD0dcL+&Da>xBfQ=g7tBm=P&*T!(FiRo!=I2DeU%TjMy96lU1 z_!C8R1Oo#`OP7`F@d$qZ^dsNG0p)X;Mz%w^<`tEdMD7KJqob)AA%aL6-XdEU*REaq zAcuJm9vp`aDGNzi`ntGoH-&QT+BGpXwJgMXeEf52rw662YP|WuI&Y8+5KpJA{#x;X zwUGbq$@-PHE4%iXy+WHLvTx{M5%ifdSvax~+dJT)u#kclKW$D!03ts-T)UrzmOHg4 zgPBD?UHT$`rM4R}#`4z>DnTo=+o_oSNGj*&`F8BsQOaYuek@B>7rRXs3UEUIDi|EJ z_?loqk%%z|ReSs3L;*If7uG~9r7$lq(r+7?jL{6C6DLjx2!M#O1`CR^F4r!2MpJZb zZEvNtO)vf2wrkhRd^DZQy6XxaZ{p+R*1PsTO-e{$z|>10)GkGbnUlz7gc#sN%P6h! zhW)!JHCy{Ma!OU^|{V)mv85x+)LVSv1WoFgL=i%+z~f4q*V=mO)^k5)6gj zwU1$Y$GD6A0?E4TccFc3Ce3{Qtebg) z;%dEHOw8L!4nr^mry=MrJ*ObF_tNUbSC;mbRH6;t{5d$8iO9S8O*d++0 z2NWk=y-Gx9MQ=CIY?uXs@LSWHl#b7dGk~uztd^FRHjW-eMB1==q5&@$HDH5@*aqrX z62BKdh70Qd)Qj|s;H{V6@q5NwpE$vbcAgf*$Y1`IfxqvU7KfD|9CMiS(MS^hF5Uh| zcrixZP~HqPGc(@jFo^SMu*^w%|Ne~zq1JJ$398){5BFj&N?48V+kGqv##nR)-R8E-pNT&-jGCs>SzY5_5M1n>pGwz*r++wv;&hmxK*#j$46om08x|u z>C^N$#>Aeo{JM?d-X84lt3=OE&-3($ea9`7$+ql;wPtD@WV&GKVNi zwA8)fQ-Ohju+qjelL|eXm%22)y`>2fh>SLtO_Z0%^|hdea!dGv%Zz&+Fj4@7pflt#~MTWiU5`HaX=x(_UzI0@hN*@ z5CUQK3@!8O?b}3hg9$A@5fLq^bvT_A92ZB(57GqPnnecY8SYtEGh)S`VJu~n2JvSb+@%)60mOwd*qEv0Cmp5TM)&u=FVbafGA$$}B`qv1eXLnZ=&oAswB+BPKbg8c+RzU1@5H9MWywXxfuPM@;+S|AkWgFzs{19$99VzO()?k1A>FcX9r3k zz#HN85fwOGAIJt-utn^2>R8SazS)FPzmcEmlykW&W%7;PQ}`WQs!l z2p+uTWYN%UX*G6l5>2f8-OBQ3<5{HmV42B~=L+6> z$4LWyD<2-_Rq!=9i-w6j2WF7FlZAMU9u@1-89GP3 zxaY>91v(7UI{n=m+!PYGwws!o`dWIr4*3$TG$Im$&|#+JHTq8xu7Wunp*PxxoTDZr z#Km)V?mv};nJ_|9z=lyU6O&Y(1krOvWaND2%rV4m&TwVGy&au0z&e{3rF-j}eT*%$ z<@UVi_Xx2Xsbb&7o4Rt8&Xav)OS3`NA%d6{7Z;P4pX$cpTzY@zRd#D~#Pmt!o%;Gr zt}xVO^RJaTAN055rw7us5hq9oEZCo!mqD0`GoH#}?jj?}5g(LOmy{V_M_6|jprUvg zVK2O->u0ZBUV!NI2;D$EuBU0Hb4=^Qr>|eHfWbInmaAuA;4tPM#=d>qE4PE2yYwahCy57gbW?aew|B zQZt|nF{&9`0ZJdyKAw$msBHzJhs&ugz9?0{GQWJAf$0~^58V|^ZpUH$l-aT!g2DA) z(^=hC1J>!3j#`@>;jod^O!O<*)RuZ zZ03FSUMTbkbe~TXohd}l%F4!8a(^15n7kjxI^&)`RmV+x+&lbJ$w-vZ3*>kB!cj{O zPEJSU)Wj6s+6P1##N+@38x;wp+WW`Cn0WPy&Ny20!rEF4ZWI7PWK>f602h>81k~8_ z@-j0I&#Qdf`T!Qh^HETi+*nA57V5Gf5PT1~MVIx5=7($9fYOdXod*aY{GTz~-@ku5 zUcH*?gEtOxO%Gl`jJW`sOt-2(30m2TWa|GoyF`U(pjPSzu)p!bpdHoCy5ynQ_wcWbWNgS{&2Il7Nh<}8uL@Qyc!$>2M2oGa% zaZyKKKMI1A2wZVSS~@#vKZYzZP-tNGHsc$FiG*&s5neLk=Ay4tkzgevh8$4if{tyx zw%gcydB*VU{Gg#gDC7r39w&&`==^*(tv%<7xNpVNHByn%&v z$tROtqAr-0>k;!hrKQK6Uw`vk$W zkF6)@@J0Dez1X=y0}jQ&oAHSWGA1m91)7S#6Z9C17pqfs&ETZ7F6;k3Vk0y->FDl$ z1Qxlk9@T(n5V{@J+JVkZDI6JkRNmi%s%SO)!A3ig6uET| zVL1L;cFSNrO8#_N8t+3iD43bkuP~Ler)-Y~CsNCNh~Xppbc~E5XpWegGy!qP=mued z!c-^z1tL9hcE|L~o7&(!lUZp>epB9_kG(#sp=Xbtmx_#zW+ffb*S~Kz6t8nfe{Jr; zQ?p>n+ZzJ?t@?j4>=hBAMm#4iD@#6oT7sIMgGl2rI_@19xs@Jz2E(V3=&C_Dw_^b#8ZgX|+EBrP z8E=at=9CTpW8zm-Z2SEAvtsb71T4+kYC2%pkM(to-6IaTxpA>WveM#Mw}x6!ZABI`hO&R>pyG5{$1F#d9#lv zF9!$Bf5m1+q5g2!W2?4_pX_%D=H%jP`S9V^``|h#3}U1jN!-dv7Q!8zYS!obzwd)^ zBW*CGx3;!c4PHGekcj*PIxHHqDTIND#czdZ74ARguDSO0LvM|bQ|WQo)K{=Fc=n43 z=*GRbF!8iv6ujooM`Sa^L^lF4ZydPg*#SD3_f&iabu7NC^OiHSv%c#X-MhaC!WmZ- z7#tL27I^%Rbzx---T!5rX(I@Z4G%JgiHQkfax3ibPf<$Y5zD(sbTEg(hJwaUus*(e z@tBHXss4e{+9Xg^*keu;9akMc zm(Q~N9cB&fAm`tVG&+RAIpk_&AYJh_*5YHyVvyh^?R|Z$5TK@ie;2A&S(%u$7KQcu z2VdcoyS%=o9Q`q#L*|e~!;_(<2>Hxh_dp55C#~w*K>EhCLS|z(8V?puU?6tw9#+Z(Mp;93gCwJ!n;NY(aJ4Z&AANBt_d{yuD zi2$}ZH4Cuv#PpCv*@@H-GSbo-=uKsa{kYXaEFA4mm>oDY%_sg%=+~6{>C^Fu83Yi7 zs9+cJ+&fK0b!D-~WkE3Bq;Xpro_qaa=bJ+x z3hh%{&%PM^>b5!)vW}X^k2f+GZuLVI95HpLY2X)7FdA9G_UY)l$ zlUD?pOhG`Jb?G4TW06g>84i@|r3y!h>$PD%=_(MnlW=4+Gh6e*BU9L$eL?RsH(fC( zwN+#mFUf-NNx>%%c5-nUgCDx$qZhJ{tuzA3lENlCEtARQ4Q~GbE8vkTjg;Mer+CP3 zxW;GYO%}XYnx<1vMXGN6 z`j=vLY&Pf(GGR_blrUb)%Ca$7eI!+~;y9Fn`!QM#<5iaAD_h`ZKjrrD(!OOI-3kl6Ry{WknkL<_8Mfn@Z-jL~t= z=UZC3Iybxf7$)*n5j0V(_y5zZ(p&kU^L4jKJxYRmw0#Ee?B}F@!vi?_1`{MH5Ref2j-Vk vU;jJel%+-Be_pDt6}TGxpAUom+Y-jL@QA5Y>p4EmM$$cej9hxi{?h*d`jPc` literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/class_distance_section.png b/doc/src_intro/img/class_distance_section.png new file mode 100644 index 0000000000000000000000000000000000000000..35f2624c7f646630b17df7231304de771b8baccb GIT binary patch literal 5535 zcmZWtbyQSQx4(phGK7e942*~%9a0j4q!KcOfP{d6NK2=r2uPQNAOZrCqBKaSN{6)4 zNP_|r-*$cPkN4KQYwpafnS1X!XP>=)vBNaf6jA5t&LaqdQdW|`2cH3OS`!h#`)~ih zb?`y#pmg6EK}cKwoj3_xr1S_vrKv10i*-+1Pxru5Egg0=CaoKt8?X1zG%>7_$#jZl zp-X5ZO0(jN%_PXyD-zMr#N#J_AJa-xG%UlJs}Pr*%n&Uv-^7usl5bLhisl@?7yjl6 zYbwsU;)9bDoL+VFgfL-^+o`@Z>k%Xdc$79)m6mM(C}zTIYzN(`)9}8;$n!f&B$J|E=ndzP)i_% zgolS`tkkr{-&JFNu5WCNDCN$`dT+Mq2aW;K|2J$-hX;Pl)zsWv_MzcnmshztIaiKn zmLvii8>KN9iQ$FCVogj;5OsC+w>de)9uLjT&@oEnw6x=e;*DpgUT@#N-TSDDhpYT# zx{g*yN2hOSD5$uYCoMhQalSJKC;x2P>^c`$pge0+nwT@e+l|w{O+`5q6P8bQQ!hr1 z{TThu{?2R*?mH}}a;!>DEaZpxM)lIW{QNG6 z)XwX(W6Qjbu}|M7CJd~&u3QOLQ&Srn82Ir{Gn2PVPRnvWo22g z$xFQ{Ej2YYY9*RhRvc`stOsi)jjlB@<`etO8geYk_V)IsXD1=04s*9i8O7rjUox0J zdcV~(_)R;IzHURD66Wf zlF|wUU7+Tf@6T4u*We)X7ZVf1DD(3278Dc+h>O26_C36!jm0jntSHAGZ?%vS`!o9; z^MCm8!TRyz?(q+nahU8kZ;1RC7Z)L{jB#;s!EqxYwY3sC_pU`Th&5MLi59$j=P>cf z7SqLT@QECOASEX!D`{zI(b3VB!wOsYr|pSgP^`9gPJR7NN=iyv3JO^yP1;XN*{SUX z75-;xWA7NnD5izUYUhdcnT~F9TwGit|LyHm$vJTnW*r|9ggy%s`#h}d|O9(sBYW z34!cJi2NWJ4*RRxS!A|V)z!pjN%8TsBSi-A|K(LoSWgnK98VG(A0PR%XV2jN+d4Xz zMeHV@L&h_hb-binRla+dN?{6xLPe|OApV8ACAW-?jSp-sEeT=4$g*RECKij2K(0~$ zPDx3bGd??_ei0rX>|?v~hsoKGw$CFdEsX&XNQNiL>_=-D$pD8y@ef{s~%}=%y<%E~AZhu^>M{~9a9(=9e!DVxbwh{Q#jqH$)s6Sy=qHJ_!V+%Ji0 z*&G_s^ zaxzWbc02v^u&`%Pu9vUt`9toqva=JkwYBNhdkRC|vm~fEZcK{(n{!4+#=(4?dZ|Uv z<+}Y51H?Z?(6V`Kj0Q+W)MfRO@9CkXVU+_8KxxO)=%WdC8ZUX{sZSA^0(_TtyYVAk+Yca21lll4iW&O(3)Y57x{?ymk$J9Y& zoBHXK$kgOyaz+Nve6?T1zxb)8ibMj2{{%o@nVtRo_AMrMK3&3Xd2X%=Ef><))fEQO z&5Dbo1V~6vOG{2l>L8|M*IrgVr}+N8-s=XA!=H^QOjmiiz}MH(uR}sY z03zQ+MUknhs03|yNNm=%#IPyeV~^VorZzGGv{NoGE`EtdqZtGrkyr@Oy12NkEH8Hg z&Y!oXqNd*cIBJyr>={ldie3TG(x}!o(!7UW84BjhmoL{6RK%`G>xD5_ zuMYP2$Gm#=s-m>iL`jKgZEa2Y^vtBpR>n|6Lk8K~-Cc8v*qZj*EUT!f7+jyW;a=HL z&3pcwDEiVqkva!}1dV_>(X{X1b+y5d6&3O~1C+c#Ea0%v1t@X-A1$$WE7@shzKcoP ziNZs&tGhd(w$`g;=Xdw0jO!sPqSLH5(6EvTC42mNp)2RhOh0`qe*h5zYCxX?C5!J5 zBBY4q1v)-HUM5T9b7vQB z|EQGKunG!N{%ns7EGsK3<>lhK0AUEQ^J7s`Rc!(6=Xcwf^c|+8qB^IoJ&dz57$*bC znRF{-aq$ttJ!*W;DlDpRd?ZzgNmEl()NLbeOXB8D#zLK<=8ra`CKeXMYBq!jEiJ9X z)2FQm+doY$EP~&?<3O(ujARxRoS&Ya z9;JKcSK#v&|C#q6^evo%IUMC2bBh{t2x5CJIlYo?Kzn3&kX(XnaM@64+=<0d`S zC*yalu5QQ7>F*oI8*YtqpzOT8z4{{@W1?Qr9F}!2Z2g(aBx`OAH5A&99&eyjePFzK7T$K7ifyw*SOZTXwV66 zrIGR$MLthYH|Vks=EX?S20-a_cXw;(=!D$=@CePrLuz4RQT24?Ugbh}Pfu{%bVybf z8ouFF90(iv9$M6GHD5>;vc9PHT8g`K%uX0oiU)I{%%17G>gr^n zq>Q&59QbsK^v?+k3qSc@q3lli4+&w6P5Ox0w*2Jeyz_b*q9zh5is|Y zi<|bpxvf`W)t|l5E_d5o=)dYe!SXALdqC_&B&fIdPJBYb#|gI*`Xi$}Ek7t5N|Y(N zCXW7bf4Xfwao5h<>MS7H+09MfitU{q-k$)X2qG;ljpiUgt{c_Ss3u(5nO zega7fhU53mIwN{1DJkGH+e%(`_7GB1(q?lqEz$lWgzi54CDNQjBi$~suA22YZplvDJuo0ZDHe8ENKnuW_&$nRS`9`FDYCT~@LG7&%)pYQwEIO5$4@{n5`TX$8>WQpa0zl4r-e z2fsdi0*{5wkD|P)Mr4+hN7auyxx`kJb(@K%|L@oZ zcJ++w@&Wa)b&WjEF?(+{$!+w1W}~~s+u7aiIrM<$X{%!3|3Y~h?e%k zn(!zV1#K@U>nBfsxp?CXBg>B;X|l(KxdmQL`*c8*j{bW6#Zws}dw+_##-!gBooc!RU0Gu*s zTu?94PD};C?flC&T@U-|I%3FR@4xGnG~!RKDm_5!lhe_Cx6O!+y$HpaKkCD%1a_2y zk}|Mz+Ou$GG;=1zp)svKvY>#|-QE2&$PrgpS5fE1i0I3Vj3^r$8&KpAK>b!NF%YDavu_{IBs3gq3zv&2N?C0Qd-kZ#@GXuv^%mBOYq58Ks5pqJAxZTxWhvlPLI~c$}Lo*mhue<Ep+b2Y(vRB7v{*tg4HamX=z+eN*RHT38s) zl1jNlP;L0~L9Oc?fDDb86Xqf%r9`A0E$rX?yt$Q?l?-_Mjg5_U%;AH5Zjks+)rQFz zjj9~bfcL<}FE$&`n80i_dw&LObDaH*1MZFxnf>)E0!+2(gN+70E2rOHY-KP(#LC0) z=~e4Z<&9~Bji`8nirzN~Nl9|r+El=d2#X}a-v0i?M>lCOWu2X!GA=H{MxHBIBA9O0 zs0KT$I~^7uLA!%JE$>ssTuZ1NYfR?*_aseCO(2{6L6=NUPG&+LL|lM8&MGOHDRFGh zte2Yp`@X240JqO6wl=Q9ElGq14DiP_W`8y6>xBN0Epxlyq!l$aDZu=NLQjW9TDnoL zA!B~$fvLIq(8ieZ4_J-{X95lXL;N?{*^Y-h7N&*y`75Ok?taaTWUtT+60Ua+Hnvmk z8=j@7Gm@ZCb3cCuLLcD**BfRrC;S`s)Bk)%O=OJ-Ilx<1b@hE3tCUx-9ztOp9Ich$ zAk;jDGAb%6p-zB74q#qM6tXmAI1>Ue0Mr`B#!+Bjk@TJgFa03~tC%BQEOr+3Iif!_ zXJ=;@t%Px3|2SIeyrc%56g;c2F{ct1?R@MTP)G_23O-Ud0$DBX?d(EIN_Z1_9=rg& zB%v1}G4|P~LOu@Y1pwHMg_` zANyzRZ@8t}*V86K=2^(jgN@ovCKp|Th|iy8-W3+I2?&%=of5`;kaqqtJY1+N2MQ8O z1B7N&jl@aryLUv6j*bTlNybOo>W!l|?gQYF+ude-2muJw#9azH#@jklB-}PkngY&^ zRXbZI;XT%j>O&P57k74bc??Z0-vH_b1BR{i02k1Sho%c4@;9oJdSq_?oOAJNJdPGW zwB!D=j4z00<>wRMy?gf-&8r5MMCQ7k!94ZNo#AcYnsmkGuusc|4^Rr82BCVV{qfX< z;jE0%j{L6yfOaG<0Dg?l(ZbV#fq`2<+l>nK4-XX$8c^FW|L4Dd?gKeyChZ7qxMhsK R2pv~M`L>#T@hy{p{{XD7dcyz! literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/class_input.png b/doc/src_intro/img/class_input.png new file mode 100644 index 0000000000000000000000000000000000000000..987b9e388e2d461197b10d46ca1e7db4d8db3550 GIT binary patch literal 14447 zcmZ{L2RxQ<-}jk>%5ETKWwfkhR#H}lsFaNCy(J@5WM?G}tIR}25*Z;Ydqh@}tPmkZ zM#lR+@B6*q=XvkvemP-|_o>*A=XBMwxEYj!gtX(49J|a1MWu<98Vi z75?0mvc`eGHaecvb|wh=D)RTb`}^tH34)6_rEpx+J$~}hHNCL!e`}77=F%kHm6?3f zc5v%`KK~c@lau_<2EQ`P@KQE!tTjx1IUwmP$|}Yin&i@0E8#Da<7ZUe{Z}#O!6|OV z&(dAf5&ENxEK!&UxrRa(+BonE%n`@!!IP3Fpg4c#=n35>k{SI4p&Jc)7|R ze&^CMD*5&*m2a!Lh`gD|Fkzlf8?dvC_I~-D_0dTOS+5XcnpE=i8uz{>c0AXTEPPj7 zymQ~aeNFb1hZ7!sjcn=a=y)G5?HqeqmiYPjsHc+Ju59}+GI|A$>x6`a95k7HXR_|z zyXW_<;bCP{Q|2eLJ%7epQ|hR*a1BQ%r}AePp2uF^=sP3iJU4#f>SRyeS#}e823jR* zAGUqI+|>W$mP|du>kUQvLbYD%C*|hm_KkX#+IF3GRkRamj22yggoDA#%F6DXfsztc z>DuaFiHwk$5fS<8%E6(brUCnuMda_=OA{{( zJm&V{AAkM+{q-~_TTUfy-lOCfFG7F(uuV-%i%_CP%j3*1yQ0=g+SvrW~$alg>BbVsv~dE-t=~@b~w(>pr2RTTXi+ zyso)_cV@>(;_3lQSXeRR7T?i}lO)|4LU%+$T~?#9v3urR0ovUTYh8Refo zv2EJ4X{;x2fB3G$0hNIayLaziuc)X<5Xn0(n2a_*ij0W~mJg&injLE$>&*Q8`Nt;t zO^Zqwt(j|uPFw>J@TmX>?=?cdL|eS39ULnbX#5=!#PlP7a;ScLTn%ih&0c6A+M z3f1Zx6wQ&hD>5O0Vb`u*#i$2z^}o70v!06y;;3fO)*)zO!_wL8l z2W4a%HP~pSy#@K}xG8+RFROhO?cVlpr{T_b4sk(2HETwDoEs6rfo=T1jhS_e4Mk#= zRl37f1L`Rp#aNq0$2*=o=uy2@{!hnB?m63dnp#}h=5D_M+6LdJ8}5sBO^LqMTk(P*DEn`LkygeSI7? z5u6Sk62(Gd=8bX+3JT9V&wA>yIz()5O?iCSEvx*bt1lJZ33BJZ6gaKNYDFJ*6LM?J zwfgwswS{``yPKS-gWB5KvZgpmENthMl6yWuK{UZPYkTa3g@mdH--n1=wejMGYkBqC zHu(#F(G15+O+MwAWnPrkxT&WT*SYg$zM{(5*+t`BdJ!B)cl4UpRTW?RZ62Jc8^+B@ z!^p}SbZm9O_wSGCcWVJpp9)}WDToiPt>sDbf!VH;JyZ=M;^Ob~zuq7#LP|=itgdcj zVPPTRT~;RN7Z6a<(6HH;nxWcz-TFI`k?V+sskhU-cSVnR{-MROSATrOCnAD@q~=U zQ`8of0d%+n|Hw$DACr?#-`n^Iak1OYj}DvEgzqBXiM@Db*0BAB!8;E0HW5)#t86ub zar^cFmx<1jJf{pbb8~)8P0eh)CUl4Rri&LZ(rnx~Ks&uKGnAc|=l|-JXk%kzw&%S4 zlpcs=sjI0uxhYTpWAmrB}Ctf^OZqby8hD;`Z&^K|z)c4+Kr^?9>z# zKIc0;W!kOe_)Yfu(mg`M$cUSK8&Py~?M8~708dU{-jhd%-I$qL3!H}b961sn6trpc z=2I#vA$RZI#dT1krk0i`Q3O0Z$+NRp$NNeSe;XOW>v1CLs;dKnf`0w_MMGR)TbWl- zxVrGu=-jz;$zx-dJUq7}BA((y4@pfOKYl#dYw?!^`@^)_`g$HB7h{Fz*^IvZU2c@eg$PSN;D81A#vF^aix_fw>)6?5o;y#ny zhdt>`T?w}ObJW_{n1_;L9e&-7iW(RlrS_2{&YwR&6}?|8OHNIV&f3~q9d=u|b2C4967o_4QL+)E~)gyM0@{bjNxs+A@sS zg6mULQy)HjAc%#9g?=>71>9TQXEj3Z!i8-&mS>br&CQK_3!DgVbVu%k2bty6DCImo zJ?(WGhh{{)793f3?4Te5XxVOIl#Gpy5kzlq@3>l$fLbgifs#If%XnSCUN|4YdF(;P zBfFzQbWDtl1VP^O^XL29+S)##eVbZXm@F^M5Z(iof%2zLZPeD*CakL)YH9-GO7c3~ z>$Ws?rg(UIR(}4>F4x4uiAE!8QhjpgP=CL72#YWUG1XVH`S9VxjgJnqe0l5kP^!76 zhFVrumhgVJy0p3Bp>W{aw}-O~-t`%N$!i(?y~sQ-p67ci`4`CaoEgVfgV*Udm|&CYrjW~ z%5QCu^89mv;1U*Q!1(b^NZ@qSdv{|c+hfkU`}1eX{n@7PlW1a9D@FD-~9djC{^R7nB>$FU-jTrPR#+M{2WcVIoO_Y9?SdQe>027mEqd1 ziEj3`b3;5TM+ajR&YopDBrfiRN`7(q?RGXcHgpG{le~kpDyp9BFaIdT$tqtiyuycr z;R{?rK`8JrnK#D=pKwObCQi&Wv^;RgjxJHAx~Z|QBf_*!~B`_(HS+$Sw9 z?VXsII<~da>wgQJv3j`ipR?c3$BetLE=yx{i8%Jl5pq|q9L!Jt!iYYeotx|T?Abp3 zVs{_%x*Z)IdJ1K45(TR_5Ux|b8xyNfMqpaErYNUmXEW;P=!hIVcV~14jgPk_L@zLPW;-r^bM6 z-MLm#?J^$oQ(^BzSWEzC#y;l@3tcYqqhpsaL_dLjJfM9Gh@rBrjTy&kVK_?t zXP@V^(TBw2P2(ocmLX2-h|8BRcXxM}b#`vQapT6%U%zg>d?`FTJ8NiePK64-q^->@ zBEpECQh=jeaXt*)Ho+Z}-2$y#2uJ zrg7eYD&=TJS}ASyVTym?XG?MUrluzUCr|i*tY%t{t>vEH^-$<{XtDn`trzyy$gKL_|c&FvuN$_8;G~Z{HQ!SAcGQDJi?rYYlB|8l*MaCxzv2 zByRtZ@+P)%vdm|_se?mHNmplQ+Q+Br&eN3@6_x`P{t60*9QuwNJalN-R2{dJVpJKx z#B^3iXUF%kF^w~4=r{VGh!wZlzPPl+%oG_FwPodJC4+)OE++7mD_1a@+S@g;EXnAw zJUlW^gOo1QeUES$E9z3KuDrN=ml@NF<a4GN%RS3<38YHObYCU~;= zdsI^TjDi9+0|&3Xyu8P+;f)uxv_Ag$^m-%lZFu+tZuOMByf5>XEx|#1#KfZ7+uO%R zn&Re`8t!oRlr&DdIJ&qfVoDJwPv;H}4T(ApDvV7`__mCipz!05S()Hal{YkmoG%Lc z=8R@G6uyy`mXf$S(Me}+Zq9sHM6_-Ev9vRPk;?=XZc8;m_OfyH2UY>~$5m({t-y7A z_Uz%3lDcG^5D-Acul|@evHF5jh2O^b=-8R5He30*KYx^N+>ix%8TkG^xS&7^CAM2k z?6vkcasJl&mX?Qi&bXjuJyy*U+OT0md}~N+d%ME%<38<6*1I$9edNkYrarxXs+#jE zIhiN;pqi>G?|4I9oezLc{>q=v4(`8(gWIpL?TVB5t!jPp3?KcwwynUq%v2Y3bZ+dk)t__WoTlESA-S}u%7{(!=RZB{NJ-;CwL-e3}+w~oOKcK`E(ZGIJ_qSpo|JUT9J z=;gark4#sh-=8L2SyuvL z#eUE5ny2RwPKzSyg6OY}+`VV--bhB*cUE7BpF3&QI5XpFVl;eR$Xp zV;r!T1;Z#PJbdI&7%<(nYuBVaX7><@;Bw9*jRVH2;++OcHBXyN?a?H=i(K}DAp#Oo zadL9T+*>fI4lT#z2nR?zuBF8S1WLYyDC_ECd44go0t1DwnN9i%@5M}=4S=neE?qKg ziWOe~gewf9%W2d6g41GeZ;$2>fJFuPmt9+S&M;g0``7t-5ypj{p(sa0AjeS;E@^2t z^e~^87`COk32HhzIyA#WpKxn|i%X>&{7!HSY-ng`@Xg8+s;{p%E!t*S%h}kaMK293 zgDzQMx%sf`4{u-J^vk=ak-}5(LDp|rb#KM z3Rv5W0(vUEem6;;iwF)1a!=9Rih{4frp8^Dm0vYP3zVlf45&A(U8g$IsT$oF*7`ss zCT?fBsr|H&pmDnD2>;tgyRNLutcP6>fLx2(c8j1*JN2D%o9c}WVr3v!{?03(I6)Cr zSTb?M^G|4O&jUf-YEyf`Jj4nAGItw*C%&QBfw4?yc;H z&peXZU}k1U$`IO{Vv7#u1M#i9b1!yX89o`Kzr$2pt*#fKjG}+e%$}}8@Im1^@d#Da zj_J6~bYIE9*ceSBe^)prW824%(ptxrYLZ=Vv=`+TSujTximQ+C%f68~>M?8i@kJl) zVoDQ7%OOddOY-MlW1fg#J7ZJdYu)u_XAHZy$9&G<3k&15uOp#bQcNmM?VDb(TRv{2 zOV|FeG@1XEAXtR-zN$KAvpwvWGgzYE;yt*}}}6%CUuwE%?qIMqXZC zIb~%MxTU{%anD2FE(17_?Z=NF**0B5gm})&pFbV-N<6lq(t4%y% zsUw}2bw@60Xn5aPS*qi8UhiG*OFi@hdsQX*xw#7H;x-q$ z_MlrN~*U4MT+NdYr5_8vKU zl&^Q$I_my?|E$Yz2LXw10peY8c0POdtPh{cgR+VW3f#oc-@k|2PLUE3FE6E%lF|pr zY|5P1DI-r(Dl01oZ{P)r@{#+Hn!XHWjnsNj+N65);>Ce1dhCUzjSZeWG-_$GuY?`T zP%~T?B}&4?FpKN!y&D@{mnwKsG%?#C4*4EOHEE^!4-A*87*YS3l zPrVO>4bH5tuJ(F@L+$_(K8n)_0jBQLrx+d{o_{BNuPs{c78S`Hb^qxd6olb-%D^B2 zYF~PBaeR^6^qIQ4I&i*`Mz(XBn!~(TIy*Z_%DRQ=?8S@Qt*ouvUTD7_&y$vvd`Nr% z@IJ}Q%=Ay%*xDKiKzm$4ft#Bfb4po30Zc9Rl}Sw-Fh+W6s-LZ`ttC*vEDp$BY=oBm z>C>COfBzn-vB&mGV^vLXjHCm{_wn&IFxQ}Agjo@ zjB8H+9;xj$Z;UR#W=P8}LHp^`C&JoP4x(6KQW7`8B_u@O*Vm_KUI2V%GBfxdygM)? zWHW?E>1_=^2P%{B4A?%+3l|2!7k|#rQ)_Gydcy6%==6wSWMnKW36F@V$uVn?l5WFT zYJIBCsi~#4o11$bxRVBo2hv#c$a-E9zm zU@W3NHJ{Od@7fU#V3PiUfpv-BUpP#c%yZE1lBw!=nUS#(RFo8j5u)NFUrbQg(Tql zC?O%@-o34hn-!fowDS3Gv0SO`!b8?t@B7@>atSv1aN3s7B8FCrA(|7q) zvb`3sOo>5vIMb}9`^`gv*ejut1nCq~NThvkA;AIwr;l zaxr0T%ozO5G^c-P$QKie)RpDJ_V zsUsK{2d)odMky~}*>xke|HqHe^z=RM?(SucjkFvb9HgR(rP^d*V9?Ap`QwM7nVCP9 zm~z900c>1Qa4@b#3#gIpK4VNtMOCl2R>OHSblrL?Ll6N{_ybb^Sx(JK5VC)Nh}m!J z>FwRQo|=Ams`V`-;Eh}O`yU$ID2LKz`pgFJ`0(+gZ)vG4#;k#jS8V-K=UX?21Nz0R zc#8sJ3rAb9gtkNDRAgYd!hrO!x=;?NKs2 za!g%p)J4AQ{S9EV-p?J|1{4%s)in@xj50ogA#8=55Te2Cfk#5Q5xtkd^k6`*ROXDqn7P2k~S3e9J8l z_w;IT%6icN%3D{IZJ)56xaaf4z=SXk!6-h~k1(y~C# z8$sZ3JiNTAW;>eiY}Tpjn(r-i7D4N*E&IYsMMYH$#0PBB0bmP>^sw7h6=Xvr3yUsh zHP4AdonHeW`1YsCp?_rO=Z{vTr9ORXg8C}B_M0EpfuVy##BSwqN2hzNyW%cxWbqiR z+GuHIb&BThyOlq>Qil)k77(D8k&yvY&SJ?C(`ZJIiiuA%Cvx_gypG0AD=R1};wUz0cW*jVFZ5Z(>iHQVAf5Fx7%s2i{ zO2*4x*BO*@x;u#DYgm78FGyTJ?WIOgI;Z)m%e^I@S|dwrzf@k+iQ^+Fd5-g5I;XZ@0L+{ zF2=IT%JuNgq^|wqg{M|vXt=br^mBF=`05~Z-I>4B@0{lY9?7^=G{%U<-A|KW_U(X0 zgKjhc4M~mT=FFfXsLM$Oh9B)2Tc8N&9}e9tFKhKC3EHBw(IIp$CKi^!rgK;B_}i0Otj8}&JuS^?+&t-3}#2e11#`bJSe1JT&vg@<=>MbbUP#@2}96F zPNU@~Rsa~glFfB;W$?P)aTAmF_!t`bRm+YVF|z-^GNI;>_3E~)S}JO%7kl}Ci>{5F=%1fm*bj|$+eb?pZ@_yhz@z*|4Gw^soMymFbi zNQiUjzIB}(Ozz0%#TbLd)+=?$^_%UF(+y+pxwS)VGy7~WFR!c^nVScInjJrN>Qq_| zUv|z62W3MWjX)-GdWj3fj&bXNhxV*Co68YU+N*O|& zx(l5xLRg<2xf2`Pb3h)hS8Y?1qNe7(s!<4u3oSQS*R!*;@04;RpiNo`1?-~aceXK$ ziG!31NDY{1WN%N8@*~Y~950ZCN(dR!fw$9^wrt(%2dp_e(Z#TN`+>4M+{aXUHWLKv zHZlt!e+P~wG;vcivjOlLD3%iDEsyC4kwb_4plX&b|5Aym_H8XSI+%a)LE)3Mv_Vv1 zfy>19sju%Mgi9AFoSdBCtsi%E6yaBm_J(wHY7!35CTL7f!?jGnQ0rS;TR(JmRs#wf z8XMmN;5Ys?T*u5|h)yvu`+{~66ir8aBn>bL@(K&qO8)rqb=47^5%8W$U2j5(2w>o( z2Na-cDRCU22%z7!Zzcx%9V+$C{rh|$qeXgzRYw9k?-$NZer5>{4wiEL!FoVYP}KdW zVf?Y1rP?c2*6};8e9$^~?iRGEx9XDw=CF>zh=h3~E4pbiglTwpbo=a0zenV1Q%6;} z=tVbX-Z!(y6jQ*1p(v8l(`jsMY^DOAx*8bdAA_#3Xa9bAGc!K#fG3W?jeCTI%+D3j z6QG|tB*SEQs-B<(mQKFU#l>ZL_Mc6B{G zJW}DmnZ#vy7*&%N%Xd&osLAb#mc1?m+p+9uihhA3H|AzGjQRZDA~$w^XA?(SPT8Gg z+91z{#XB}W9y>#-*L_zSSOwReZ@J24Y-}uITt!2>OJ-|%d3pC6JKebVSB-Op8Z{0x z!hH_;{keNLSAZ8OC4&Udrqe3z|H$m2S?Zpbfmums4`LMTw!N^i1Wi=g_<=y z$h&lnuC6^+1qKZ|%M3KJ3fMyQ^z;XOG^vLkMHNcR$PC6gln(T5_CEoI82N@l9CmV+ zV^n_t9VvMG)|q}1>h7g{`(55Uy2}5JPi8s*)sQrqG}QzJUpbGSDfU{-d90e5QRFt+ z;}0&!1L_Xm?R)?JHh|Sa840@{N){HDSridL5&|zchK)7(>t~wldMPLy?lCY;XMBh`$}4dP!RafDp_0agX>QP1B9eA zXqa@JPar*lZj#5+ZMx6j$7dZqr)+Qk^>?{N(1qwwf`lAeGkH*91RS}!x)U;emVlG9 ztE+iTpA6%4e52a=^IM=uD?%-U9rP2_$Yg2uJE5UIl9rKCcU?b@6lk{w4GxW0jQ(~4 z_darcX)E3U59d_M-aV-uUmz9-4|&dxm7n^J(K?>zW9Bh&DL1xK{&I}&`4IM;+TN;~ z_WOl=yu5~kRl!8r#?mJP)6)@?pYtIz&_bYy|LBRA!YL-&e@~s&(o%ME5}lV77Jk`U z)Y#NCgMql7xUsh4R!~?7B{8GVscn1}mMCAi@V{s0oX6xTQ|)N*KG+d(oV|{e}7m2suqZiA#f+$CgP3V z=j!XFwx14eWnrnTuBK9;w6U3>3Uh=oOCEJHGnA6z3+Y9Ewl@ zm!-?%V2H3Iupar4#7~$-Wj#GRpo$uuS)3&Jojn6B#}|J>18`cJwIZW41mY7q062kc zR@ApLEMy1_-gq;FMO2JY%KsoxzA>tS3^dos4Ta zZO0qHPyU&FG0=_Z`EXHRzwgDZsHiBuTYCB1@tn-f)L3wcB$a(7o=jV|thcZjy_mVC zCYDp8_CV-zz2d4xE=S&6x=a4QVmP`X!^%h9rgmcgKUaxNK*(7KS)uuf!^+Z}hL#p7 z70--!>~FTo$YUIRVDC}&{}BbG6`08|2M`mLhI8IF_Hh`j z{o~`eF_}YIMJb@(#Ydg^kD(4z4+s*#}*__-vu8~gh1SnroF z(p_c0eqF(W`$qk^=I-wJ*LAut3_Z~Vvo>C!6aQsoW3$=B#DwJakSdr>R-lAcc64lm zFb959hK7jS*(4?=c0fCal1NNX2N|SEyL^9r&kv3ZXw)EL?BP45Z$Sx5M6VztF+}^q zEI%I~c|DR)!06+1xxXd-Y$+kW)I~amNTZN`?~^BHzHulNsa=yvIb@- zBPVA>YASEMloJJViZ!sy3OVaw?F@oZ>1iBN`kQ*e)ILlUYMW3_B^<<`W39XG6Ch1U zUZ0zpDbLi+AD2#6Nl6Md&l8o97@5+hre*c6uRpypa0xLo!W;JsmdKZtEa-oUgSvfT z{`Le7149iyfwXj>6oqme)!~VXi;dkOd2|wV2J)Qfjb(R2T=e?=d-r&A-jpCm)<5G8 z=;{67!S+%8^vp~;5>BA$>S<$Ksxo&qTm5nVmnfDl`l7$z5TrG&&e{5K{_jPvU>e3e zGrhq@k4Z%yZIC<5pVmE>R^*zFCM?vX*t1)&-O1hRGQl`6Dkiptl$}5?V3@Zk-ef$l zwTX4tuCRp#_cNVZ+S+@$XP#d_mYSHTF@1gVmBrnHKk9F<9XbDZd~b6u`u@fZ8~mwW z7m8QMoqRj~=J_ zUR%5Hlif32*_4%5d)hfnPCd)W>wo{0qbJ73#*)G@j>denCFGV~>3_16_ybdFFKP3{ zieZb>!ak$Ycum9mpl1aPk~vAsy5X1U04Ov{fOMp8EPWTq3a_X*fn0_!av%6;3|kw` z9Qa@~7>KNFY{z+-x%chcbc92FMAg;Bhk8N~pED!QPy6<7LuKtvo!3rEU;JUz5@bbM)1VWJo~&^s!tswi2zy(wM|o!jzT{r#{hhmFW%?cw1W3~RWC zXh+8L=O59^4JL{KUnt~|<8bH=NWJt)YH`du-xzv{Xe1*cQ(s^$+g-7O&P$g zKuuSdo%|%1h*%(1DH)k$l;IcxV>@^4;yY)2NO6+ZF|5RXFJfPjpkZUHB*6ifG>S6I z^*@j;B*?wx-UIIJJVuM5hUVq~7@#a(rQ%3JJj=DU&pBdnuR8I#F9N&Gc7v>?Xh+wF za@b8^6GX!}2dfGL2;@F?j1#6pw3tP>pU#t#sK<}P;c$>42Zy(N=T5>jQaS1{Y3mgb z5CB$PLCxv)q5oAog-84Lx`>`Tje>jj(7w3vqQBeVJ?!QMFLLf*w)>xRDCL#qP zA|_UudMb($EFEzR37w~MTylnnTr2`K=`%M`L&8AC13!Kocr}gI2+b)lJe-~kSSf1Y^yT!Y7;y^h>?K^ z^==o`;r+NFS(>>4uA|4N1xOW`{LiVjIOi$cXy5MS{`1eDH0Wi)EhEj3RPd1)qPux` zJeFqnT3K3ZK*MHYGBY>7i>~|y@n`7ba4=gD$AFOoxDP6#glsh2ntw$j>s$US8j06{ zrln?OodF=@;z>rCwRLqp1tBJ{k2B`nOy&9K2RAap`-FuBeB`(W{Q8H770CE8M6cT* zyRa>C>PnRr64Vl(H>n+H1j|1pPh zHcU(rz7%PWAx>I2z5Cd)1RSAsjCPyXK$2uC6OZ?$^m-ifu_s8?9u8g{XeH=ucu>%p z1X(p0Q?r=j{55ht^ODx>dp4m8=aA=RL$8H@hx6x8uB;Y2BcnH9 zz8vOK>kDUuJV}?yZJTvy+OU<{z{p4da-#&9YJXdzHhwb$k9)vM&!0TPuQY%DE< zAn{0kdYD%F4pfRnMVvR6$v_4ykK5ADBT$7ej#w^RaI3IfK8PE zZUA+@|!-6g~JaPi+(&nt5??kxbk86^FKrI>&qjH5LJAvHenXfoCEf zs|P_7xu_mP8amOoVXLsShi$_O>@Y4+RQ9>WP-dauI*uajqdgdixBw-34F-I_?DGjn zVSSbKqa1lrY8`Y>KY}J^T&YYeJ?3;hZ;J`iPAY1S9gO&Nx_WMQYfm%|vj=+d$g)gbueCn?#ZbmSB7aGT5880$rPn&SbJ8uc& zP+R}Yje8Fs41%8Y{zZA3V62cDBX4!ipLs5co}O>Z(`&234+HaD-&Wa0nQN+DzgbjN zM0f-LU-{aA7WhOa@Q}inRTc;U6bnUm51)K7);VqbDK_`hP|VpBC2nL&F)lU`u#$`b znHQjuBtCsgjWD-RZavcQPLL$|8+89$&@=t)J?QYxYg~iu%gFEpT<(Cq*Bf>NOkF8# z$NQD_lJ{J)08bVY))qO*eo7W6nFfF`hNLJD7ngS&TXFc2ObGzw(bc*?Q(qd$^8TMe zCu2nM^B6BFY!eg$17JV&?OOwLX31H(vVZ*ztLZ(L|YJLz4Pdi z;9R8I`L78$O-d0QP1lYGEAYI~%@2>--+6x{jFH0D8r3L%wF-neH7;HZz+)gDdzMG< zj9tti#Oy-dT~>#bjkP7&IX~22IiB2kwguu!1axDbnNRot%i25KrqA;?BbjK;HHP`g3slz-Kdh1A1zC25d5>9e(zgzr23t zJakjd!SBcIbWS(ji;D6kL8`!+c+0%*^OMyY;1Jr+$}XC|zrC$VR%`o4PH)%6l{`gO z&6(u$Hf{EhRH;&&{_!0*Z`Jc(L24Zr^;l`ECn6s`TB$ZWDc*j6zt$~lj-f*Z?~qbJ zOLW*u#6D_io~|9mCdE0YS_u^+2wl?JGm93|m%fg+`fcbX3V}H(p5(M&DW~NRc-z%G zU4C$|d-2Dz+sv{=6HH(c9hQIphFux^TSj!a6MMFnwl+!OYjtZv2?n~3Us-?LCQait aYQB_&VVePWeSCwEIHh<-A?t+Ut^Wfk+XEW_ literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/class_input_factory.png b/doc/src_intro/img/class_input_factory.png new file mode 100644 index 0000000000000000000000000000000000000000..e8f1e3a43523199a4487c06f00c3177e33180020 GIT binary patch literal 7171 zcmbtZcRZDU-@mksNcN^qvXf2rI7C?)$%tfSMIn3qk}Z-=_RpTl-W16ulI_@(k-a^i zbKm#te(vXw=lSP(z2wR{=Q`K-`g}j{^|^x7RqqlJ&=MdBLZqaK)<6)PR`|aL-X-{b zbEvly4*2$px(*0()z=*ri%YKtXH~oeNyRF<0 z|3HoR!7nKi-V4Z5e`6Rfe>=}t!QEZ|xbu-e3CDH03KC5NbL9my1%8@=M=N>Enr}s- z4=1HWC5ly(GKcsY)`x%9876u4+PQl*E*?m9u8W5U2I3KrQ&7mLsi{3ExksNe>);XA z`{&N-7`ahl{~f+IY7=ihaW?ExrvlH}LL{eNC?YH(jJ z;EG>lrpN3W{UReZP15;c0mWakR1)7sMBp$mFhq9-(;mfy z4(03k29{V29&O=F#E8g?nF}_yw*6Tuba4p@PZxWVWIw!qeNH(^l;Y_}Y6ek9pOh4) zWO3KmKYu+noWOy2nWqa-94kgL?xfzU|Ct-%yOOU*9N z%+8WfQ{(CA=yb*N<02cq-lt^VXGc?ijt?BFs;Z_tqB*f26SA8Ojfx_#s;S56cn!ok78yK?0cLNE4;5V1enwKX+0Z5ke~RO(GP{cYP6t40&aCn(rDka-^m z>F@6saatjN`SN97p7xMA-;*X}|LEvEa(sMzm4+sWQ>Q3Zzw$Z3_rbotCinGvTx4mq zobzyZRiCvtVWBrA{4Jd@ij(v5=;&zQ(2!qcrLcyE#=Dr9OP-#dAMQ9@x^Xv*{E{@> zDRe4flBm<`hzJs-X<&dfD=SOn^ZD)74ZKgE@ z2Qf1?g`CX<`*V1~^(Qyya-edVxT8d~9l?;7I zN}|X*+rWGlb^0|~FNRzb6Qct}B0h%oZul7J0X#fBX)P^sXze$!y=m@yYxa(gHjWZB z?)n?^nr$n&Zaz5I2vsj#y42#hmY$BP?&RS2I(CUyOOf;}aosZi($@C$+xwf)TYSV5 z#f&~o5^l`L>wuDOTAZcy?jIe|y{U0xs_7rX~as z0-Ym2R$=?m~4E&M8d+te`jVIkCd8mY{d)PFT}mmsn~-&j+gEOfMt@vB|F ze3@R-gZgN9)wiNT=>7ZmJf`he0f94i-bZxf z#b7YSwIZQ{2}MOkEwO~dUg<qlH(7CodmO+aOtnVH44)S>m19$D?wCZS4y zQvdTHxSag-bR@z&(m`yf{Ea}PNakklcn}md%jhk&#aDq4QSYk!tT?H*h|m9{GO%q zd2_xqQNr6SVL%cjMlP27F^|p967yT%M?P5?KYu>?w?NcT{=z9cFwlDAndH6u_Y#~)39K8G&$;Sy=Q}Xfi|7kosA;ywUp?)Q8w7I;zd}K#dRMfT} zZv5z6G%Fh$9=z#OUcO^}+s?|0Lm`y9KiySpFH$En*E2A8H*aj))_HSI$;H(b1B_o> z%SNQ(a3%n-Afy$@(Y>Oe=cs->+<5Aj;(e;S%x7+Hz7Ili9-sp6<9+rg`kZk$96|p2 z>o2^^mwkbnv7k9UIl3VzNP(09*szFQ2F;RXCdGVt*rF2=|R7!#a?j{5)m1joBQ8xJSIg-oYxIqTwI>CyumN|^yxg}u{Ysd zQdt?0nRydbA|x)3`g&4Vm$HbM*yk@_E+{A{z*^3eT)%UN2AJb3T$R^j-#&VIFe*CQ zPsn!k380Qz(2Cr~#s({>7~ym{HY==oJ<>)k;io| zohi2;<`xzKa4ycX120l4s_ZhZycHMVf$h~XDi#(N9%13HllAU?JfL7`G#V>~f#Kl+ zXjC(}tT&P~%ggL#I*yJ43gL`zOG6AXK66Zyl3W3|q=-FAQDb8>QarAQeq2#!YAl_RAAJ|h^1Xn1lSjZ z&5q1$r>D0UTpKPdoY!UJ$??W#VvZm7(XjQ;EG@5da1iwL^k55L=eji);|XkE^6_JH z5E<*r@5Y#0`u^ZXg-+0+QEXgXTGSO*LmYb5FEdM*=4NN*7JE}-52m0~zBM&T??1P+ zR08{!vAOvYg`(v*C-mI>#)?LR(4i-4oHD=~qENxX!6>*F6l%1=Q|ykYD8cga>CyTH zpUthU+`76Ch`NHpB@z<2WSEDir{&6Et|OqV+RW+Y%XBr#gEt(UoXgNkgB7;=fb$IS zWf5UvS8lSf5F9xE{uu%4cMpw@kB=V&)jd2|ObH5nw!PF}W{;6Yp*nhdv$-GF^nsQI z20jD1BENc7z1UImbl)UF+?9`nWPWb$Dl%GPe4d1af{IEL$Y#04?=l)~YGb3!$jGSm z;DHPp-O$h=;J#~vLcuwu%3?Q}nft(d>12ze(Vr}Ovo<#DG49;MUg?xRP2al9r=;3(1PvgZ?`w4#n|(J?U^uC909GD;-0 zw6p{UvazuE>s3Bi5w@FTPS5j7Ei6>2w3}iBU>E<#x%3kz@APSixNP1N2+ zo;AO|h%L*VJ9n5VL)f{wRn2sNudZ75CQG2v+cT|~2?z+%0Z%!<>4Gbi%&aPxfy*uD z+9O(Oj7m-MA&n`U#ee$rNl8;PvdE}W6^;HH&cy2ELH9a`NLTr-e{db{&xQvn?szHb z)?4%@t4vN#V%OQ5B9#r6EfPAU<2b+5u-^L!K-B)_%bS^*nKvcSxc3wluW4#(c64;0 z(rb=xqtYX8+#LYNwKA8Mks$~7x&4*Nd+N^uRR=_oXl8ZGx8eBkm`A~ z>(r700cLK_6dNoche6tM*_g%wR)WlkwUI7vZs!oJDTMVr1!6#ak|o@qj#s?^-osUQ zVySqws)zVAG)P{$LLUfrP}DW=-rZzCCgKAgpsTyv>_=o{qtxJFUc&dUUva;E`$nX9 zS9*x#q%Tcw-d|TwucfEw3WN^C2hw3vM+bqBkdW-b>gp;E;(56JS8gtQkzxI4jvL3o zzzLc{-pOX7Mi4>*9x*X7(iBK?BQ-7U`iBUJZ2O0YviI*_mL58paain;(bOa>)GL1t z=2n@BS6KKi_-+INN`;*F+Rx8#LqbeU-%OX7Ns^F>iOIM&k;nKP8bt!vB0zpZSgUwG z5uB@;{q#qHF15h3tH^YF#EpI6u(Zs~i;o{aHmGsL2U{pxv$fFen~*^J~ynli)Tqyl?a4hZOdxC zbWbadA1rw*Nl{VEzXL|gEPXA%X9=>cvukD{h@+$9^uhv*=5D@D@zc}e18f)oYpnjF}W4h!jUlg7_8GhmD)tA4;?~ zUVUS)Aui8x&a&Ojs!Jleu1=hqnwpJ}_{tRpQ&VP2Zi7Gw9v3cN{MOxQPQ$^$L2IBU zuUC_jlb#bMJ(St8zwd(4c&Muz-(^;q;K|0%PsaJMpa~LuT2_|-__#rQl4o}SWqyAC z@PT2<{g~?NY7y^K@tzc^+sEq%TZ^(r>yT9I>gq}y7FBfXhTJ=jP|XNk|txR9C-7 zZ#opF|F|N7OcMedd!$Cbyh={~ z25cqP)=W(qRgtDE-Y-*A=@^~coASm@t-@9u21~x1ULa>~+e z-vrV*z&5m%7=OkNM?f=7&CQ=eKzbkwf4TpJ?WOt)n zDNfK27`C>y`ZMoSQPa_7l$MhI`cdc$iZWVX0lJH&A7Fo&iHUgZm$aB^M`xRRS|y0Q zK*8wg#o4JR(ge1e=fw;f@=9u59X*7Iz`#Ihz^#U+=8L&@7~&Y6Zc=%i9xSr4v&$$c z;RDi4U&#*P%0g?3cpjGZ^){THx>rl3uyb;LPL=Vs-&#;Xq${6KKF zs#Wpy@F)Q!Vo2w~b75v?P!2;fjKEdn)eg8*-e(fXG%%3M<{Z9HUQ#2_`vzGt)E&Z^ z%ya!5t6xBUnBOCx0>i>6xsy2bVx?!tvKykxgYw+OL`7%dRItzJ7cV|`Q3M|5=aa}%v``sEKVUPqzMfgBfp`T+V&N=Ek4yqgv?sRoK+Y;DciRRDfP zZhf-;#p!p}8y2>k~V>+YS;9uSC?H@OLVwyz(8^O*W>RMZAthu%Tpq zJ^XR)D;X|I&c{Yb2`tB;&gJ6+r=n%;Z8CW$z&Q$*e#ybX0Xt;{Va2k5y865ElrtyzgmH&$s^ta(L6MFkQJ`RVB?kDwsP{zWh(B&4M2rFMhPi3Pc@5aE zzae?0K`$&#H8u`7;ivYmY8vH@qIK(s3v_*9Rzyup+tS}p0_(HtQ+tQa%huNUCBH>Q zMFWF^n&02Nk3~cEQTEyCUL(PxyjG*y$K7lwf9Y&;sjiGllIN(FjEoFS6gDZlXM3A| z{)~fhRl*0=d-n)v=;$uDryPxe{XJ1d*I3_>Zll(H1?=CJw+fh z?3U7yO{>m)f5zRGf_p!Bm^?OcY)4Av_fLxoJ6CA3ZW}e&Xoy0hA1rz-20Zy7sbpC6 zsH~c#vG}85f{DaiYTk3;4u5{K2p``lE#>1fsJd!wY}_|EXcKchG&F=+TbsW(-| zjJYcZDv9|_Eafo)Pm09hfdHfwuZdQdU;mJv+lEn=U!9#E3ppJfZhu$fHEAP^-V4!o zg;`LEjx_{+7^QvzYxl&~_SW$k7*lAiHz6UHDR1cw+8n4P2;`0oSOr78#>n85)6mj3 z@Xi-tv*0}3UgiSfdQ6%3nU@XRn(;mi)BJ*Xicv{f_5e&6yOh9N@w$I^S95>={vETv zUd(gMbhaPB!(Nh^qc;qL6W7Qs?ED+cY6qM1EZH|vH$OW(c<>;Jy>SReXhf))SVDM) zIm1ZGBc)6Keol2((Yn}~4X?+M69@mtVeky6 YcVKJm3-<;qJk>*#1f)@tF^-(D@qewqP~Pep$KGU&?@k69sJF`hyx$}C(gLxA3Qr5 zEe8~eunqZ(5zkIYgF;!ztDJ=QUYgEdV|Jn1rtg&lU2I22!=>@nqo z*ZHATVe{1nZIrjU3`X*kO&-zSMw3vGU46_-itA!G*U?rTL5+7Yl%os_Ycgg3Z}Yf| zg+(pRx>@P=w%du{mdB5gn)VI(nfFzSFG54l{_HDVrWUwJ7sT10uuZVCa#t4U7F)lwv8D-*;DpwHe87I8_%bq*+`T?G7pJ?so6gxEd9O!q z+}zv|RQwN@-Izk?v$C>YYz$qGV325N?JFsf3D3-AN)_`U?@yPYa4XVu`MtZ;$$ab9 z`*QEn5}8!#D0)U_W~oAlNpX?zuT41r`Qh4_#btbXrQpz=)m|FE&bavacNqg@tM)!; z$2WXgle0546ciK^g=gY7=NcJk3G;e_)xyKWNv>WEs;#|?YMQQbXkM^ON-Qhmv$nP- zrlFa-epYW)@3#MN{zGP_f0${|y#O4%QA~Dr_JGi*bAwuoOG_klbgx!=5~Y-tqmM;J zMQNo%2p^c5USC{XB&MdmL_k1rbbRcTRrNUv0~6=spVaNX*?7WVCXW;p3{6dgFmVYb zH8d!`fB&vo=gc|xLP|=?^Vg`xz{p73YeuOO@4xP=)$iZmDl9BaI#gCxp0^W{k(ZZp zbrnkB)WJbf3fWzYq!;T>y<^;QnM1#Uc5ra;Xt$FA1NG(07nE;I4C&Woe%x>0zCBh| zm3sV`Sg+BW0F_@@h?bGLC?Ft^k(qgcfq|jk^OzK6w=;jwPKefXx1GZ7#fy7$4PFcD z>!Eo{>2d|X+;Oc-&Lv*HeA)HoOY`ymTB+@vxW%()hD#lVRD^ zw6Y2(pb?yJ3BqTxflXhtv$wy1(yezTNlQz+(66ehia9{mg(9Ypv1kP&rU$1C2iCeRtHk z0||bc<>%*1K6!E#m6YDgFo1iRvI*;ba4?Q-@a*Irs50iPpGUE-1l(snKUpbk%bb2rpn084W6FX zMft+AP?EB;c=geoDA(P^AWgx>KYQ|*8N_KXUAn}>&u@J4*WKM6<@@K4=jwD^92s)x zjEsy)x2?!4K7EQ#ObqeE#Jxmo07q=-y>|SepkOjh-aF4A;4|ILn>P)<#9T*S+Hmrn z9n}=ariwxd3JO*`Zje^m&JjXOW#{Bzp!j1(t8DdAlDfLIo?c#5Z;FbFF02eg`R(lN zH08)A?z9p~7z||GOS)rAKkKnAh7_lhlT-eO53S|q{dNcI$~W2A7JmI0Kic*=@0pO1 zk?{==$3Ht-A`*4m!`j-~S|2Y?SNoQGr%61cG62?VG?K5JB<3M_2_L`I>4$oCZS4hA z!|^H&^4K5LKej|OODBc2!}g&hEi7*05Ya~D-PpFVxs+1+iPZw@H+I&~fy9W{jKe{}r%HL>UU-^0+z$PQcvPhT;Q z-!jz?+^Nv$m6eqda%j&A@4qL4Q9YLu5)!iCzyCJ#JoLf+`xh`Weoj@nRI#h9EwqLR zSWoc0FDxWGdS6^@-ekE`nPjq%Cv0Wp=U;?%+i=aoeg@Rni=smF%yB0SITF%d z3AsB9%96?#uMTEO!=c4!u9bN?lPCKT{M(0nX8wOCN{w%Fa+=OE2-%_Zef~P#ac>(M zm0_7E)~$inT#!wQp|%<;y!Y%G+uq(DF*$kg*RPL|QcCweVVm>EO>m(I!#Z`D^9l(e zV%YN{hc>@1pU~9bPZSv$SyENi`BuawX{pX-JGiDs80wDKw42O~)7;FAb$WW*z}osU zCMG6_R#_m`5`}3wXRcCu3==x7p0C#O>DNj?EV!3(INp&rvW5okfTPRPdRJb+?$=347xne^*MI!LL^*Fx_??`%qZGnl zt}LgVEm&AsfMifU`g=H+>^@aCnHJO*fJ4wyHRp|wjg8%*aqnxYaO`gT++4b>Q*>Nh z;BBihNi8iZz@KW*V?MI0SKno42d1Xd0@k5W9g%e5;$A1$*xAFij^`2-$Tx-;3=R(u zLmC?;d~-AKiHJf%LU8AV18|AVyw|>v$jQqqKYomomzQ7F1lmc){<5*LakToz_OY@u zhOn@(sK@Wi#+{K@pOuR>Z>_I){h1Yg@<3jDtlguD^X5(BbzIcuR25NJSlFYg+@hk$ z+U=ZVt z8@NE1AWS~>oF5&zj*N}@_pB^J^*&lHE>O*50^WP_n!;Hj7`nQkp0gkRoz^2!xrL06k&;82i{7!r&bW z@}d54)+6-Qt01W21g@tqVO3Hk1_cFC@)}`{ebm84X?}LUEhi^uU}}oZl^FhPIM;BYB`CkB=plgJ z*RNkeR``Fi8fOv`q6CH!@;R%242ul`>Byy4S7+Ko4k-Ug=a-PnmM-+~d=GcyW`vJQ z)g*aGM+dAje*LWmwV>%+MC@I=hN9rsBXiYNRxb5&cmAG{@HuOx_M4f;*l7G&4=L$z z`Jp2ry=bUyR>|w(;wne0xXJg!CWvT7Z2D;-b{7H-#{MrsCNZ=(U~WwRHIjc5>P1^mHQ7 zd?0!jK;-ZU3U+`Dihlc+fG{Kg*c|mSXLLq3D(;Atg~edJ=;=hQ(+BkCZ9zdfYch09 zr91z4u|95M&jU~!2L}gsYkhR$TDU}M6}4h^HM+7jUqVJ$8YE-QOabTy#>Rp_e&pOI zCZVCh2N@6;60#IPB;HhF*jfUz3#CvV+jxE^qW)1k2x<-Q;~jqfE6|64+qeLsJism- zdi9jLTohVbTI+L-5(phadtZ}~V6dHQXwQ5QZt(0G9zH(4tD74mJ3GFlDyB3V-PF{C z`u+R2ko&<+GBUEA#ddtZ%0SuZwca-&N)ms`&d$zCK7DFW;x)G0UsV7-+dMW#4uTHO zoP4tAXXzDKD{N2Fn>Vf9-IqKLw@f!Tr)#c^jg6I5R0IYDVDhta7XA%=8Sem(n;Caa56D78^ZeF&9HEA`0CEv+uNI`rf7z96^zXW zt`kNdur#Ekq#PV!Tz|*q-Z5nXswRAUa4$ z=)~OPE)x)J05*>d3`jzIVfn&aV}B!MeL#qh&kT6=K0iML8pqzw?wW{*23C5 zgihEVz5FZ8D)0UKm&+?FZ2bJOp`ox)3t;wx-#>Nk`kaYAv$RxER3s$1{pHOQHMMp4 zHTS2K$nfy+1T05xu6_pc0r>Oxl0~C|+j5(lB$=4*+Am)u zpyct5mJXLsTsBuyR15}%h{(B=l$Y=d3o9$*^?`R^g=1M2{DXq9eRJzZmO7)T7~={G z*izrV#XvDXjPMN$!zrW%dcxGe>RVbsRgd5Uo7`f{$@nR9{zLZpQo6^F< zLbdZx>h7K%xl*AeKqo843PM;P!2jD^~)bXIr57@)Y0t!xt4(g)k%}BmfprDDgi#QkUsP zDK(08NxpdxUE}2?!KdIdVf95IYSOkUwV3~+_|4Os?mzTNrE0h7*JG9%+ScF#hPt+FU4(qM)%X? zld>hyN$7_UTP7wb0nqFm99n%bFq78Ap4mQU9i>uB!=gCSf4zU9aK*l&uj^^}%a;bA zO$P|K6)y{T9jBZ}yUAlXIXY%Q>Fn*I8eyRz183Fw+#!kv$4+44jZS)w2x0ujkjk%f6dhsaoGy2s}lhPoL^k@2l&h? zDeW}w@@s9;OfJ_Cx92*+A0^SejE}z>7Z)dq-Z?z%1gL1UCO8J}%K{3pT}Ds; zw&Lc@8HG3KEP7h^_{kIO4B3w6snrJd*C}m@Ju6H+JjDB}y;p8_!V{zAR zvOJ`CYM3768)7JjhExCzTKfBy=I^h@vuk8lRFG9xR$gP$)X_0MKl_VHaSrI~>hjIW zxqkWb<(*0Mbi=j2w->erb8~ZeBmvuoO>Bk9)c&mvaOSKgzadc<6B8rQU?SE%2BbK@ zy&VPe_rAV911~SHot@q5Fa`VT$5rcGED7nK>!_vT9PhBQJ~VQwsjfB{%zOYRi~;Uf z*m3=J+vcI*tk3yh!5a+Y-Y z@Bn}mNGXU(NSY7Z7r$6we^Sb6A)%Epto^U=?Mr|#% zqM{;nt1nbhSy|cZ^zRF^U^S>|Xf}G^+*w{;M%Ow2WMaw$W{-XMj`6eW?tPP)#TGeFkAk*4%*>dO z>$K-9XQ5Eu-rhzzD3a?-@g_R>SX3~YhlG7KCq{Wd31<&F^GF6X=SlpR_4=_t#p!yy;FYj1c|-!3ksTN zX5LOFeFTB2Q)#`yTZRvX5Wvy^_;qx4y3Ol#;)p~)6t<{fG!7eBPd>5>r}PP z&eB7$FfcwY4gHH~F_4pnz&i8xHBjD7`sXJaVI!l@LSfxeF3OAS1(jO`j$bSyu>Pkd zGV<~|BVy|1N%dh_wz*RWn~P0yo;lLeCKX~e-Y*U|3)>QNG+O06wKTE*iTnmunrHcX zJ_xMKCL4mtTbyv9bFjf0~t?8*(6b;Iq>tbzft!AY)RqPNK zCno`bH;BdH&JuA`=gWov5-p0s&nge>-k zlG*YF8(Hh&;b9UI5O1Jq8(WpKm?G{(8#0FpjL7qk2qOL)IZA3>^)wJ zl8{kQcvZ^GvGjpQ+bq&13>1W$hsTw~9#AzK!+FDyF@=U&z~d}$Y{()%{_^FevQM9K zKxU{YC=e9n=krjR@$>P?+`H!oe(`QRo<`F0(dY*aEZ>^5Rr@JWM#^?}JR~HbYli>< zHk$k}(JZ<~r|lH_1BF`U=#$Ym7X8^OApv4+Y+)4@6_8Yh12-Vcg3r1}M&d$4FJNMR z>Ff-7K3&~>ho9}{#Ef6d>h{HRp%?D zq!tq;hG?{jv9S~=q_3sGjPHwzz&<{k3=2K^{Zqc``HWG~4S)n;IKvK4zd%D98wEfe zv)M-1U4PVLEv@7MgSk&u6k3{^k1Z{4ffEd7J3smLL%pG`qhkm-F*KCGxxjRHrp|@? zVI*x>NeK^RZdlRL(GaIxv9Rh*xeW@&^Ud+g?xSy1-@3JR9zP!Vju=)9)amb^0iYRE zQ&SPe03Fp(_?hlYAp0YGjtB_$3?|D=k04Pbw6U>y^hS^X?4Kv8j$YkIovKKsUbY^Y zpKOq9`b|{7U>1Bn9SUgD1f2$OV|ubI3X~lVLDT%~XAe)JkC}W8&cUlprK|QDoSd8u zlI;JVU;U6R`rj+CG>?R50UUe>X>T|=XG@uBPZE`>A*qhm!&_2OkiQ{q3I+-XH84C3 zZssBTtA~b$jH_Rh1Co*`DQRf->3&#rj6>;TlR#(&^bDqjR@go;8cPX$FVGm6)%zgB zfR&}*#lj?vD zfA@2*Pl|K@8w*Sx{8yR^Fn4bLR zO)QWOBm{$yueHDT7%S95@{;qTP6=%~DCEpnGdcZD?qi{o#W=LKdhBkHhDPss~{>2%b0@ z*T7IsLt_}MR98!j|JUB$Fa7;dS~Rx``_Fb3q^JS&si>)AKvpZH3Pl60g@&$!X%uk! zuEux!_H}rOy~D%2mX`ZWOtoI8f&}!UNuXNXo%n`VEAsle9KKOP-T*}@$ARnS>@4`` z(W8NZfu@U*nze-LG|U%b{Fk3l3u>{1tBq&KVJer+0jh<6Vrpbx?|W38x&Ea=Hk|&W zIYnElumg{IUn*fDMaAn{emKS|H;u%HwU=ZEW4(S{{46dZf*)QT8k_!<^>mY?43B;H z=fiKzH8yEiYup6&$#)H}H_XU*uvE=?9nwK}vYAHB+JKh0BkPGR`#i`LCo(j&31$#z zJqh_KnU6GAsHnoA)aNJ5&0YT-@q$Uv@nQsvfdtEtMe5erV}nbLU@?GH0ui9VQ|I%b z2*B=kz^vfGmC^RG#R->czA`1ttjwx)&uoct)JRJb3EX-Ow7%f67{{CON~2U$HXx0rD(NfwR(kt$6!4| z?9T4ugPXT*W%`_-b$$IB=;w!l*c2-(E1-;&FZI_g){7e&=o!2YNLpH2l9ux!iqfpH zzrG*$*>OWfQ&TeoyyNiG49EiSD;8~dY;AA%N3h+ve%%l-<*~YYF!&xW{f5iX2;f2> z9|{>PjGz-C_c}Sar>;&Oo3HwqbpZ^z^KpDkOv};roBTZTYX)#UH+OAh-QDkcdV2Dh zeWer<7G3~U_H-(7Bt&E!>D;OeJ3mj)`G3EZt0rFE%pl>MG1@>$PHu53R8m=)1bjpX zr10QjEtPh<|T z|2Hw3Xz;3QasbxE)zHvLN=gE6hKzSmzQ7>HM>`88Wo7;l`aX=Je-(sJ!34<;$Oafp zw0dlR4l!&EX8c!N!)5uqXBBMt*X zWfheRwzk{q#v736UL+t0YG`PfINO}5s~X4l@b(rLw4I%XjQ>_P>n_2iON%sblw@U_ zcNSVP1ZFx@%}e*b=&n~$$zY3S@NS5yc9b7VF&qzNBFa_I~4w#*z0VYFk}QC|{oK=CvH#+Qzc z;Lwyx_GQx#3NkVo5Ht^fBLs+r+Rx6yixdZlN9U@w_ zCr=)L&4`cy(h+dmGjTut&H1#!GZ_TvI@kvENSvgczJ59YQ$b;21oBnjFf`f`=9WW) zgCxmKzaU}E2EAMF;^bsX+6qiIaJ0L$5zgH}?DiAN8KJmaoSdN8fHAJ1x_f(b03B2` zH1d|0!*LS8eBh@ecL7Y8EakX9ynio8#30U+nH#8D-*^f;CIeRK22&ZnA&EEi4c+H#!DnaLaGhc9yI5jR5DY+ov;fg@ zpp5_l4f@l>P$}81zy}d$oe&2BAw4?1orsI9q3bo{1(&hs_-QKTrVkC2Cw=``7g9hv z>I>6Dg4NaAyRv@@F~|jt2)x)E{clAmfXkZ!uI*sUTs=JYM<<`i*r>?r>806rm1SmT z4h!~v{d%-qBYKMP1_&uIw8RVyL>X+Tt+~c1Tq1e{2vOe_>Cl2;Nj4AtzXZvzsEEry zAOOfOQr#4WpvV3(p*!n?%$nNTnMMx#AbDW6M9Uc2#db8!X39Iva)($dm1>uK+K z7TjBCnVzO4q8BB$l!_Cbg#Ux1mwEK44Q33bmZP^yi{yu7Y}N-M;)|jeyMThwE>!ID zL~4TljFR{<7AWV|Ea|AG75m*$4gKcHNh)}2pl>NiMqw_GBlNTa0PZA-F6t{2(cZq+b0LlQ2#`X$IDk5 zLaZcV5RDYycEc$lOxZq;2{>L=i9WiZ@PloCZ*K>1xfP^4B;!Uu`P5XkQl0pHLd4smWIu=D~@P)SLN z@7uR@@a`qRAJN{p*w}^;9F~-p`axO-U%m$OC>Y|vwH8JI0)6k}>oCFLfq(*;%EKVC zAIJ9IXC60u1A}XjN|2C|vHbSokY#ot)lb;+>se`OYr{G}8E-VOwdLlmL!5eNDKHLz zsf@tDlzg$OSY={o6oWCi2^;!3xR9~`cr;eC%mfb<564atl-_XE)-4gboWjD(kogRZ zj;_dG9HsL~bP=EU`0?ZJkK#t>Dw?0ccfzMtHyz1Zw8XLeoS@(~9gCeXOs4TE2s z9DD&V;x0Ye1c?rltAtc@4i3`H{QS^KZB;TOiHtHAmxS3!&1P}$Kd#OyVL8%!P~W<> zjF0*SCS;ym5e*k480^OAKR2aEUqMY@Rk(2YIsGq8Itm2a;ra}m`%u^n46gJ zh-|<$hRcXDcbHut%%X~)1=k8R8UhnZND@sS(2ggE+flX+$2io~)DYWI)K2N? z)GZ2&i0tF#LE;I60_?LqWi>T4*!o}snqY|6QN#^XZ%f`DrIcHZb3wcc{gB;jMI0x$ zw71gp&$Wy{Yy1KNXdr;f=QFoD^dAepmb=pd<3`{`m>QUii@*#C;6zzl`w}Gi$V32O zuocGZCC`Rg{V=YQlKR6ZOfa@O|Fb4BH7%?N^a9A}y1z;QAvdH!Hyo=zS30-9fr}k; z-N*8YT=!sZ23>5UX9WYB^1X)>&s}UrCsSeI@aONgPbYW|Ue}#@!Qyu?W_^yFk&*cdf^eI;mVPhnHA69u)kDKEprWnol>ya^f&Eu3|g zU7eU@P~vQt$llS>q#JsC5DwF#$rmFoHdYFah7D3vRc%dOT3LCZQ}z5hlVy2dVIju_ zNh&HT6AKF&m;jUfpw?b}MI~&{LMP#!TKp8SSw>MY60XlgsoVT68o2IejLsQCuFD|y z1$rKytF^Ne7jeWK9Lw^@sEdlHO+U&i;#cnx*V|BIEY$t{^oczU=9@6)K*s)XWgu15 zErwg{H`Lp^_wO&kpc=s-pvEJZlo}cspd?-I;u(tUVi=I~g?bQhLL3(eHaSjWW7j5MV69b||5UTJX0 zgOHHW#L(~_K;Z!-dVHNJYecXSx3qM0VgW0WKmiKS0xa#v?+d>sVY-&w4~TM;k1qzv zAs}Ld5NiGR&nYw-(W)@A%PuZfx_kF-1zZ!cgj*inIJmg6U>4@~@Art;U4v1Y9Be9* ztHHINcW@;m22#OTe3i#<>%~QiZQTyHo~kG-zXRUI{~U}2hNY$N7^Q*-z+zZ5`(sx) zZVajaEQI;W$l9!;$H}JktyeCAphAs7V!o zy)L0(6sdj3V|d@-A0nVZC_r;2DI(&sU>!<63Y|HLJyxtw#AK-|sH33~0;LBIzOuiE zTySE~`Z$uuV&Ga^dwZBuQP&G+0M-hAz;;rOKZG68o3;8*)CqrlN4jXshZ3M`Vv(eDd>lz!A(b3V}?KW*)OF1iY z#Qs^;V}3Qn#Dfk~Z4LR+ub#Zc%tAt^pmP1^gDOI-`05ZgJR`#lyWU}0X0)E0ljG+i z*Ka|Cf^BbacXfBeX!eiuii(P)PrMetTbv#5uQa~G3JJ{!woFcP7Cpf}u3~L~D=2VS zmKlt@)|Zz?{Ld>`wA$HoYvRabLSk0P%~RjK``O>$?~ocF{{Z2?>zMt}*tkei<;k+? zcI`-Xhvm}Bia_5(6BBYdIXTT_QJA5jVMAelzVmP?Ov3hCP;RbO)s7%-fQE)f)f#H( zWGJyAw*2Tjb_ebFXmoXXS*crxVL;i;jN`4aDe2X#Nv>q52iBX~?Sbi=s3!-XVlHTp z4o2NtJlI|*By69bY_>HwLm3$ve0+TWXrLO=x6x>H78Xk-A|f(Y>rDoUdM#+WvxWEc z+=mn&KW4lYtK#e|)Od03|B79X5fXJ7krXm4N6Nc-1~rFV&@$ig5e*t#P&Y7Ovb3_= z?iFd`l9qlfjM&P0($IrhUxF|^^9g8KVWS1r4X|OZs(~0JV+0REf za$+hx5&j#d|9SyG+5N8X-&N7*`r7d&27tn?y*>RZR;-XFj@00bBSX7oS?e{eNaQaY zX4=S*ix<9bOVMX?oAtpF5fNrX^8FUAPn4aVKec+8-=zvO`<828Ki1K4DVUg|b$@lp z-)54%b~g7z>j=(~3xVJyCMGT@Df#+4U+2$yEFdVB`1R}8rIsC}5lA@O9UtBC4LpO+ zzU8XLxgV?QXc?FsRxI-216E{Mjxps=*S{ z#0lKEeYQ4XRg3r6s(lDO5g@RKS^I-pL{t@ByzaMi&t4$S$~d! z(3}Qk!_C737Z;~BGLo-r|NTL$O$Tun(iz8D)FnaO9D)`1`}Gk+GuZt|{?o@?f@hl( z6l7#%@ALCjP$*76Kfm$B;?uXs=?3Nfna=wN?Kva_?3GmD4Z^WBvgEapz{>g+J7z=1otE z0Isn3Jw3RoDeywV^N2LHy3Rr z5I~?E$9avtNg`IAvFxW8m6erKw_*bwoSdu%3LY5L`-qJ)l!a5%u&}WBY*(?%NJ?gv zl*A5IwI1QX*^$b~*zUzhISpn3yd@a{x(MAj@dU;8ROGuPiby7-7N|vV6_(Po@ zr^2El8+1ZfxBtwH3u-zz@ZXAU%efm(&A@QU%F3#K`zx!uj!u$BrrdL3fCF+03JW*4 zIL-hZ402x|kplj5L*wn1&GE@e@a(OK4og6|S=7bx)e^G?(%4yDL&NUH=-61*r%xqk zW@i40kB0&7n$-KyK)NVYTxqFja!N|e@G#TE51RP>BPAsTYd=38Y9fHd#l^wT&Mq!T zo|gz<6PQEON2uB%Ql8VROu(ujE-5L7g@pw?;JJ;>o%;G8JO()}<5TubL+)*_d z5RJq6pwIS)03Dm{GBLzM^4Bjt&9qzF zHmJfOmcg1wLFwu23KyqdQ1kiOiN{PkiN3zRqFVm`>lk3W+1c4p(9!PVbulp-#MvI* zr{dzox2qc)l(Dns_V!oY+%_q_D|tmlsYfea2>VCw7y-2w5)#6>y+H+@F+idgtwh$g zwgk}k4EgB(e%-Z^FJvhxDW{jCNl+Y&+YDUPS8%i0D&Yh{CgDwI#IClswvdsG+Xflf z7Ih5`6?1bgh>M4ZI9D}>0J65RvDlgG7L}9?$;jYXSy{n(-zFp=*xH&_F{$yq)O3C< z$fKQh1%W_-OTuMjt^%cJSFlc{j0P(F-!9zRN>E!{3(Wv-$e7*;XAJ$u~o@s5_H zs-V!!;cHeI*Qp|Gqq3u;0C4mWu%ysjpb0RiFR;W7AZOObKM_a(OR zm=uHuJU+vyIAie$HvTUZF!!@ZU??Orw)x6MxS0S`1Gm0 zEB?9|2y^fA@;;8TtIGBC_D;{whrWDC06DXvZj^@mV`cuGQTM39J~OUghJQyv6B2@PI9$N9$d)B`Z*T8^)VWVh(2!>*xT#YU!MxpVn6z`J&lw0C=*ld5 zt7cs@vsj?%uJbl7|0jF@|JugK-ua`a$5O|Y8B5`!<65VZ^!xSS1mmxYA@VggBZ~|HQZ%Ruuat5Ay zeQ@yg1>t3=LU=ttHanp99R@%@(9!mG5c)s+=4dQuONH2`e( zKCXc)7U<)QE1i{`ot?4kL&e77yNf?&+au{PJGnZoljSyKJG;9_7dq*(m%O~ZZi{jA z^6oykDJRG3)^sKf^5-;w`Ay@>t)q#66PGkZAP3|=-@^b>R9j06>|wt4{7?ou-te<6 zo(CQt9ud*egwWbV1FO~7S1&$)mH?X+pOnGKq^ha_CP2)(i~5sk9b=W-q^gC*wV=U*6`)$i#>THW{(w}LI-?nIo^0EwmIxTC19ekCm}ZE9sD>IdS24Ol-22obMdwF6I@ zT3oyg4cGfhoSvPD*?wb!ii@N#U%sruMcoYg!xOAoVv$o@7=^pLdypbmP<}qIuxTw3 zlq_LKxiMA~oR!7({{4G=bl|3K0T2Qni{}}K0=i(Uw&GesH#H3n47^?a(ZV|>8CNz> zPfrMnkB>KK3Xq4)fv2AK4h-mTs1z+JtSl{=cSJE@jtA}Qrqav(_8ox=C+1kg;i>Ze z(&-AA)C-hA;_JM;8|k;b!VrtIvnr!iZuzOHEC9sW3A{SAG(XQy4jn);tZz`{nu;?u zHRZo{?L|by#(13?kmL&Y=~itF5Xl^%Vl*^Afgf}a47>r$P(dQqV%f4Ed0N ztPl`CRl%>W!Ec!^1^eNC2af4 zZF=WcFgtT3uq*)le+-0p0Dxr!PH)lB*x1=6#Kuy}qjCR4M1XyEnD0sCPUv1*=zC{v zZm!sLcEGy+_j5QXk`WP0B7sL_phLwY;o$0#bi8^lw^UR)gg2>bx@z0>dFJ@8yKh~k*I*98!?=SjMUWBf|{C?^Q~}%E)diF!)*C{?erW#*#xi@ zcn%$}wywTDJq=B0Xz0(K`QG^*87ZlFfQMp}n)2QgbtE@q^gR?R6J&|G9)3Z=>rPHi zg;;F<@v&cFLBUkq>gwu|lLm5NHX;zHzJZZZ>#tw5AQpGl`|g@MIFJC4*gHAR22&|C zPq&4`Dugr7KpCFGKmYsL&cf9-7GUlCw}SVIJ{uyyq~!E66~`2?Fly3J$Y}I@v*{wB z3az1~)v@;X^Yqjd1c6cv>-4Dh*@oj?+oCP(8aFo)1lSel@cYB`)^r=_YGHsfcjV<^ z5PnXOn3&k=2a;VW`pDDA$EW%GcS_)}d^d02b$1tqrpBL7c4R39yKhd&>pyvNT~LrL zGvFA+wqQW%`}glpt*w1aN=i(vW z)xNttU*kA`WXgFhkSnXG;Nv_7g8{`&p>K4QH7_rZ>9!{~G}Ul8G28UTj9XTg1sp}| zR7-GnZfs zGef|*6?qc2F}Ucbx!RGD5l;sxDJk|6 z6e|SK1KiWRz1_cwcxEcpI+kci6{|{Ls|)Y^SJ<%w-6K&F238(%#zQPoK6xnVrGcnQ&l3 zl6d9AtyfLTzGuJXo~07L(GktUz|c{pg_;{KvoffAc2gMDh@V__S&Ikgcnx znHv8?VG&IU2?=0-FhD+}o*pe64#&B@1H&`0s@iBU85ukIi02ki=@>AMyACq4s;Vj& zz9}gxD(25$2~{Q{BI3Gn;}Tn^#dxhZ0Q|;VsstXb*7x@kxDxM|fg}|Y67sbAf`Ng7 z8uZvNPFH~?;&yvBto(1quD%sX&whQ`KslQlq+ltK-H&YVgHv&IbadaDy9X)WyGIhs ziHHSG*ZtSX*w|`s=_mSfX;v15SEJfTn`1Rz9=I(F`m0w7A)vwGHC~G|0DsB1Jm3NX z0{B(}`5deF6zz#IOY9_fCXP6A^^LCKAKOOx(sf0CgTRLKxsj8t2+zW(d?IM3YAaRLz5palyqRKXNR$BkGZ8K zbwITWP#G19F^dPCoPpd=o;(5dDhH@w)T>wA@#+H(rt5N5NaQ4Xm!hV&_BD{Qn(FF) zFfqhcq@}U#931cfO)dZYITzIa*ZKlC;5o&{RjnT^JKqQ*rB zELV`$2j2!x{_DzMeuTf# z{r!D?Gc)bawtaAae}CF5M3Vjo&R~gfcur>Ec?!tf+8`EiC*GHP>e}1e%P%VW59n51 zZEeA{w6tB|?II#dOzTwL8ul4)-@Y9m7e_TeKOYZ@%w!7#X{fccvu0#uS7rv)!fWHLwNEK|FJ_@A+EgkQ#vX`j2xZDg43&XGR@87>a0l$v?M+a*fo-WhE zxC8|S!M&Xp0Y~pW!HLUO3D79y21drk<%8LB0QULzOozUy>G9mUtMd=v6=45k zQSXPmdv_Wj8OVWZ)1P}tCPV-ld(4GV5=gY{OO*m8Lo2h#qLmY3Vr88L5)J$)UE5F> zP;Oc$@c3cVz@Loj>RY&@qwSNZea1?$cIX-xm*NKhzG7Z++vJn~%p8%+=u==Fl|2Nr zU$S{uX9dR=8SU5A`HsczKY!~1Is<0pe#T#klZ+8?s%>p;gh4y|+li!2m6eQ9(y{gz z_w?GM84l@ff2^TC$d68?WN(X3|IaRhZvovG(Deszw1<7fjllmOpnG?-#;=&pNMQ6(t!`Vp?JZK}h9frBo3FhXnrbe3k(I-ed5* z2LBM*%4*po2w6M&2PgIx86AQ!A#zgp)LfEQlbvd(vkRF-H)$U!B6Zh!M$F!%rQxbx^10-Wtyr{bfh}66cAxHTx+d&L;gd3>2TsOb62P@@j0c<1$zRdiJ2Jl+00kLljR+jWJhJ--U;*Q)!^Nx^97ux*qGgDr= zq|I?gVF0f5SIJd8HL|%`B6ogUUS3{S)o)|NR;St)$CrTAB36QgVE)sO?&vECBF>!B zkqjK_CrWvFc^96zvfaFCIGA=%v(fz}T}Tg>d-{y^w_1GUdDacz7BjbmRxCG0wT+U% zw%uef(G?v;NkT zBJ609?$ml~>wUj~fY$c*Ga(@%Guww7dwZS9BF=hs1yfTx8!n>mJD+8Wlc_VF8HkY( zAlTjCUtLZPc(NZR5+DhpFL@&v#6s}TQ8oAXlU3P#?>yRFwwv!HH8L`ikPc|DoR%3= z_d3_z+lw37)mCo)h1+>eCnqPTd29?592{&o>*?u<5wyPiCN}nSp|;>?9}$IuNOs_u3sl`7iX+h2K|KW0aJX4vv1BWLG&A<;le$KY~pEESpZ}Oza!NED$Xd~|s560MBUx``ZXzlAG(f2&OhRihk;0eLa zym;|qF!%AQ@yU!YxsYVKw>RQ`yjmsXympy{gyia?rKROLhDbtVV`HH^cW{xt)ycrM zZ*^BVImymZu_K6?g@xhx2jc{OOR5OQyAcHi?Cys@;?EKj<02<}lQv@?jL$*+*zGJm zI!~cdq(k)N$&;P6Z*=io`T+p}1W&B>^cd>v>(l=ECva>`vxp%~kb0!eC6t?oXZG~T zlwCheV~Oe$V>=H(g>kFKuLEGWR({=HT>r{e4bO(0G~YJZuG& zjs;W9`}fSq47}Oh-%o%n{rZK2?CkDtewJZu>Fo^(_1c_!AnI{MIX*t#{qdt^Y*JW+ zKU5d;qp?+iY^!O_ky#5*jE z1Vcv`8jFXJGm4*4$(NF9cy~iN#n!9J`di5M&jI_*}`5&mMQ4S9e&&%%xN*bG+`I)kg@S@&>06y( z@5hgJGtD@f+S<>cEmTxhTl1XKZV11usHiY7H4Xgr<)3G8 zn?a$WzQx7sO+!v3zoIA_98<*HMwT8`ef;QBwz;#@zB*aOV?K0sX=#b+&K+9aIw$|v zuP>lW$jtQHobSp=Psi2M(?h)BgmDp*ft2vxUirSae1t!K{1CEVB*DeSwOtwGVb?4{ z>YP^Ze{b}NPD&!Vc=00K{grFi@FOB3&XSULz&?;ceJ2Uo;cjhh+1lB)DBu0#_v#gH z7%e}spv`pqbb}j@!_pwZi(;Lc3-8{&Lm^RKK|!Sa)3mb`R~R*y-fbcHnr;bC&t4?8 zP_qEz6FrrzOphoqsI=#g$ox>t?V#16aXq4J3CSm5)!`Ll|$R~GCP%6?um2% zB4x?F0cS*4S9hci>u|Op@PEO2v<1l(e*TK_Phl96&Pf?*Y3a~81+k?bg0H{>YQ(-) zM(x=8#2^9Q*Hi)l|Ldp!C54A|Y+=C{Z?LelE9O-Lz?ktq|MZSu<nmqrc6%~;^e*F0PbUh7H;<9O|si|q3QUqia zt>pN};C6rt>w>5Nf5%%sQ>=jj^CF8ipk7pLtd)j06fAaiq9RG~pChRU4-Ag?Rxx)y z-OFB9#IZfjW)c;>eC^t`jjgTwQc`CCH0@R=_^Yd{(`>#sYF1g(cZSmuQd7q}#rU=? znf*R$%OQ{Knip*kjiNYgQBha7+EGzcdtN#CDN%5K@l&GV&&9sCzCdS41^EJcyk1^j zLLwrPOy`+6I7p#7Y#kh=tgSf#5_$RfI<_!;CL{nffgPdL&o<{ex(5cjf+((F4GmwN z{yCoC|L*m3P8@ppigcKFO^tA^<1zskS25Lba6v&qdmM+hkW6i5Wo1caW#_j#XYDuS zzMGZJ^P32wTkBwM>j3xcBfb>HLn16J+}_@fg>FCr@A|`ce%BP@B;@3X-1gV}BO=Jw zrfTr``1nd4h=_=|`S{u*=tWAbzujTit|WoF?C$GBf&Fz%Oigv7fYqzGII6YpO_2Z% zaA%?Z3V5jlGPbtd`ywJDbk6J3{)vf`%lwG%X2hU{KLsNrIh57X@82wJY(%H0r-NU= zKG+9n3}65C3q4~*B30Z&D6o`+8QQ|f$0sT}`rgm}WFEUYDbBv`?z8cnx~-+px>WS^ zBG5f*^&=|GqeDbJPcXnY?eF+42Me{UG=8>W>lMnM8XO!PFbN7$*VNRY=c%Yj^1|Le zQ75q|J$=i|zqdQBwzjszn2L%jWYv=SMHV^oIIlcn>4u#Lgh*Iy}eg zJ@JR1fb4S6;r7pGaH561zAY})FY~k2p&lQpskQ&<@9Cj9M@~f4QrvVJ(iO>=p%Bk` zuu?YgRHrjbA)ec5MRVnQlm5!KUkkP#hgcE_0JtTmpy0VcQDP#U=gFoF3W;#}u__xz zY5~XJYAfSqgc4RZoqc@;9R&7JDhCJikrXsE!9I9|m8=}To8p7liBU$93?MOApMbJx zZf-_^UknqcZg=LX=c{OF5O{caRM*tBeE*($T>e(jhJoy|5CX8{uslMF?j#hm_SKI7 zV4EAWk|@Z4xS8UynXcFP8s6eEY9^SP;`sd(kk!xtK4rF(y4GoR0xMt1>AW^IdpbHg zDkCo+qFKFUu=Y8FaA;^qPr*cAU*Dv204qDA|Mw~=KpXP)`cYdz={NE5g0zdPtE5O! zSeTTm>V+cRx{-z7!*Ggl6Gh(^jJT%>reFGho~k~JSbs5)E6}bY17Nm17mW$4qS})K zIro30C4CV$gQyF_5E%$$P@zrp`SWMPbM+H3aS59W3NK#p9=MAqB`4z`P!fK%wMUj# z!QZNeVX~((tHA)%Rgeb3p}{v=^MH#aw+ z`IeRz9N-=6DCb9yC<+P-uiZIw0hCf_MPx+<|IZv#SlYp67h`l(6e1`nNP^);keS(8 zA3wh{!CUL!>Zrxs_WUH6yhB6J73nqHR8Qod)<<#8>rGsoz#t(L%S|@6_t_w_g*mh< z3wmr>SQr@@?>PQ`GggCxN1$S4bd`caT}@2|T3)xoH5Oou2vJv85AOI2cqgl?oBYuf zH2-aEGjfxI;~Go4R+&k3Q&W?aa8MA)__GKgRq;Jd5Su-{y{e$ZDJY;bqT}PK(TmE< z6K@{6_xAR(u%s_67^yyb^d9K&CMV~0M@L6_IXPyQblA9e{Nph5HL+p5UYqtVtGYHO>Ll`-{8sNc5o2ujT?c8in)2N)Zv#e zU*ur9fMv>3Qk$EbMrLNRT>6b~#;%9$(?MBJG`I=I!k!4ha%kIa1h<{8T)A@jj>B1? zUB9HH%ODa7MMUbPx8b&0Z=|}vii$dK9sKh7b9R%y1RqY_S_E0_PYwl48l^o3mN=6- z&;{DWZhuV|LqjtQ#Ro68zn2W;cHJ?9S8x#VlMP9bnscBeWaZ>=QU?M90|^oA$-$#t_R{E@E zelzo(h6#6O*0;XN{grV%z-T`|KM8GZIuLI*L(S~$>?EQLSfr&`~oFN_p)F9+V&r)7qj!HGKMX>ac z9~p&(pI+Vy2?~;c##B^P%zQ1Ws#O?!7ht)xv{c9K?YnpB_4Owe6QM0R%5~wQ05F&G zpA>ig{+f@1l8c*L2C&i;#y=?LhO!}01)$*Fc7pr6ySt?hzf@s2%X4)A!pABssgW4~ zO^m>E40Qkd{QSuopHBk=flwTJjqYqz(o)rq%T&;M$nZobyKXHdCnu+^qocpCudfu% z)!46358;{=l$3r@=eK3Qr0}VR?T0$O)hH||@bmS>E7ETwL%6xQz2o9E@Y;&N$0#On z$l%NR(`NT6bwyu7y7zst?e!2!lw*)K5g z3KJ8Om6dhDcxPin0_s{RNeBmVIoMzZcl9nAKl*A@YAU1QvuB$#EqI88iOKbolM`Tp z>!lAdVN~~aj(k(Xfq<38Tz8m2IYFmpn19KRR$-;2+tF$A6zl2kjtUMYat6krpn#V% zfsSJQ{qY@_N5U`D)Bggap&Bb@Jtc&;p-s~tjTQHY4@o)n8o%6W6UbGx8W&$|u`DN&y^1pEe(-wnX>ZMy6-a%s~ zeI%VCL9hd&Vqz5M&kr&w{y$&OP2jt^w>_ej57v19U@_6=9m!qK6CvwK7Xv1GtiGm`fzLHB$KO8vFb<#tDY3Z>?v z_1kn211c_N}g!B@b!cFm+Rf#-L@jN&cBB6_xARZltV|h?o4tHI}0Sm#}g_j zD8OOU_xJY)MMipYjAO!%91aBVKB4Zby0*6Rjt3a?I?|!NgMg#1e zFSKHX!pqk#TMI-ZMY^|~IE92TpsOXb-ffU`Q+LI^t zKP#=j5mQrBBMC$9ECX74`b>v$Fg_ zsLM`eOR!QJjudEtJN9X86c;~U;RC6JZT7}FSgTvFcF)hxM|<5YQU*lTy?ggi^$Y93 z8RmRt=j66O z!khk{(*2{9+zJ|$)`Jy51=XyO@L)m2fa!c*E(+faDrg=Q4=X#npN|jDNU?t8Icm-s z(DhvqCZ*-)htlwwAV_Ol8_Ei6LLNuA!DMoKp18DkcD^_~g?$0RauKjNvA_~~Z((5p zLH-^Ncwud9A_>VEW&kyVA|e)ztn>P6uU@}CmtWl23U2p(Ztl1d{hK#$N}SjAKw``Q z@1VlI#g~u=q^S}Wf{M#=@vC8#{yC1EM{{#?vNAG(4h{~o_wM-&fBh;4UxC|@mXfkx z?0XNy#*+8#ZifBOel;B(MIIg=BS53L(M-7*GtebcQbvY`_hB#6K?q+&z>&|-;p5|f ze#7>dwwvX}vl|mJzCk&r11URgX-+dFGg2Drmn&BodFV2U?#@FbDY`tq8ezmR|tLo_~-G3hy%IAJy z`xM}e;!%uohz=EsEv2PA-)ih-^6n(vaSVZgr~DkM)NH@OP_7 z!S_7?lY*8k&^HTca!@0(va;v5={KRu@4-m{TMvHz+yYJt4FasWVgM-6tn1Iwt}o;p zoO<=$9!|H_v(HAi(VH);q{3~(IRz!h#KibQWJK46EvH#sl;{GjM@vg9tDqq1;BdRj zptPKG4=f1Iu=QP5*B}VBAQPD~dYi6p>Ahe@4CmKw1Yu7b5Gvp-nvofFMbL8#3I+ns zyY4J8Yy1P~BkM@ak%z{=_)53>G=#5LqQ9G^gYND`M>=sY(x~@Ji|FP?9P4 zQ~5fj{0KThG9bTpXasK9aAc@%Oc2NsTP%->VFS#*=Sr1(?c6N5*DU1-7_I>)qW51|q z&8?)XOAmb73389ewEwch?_na#(V`B>0Xv4aTtrtUtH^<~+90YO%zwfKNf*EQ)hDT3 zjR&{`DPoe~MpblmL0AoZ@7|wYV6cRGWpksdCO6Xga zjXso$0eaKbc2^*}2nGvzTPxd)kuuFm%nQOVXy4hnIhIl~kE0#1xHu%Fq|pfpL7=8* zV381O&TrM(&f2|Rdk-eV9KH?h;t zKlHca+en%F{hQcF!n?a$7D15;D!0UTw$)3Ex3kVq?UWmo#~sz{(znLJV@^#?%`7bV z4GyY2|K6yZ_vb0iI@iu$YARkY%sMl8-)gsgPGklw&EF5V!>Vu=$sxxtr~5b5Hy89r z!Ogl zqoz2~a0+_*@bvU_lX-ekm-A#~WLA2O<@<7$lUr7j?_5ocja#Os>N}=e64ODcLi82( zAe4$fv66>xHBNQ(W+gueJsF4-KmY?zp{m4;Nwt*vfSK zCULL;V`s_92@%D&y!b%;!Y66MU}IPdlMm=VE3B#N4|Qlp*=eW`bw z#@*2o1{W8XH8*e(Ii&xZWhSK5rV!PD1o4TDy>$8V<&BSAO}DjEYoYL4KxMgQ=+(PW z;1Q5`!`siTtbmBWX0E`kYF67aoBm^HWaLLmC(zv1hUetugb{ZaN)h)UPIHP~&3Tl8 zH8&>$SE-mPp1jQV)dpOSJ~|XgNl8)FYVPgnVFo{N{rYv75K!6EG4(Xu1G@(j7Hk6e z*AmkKhTOH7+Tn(Mu(2q`hB1iIf*+HCuCe{m8*B1|&|=*e@~pPbP68l0kg$YRTVpUp zp%b)5iv+alqeqW?Afs!AMvse&Lzj2M6oNMbQrh+(+N!F!VDiE7p_3ADx7wA@ed_8& zz~u5+j=nHlWSy4PO?DJf=VW~1lN z6_r!P!G%I3M=NB@MDYkO|6?sBHFXS360$Ng&r^JcdXZCBjs!X~nV^-bjBMs?N{PU;A>~1aI8l-d+xf5|ongOK?(V?LibtNsWz-w>^#=SXf@z*}aD* z`B%Avz_c4J@I2N~SEoSGTFe;DtnT3T9QT7I$eH|N{1;HLmUd4;Ot*vx0*1`L79>1sEAapRoVw)>^Aa(5S?93h) z{ZLjWr=%3Yso$t5B?ZiI6)69X?F>Re0kVFm#GnoRsGuN-TFf?PTBg=P2F1YbQc$dp zmHGl2Ro91xh7uvb`Sv5dv$L~OQfg11%4cV1>rBdNE6a_(4Kjlqff5z=kz{2W;gOMn zMMazrj*ii9-kgD06*9$i*!J+w{hghK0=46vU%mkQ0@~7$Apn%ZC2nf(K5IXe^VJc;oZUhcp8oacXAs+?9dk1? zGwjM(DPj?y7D>x5-)9pT1oR7~FW=Wno%1K`b#!jSFsw!P;ll@>p5px}Vxf?h;2?n8 z+%SE(dhHsHgzugeo2#qq#{NDbQe9V<0d@fvfGS0}Nz(*VGqbY*AMmaBpkH7zhjKJX zYy&`n44KILj~IXXU*%U{Hg!KNs zbo0s;_4xcoxoRjNG<2z%Kgyl~&!5Cr4Wb-WVNGc)@PF(0I1S7{Y#|7T;3tEj_}xds zoQ7W@LD3ii76x~3+v)haZ$B{~f|)arI~y1pvRqeoa;i)a1&gpy9|+uX(HSA_`yCn* zBJ^>*_QQxXpGuX7c1ZVxrkZlvp0>W~F?b?0bMNTrz}#_Q1!gUQYSH+}l)MEEcNDW`tpl5mj?N4)I3Xe7((-a!Yb&mx^;A@L4=ulO@v#60 zC=ZC*q2O_brw7rT_l11#vZHx_gO9)e(4Z|Lg5WEn&jR2>go2LZ$VKfHcv)GGC8w|8KGP-XH9wD=|MlLJs5(#Dj#i&CRGS+|{%C*OH_ z&`W#pt=9e$NP1WM&#=ZkWU&sgmTL6bQ$VPTp`1~FXZvXCtTg&F|Y(`#_`hrIOmkpLq%76GpI*RHb0 z$yt3bzqPV9Kkp0gp&2h?LD(oJDw+mkK}axA@?xcY!8;6=M+~uG+(EJT__-BPxUMP1 z!(DN0`9#(*klrLTyqW6e%kRub|8@=y4oX0k$8qVC(bLlx=+;reEGCKHL>FqL#A)>@ z>K$M@h7o>oRXUs&AKi|_L%UOc@q-yWn0;P>ngobGST1gw0UHZTg6v4bP@I5(0QC-_ zB%uM&2^zo??CC7zc!)Q+!DokCKVT~82Q{Hl_|zW)bO}JY-$&@P5Af^)SRd5uKza}F z;sYP;{Qi0l{0KUDMS^u60!B)YN6*6EqhD zb+ozAa}idZ-=jC0{vZ^U{ODvJmUVEv-c)MyT^wnK%>bn0a9M)4zKp=p zR46oB$w5Bt@9)n~!*JokePGA%fCkrH`IRatbo#rV^$&ks{PcR5D?dxNwjVfu7&1S3 zSy{95BL-zx!vtf#=0AA`Zc%5STA~g^zWC!u#Yc;wy|mn;i=YCM+6m5~;ezkLPy1A* zrqiQa40k}|yPoA@PFDE?v9hwV zQkcG8y>X+ehe@C~GgB(v;v6|SD%!TIJFxY>2S-PSV* zZ%d&XZjhOkWdPj1%5e^cs@SI%d(#D@w#bDpuA8@RJ<`%*tL$&gD%oKdQ~0}{IXW`Z z3E?`+?u}qIVoCG?o@U_CcRCgvRt)eR14B((zs51}(2onp|Mv-?#R@Aq$PD07mEWVZ tS;oJ#T;onxWd~gU^N`YiXKQ~E3nIEmy89|$;lV3J?tzk2(S7Wz{{o9YbejMG literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/class_lidar_driver_impl.png b/doc/src_intro/img/class_lidar_driver_impl.png new file mode 100644 index 0000000000000000000000000000000000000000..c219a3f92a0ae48cebf1e7a0f84b5fcb746109ff GIT binary patch literal 64595 zcmb5W2RPS#+duwoD@BTij7qXX8QGK>vI*HqR>&%wlu$-?%Z%(*$;e7ZMj06u8QByv zG7|sS=en-@d7l4sKfmAac&_8RkE>gJea8EJp09Pj167sfcI}|uK_ZcM$)A%}Cy_P^ zlSmu%$+qGvZ+21B;y>H3ozrzBktnK(|80okpg2S#9VW?3pVf4E^8Kr~e(>V@($6|I zwq+$YcJ}OWBVF2OHobnV8EovDj~=?HoDT}N31XJGvt01weby=Kqmq*0jQI!d1n=wQ zOO(7IB@&r4%{c0wqas(~ZSt$6&-SZrs-rWcabb9Ydp|A4^^5 z?p{y7e~!ED-u%(BzyI^+qe5Rotq_^-Vf-sPC@m$od-K`dw@0Hb#{T-+OwXQO^k<2$ z#p&HGEiK)_!bJYp_pWNNRcmPf>tl#dlgJ&f$>#Xydy^8Gh@Y==ROEBQ4{tu}VjFlT zg!m<7&77?*RK(W?ic<_eQ&3S+jg60Y6p>QY+5WyTBj#7HUM;PxbQX!?QtGrmwLBEL z!NtbLHb2>wTf1d!VnV%s@ArRxHL2;rsZECt9s2&`hqeB*!(@{3Q6Xda#!w;05z(6& zWWFEgaYwgV(i0MV+!v=d%q;eKKTS#5 z;`8d&_3X}hs?7s^@*)xv6+OWUDSHeIzOv}hCmwTjbX;2+40Y%_l3!53EF$t4&yA;$ zgL;SC!bHu_!MaR?>$0+2_wCy^J6%#z;xyK>ft#EA%KJw$FRr|AP&%|{PgRVOSN%g? z^9c{J$an9~`QEy56p*Z*T8tPQBVlHjN2ByF{yF@@*Dlq*-fDPEH0< z7u6r493{1Z#QR-eP3^MnEp;sxA)c>Q{>enIY{N3z6m{Lv<$e42H|C05|NgGquHt>X z_gekhpWnJKEvW46?UR#}BR_u%I~KTo@9~osEr)~es2l8Fzt=3`Cwa5HTwLi9-v-TK zx`oL{L1S1{8m;`w$@|A;Rz@Yt9z30+{MEO<7Nho5c0-12r5vN@?XWN^Sy|cDY43HZ zL{*FLj0_CQzkmH`?dqy~^XBGLxzLT*7ACZ)cWkjMUp{VYYwI-8F0X8AWz~SYdw`c- z7ea43Kh~Q3?Ah~6H9JVXE`z)9%~%GhTA3HFet8+#EV2Hi%g8&HLp$fB3(inM-k0spwJl2Y1vmUCND2fy80<^gP-J^EZrAl-G$u2wERihxrX|sF8LJe?8NGR zA z9oo2i?_Mc91FUJ=hi0tQJF2RxNaxOuduMN69y%bc+z(wSX5?59@|}*)F(FcI^89nS;wPXTogW` z;wxn4=H?~We>9A|e?0sHujI0sS?hB%MJH$H@sFvLA~&Xvv9QSX*1dZdz+JwyQT2T* z+r7ZR?IiED<<#2WyjPkko11gn*S?lGKgG3F*VSq0=$unf*dbuod$}`97x#PGw&&bn zZLsU&*Bh2C2^((SyeTa$eQj>!Jz5 zzRqVcr;j&Vh&)xW~JI}|}wPxw^;=x#U zWJIn0e(O)k|4ZQX>1d-v2M&;~O?GDQXe0{f+QaJX%+cE`I>?;18 z_NQb#&c+sq7uo;)yFNSRf@$e6wq4D={hRuyrVNLPYa!tQzQDS4`}I9AJDW3s_K4M& zmu%+Eal_v~ztAtbcC#^t`(uH17kgJ`NseI|d&P&Qrp*aTk54;ayn|vpb9Fb9@H$B` z`b6u}*H52x7^u`xoCY&<%P)O+B1BC?^Rq+S$nv}_7b`1C(`c6X+|hXNt^NLtUX}Ir z={?VRd3kl8U*5hr-N$m|$W2DCr48G*ZR>TL%x3TEtE%$tEpwlHFVJ`Y@neqWha0q* zEbyt)GBQ6WGIO81{Jg{6vmhH$CJn_Ffma?#f{n6@6m+wdCh`YJBJ9iqhG$XR~zj zeLtqE%r$W2=3W2s#f?L8Y4p*5X-BSTN1ax>o5KuI1{;-gHQC4eDkN@9_h$1k`e~l! z9QhD?@0h%E`N_wJMR!eX*$~5R^kJwzBL2GbZ5~v%TOFC&AG7rY`p0vgGUa&t&U|lZ zZcdf*rx@mXkl8Dj^^|FqBhYUfmiC(1fA*&b__FoV@^VyhXDIQSSNAaedlM^iX8x-M zOSF}_FE)5o4DDh5vb?-Jd<9zo#f?qi-BYwngO#~v2{u;NmLivQBWp{``bkMGIhn4a zyR1>(}wHwrOj3u@5^=_lk*%i3wf*ejrxZ`5V4o zI`=^&ORtbZKD@|d*&)5^v?Z!T95D=L6MT-6ITjG@A$H(FJ0< zKDa)b97BT&wC>}r{_^Fbq3FVw0_zior3X}0RM18#gMxzCmAt=IZx0U-pZWQ7;AyCM zQeNJD8jcIbCMIV!HL0`p3UeF`&<1r}4PD&YyZr0Mfe=(x&!D7mR5*9!8cF0EM;|6r zsScqRiMvj7+g!8zm5nPF?r@*??;irEZN5~eD8`)R;i+nDyhkr`{eD!GUw-~6e+v3< z66?#9sA&mC6<%l^2Ym3m99HHnh0fT!xe0TZ&F?{B?$q$9|5RbDH+9&p;&+ae${JboF#-& zA|x^K$k*35a`|lH#XWUiT|GzwbYVVz{0?f%ri_jv4Rv*kPkBdja&j)4n>&uR9FYy7 zlSea<_%pwkgkLtavM`DMJ@eT-zBNha-inA$qHKv_fM~E4sF^-QH?i?3fV5dCScn`>VHcqkt`o^ z`~WSjy1srB$^h5&$7K1vt?!n%{k?Fjcym$Uchd5mTf*eO-6l(n5TIihR$6q zw0)1pSnNExk3}VJXmxq+e4MB*Q*LRgXruyj#rm2EI{X#1+uL{UM6sIvQS-{Oa2Z_cDY6ebBoLCWkvdz)=zY?(b|)~xwo1I(YtGKh!orVGu6Y5%eAsi#+5s7^ zPxmU}!QtbL0Yi(5iuwl!HSFq+i5|o)di?rq{zSsNyzLKO?shV=e$<#Y6OUBz>7_a3wLEczu*foPzc z^3Y03ZcK+17YkjuaKYoxLf7mXy|9z<&u=vk9z4i1YutyYYFZogrl*Gv9kJ)@*J9VX z<0Jsd%l(x%@r>J2RTxntf#QbH4wF^l#Xo)iY(G%t$J5-3$2HblCW5+h8Fw}`GSblP z>+AdAv<)rLiP`K>{ng&mgOrq%vvYHn?P*jJ>#Hwn`(%xb;sNLG;a8l*+PHf4YTk<% zgMSwLQq$7XnnXFmt3Q8!s2nSN%ChZP@c{AV7cX9TC`(F74a;899Y!5} zfU4J)D7B4_j!w}2+vWsXwyXFxMqbOzA3l6|@aWNVpiY!6=?bqud3kxpCaldc&wD*KAb^ba^i{GnT6XNv6!0O((GLSZegq$rKVei(=Yz(5L_WM! z|E^nXayZjzEb5U@`KCRuZ-hR1LI=Kbyl;=9q9PMF_jDk`YgK``PnRz*sLrl#h=fdiT)OBz6UdC#98Wn}+|kpczbwvCIoA60^9%FP zQipH&6#=24EQb&K0OmhadW=sIIj5*-I?4hY!Nfq=TW zyAwF%^>n!+AT6FB&_Pm@@RluGPF-m_(Dw18E_Qf+e*WxfT=T1|pR2HIhfNGr#llWr zezzN6I9jovhQ=>7l?C;e>F{9^R#RJB8?iM3126yhQb04JyKkZ46+ZD8Gqe5dko>oA z-vR;yHyD4b4n#4&9~Slo#PCz8>kIw$x<<5dleN`l0s>2{Ep0-_bbYBRC$}v{UH;bA zU4Y%+?s1nNK5=5Fl#~?eOEv1(^2}RGj;u@qHF%_{NwFM1z7^XHdob|cJ=5v{sso1( zeattNbB)(XRYngXzxdMPY{YRTmjS>1dHMMR01GjTy4Zx+H=}sLJLv@Pqw3Ao9+YHE7d*chRmii>hek75U5z=!Vwu_RU3*0!NlU@-@Tgw%F->*dVlnY>kHrC!A~ z(Tt>{UWkD+`IVK4fgA%@IiNoE^z@Ki7CN*+>%#V@sIyXIU%%sct^D|Ou;=ezt$8L= zFAECr>0xqrNLg7~V_yn5NPr_%ot^uvt*w_A0qUYMJ_5p@Q&KW(PgC>BU`aMSrfA@= zZR8pC>qmEtf{0Z+Yw(>9sAb!C?mQ+S5R;sItk-kV09+D3b_G>$HsG9$YqUAwn$N`c zt=ih!#d0)<4mG0eZs-_`y>;uBhcW|qDli|)xt7<)ODzd!X-6sh7rKmMnzc<#j-Y$z z&a7@n8*YxL6>}cOt|=@ONGPG9-m^z?eeDnbukp_>Sn5IO1Rjs z@Mq=cDwZ*^Nb29cOTeb49rhi0-g)uj#S|}Y>$tlsr_rdhhZcA4+_^NFTfr`-0*YAr zv-Z&H>RdDUk;CGY!Bz^obHMo|yq~B=PImUH%F2W`(MAo2^aVWRMin_aVW$98?nt7- zZQVtCZM=;+n5r^-n5Y)m+>QWyc=+Dye+p}h@2rdXPp~j6tZ|Jj1J16Bh=$cQ+FZSQ zK*CFOFN^XJfV|Jdg$oW2JWR4d_ZKJe{!y4}-n=<$*pz+(dv^6#w_S=XN5i-2>EpDf_|Yb zeS*~xXzVupEt((Oi4&2GG{N`oMZ~vrG@>@6W2XQ$_LRBD0PL%3YHB_m>m;D;TxRF4 zSbRftiH%k?Rur%In#VJhcx6LF2HYK;xW@w^0fHP5sO{RdGjekNPy;NJZCaDI02;ou z{rafbar8MbnfOxwE%q*Zlm*;NqfswOSy>s>a&T%YBr1w#YHDgHK$+?MQ{g+5j9dbI zh8{moS)uyFhY*y-pUb21j(`n3jE{5K{Upy`zI+U_ z3qZt4vj*yo8#iWnJg%*;55()H<+r+BR#vvU21%&MX?zdxK{Zwgs%{jmO?n8ZW-DkR zP|1e?DyEtFdEzhGG@kX3jhzFUAv*cJ{oGfE8=}CsqZ*h_oCpHqG_kgB?0<9X;VILt zu_8A{Qeq4t=q>4-df^k_>*2Tg0EpD-@$rk~#y85x;Nerk#5fBpJ( zLihP?E=WXQo`JhaD6Ad>JrB@J@|_7%XOGI#FAneX`kmeMLs(eY!aDQHs0B2g(w?C9 z$(^8)d)751U9l-vR#s+LUjZW2=XP*JXv=wdiPIPivL|sVu2$@*dNKL4IL`{ICp9&7 zOR1|P)uck2$f46$jmO(khHckT=;DoS*tK;%2L}f;`6$o3cr8qJsRUV&SMjn+NEn$G zKe`)mCq&hJk=c)G`5Ki!vwOj?C6g! za>{Gf1*Nh0Z#_-

@|2QCD@QBj3$0GevM-!o2z!6& z=O7@#o7&ntiBkS(X&qLhb46dA)&L_dKR;*gF0{+NR#DjJbqGzm#A&<=K-d-C)&ku( zxPkiiqcmr!(HG6)gJ?H2Q$%mRkbTiFGm}Hi{Z}$7Ir`HkAJj2GzMu2+$q*Sz?p1Uj=@7wSBDhuyuT`b6Gb7Uf`icq^Cms|Q_cbcqrdwvhJ z&j39BkI$3_3%U&7HZZ+jVjKS-)ao2*!b$zAjlTLLO};kZ3L(j#%i|}Pi>s?W9v~s3;HseI(b5ZntmzvV z5N*`^&%%E6gG*56b{;sH(8j~ioOn!KNg9B^7`_?yRbdLio^IiRPzc%<#L|mLHrC*W zEJfth)w7=|>CQh948v6cwa~Av&Z(e-9uT}{94q=nb$0t_VCyc$ROQ`q&&-n&U)c4D z=NP=+nl`0(W3qD>h%eCgITaPTbj^nDc3M6QT**EN@#bai<1luHv3Nz@<^!h7e^X$o zoZ(knuJR)%VcpkDz5Porg6ji%m#1JBd84P}y&PDdoTpO@!Q0W|u*RX*W8X+wS+PUs zD)^xHwSHqqfP<&g1o4WTrOcsmNA8OTK-(gte)eq8xj8HKJWHEAxod9Sc#1htbi`@;$+xXe$b_{F;1136L8{ zO}1l4xDj;0!j24WS=l?QD?cA7LKEp&Dg(d=4A0bLK-nBcRi~XUgW&076>ex2`XvSx zKq9WWk-I{FSai!-7l&82UoTFS1@2|xxl~O?+zOb~8`wchaLBZ?Jru7GK^kscUt5$o zt`ZkiP{6;#kJz+m{LB*lY8@WW&Oc1b{{vkHvKSd2kAs5)$W5kfYR;>=BV^4Re}J(% z2(U*fz<`)6+taL`AXmVmmTLa9Xv=^lEMH)M)Crb~RIlumlo}A=j97C**KMC)(N;6J zfNeTEd(g|v3o>&3ZwqiG{k;s+@1i==GVb0LzCEF56e{48@NMwq>C^kVxCb7p&R$e& z`%fj;X5pi_S?kA-d)J%z=h3z`R8>_+PA>@4^5>hp-3lA+;?yrdKuEdTgR8h85I2ZA zgz9(3nM$Lgv$HejnrGJYza7M!qu*9o$eP6$76$D90~^e(6gz9tqX((H-jNbnTBD`0 zz+ZU$o3=dwCd17P4GrDL_dqk7ne7bZs`ytHU^XLSncEDol)`gmegKc{ zdvDoef**m5LVSYqnncI>N0%_Auq6bqe}7Q>+d03%(m?V2d1~Bi+9n!j)(OJ2Yc%-$ zsi&t@)`W>r#b6r2f90Rz6Av`qe|xsQBvIqSd@uQaEYW9|Smjhef-QAbNn*UAM;+~T#10pB72)6 zn9G|yyRvj|#m3S@ez**c4Fu?(wxMfE8xMgI(4UD?1$+*jbqZ`#CdI4ZsW|PDKnm`ox3s5gKtxSbXT1ZQN0fX;#X)#TbfPZz z;r&H_nTF{37I3b=-Bo` z@b(N}=s5dQ&f*>z@_%5(4Dz330YrP9mL9)+M$ zqECPmr1tdQ!P}P=jhRJDAN=uyld!D#D#q1~NyoxP0Js4?C) z8%nSZ{N5l2Fgt+8D>c#m9l)DONa!F0 z$!E&3J1T(yfP@Bs)RI$DOs-x%A*YxdAT0g1-19dSQclNs_)if}o-~1Xv2k&ATJ%Ih zlJz6h8aM(G(a{(Fe&WDdv-!C?`5AN%Bl-m4%y+n*4&t#4mvTRNfrk7`*jg_8TiD`1x*8ot(eglFAL4-RvDvx;%a5{5xv(<#*-&crl}vUOm)WdI}UeY=#Csjg#RB> z40-tQAnd}oA3jjX$;r89=RF@`!FwUpBtU>+>oKT558wxt?*4+zO5Uqi&!EtE7J5OA zv4mBhKs!!BNtvtV6`J`W-w1Ax{a|gr<;UaDM2ABf@$&hExd{GSb$h$>MU{cR6hm7B z=3~cZQ2ZJy1Z=)Uf<8TojU5)^FE1~@eEIS<&@*C>S5$bXEW?PaFMNHbKp)g_6#7ZB z_xc(k2M8q!2n$~<5749zD}>3gdGluI#z)qB$~_MeB4MA}tPqzU1ziNt%ZxOV&%Ri&vBg3# z>IrG>MBI(DY1{t?l&b`nlmw9YwzoG9_1hE;R!2vtxX=VigJ8)-!WNo!|NQwgmad7d zE#bdFQ|Gg6OKxzy$*%r(9!DjM`8Lu2^t_A|l%9`=`ErtHLS+*58(J z_s_TQ--B>1SkdtN21ZBWZLMxdEB^%XkDz3(>wgw+-esDlU=)ACsrTw#StyY;@>sey z)mNc{mC=gW&qoGfr*k2DKf?3^pV2`;$fFdLYBsxg;@b7=$2m9@y{G|re-ri@#G>|+ zCs?B}1W6rb^Z3*9z9VV2Y&p6w?!cDu1J5C~ppxuhV$4K&r{Lh=C|@2qMDqHxpj~{z ze@pKu9o0MOQ=gt}9C1Md+2DK9cC*lRxe5-S_vl*Tu#V45U z2KtH}<;tfnv{R*rWH9_jZ#!pVl2{uMK2}7wkn$h8TEXS|Jsut&2gE%DIWNAfMA+va zaf|m_{~6Z`G#W2F7WUllpHaflE^rMLz!^j=!}IrbDDswHOZXwaqOB2nA#!6VrT}|$ zfCp`W5@%?_76EcfS7#g1Von-Yl3c0ZK^Q}t1I;S``SYr;Ut=Mcv=!N#f^ti`xCnv{ zLXC(As6>{8BlT;Z$tDP4Nl?9XE?#t)XlDcA%=8oo|4>G~2d^dAHP})ct`N)U!lVP@ zcQPn=2p1w;6;5={68?4|(xjv$7qrkNXmm_?049bu*6RVb=-DdjF#*Y3NA7>*-h;!VuL^owrw~XU!nY(sFLqoU`-d4D~y zg1a?%{_~xa|Ba!OD0cmlClc*DZ_RKTCm1Bl1-G zd+N1woP-Y=A6~{=xLIh_sODjAY@@nVw6qtePQ9}3QXV|5u7tEB4`eupLhsd|bq>kj z%+H#QJ}rM6M#j%1zX#4BY!VeOl|L7O-r!_tiZtKNv8PGTos2(B=A1fIkd%zCCS+$T zL3&lOkw&0*!2XhSs>grGtf8TyF)Z_)F^CU71oq=8baiog$I;Tok1o!jolOp6OSqnpf0$cHTd%sa+<+y`SJVXI;KbWGB7=AtIb}ge~sexigO*-|N30 zs&IXE;9ep`2{s4D&I9m6E7wEA7krTSSx?{~jf@fzfVrJY6rATtiwwYY2YIjTK6p@G zS(ySa5?Q_NSeiUB8*|BTO!b5f*8Mvjs%0;e{F)h>R_{9_3a{!+qH4SK{e}rA!7Cr0 z=%#43I662WjiP6hc_CdzeEBwv#ZyQufLq96%kfpcCX-a^_}{Ui2-tz&CMFtyM~OxV zce<@e;_;IwLAP#gf&!I-rsi-ikXbRhB~6V9=7%z%S8GQ{4dhJxBsdbMN;n6%Lhcu& zbbwgNQHY=u+mAFIBtb>wljJ8s=6iusmEfj!g9zush_-ijCPZrRj~C|63@CA^jYnbV zs&YP{p`}&8QX;hCG1!Nwwxm_;>e4^Ix<7sTWDH71NVE>aJ4i;J3pAUy?mT?#*lmy? zKTx22bj60XNFS?#Jehm@2EKjsh3SfI#ziB%QFB)#zJqWwwArkle}TLBK-87z%9Sfl zlbylXdB{J@pw?%9uvc2o@l`!!<~-kEdgY2Nq7&JJT3X5C!gPUwfhx&~dueEDPy}>} zt{s6}S@rhqEfnhx_u{I#T%erd;^MGJkM34fNPwe7O1MB0fB?Ijj_$mNM=4!l1`-BE zMS@s@aDM+snUUz$i<_d#VVkzB;OHO zlKJ%MTfp0DWEqzc`}_3Vj2vCvw6ENgPULz}vpCVTZSOyL@DA}Nc*w&rzC5rmf%!Kf zpQ;R~jmk2JS4GI~;AdwR4%niM!ytm9xtE^){q6008)9P(k;mPK!gB>U;E9-fG~%t1 zZWGe!n%@Qn-T;<9JZT~sm2^C_rn-7Jyk+E?n~47*ItBwSr>&;qSy-_3+zp!BcOyGm z73JmMAX@~{2JxMTJZ3vkD=%NULUdN*3E*$r+cnpSl=b`fyHv&Y9oo0=4orBW^Bp+l z3*N4MF{VM7E>$@;34GJ(`=>BM6T5v&l|3rxAn#UWM8Ptz-MBFdJ%KQ5LAYK(c`$Sx zrXj%tvA=#jdU4mTU7Q6g_O2Il4TC|nL7wKne~tj1BpG`Dapp2AZ*re5lS8V6;8ysR zG1|8KZh!edL=GCs=X7;-iS+;sNc8ScpAH~t3N>JJ+9h^q{0)lk(>=v|K^DJ%|4u@h zJI3_n0vU-0=HYf}9i0PvkDu?y z(n3cFkBQOFIF(%f-V2C5JR$-3@;SwwZH3^PHR+zRc z$VMfabQ92jk;~7c@VQFYRwki*KL^l*WV-~58h5rE^knn4ZH~x8Da_H_ZfH+S)X<$b zRIL%x1^)w-CV~}!El{_ID5bAmJ89(ohd*J(XX}?(V;N=Gaf1sP5~F z$5$IqZ7M|E$9w&^(efk0>jjy#;x8Np^C!AFasy{N9zw6lEA@n}{=K^}6x1&%I~#U4 zIU+|~yt#lNNcK~viC5qi3{UA{FLx8RZ&TAwAIOJoCC=8x8<>I7|F;CuXei;L%mNr9 zpc-NM1MN2K6g@~!&uJvhez&bV$3O(eG+)wIRJ{M7hm*V$wkTAn;{$jXAdo}~jRexl z|KYFL)KGs)XmcijT(-m0q|0CGJ}v;7LoS{9S;y!ICS}E_0{X~DtIW(2*fm1eH9yTx z)}f^1SMJcLu$Wk^K(EU!cnX0i*Rc9%!SfoMCZSIiy?)*Jn?b^>w8vA?t<>>Zj#T~R z1BiNVmSa%k1}7&u{snW5W(H4{+mK9f?GYcs#)k{JFb|HX@liYAl<-9p>g(qn5A9hr~`!{pvVE<>D`r0KX7 ze;V$-8KovC=mqB6=eZbL>*;`cPnfLI(wiaAA{SAppcc_#=((UpI5t4;P-@`PtM^`b z?5O`&2`TtDns|b@R}YFK$`dm?yMk%RMRaDJGPeTRx1s=C3QyaH)%w`EKG&nAh8u;_ z^4|quBJwy0Cx3w6(b&WyAg~|B5pMG`-nEd|s$fV+h*rki!B}2Z=a%+Z-m_`kh<76Q zqQ$_erUw}j8VvDZAbc8MzFdu28lq$z6ug#DYJ@savA*UWrTzOV^008pfws57R0US} zT<$6I<;xc$tbqde^5x5GNOBk%5pFcXBE;_=ru+z$S$zEmEfL*CZU+A18HO$JNsc0~ za^uDg#KF+R%u(EksOaDGBq7iNVC6z8h(kqduoSrZsS@GuG04GCEuRQG??ATwVr(}R zlk7D_nTR2wmoG1aop_*8_)N665R4MRjI8YJVx%^p=sSEdEOVnebm$%wL*!0~5Fcbm z?ew01v$axwK~a4JDTL6#VAjRQGvZRr5zL|)`2pPlajUVOVqSDoTB(%+p*sFQuXjiq zxGl{bfz=-=;tG8p*~rL8S&t(kq=0RR3@21f+HNp)J7Bsiy=qa5uOujM!Xs`Qp2@MV9h`>90I+n^4J&Odx|xt zO4DLCxFUSVp~OK}pssdc9z%8K7(M6J#5U__7rXpSx@=*=D&{hi@L}%P{Cs4u>u9WS z^J08I)T`(xPo7vszJjc&j#^0HmFD4%JlE!PFcMX=&JTPxv$NxdynVjJeKE%gPnwMo zNdRBHwM8m0FGt&z@~o=@_H8C;2AV(1)-!RZpf}f|ODX0S>CBq(81h@{zpc161V+6yEL;#x;cOnnm)dtz`81w<+ zLfcTvQV_>Fhj?d1IT)Y9WTD%F6~b1^;ROW+?dV41V3o6{F|cR}c0h1h?5Y$5Z`tWz z%uGkd#IW$&_3D?4i>}Q(!~+uId=G2Z@G`bLqBo+X_d^9kl2wn} zjBxM)U+C!RK}!^i!|c|T)HO5?3OQUZ?w&k4J0ro?a82ujzrTOo-mEY=IwQ9E+Tj z?Cse!IVU1L(UXJdw#sZ*j)ji4ib`$+hv5#G=FyUg*zQK<1`B+424dD-6|nu-C5nFX zMegj-&;|&cxcrb}U|GvyS4p@+Z%Ibs*gvM8ie4GN6A}7`%X11d9W5>Q(JQ)suLeOH zB1Q_n6xxO6(pA!y~DP`Pu;k6l_g* z%1Hgc(p7HP)>kFh;o=K<1-W_N0TTYlxU1b!+WZ`WoQ6pS(MBqdu53LP%$%z3!cZD; z=tVz=v?k!}OuC7b%iA&`Sqd#Ml$BoIrm}nDV)h|nGnwhKYXcjxnem3Dw9ehy8icYu zH`)w0ipUE6oSkhuH;D3qKYuQ=XM%S^SVu(lfpQq^UI8x%$>DztJU0JG9n@ruGG2nH z;q>DR4Tcd=%!r=^1Do9|gVsVDK@MAl|G0RLQAHeN3S(>Qdl39b4+;# zBH0&pkYdn&!-fqo;l7QJ%M&AgF!_NMPZY!-lZP)o0FfPj#b*!*Mvs{dCMG6P(Q30U zU%!6E?3Nh-u8&ngd-z$YR7i8kJM7Y=t64_i`M&n&t;ir_;PhR0D5C_xu_vO-iC{X= zMYS%foK4I5PpePSlxC>pwEM5`>;g_1?59rU_Z|{v7IDEE|9?4rjg2?=Q&aEWzh4fu z7$GFUyWOCm(21MSb|1iSQ%DJi`-WgAF##{O(-uj$cgjV^@@uBng6KJ2=)M*PgT4Z_EnC;{@;&e z?LRa&zJ($S0~YB<8E6|H(0Ye=Q~9cD|8Jc?&7R6!w&EoP2k+ix&7HNExp=~KE?3p6~igiGe;+tTiw z>Tr~Dn;(0Fw01oN1!TZLKi@IYK>!(n-v=q%9-A9#Z$nlt47ghV5>b!=M3frqP5~XG zvr4SaNcoLBI6A_5`1bWipG=}^3j}PC0PT^QXU|!yhSL>>`k>`(%FrFdKBZ-1rh(#| zNB6y1bhqfne`Nvc>ij|9gDc|*&W83tBwFa{W7&t(pNShfe+B6pBG)#vqODo3ytxU( z%L)`eRv6p^2!_b2STMmw#!t0xUoCV8B3Oz`g;Ek_wKLuBh0*Kl!9c&*i9;tT`EB|$ z2VcW?r8F|?Q}5=OFb1^>LayHtd2F;;Nvu;M1pQ}afq<^yM-5$%kY@pRJ%g|ws(}fZ zy4m$khC)pH5rOa@g?&gPr6QCFhLhXdeD83(#m?f$xtTDzCI&fmWwk=~uW{d<19BZ& z%-B;S1damJCis9PX8su&6e>^+G%9R+XNk)miZfK|tXCBnQ(&;G4;+a4Bi3;5o4#(zenXeDOa}iLjo1Hd z8L$WJM9Ko`xc3N@VMgRQo-`gJf@^*M%|NX9uLk18)^fCNVnUv9_ih@6%?j&SjgOBL zW?|`kn<8XsC=8vdu;#890x7~=L5ZVnq54@&R~rQQbnG>Z3ACH_~G6 zD0_H_LfCNF+=mbu=1-yiM6=vSS)j&>hGPIBET=8zIY@k=?N=h==)>+%^5O+AJbz$5 zNH+d>TB6~Ec7%}Ezud$PTDg*9+E3Hc&M{1FAuKkmf-rYO%%GcqPWDuI$AkMr9N9@}Q?ja0^1POh!_F zwhuDe1ANvjaP{1qZH(_CUMR})<($JS;|p1Yfzlz^8}1znTx7M=Oq;sqGu9QJH*6h! zJAM%0=g*%H4ex}5)r{=ZPzkxDCoz2v=rM|Vh)BT2ob7rN^Ig-}W-C2jRm(&~JJ zd^1jU?tFW<|K-;^NQ-XW;`ntS;FLg}Z76F-pWidUp7;vTizE`Zh_h zt76^Yk&l8M7yX4t3RH)*woq&O%59malRnRPX^U9GDHe;9pL~TLShPfZ3Q*YnW{-?1 zrOuh4<7#_NrOw`Gm%e-M>+e6eZj9D#eEr?mxZWejI>-9P$oLD9xhB!YKV|Vr80Mvy zHJg5KZ?f#(@*@xuuGMR^Oz1#F5QmJ6%;(V~T7>F;*0aPL6rNaq1$7r&v< zLI3nemjpbcu(O-K?%97$5VH3fya&{+e5Y}Bs2VpWj_@M@44wKdDlmu;RIxWe7YWav z)g})(6l1)?54tS`cA~`w)^>Dt?FWVN!&ZX4n2!y1-4ZYxL+=-fBUbqN`SEDZI63iM zfw}nVd&mk-Ie15hj=~8qjTnD}`TG`X*ui^nN#YRnVDU4a@y?w7Qt7_YcNRL+uKRI zz0%UNvZPH-nRtuk6&2sUe=P9u6W=c2+~yhoed2Mc?K)srJQ8e zUMl2ZLZQ{9mzS?a#SpU3Ma)TYa4#wiVJ&aQ8hMob0cW+KOR9;ru(x{5x61LMCmLo) z4F9M^xgt7fM@NUIfq@cOV$&#Sw}L@0HqYyx=p4g!IEK=g(L0K6$ivT{;yO2?W?(=+ zCxOwXWa3a0+}Jzp-p`2MD@jW`J3CWTQJuwT^)X11#NI-#Ln*1`7NT1+GJeo%d!{~N zBDlV`_D+#L7yM8SSmy8J#2yC({F?4lfnRgk#zqNMJQ8X-p5{v!{5a)<*3!x<95c~) zyRG18@)$csK35v|^b&Ic>S}6!4;@N5-SAk<{WKs2apVGnm4Q2kv;wgrotK2;ho^(# zw_(ja#NY&PrMd(yW8+_EDAV3o$XRmDeDKKbXb24^CawZ5oO@#thnv6Kg5dq* z1DghJ9K@>%^EHUIBss_ANbm0jvZE|`=IG`os-xp}7dsOts3;Hp1kvMRNXWef88eJB zQlG1^?h<|Z_+ZuSN?2xA7PV_$P7aar9IqJx>tBsMa%*s*JSn+va9UtjMXriE2Wf z{@zznq38ce(9b1iXA1OlR z_i)Dg5&xtJjK4ZHiy)^TfXKa|Ej0tzp!x^k9UhpSoh75BtV00u2nWYK91L;^5ElU} z9|);f6ZK?OG}P3_2yriATp}Sk`8M({yg&1>I;a>KLvbm@01I?QoDD)EL7dr!P#}`Z zK81yaElOoL0|rA>wM5;CL-@u=aOydi#4OswpBuM8#{WFesKU9^JI3!p}7nZ0lfC+eUA5FH*+Z5NgrfVc^! z!-{T9GYHaAAjnIM=p+DD8RSf(svJQ2MEv)6Ug8W59Kf*eAc@8zuo^@m1T>O*|Nf_m zi5oD2#fdF?8`4f9=K4W#aC#Ucnh__TZLFW}fzwwHzyJ?~rg>MXu4?x9eT;+y{FF{z z!E$?y-vqz1UmY3g7Tq*W0J&?Gd`^_#(V7ms}=QH zJ+QE_AgS;U29G2X8br+N!Q;n+nDd^Qo0Ebs2e^W>m2N@XzS%f@3E46o&~6F_(Evm^ zsxb710b4mwPcf*aNLOvmGI;%}aRFxm@obG79v(&uz0@3mGaSI*g8-h+N=a=ZJgO^5 zsu8o*c)_(;K=zO-NfrXOu~2+D)P%9kwsb1{`wer-J(*2lHERKJYwPG>1~8aFSUEj2 zGXhc*ltL=1R%krLObvZB8w-mZvbf3k-fur$BB2)aGf)K|}(OFS{IqUC|Q7 zp&igXssVK4?+Lm6Ff$7ad6c=Wt+KQ>HFw1uAFXxag1V(8 z+lB-zeV#fVo}JL`umU z-k}PL178_Z3790!jF~C*cCVfUlwwC zFNT&?TBkUlsq8$b!G*d+POfOzmZ_)>HRvW{%m|Ub8Fn~@#9L3f=WBx!ycH5>1nt?& zU$D-J^?_m1rr-+al?|J=CZO?seXn!!4HcQ}*CKnVvE#juK14fxNy6*rp*_{9IfeK@4TMc!Hm7V=kJC9MR%S}p&)!mpD-~eDD!W_Ujx0*+p2;0-2 zLI#mmw6Hq}UmU?1Jfv%|b2PQI-hBN^k7`hagO7-rBH{?L%hV50uZU0uEA!m42L^Si zfPW_)DgZ))f%RvWJ@A7^a1xZzzTLZh;L8vbP$al+K?pvSy8PUz@$CE?VB;`^-^JrY zi3$$0`8JXdNcA0jom5gHj3hoeKe?#W!Inbmm(PIUgUNQ+f~D z6^138*tq|CG520NxhF+Ddh})Bc?a-xLRuObmL#%8-ynMmy8k*cSeBfTaTn)>@CjbFhTVJ!Mp=E2o?_&ss^6UStX@i@K}fh z$m*XzCO9nyC-W4Qlqo_V~GFo&T)pBvyetTarV zfL6-9g&;Q2@R}CE>@LmpzabGviO7yQ;(g8h`X!4lLmU9d5L&mnb{^0b;E_1-1mCl| z_IvsO@0Fccu_ThAp&`An!^;$BA%Gr2_eH7p#Tqw3sQV;8|BsV>01p_MrKG2)Cr+jL zusvzzf`I`s^G5Q)Ss=u>qauF;?5_r~-arCc2iGF7Q?KP~T^&Q_vI*y!*()s?YIi=f zR-HHzj$>3pVN7g?$6mGH$m1rlPG7$^MavVs)=vV;u*V@)GcKY4ibsze*?0ie)vt1x48 zZLoG1PS&IZldUEY88>%x@?+dC2;ogs97PG^6DJIAdp>=O6Ah1UfzaZMNfc;}7-6}C zTr37Eae$8g#B)ff{Sy;A5^7p15);p!J1toWEg=D?YU25zH{evIO(<~@CE{9ITGcf* zCeZj$F84kpI5;skh+iCvIPwuOF@p&d<>xp)@5IYyAW&vzW|!5a{PyAeJSUpsh6aVO zZIcrdEm%&5S1HKJ8~Y9(y;K!Nw%a2bB*@dVtljMH>)Jr6_J!O`-*o!Kq@*g3=rBvy zsqd_UQ}7*H3+;>`9-cu5fkN{Jf{{IrMSwG|px;L%wwgD3=7d<#zsALBB`@T(DQ)v_O`UNu|?Q=%gyiKC2y*6!iF zf%2tqbC5D-4+#8>~f17~z~A1=QKGd>wVJT#R2YC0n; z>voa#6TuR5UjtxCsD;co8?r2hs%gMb)Y{@YqiHiLz%6+8mCV z;q|BG=5C8`#%W$hpL!ox>Vs0#{q+!7BS>rOloBPmqDmV?9lhLJkg|xw9Pr+*IXasD zl5m+JA(!k6kO3u7RY!*`q2>=xecOYX!B7%keFM|^9 zvv12V2qEyQDH2iyNXNP*k+_Y@i8FajEG<#C$WbbgTVk%c)!422>nRs|u2I1;LQ z&T!VX31HoFL1x{ z(B+UjL9;Y5GxNi4mhGS=5%D}^1rc{Zo|y`wds99-O(h~rpe5jK=1-Mg%+u0uf5xR> zv>O;6vk-R>dVto?vT)fD7lxzth(I)vm?xGRaiR?R!3K0r$QuKAak1q$ZS+EpK`DA$ zSGNt#_2j8j8=&tXF_SWd7=(t1S}T?ef}?qj7fzJj6FkfC|B?14P(810+y5_Q-Uww3 zrIM1!oGGa&k|rrblnfb*5K<8uNTosBR1poR3=x@9N})lCA~YL988g)Tx!CvnJooe5 z?^^%0{(C*^S$n(5@Av&)*Et-=aUQ2(tMgPlk7mt(eZXW=B;zyHR}tkQan7SHiH(dD zpj)pgSI9XeTbY5|T_Ci~tgMzPuI`W0k+&Cf{rXYbT7j!T#CdzG4jj0XN+brYxwkjm z0r%S9+nb_iCOC?Kd^WC@)2nF0X2!?6me0&ciisF-SB#=SI+vI@Krsr(x^DY3k5m3A zDr#fhp@GSUw>Rzka_W%10Z)X$&f9aBmsbEeeqiB6&d<4|B$@G{XG)XdRvg!?IZ6J4 zlRpkZM=QbKG8o$5+eYyU=840~=fj8r7^Uycph|_AYIvCLT81lChGNT zM@2;&*kkF|t-H#Y(&5F%#LPyQaRBBx)Y~TNo;p5~#3!BuU9%F34pBZ{xHe>MzxP)b zy?E|JO{X<_^vOGS43<78zz&`;;peDi->Lu8av;rSdGYcki>OuPA8l>==}OWa_QeuWwP0@of`SxHuPWEI*>l?yYG}kp zE}ZCH&zB+hGDCpd*4WrsgmUp+dzyUbrMNxF%JKlJrN@?%2(!Nym(L|`*hS-d&2ppL zS~Un%L5xz_OC%;oC)@%Nt^zfS-8ch-dXRGYdQ$56zGK%(;ALBKu@@~}dM7=B`rSS?Oz91pa%+uNPOq8gsuJkQD zH;QucLqmfu6;0FE8_kPROOic2DV0XVN_mJLv$-bu$@jW_ixeLnIke8zb(}~AU<^y778MoU{f`x}?Or&nC4(B|tv4gPjAwa;v^ z{JEy&bo$Tn4^VgCe7UYm_wHW2+j1_zSU_03LA>Z_ZviTVf1;To%ZM0Gvy3rHWL`Sn zN|Snyb5>$Z*Av=N3{N=?wncrp^4*G>)K`i}=z|5MB@v}eLdvKi?p9m$hRsF+@2Kt$ zjD{u$NO%Qm7Bf{5wb)b?s zIN5y?nEL>FTEtU#9=pI1KTcUc=y)ASpBSvJK9h|+AzV2T-PWx~kCNwgJ3^&4a`b57 za3%4eGel8fe!^d8rRZk4krA9Ty~3AzT_pfnW4utAuDw0{ z^k#n5BXm$c>fYxP8F!!~OIuXPoM4;2JZ$QiJ$+a1%Q1d%-kWP&9=4OFWP)e zm-L8qA{yciPux3yW$}<9?*}~Feq8j&Yo5bs3d>4jrr{Y6tZ;or#aM8{kQBa$xmf|F z!!RkLDq+y|Mg8X4rlz+r3TN_SFT%vb<2Q9eopO-gP^9IKy|h|UZY+@N(5*|)p5CJA zAZTG>u#LwlmEtSlY8vbxKf|yE|Y`E>L>TX)OMaxqay+z9*ob z&&N7YZ@%d|XXiBT$F98}Y)4U%`J#*K0)q0)tpEGH0O~_`t?VK&+rJMTGMzuaqnn!> zIEqjkWZk=`2bGDaWwE1UdkBaRjX$j(<)T51iI1g`NtEa0Uju}qEOP<` zrqr`%+;QU5>@PcFb^KJzz;^*iZVeeTX4EKwUx_}5*h&42_0G*zG_ZSD87wOgj}qk4 zpAP+g+oQ=cDF74sDib2*rKFFLkVMqgE%Q?2M|Ln;X<>g-A5vcm{ttC3t7h;kgH&X)Ti^(`d6PF|xyh1^( z9Xh7%+q<_5;26#PeBbl8(;Av(zB+m@xMH_>@hjt2GpzW8g8+LdxucNv2a)d2EVvp< z)|f>zSJxn3J_u?pPhR)OR-0jo18-S?6NpzXBXezAV-N!rwJ`UxDJMPx(~H72TV~MF z!Twym7CN2#O{o2F851Z3v!+n1qehNIfK;)ZvO`aAq}%rmk=Oen%M%oz9uU4^Wo>O% zUszQ|QngKzowUP}B^SCmcQ48XHVhOeQkIJpNK*q#BXcbG6vVjT9vOVu=WWw!R$X1) zu7+hxmgE5rXv?<=z0u}vfh>LYy!#;6>u|ir??)^u@S^A^TGr#bCWs;)7ktc3hH^#I zPiZ4~1-g}qWyud(nFIC;JE{5Cw#dT%Kx=ylILBes=+WiJntu)gBI>1qj5GXM)qj8k zv;-DGl}Xz!hGywSGYE%0b2I%#H7P>7&~fKId^nZ7N>}0mSM728rJ!KG;dvQ8#uWHU zoKm&hfA9pe@s|@5Q)RTZ1^5w7^){OOpJK28>;1@-TeSYr>2e zog2tJ8ZUG+DkcnZc6Z7l`?uJ0dkSp$d6UDNmu}MUD4k=h;}@~Qs?HU6!3SCMMerfp z+~%(AvM7<}B2-lK1UA>6=6-@DmnG^!mM7_2%{G1o!49Q6P(eL`yBpU;1X)iF6Q&M5KW29=q`*Tv zQ&YE%->Mvu5tB-%go?Mv>w$T8Ba~|G!4bD(>#kzFa!URq?~>exuX^j;mS1hR{WzgL zfNQZU#`wc0C4c|aPQ0u^Bl81;$LRm4q+nZ`riNCfFACVxam(5;FVlWOs#2BlxLg_- z8V*8@$ouCv4E%;j$33uE&9sjs_T%*RzgEtG4Pc^YH}$vF^6*wjr!IcHiTkKn9rA%= z-*(qLsdT?(zEf#>`9^m7<5{V&|NHkXKEt+<3O+HS>V7tnLHk|;6Oclb z!aLqup$FFrt0{FMy?CX#U5S8mqO|3T+}lopESPSHY6)ffelctc+$WK+kY?l85F!KD zVfw1W4;sGe{C*N%TS3;YzIQ2l^k%@siSo>Jjb)AllJDRzB8ad9iinME2i99{0;s%$ zGDDOB{5FYAxiwSTf_235Th^>!gWaLdTen~(PBzJOf04MXNt$Ueih$a2x16(bVGqhj{GIb%FPv>9sj(js*CV{|%@m_UU>O;w56xJA6zy?)!Yob#X&8MF8D};^LlUJt0Dizt zgr4#f^nFLs$?+HAyYGX_YWm1KaPNOpoJTsS18|7S<<^a+&zcYufS@hl(4QTu68>ut z#)51G`s7*dK-o#>`95jpQLi{ z`TjO9KPnZ{bzS$-np;gzq2y0hm(;^0Rfg#z#JOm;C0Ki4%>Qhj41e zF;rqRVfK4OUFn0bVrJQ`07uexG}F5L1cxcprtMjfY!}$iY0muxpS8bXzs~Lx@5VJN zRv7XgK0!e_E?+(XM>m6+%z3*KF!az7>*;Oy1EZXRcj#*B7k%B+Qwl|qImcFj1Pmw2 zT%7wd=k8ro8gChyCyyT^$Lq_lHL-IdAN;rEVhZOSJiV5-jvq&sX0S7wVqPXNF>wxa zCi;4MU1ahJV$=DIbi&L*k+oIGQTQ-nqAC;;-rgrr{i zwf^Z&@E`@n#mla9RGNV&>4zgokuox-(9Q^K^TlctJv}s?r?@PNilDp$>29>a6l7#H z<|ca3!p-DeTFjd_17ri2g|Zb}t;@ERv~Mj(dvL6D%h&0;CR-OIed9=C>#AYU0y=y$|*@^rrwHH~O(A?SqO zKgx^vVIb;gg0(@P_FTzT)DZrQV&UTQ!U%;G8 z=apY{LGC3qSP3Z(L)H#l&~WATy*Cj9Tjgg+UGPg%@*dsk!rY2u|D7CubMYT|gBIN* zbd;08H*y3l(@4jlJu*&RQ?rNBpy{Q(1dOrdgv<3uGWX_fbr)y@lX4H8rSdDl{dZzS z26nLX_RAN*t}~xYw|%5IuO?)}1nrO81LRgbSigPy^#C_rt^t&y)P*6QqUYDAG~?ok z6%=>Y#ML#vnH6Cn7kX*ef7cKheY*K2IT7#=R9K3JOqkUGJKUM@At`bC?LIFTmX-J( z&8fnh^78H45~K}c@x%uhv)hG*-M39THhgaPr;Dgj4)$?G$Bku5>Dj(6E}u892??6+ z_vY2BcE*k#a$5r*v4Nq$ton>Tm-y1!G{~^aER_(I5gHvdHyz+b>qZ_sQITKrBl6UO z4W&nGNKOJds4EBw3$y2(FciOw0#7n*FynBE!o>=1r^`+pY_x3c&Ef8g1ZIz1?(`D9t2&VAO#AGi~a5odbN2&^{)Y) z2kczVGH5($3qZDXizG1~y_K01x<>ytV4@YkJV zu}OdM?~IL2;! zZbxEk9srJkY&2gu3_wl>T~0+AIos7WrLax_fKs)?c3aP5AC?j8X96z2r9$qF0OlE{ zZO@XZu}tmO-aq@rxHmQz`k-7e*)xH-l+Z@h~)So5K8CnO`+p8Ch`jhb#@GCaadrT+~sdK3{zLvIk^5soC=^jsrT6;v{_0LOkr(6JY{;fOr)%fW0 zb;i@R!^@`ZhpW>|5)uH7w7 z-cU4W*hO*|WHb}D>+emXwiO`FG_(-NMvNHqga(1fD|qy1X~U(3SAr~leuB?Tuc(hf zeFq(Ocomch`%n zs*(9tMPr;cY;2n6_fSPyIq>*#`%@0r+x_bLwNLkp8!p00^q#n7B-5Xp)cVb{vYJM! z+#7LLvhkI#&{yv1GUy;Bi68jSh@6SErQ)0p0}fyTPe0P^-pCu2YZ!8uN~eVw{0z>i zin?&2JB{B|IA)buhrPLZEhRt}iOcg94R+WwB|3IP?d(%87uXy>b*c@O@&xy$`HJ;s zQox&IF>R!b6F@Dftir8aVS(GVCsMyf4L;p=t)8)L#rfZy{k;=C295k4_g$rvVeX9! zsqeP?{P=5QI*1#N7G9{0U|BY(^(#fMiZW)V2`keMt`AVO;Gg?7ZAL2ERSI@Fzl|D8XdH_&z)Yk+2cC)XJ| zm|O5mf7DU~Bn2 zUEx(@SZMJxO{W{TlKJv1oSd{M)zkAqhP|i%&QznR`&09IRy2Kl~1Nks7( zNjCyAd+)$-kTf0w2wiv`Dm%Q$0xoO*mxOIs`V3YA3GBuD9`lN=$UPJ+6)>o6|N2Yz z^|6@i?erE?F*~trg<)YV+#_#mD;bvBoUoXGEg^1gdBCTiGjiU%>oMT_n8$x3sbwll z%q-y+>F}jPy8XQ7SxAfOfml0Kt#un3t$&iV7?q6k)2t4)S#Ki747oFJ-gDxsJW1(I z;FhxPCq9o}wAi)JZ{>5;$&O9Y`VXoK@_D_IYR zDo#x2O9B|G0n5i2SG zy0q29zz)oHb#NPU)rf zXJqF0FIlr=Oayg(!lW&Yv@hN{RYCL{fWBrx6#(=F!hYyPyUv|Y;l%{Ii!qE27pZ%f zE;@91OX$29W|~<7>L#;4Q{c-DpFc-awSC7&fz0|lsu9e_fb{O+WFMR$bgS0$<{f~* z#X3hTKlK>h5&+Z%ETkGfeNtl94A@g~(y`}@pKHe*ipf}xv}YfuVw%W?b#=zvBD+kV zn2g!OiBm9VS1GaFYPQR4TS2xd8s(%kKs$>;4#_rNxT7 z#i;P72umSG3bitA`V6$azAaoV4&vFN+1s^e&qKtxrA6k})`rdBi*IDXU4faeK=v}T z7m4_P4@*FaLpCmFHO~pG(cpJw3i64Eo$1~JnMQS3x>U;r=d86OS$T`CoRY{8oawtT z+r!uV#nYnCEFsDxCp^YV!YoX^uuTyUf_6cCbjE_j#zFCZM6n@W1~tAam==F8k{mxi z9~SWbFztg!jtmx!DT^g2=?%b@z-B+qdYC-QU^{ex>y|A+$VTz)!yUgb>s3+UY$wMWuI9z(gc;^2fRUvf-o?ak%5bS2!P9ejbotyD~PM&UNo5hjMR=A)PQZa;P61Z!zKw{G29EYQNyCVZ}0)Y$)5bK7cVHCoR$`!nAROWVB6 zErO<`4pA_lwAAf9;~o!IjnYHnv^|O?919&RK0 z>vjuCy0>YH*TxskLvjJ&H7v*Lo7&j4 z=dheSgS2Mva4X7>3Rf|XKwsWgTE#(3=JWu)zs+ac5{+T%(!~tQTr;y;+o1ge^WT$J zX0sC7wnls>$Q((Yb4!|q3wn)WHUWvJA~ngjN&Uq~?>6T6#m{al|ItMcFKH#hy`^PH z;qWEtMSn>UB#2P~paHBu5kx;(5e`8iIzV`gTQwh(*fvrM}OMZ+%Rt;7(p+C4%q_o6fBckZ5jR8W#^`zk9d19Q=XPe81r^0`k3Cl}zLe^W^XsxGyh zJ-bV{T)}1FY$BBx)ft`o{}M^lww-z09~4uK5BA!IQy zD{bQe$5sD)6}ho`QMXqoSf6jL=Y;@k;i`hG#_+GK(xCDm@02p123j{NdV--Sp^!pw zR}OBOJGV@ZMiM`h+?gL%IyxTg(wb)k`yL#Z3SCdvyfIc|qSG&oY;S_jJ5jUEdZ;pJ zkUhFp;36?{1R~b!R2v~P$;=#)^Drp1r38N@c{+|H;1ZvbR2CW{89r@3t&0Rv%GGp( z^SpGxsDtCytE^#ynMOsySYA%f3Bn`|qd9tg`F`)o1&%9M($;1hXudaQdaniFyE3Tq{J=$VV^7G8+2`wPcepSAquAf|6#FbtyPYIm)X{@1$MIvS zu=GI)k4|#)Wrp`9oM7jf%6f<`{sv^BD654Jcd^+h}Ov|-(-QJ!Z3EF}ZKq?PgtdQyVr!VY7 zbu?_`$aFRzfCl@r=~vj8`0W4mt=^te`zG#?hS(I|nczVXQQ*PQXiDWZBo9T}0}&O} zX<`Sz^u#F>Z54L-1&_V*V_9f=i-jeZ#=VcbBJMC?^)k_N`ge_jE z{9dA0r)U(*18!B+&$hPqA1!XMAxwxza7z9iv>i2HDgPNbY9f{YOL^);kkZtjCTPy-GiL0BtrbcWbZJAS<>pvgij5dNSM60R z|4R>d(rw4w1rlslg-PkKwV^nZ==(+^|LLx!rQz3_n9FEaIyJCF@(&Ga^!!iz)e(N+ zt=^uhkhEDF#PvV%!m|CzWLZt=yvS*<|DRIn*u$M{I^?>X&`_CsvTM(wEj12wpW=~@ z+E9oTpr}d4i$mkI72%+of4z5ynv@;&deIyPnuvd~ur4=pw=fA*(+@^58!RmkoTwRD8lVA%Ngt9kcy@u#$fvfMez zfD@kqIlY8~*Tq@>B78j@&n!m8qo!f43gOW5YiTuo8JK1%x z;o;~}ZXg3XtXUy&x9 zwD0XRE&S3PP(z4F?}7 zB^*#$T9=~3?9fegN1&VdK-`nw$B>7I_w0G|{HQ^yPpW#-!-HESa92wGbA6o0h@Y?u??7(XY z|G!d-?3 z>eEnL)qPj@htufrIqAxkzlnOPm?L?6i(OPehcvDx?oEw@P~<%1;f~h`V}uy3&naPS z3Z8FiWyN5>%*RF;8MCmj6z4-P=?A^(Kcg5o1|_;f9IN}Cf6sHL<^9@wUPi;{dU#DU zOG}5domXGly}NaF^YiHFctDmZCMKOJrU|eDE(bm&t(8Uh3MW~j&62vXxnEm5O%|X0 zdv`J3vPQ^>i6QqkYhZ8DkJ3k2@f=WL3RWUSaUV9PcCw%7GUqFnS^F_`5ZYw~m0e%C z=E)&Y#THshvb$ri769TKO-3i|5N(A7Vzdp&G7U%tSp}z^Od{_spjoad=`Zk(m%!5} zdZMzOb9$~Ps6uz0oUYH&4ka;0U;I=nbW`9^*9F&%5?V%FtMPm>YK4z!>F?q8>!(!`Gt|C;(qXku1vo7n5Q(3Xp$)uiL5RY!c^E#fFrkO_w8KUypsLe z;Gfz>sohpFHZyVx9m*7v72iRx8hhK7r#j7_Gv`sHy2GZ|YtG2on3^iodqtknFd;nC zbNB3Fs%W>$^tXa9*?#LQ^y&ZEfhQ@58bO)?>$DNJ1^ z7kV_xN>}H?7hP2ijSMORapBokAgtDyxm*2sf@@=HMVCYJgcREt8Ob4>}o{nDlU#mo2h2 zZ5#R|J13_e=My3K0BI417?g^%6JqF%$>@!jH)Q@Mj2edK)s4~Sc^o-ujdUh-i1iLM z2KZY_fVPPFwIh!)HX)psQPftD2YPC6P~{yTUseb`2TNhI#Qw=(f;|@(0ErbVw8;Qgj!h zghTAjkZIbG_>1onl-|YtVU*Ai>TpE{zP!%n;URMq#rilAsOhkGFbtLn(lC^r1&{`SbG`Ldbco1gFLr>>@G)=Emsba4Bm$YOtKWnVjm$NM(# zo37Zq+lqlo7#LM+ukk9ny5wtp}3qI@m#&*5?#skM5kW@_a zBq`>1isCF=I(NfB;ZW>Y)QPb)nc=HqYroo-HQ$F03AsEZ^)zLI*knD*p(09{2T}5A zIC)OP3YU78ox9tp85z%K)LC;0O^XJ5R=6g^wExZSX25Bg%^LhbA# zCJIOyRdFT_O9PqMN7)Z`rTXbII1n=pC*e`Gq|!G-jgW5PBXnl#Dp%(tLR`~e(mW#RZkmKuX^AsjER*LdNd`k|w*!7ERoLFMQs14oa zw(ujl6W}*)5uwFyO%CRT<@q}pdU4qXH#iEN1B%KM1EXIzMOZ*KZ6th;)(8>N~xA>v8lVJc5_ImlciQ#+cU-46V`tvV}UTKlDjNV=UuC&2mZ0`r`M3kZO2!v11@Kt+e#2 z-d26?$MQN=miu~j(M36FiO6p%dvc}=7uOTf(XxrRSqZ0e z?ArAH97r)ua`6g4Yx?;2sRQwMw6L3OSk_5x!LZqifzz8}gOv_C@>Ci3LIjIf$a&ln zkf*ml^MMwHJLLcMy=ppGKY5YT;R5Kil?1~R4UakW5{s9^j<@8zEljBir*OQN_!9V1#4l0Jy?PQfA?|YqP8YR> zvE3jz;}R!ro+RbmProkg=lQ|Ie@;dW&HKF3ah_7wyOR(1kjdC4?+W^ikG^PWiH1U{ z=IJ@b(=vce#3t-uo&k?Ha^q>Pr+64*5g(HS=dcQb>h?AMEJ^XaL2}vkB@!_LZxjcC zK<>LR6eI%aAWHO{|M?pgX@ptqm^3Hv%u||;n|131XYfda+rf@Qi(f~l@_IPtO z#7G(;EZANx#Fx7M11@TbtDa~P!FMMlXu``#$aNm5?X)(%n~!r}_L%3}rZPNKj~E^0 zJ_tOFLrcc6447FU*oY;Vj1`04+#^Cy$MWkN+cR0LXU9MpW|hJd9_xwc+dlrqOE5ow z>9kuO3yj1%1z4Tvy%rD^4M?7nSZ37Y+O8mXNgP;Zk5?H2V}^Pd+*37h`oi|CT-?S6 z;gP(|o5Q*83`H#bTLT}s?**~ugV+KL&TjAV^hFgIEMp4cR;$7*9RdgS+zhp=yPvK~ z{b8g{M!PY5!Mpi=ee@a%c$OBiX8P8vKdOZUR{ePY*@1)1q390CBjP3VB1Ba8qNRol zrCi_dsR_)^>dK$njRfSRUB!kk@18O7P(R~BZBagpjLE-upuuAoTpbMzdi(b63d=*v zuEzh|Xen{nsE4jQj#$_SMR$FiaX_j0kqA|0qn451YtpvO(UtN^%vY+Z#oZK5 z*Nf`vId+XmfsdQTcHfo1_Ijg1-Dco79;7|srL6rr=>|vz7O|Z14l+~{KWuQgv&n*M z)4!Bu+cB3*TXQP?W5cq}JU$gvk03*XGkefKvFl82!)ELS`xqPFcP@U&D`jyGBA0cM zY4f`JoG2f+i+-Mv@Ayd8ZWYu5ZCBNfDcCjyG} z0JaJb&z){hu>IT1HcXe@CX@!x9}J)1Kq_Llv(w8oY2-vXK)iT7 zD+%~MS>E#);reM2+N0->KQG;Q?62@;ti%reY85?|j0U)u2k*X*N+2;m^#b+XU z^Lb1d7Nlla%3p(q*OTrNtd?zV?U>nE1d>cP>Skh++fb(Mqi5Ffn0wPW;2!<6scLFx zZhx!^US^m&L^CI+VON+{tOY(H@fM#gY=$)eJ|L+Q`_qXFBUq-3I_)N>;~+c7M3)Pn z=&N0W0@L3pn#%eBQ!luUq_8HD$8!pV&gk5wpu9(qs$s`C_B(Nl4`Qe-#!uUyx`%{{l9=fr&5%NPfxkYXwNzdLv+nfn>Mw%iD0mE z=gxq?wpo*a)s>fKK6w(3v^Fj_NbU~dn;X2ZWD>O;uIGR0(56DrDhR&B$|`Jf^UnjY zTrKjhyKSW-7H<3jZ&qMAXPf_1b?^w(wWIJtZyCW=;*1P-E5n?hlfI|n;b8{1Jde3NzJnkoJeA zz82s%%CT^E@~Dx{ZYfwFTs+~F%M@JP-s%Z!H}%8!$|9(owCNAzrMwb|-=s+E8^K*o zoG76Q7r_E(WM+6(;B)(;!ondR(CN%;oS(2z;7xuhTYd)|C0C1*LQ5N)zt0`1>5B#b zq9sc#Uif|INE9a69^*;LxxRJyu&uh3H8=5YY*oE|^QH%7=m<9S0gJ8RaZ!0o?=EgA zuBxb*N=Jo%wSKf&5({r}p|^4EK~&>Ow2IM_KLRW*{6Ys<QQtbBWoKDYBWc`w)_ElsN&osbj03IjGd(iOLZ91>H} z1Rwx1su(c?Y80*J{NQ@xy_?bD&ow)SM_P%G5maElX4*0aQKV0vAvm!zXDQVrVFMSm zY-)HZu`7W?Am~dRSj5aU=`F9g_!QOw-0%YoT45MIgV#h_ivrZE8g*XC)e*U{0X7>{ zb~)$J^Klp+F6S5lfh_2$wWKY9;|_ZU@lq0Xhd4LfUXBfp7+MSk3|*KyH-fG0H$e@B zzd6x;H`qeO`}fUh8~d~OLuW{!NDfLtX{J7Q=N{pG*he9Kvf|eF;Mo*-13=vw1Q2HQ z6z;r!*P@ey+bSTU6p<;F@Rm^0*XKkUrho#aq2zc`r1Ckq%E8sTsZLeXT<2$hPTHdE z;KAFP8f&tz7i+9{LZAjXCnn}hSJ&&x^1x$I4yTO^wOEwSi_}Dt2-21KOH|SG_1;@@zRadIZn5A z`3n-B#TYn5aSK}YpStG3*NJkSKWS0_(2(Ds;=~TsOUKVc z%Yi%FE^3CLVk1XpR#sb{FM%k!Z--8u?v$1F<4=M&!^kH(zh$5v(HRP)KnbG$kxP;$}Ai#^8B{;Y;S z!ofQSN28y(j+6!|>q(|-Ay!WwWvZULoKxoc=Xt5^GsM^4useN>&kIU;qwy5t0`=q1vW*kxi{72IbYh-MEkU+xxPK1BzGBeX70aNgKL{aMxq&X(h``xFf+ZF&+QsYEOqA{W0Rmn5y;*KZ<)-y=!NxOmFD7*%cTK0Yx1DU~wo z!2by4W(N-CnlzmQQy7SCHnRB_Tv`N+aKQnWN8=wm#~nO*Vp@^EItz)JRlJ#~+{L}27BhVwJ_$!fpf`Ob!sC*>Dl-&Bf2kw8*Gw}vKYvs0ZuSx`J~qxlh*487j8@hZz4~G-TOi(SFAfee z(v82|s0rNe+wP_K?(HcLOesv2ht^o$sfBoBKiQ|Q^LqVD3(%%<>U)hrv=FrUa^DZ9 z4jry?Zd+q^PEYwi70X(UgplL*0DK6CA~TVUWfNv>W3F?TF21d(QeagrHI&fj3zhWCd?6n3Xrps#DFG^EA}AM2#Z0iV;VO*5Be%hz|{Fu#`@vd@K6 zCH3OX8$SlCVK&+H)0Gp!w~!K7jV{ZMXs)y7^i6ub@JVi4T(6plv)0v6+3cmc)q*P< zrkI-_U~*_weorv^7WBdTV>uFkA zxZ_0=sJ{Psi|oo;IM%?RAYFP!5;_~e#eV>}1&nuQ9%Tx90cgd@h8>XMP>aXTyL8rO z0jXSCE40SgylR}hYmKY{k5Z&MVeo=(iMJhuxGU+VtLy5@watymZwh0Nud2~l!C_e# z=rjHe_}k)oLvCoZSeWB0t1i46SqIBT)xA*n4Rl_DmZ$ch>+6U|>$akkbJ|j91L=tc z<+OA-ZEGbt2lQmhcn29s5c<0fsx$(yi5kmQP#}+R;O!~enfVg5 zJe2Gp^f($CgQGNE*T-IHo=D|KpXy5=rT%ahk5ENJV;>!iRLZSeNSHs>m0F!ywQzSm zcfEzM_yq-=y?i{e{8n!6e!d^b5yY+4?%pmNHVF4GkNJDV$S3yoEmI0!09iz1gm1I} zh^q#ALP8<^0#_wK$-seQ^!I(@Y@It!?SZ$55ZsA9xBMBjwWBbUsGQX-QY;;~;2?m`r*JVPLVZN1$g9mz2{F=#{x%w- z9vB?5>r1#*XSK4LDs^gJs;|>(S$jbbxHh+4}>j0KMcM!g{^fB zDGbSFG@Zg^V+r?G`U^CmJP;XqLTFtiY}qgijh&$s8V@st^uec1LkEa zCx^|cc{9!>mZNxY3Ax3lALGV)%Tu%DCpG_EuQKzX4p1`SGLyzKV&cJd|24$OM)I_n zr{|}1B{GU#l*AixxY4xZ;~xS@_K|WZ|NJr&F*s{_Y0UzM!u0IyI1ghGc?pwB=Pio6 z;1$bf7OR5=)(zas=Zo9bDmZ%8!f!kD%;qdqcc`>7HqHP1-(G_}VoW#rq)Q@z#OUtXCGs+@jtWXb?2!B7Rj!huG%DcR})V3;K=nhoLc4 zSz8%bud;3a9%dsCWh}|Q!I#4oLQ1vXo6#iEm|s|3I>-8O;FyeK#|Q*1^)*|$9))HS z4t(q}i89(zd-YWdCvR6L&}@I5HE+9Dsu+1a?U_?k zDu7-jT`!r075FGMLIM5|&LJVwv;8_oH%|tfnEloXh*_~^lyXJB$ppNLP)Z}pVF|EySEN|nBP?(Lxr zPIS!Z7Dm|4HfVc`ad}q^#?EQ3-Aa*!94eU1R9;=Zo6d$WR(NJ!4;YzIjqRx5#5#4p z-dMVl@KvtX?{Dx0kY?ZJQF7orbM^HYi^Y~eD7ujrI==(MK1iL&I}j|0#b?aI&m&C` zJqz@ZZit#C5g|xRwm)l3IQ-ve;zRQLWbKn-_->D4=J3U7t;EzH9Vr0cQo4SeaF5{~ zFkno514ZoIYg*#^f@9B{}@?*abQ3o`pdnlL4ZT^wG=bl zGP4^rPo)}lANT{`>Q!D{?)^O~e*RzZ5r!*pp7{rS8c=*UmV+H|wJSQG{S?yO=t{`1 zyx-)8gf6=G>qS_wjI&@+>@U1Vd~*CSaC{PP#!QKLif#eRtJ)9g^8Bf zPfn3Z@1u5MUvVJZ!}edFtc24z5cd2q3$kK>dFSoC__VnJ`|*- zMdhW=tx~}Gk~voCtY1|ufftV5Y9XT3toq1EmD+`8*(#$(T};!u)Z-3ansAJx1P~!2 zTXTfZiF07hVmIa6vTKKE6~#u8ev`Ik@tuT#82yFV#z=PrxT;4Pf$<%GIDj*1 z;Iu(lXw8`;hYX00lnyU$8%9W#>dBv)%?}>U`^cXUxtl-O_!+SFB3e-jkcyWtJsE7f zS2@(R3g%0iyiDMKMUJBO9l(S()wB~98zNy6>zn}Sm6R$i5B<c+ogsfJrMT;#2H-l1uT^^s43tOpQyIvqB=^H z)T3GJ6I5?tc`Z`nhlAx4siXmr zkTDGO5>{OQ0CK>wnG|sCJ6_WsH%^#NOE5&SPTf2lwio|iQB8pFQOjgt&4Q3=)Wj%J zWn%&P;lcR#l3^?vU|(zLn39(vslNo@3!zSa6TKSUP&qQrZAD8%e8t!}KZ@7!3d|}x zxd<8(N-hVCw!PaW(Ad6FJ)zZ<$-E!SXUQNcC`Tda_yej^1*Rl}_A6w|TO6;t=yF=x z5t-^C6Wc3z;ihy0wq-Zl?9Ng>bOWyuv$NfF+k)~a3FNA9?V2?UBQ*G}5IKyXd5YhP zDyA#1Q_cg$XIJ-MpTlBUNb#6?g)X|@Out4#FO%Fgy}CqEeb@o(NWUJ*=rpQ}>>8lc zcDw{+V*|NEsw5rd>rLNRA{(I(m8Ik<=gSMpI89hvT52&uBYrc$jEXSri(ZSSQV+d;joMGQt*}@f$YarG zjGG_A+i!<5fe%2_)IImPBY$btcf<^O9P11oF~5miKaX|JHb0p};0I9M44`4SJf@jOK=hjsift-QjPwBh zpT3ciZ%KVYYO~VXNwfhW-x$FSt{Kw&oRUK5G;_U^04r zs@6!}30~ZBhI@pKFlSnQ+!@BSUOl@yhF2DSy^Nt%u^JTbLqVmVu?ZnWh(L7sVf2h1 zaaIX}y`)Y=b1)m+2ayV|(WsL~R+04GoO@+xMx)n)CLp9X`<}$LqG=#Kc^XCQLckkW zZwI{dT^dOF!$#10!Q&jeya&K)C^!sOe6sx>QdNJ@wYQJI%9Wni)-pMY6e>8E0LLgFOig z46N5Rlzcq7q$GKD{9C5S%*;F9U*CR!)%u#o+(vubhVLzBD`vlcc9l`~_T&JI4hOek z?OxFI(X5u1NifpVA&89YzS9Bt&Rk*xmq&AvU6`!b z5ZA6_M z%=DegqYhMW^ZBqf!;WK^H9E0Iis_JzgpC|r zu{&1!KkY8JVZM<1G^hy8rNg|o3e9EZlkb+Aq)gk;Fy~z*c8X%bC;)B-!ClnY^lWV+ zh=f#D9S~j!i3O0Q=*NQc>R>3*1Po^pG~h$qKMZ9?$%~4L+kDj|vJ6WQflj(%hiViZ zMMl5^qyg(>+7}Z#d!!7rTitC?$`jZR3teoM^r2cQ2RWk0@`Zwi$I4Eve9Al%Kd(n^ zABa~-G11!+O%cHjb9rqsDx-J;!J!>qxa=jOjl-WOha#d8XBnZF0H;`l0)Sa$5AX~b zs9IPOVi8@+VVX#}l;CX;kwOTLbqPor6_7AN^?-q8V$MN0=<}MQgE71rOEw&0?mk^9 zL0w*Z!{#%sS}Mz$99MkG+%xj{ILevr-Yq`Kn`BPKS8@m;q z3=Su@iFq;bj+Qr}Ws@#lssXoFo;AWqDZ{k4LuHT13E6RL3x1fGZ9JjXP-@$BCTn36 zGzk@O)XX+0Qrh?E5mx-*?%fLG{zH$@dy9^QK2L(z_A%n%^g$p6d_?)R`d=FOf(tFG6eT|Z~$fw`oSRQI&4|0!A0jqONs^t+ z_$@C=bN(`?_m|5NdAN5XU^?c`-;Pc!Ct7CCqZ*UYgqsafJs0kouSuOPs}^De-`gJX zmFY!C%Y2AGv1lVWZkuUi($PW6%KCTrgkV@bX9HadShx-ZR* zQgPjO-$-q%Tr`d*VYpqox7{0xs%y)kZ+4YfcHQ;tN3kbo zqn!@w(6`aahr({3(R$3VjPT{-$?ods9-ea6sN7|9v!Po5@HemPSoYRa;QBOX7AMXv zX>xe(psd+v>`gc_Xv=89V{-FERC|1`zP>)%=BS*ktQe4ss7!C)sZ%v=v;*oez;HA2 z6XPMbkdO)c7s_GP;!z=?#Tot$&Mb`pAp2&sbn5n|vgQMZ|5r$5Y4i)chzWr(iZ}HZ zhZ9Da^=hn}rZ(`#ui)_p%OC=zucuOL86YADZxg~N32CYT>5V9WH*8n}5|-V_CqvY^ z7)ptVM>HSO&|&_xX>AD1qOvAsNra;{i~?Ad*u9J+`PswoU%$=0;QtvNRrN_K&vF;Vdr zC4R_vu&wCO&we{RvaqhFt;1H(hsUY*e7sPUBjq(U(+JJWpI%P-Tg}zfZTLU+ysm7r?X>ij5oPMl zC$!F;=<98#dOz<>SeTXPE8#M#LvYmj$=jfm6!FgV>c-U$TLxePhQ!hjDWV_bQ9dU? zjI~jhl6z#qm+a^qb-ka)#v?wFTV9->Zz}pjxK|%)V_%Xa)vqYXfm$qAWlugrnWPTE zbY`Zscuk^vYO9bAbm_H!|9qIo6)Bs%{`#vef>8feP9iY9spg z8M`jRW^&Ve_vUV3C^EWj(b1^U;bc&1P!;2ZrDkpweepQ1L1ODVKb~jjg(wLpCe=k1 zAI+`Equog1U4U?80kUN2PiZd53Q7bHp`gzI!qH<4!0X118+<6}D^th?(S4BmGU!dx z5s?*s{|+nA4L0BC27U;l;tmWAJ^A=)ck=Vi07MCW@|**c2qt zZCPFj5Vp_m$AH0u4bg=A@hy2&IG2YIMr9#Zc@G?NCHOi5H0-!&1GTf z$dJA0$DK6<^-IU8{KeQw=xCw{VdZ37(XX)TWD0$^y17+ws3nAFP~oo!!=-i9V)i^pk(ReKLYAtTQ37=#j)egr2=vk)TwDC#c?bNEAg%-fC*zrN^m-o!CzyQfa`YbHhAamgzutR z*j5?Jf)&rMjFONhjst%YZKKk!v*M=$oK$wre%R3oCgFA)XjOvmJ)%?0%*{1vG|Rz= zZ1xix1O?P^fH@AfSW5E0TAkZefqavt5z;w-d+1Ie9^MF$%U0Qegictwrn3y{oj6xo#tLDZBo+dIq&rA zP_8cpW1heQB4nWO1G?Y?GgggnPTc_f96aRX|4<`3=)Ake)w9gL_VK}ZNB_q>5n&Tg zO3A)n(`|dTv2~?|iw6U?SorHrvB+(8toaI?6m!?kGbNJ67M(JS4X)8hxHe&mVb%hN zz#I2_D7cSzt+%D9R!>^%i##|wPy6HMrb)8Zhr{kX2>PBlq;l;*_wmY~^*I#qJMrtb zQaDw*B8?c->^uPuOu)Gm>mfIY-~t@a@VtA&Yl!C7P5l_h5EI)V^Xrk%2z0#4?`c+6 zjK@^QQjR!B56qeo%*4m*7MU>b<^u*9mGv;)KE9z8i{aSOJ$_=4=5Up|)zMamTeU@D z{QsI}*y|Xqcl1EJ6x%{q+n?}_qACVJgrx1o3k4v#;luGR-yNeIpzn5#ga*4o)VsNv`h^5{AsUb{C#e1Fy( zxhD7S*)#a@82$QfDYStMRa-~=rMkejyTh`DDdk5qdnmj2X)GOVY#Y4n?pcmoaA=rf z&&LSsDWo$<*`7}aloC?c(KUjzAdj)q+H-8O`%!R^&@1n_><2`J~EI5_K9&`O|Y08^cJ%Zq5SLSnTM1R{!- zRQfAb<_0w-xc~A4d=qQey6h0}PNtFlG?d|-W%I*__zQu(=ABT{+b#kYbGW2(0S(d~ z_R4Z8u(_}tRH2-l4qi9-^XIzKFe)1cYA_<}ghXR7k>Bz)$J2pjrh;)N8B4N$DdzUy zj6Qe)RaFkX0kSKF;ll%=iq!q@QZJxG=`LZ3UnO|jYta<*S*wLHlE(J)wZ|jD=RHKuxt0X7`@a_enRKv0lx(H#QoplYD z8AD`gA>R&9n4CR`mLfzS1q`5@?7`$MM=1-sGLi!OnUtJ-l3_q0ctE|#l1kxf&MRWj zZMR_1Nnv5%ix<-Eh`l6qAUE-j0t@Ndy}L!6?8wGf`N!J;Epvefpk5fTewbuGjlnd&q&-zM&JS18|4(6O0+w^$_Wi49WKSw<)}m-Zb|RNZ z2^Er(C0mRv$r2$=p^dbVwT)CL+t^x&QiN1?V{1Y7YK$7&^Eu7D?{Pox`W*Lt+|SH3 zx|ZMn{GI3b{4NzSY$5>;!g%FnuU?Iz3#XP(+@An`v8>{nHVh!VZOS2GIh3B?e}T62 z`SWZT6cB;v1tO_K^|T%hfF2^|ECF{vKbRj=MCZ+I<$gP<1Y-M^AH^rAm zD=xSDp+oZn`zuphzQd@By~&;TOO_QTAPEF%#<6=xk4=f#v~bTRT+HlIIY_2wR!4?+ zR%93>8r6-mIXLiH)CexogSPfMl8n?ND&>C1$rLiC4RNwW++S2&tQ1WJr~HlCyv@4BQ#rdj?01gd?q3bEvqO=?+T68#5LCZ_Ms~a5eL#x)eI4x+Imy3Y zdS}$|+-oMrAI|0HUvpI0-`4Y-J&6!&*OZygSNB}b@UD?9I!u$K$iE?9hwyLq3GjwG zL#?!iWz{3Y*#4Jyp{y5A7F*T^#T%{63hDo%Fs6{1@tU^P=ks>aTkq5NX}hLnw73Tm z1nYvN85f2zYD1FK1YE611B#&iY3a+(jW|_*RuxcuaI{^{HKyrN`SikY_KfZ1Eu+F(6{|od!cp~JBY(z*XgdXBXNqY9h_aMmp3eEnH+PP)Dfo4JrVooT znv`Ftpp>*W&=0R~`L^RfBuZnA711%6JkW$VlvhCuI=1-nU|Ett3LQ(+!oMH<@b!h_ zhr2f9&cMB`vPQY0;txEnuxVOA0*aW=ju&e6&M^ZeT%Swy$JpO(QZh{Q z2aI@hu~U0eUmA6M$%2L<;<$#ZZz08A&sd>%rMsQqphqqv$+lD!~rkC zYM|hhy?&jNv~T!@-CCY2vPGK4mloxe$BBd$lQPBzg27BkICu}nt2jFDzvtK^bmFwz zpURDU<(GJ;aA@e$UU03{_q6gu{CBd|i9$ea+u{Ct;iapM6H}#=8J7+3mevJG7;a%F z=wAGVe%MON&i|?r&F%mH(TE;ZI?Rh4<&u2h&DEAe)K++$IC132+UYwix+JR~Na)J_ zp*@Cku?v)onX`h6iFJ{7O4vHI7%28{(45>Jy%4*;hRvEemguJQ!B8nGP9HUTXmc=g z|D`Zz>+pLjN594|E{q@$Gd1=7ShFjaF8Rq?>HM^H6lt7c&fNZyJ$;q*IaVFl!{GliT8kGZN9-qW*{d?cvigLE@*}oOzv~xxKSHhvQ7LQb zzTC{Rpai227ua?evl?T4xS8RG%81}aOa0;aapUH)rHAa5;%hSHUz}F%5k#SLVX5#Y zt73k9J#-%}PG4fsjT~Dp_N;3QRRw+6Rf{Di3!Wa|`UelQNqX=}TD0A(qDpqhk zKdnRadkN>R+lQx2fKIc8JsE;@Xz_`!9-T=;D$#;RQHLHeIb7`C3B|2O-I?LAfg>73 zgQfI(ecPIgJczC#n6{iLUp5PLK!S`+zWD=ZePg9D_><;XEgCR__e+H znn`H-dVWX=CwIFAO@_9#T|FN3S#e8IcSR_hc>A+sv$t4w|#SoC{UI z!Q>~^1;8dOt;BUqm|g$_U)dDUZ7s#KitcPAQ1b3~vYK%0t&n6DZohu}g5qDBCJ(PM z?QRa4l@;#9Q+*n_{5@#tvx|M^|G5LWeR!$9d(Vm@qf|3*(LZfh zzjwBQyM@Z}*lzZIzM6SST84h{@xAtbXr6V>w4T{WZLPv3#&^kXU-$mpz31m&{_$<- z7d4vZT{SwL7JofGt?-4XL-vYubmPJLGPWe(vkl}Dwfd-`md)qo+}K3W1bs8?(c^Wc z;b{a`jcC-&Y31~nU0}kV&9_*~^}j&H>|jBqU3|&zjN*a<*Wf#>wzD7r_aE%E z;^1ia-LZSObK^mAu`V^>fBt_(`0G8GGqL3Ci{%<2F8msCuwI7!QtW{PIa;^HuXnqT z2xuyI7>{2MGtrJCSjMz9^W*~=Q6NeAzc9xe#-K-!E|3E#6M0EzJm|g z4W=R6$rcn3JC%VPbGAp(RwHqxGY;R)g`wm4QFX?q#H%(X%3=0fBF3p+(#(6Y9J{`H z3T~NW0h>qS|BbJ4bh~`WxvkH=?g0P>e!Beg-j@+gA@A;l|^+ks-PFiK{P|EAdD3+n&5BAOMqki4tc#83XwO zqa&D?$MCv^o;!j-5d7VMfYlV-CNsG>#RiZbO2Ug|=-ZWUv7UZuBVR(Ft%)R7x2OyG zgRdSsAs*R_gRQ*6uPiC}B(_u2vwRv3i!s&fuC4#=$l=2y@xR-aKg5vtrS#VIIYYW*IkCxGh{BBa&l9!{y97Ml3*B~N*n3bJr}JKh z@BlBqtidksH!fe>_^(LicS4;Jbt(_IL`%@Wo{o;dI+CdtzqDJIN?nUmdkmOEU{lwkYH~_y2o$zcZ&K{Av4k`!hG@^LlY@!!QNy)O}xm>EchL z6YQSUcd}Hr`40VQgnEnD3%?{{3rUoqFWZ3u*SfwOC;1xG@Geu%u<`5731;@+Y@G^G zPL;(PEdG_BCmCufeDU;w%Yb8vO6>e~UJpHgM3i@3i4%*23-XyCz1upg8OQb+b0@0^ zQj}&g4E_ud>oaZvwj)g#+b)7KyJSqk&<~*abwbUKywAIJG#(r7@!6xX%60eH;jrLl z2wQ`D1#E< z%f6!v8bcR?40I6+75Fyb`n)TycrejQG{mP=aS^yj)Mq{V$7U@5bGPN@;`Q~53lR*s zffbYFy~Mut_&B@irr}>xfmN}zwG)?njtGXvmsu+mKg;^K-C zl(-qKqhL50>6Cm9DyUHMTvH}L{8?2}TrA&GZS88&)@3QR8Xf%7qGHuS?C)uKx^fy6 z;#LSa*SVyK?VMo6ilxX+!DxtlANTfJ=-H?ajSddzYJ7E1BGjPCg=*H-*ZvCMx9_o` z;nZLIem?bTfgnJLEa>h*Rq-xp4e<%7uOBK-Sf3;wG=bw1xpQY3-`Hh(iMYduA0?L! zBSMN=NA=2PZ6TfBY%bbKD{U&5sdrxe{p%odMx#Cao~kwVc@%tL?Or{Oddrtx?@rID zbA?i%&Xc$ayBFRwp62XZZ|0z(7jtabC8HS>M1-yoKZ3BBm~DI-X5(uVF!3ai)9dQq zwJix9QO2B0oHS+1s)gD|5@Lq8eHu^|?z|U}Edo}vvs*haI24{QuD5ydiPIEFQAkcp zn}7NpL{bcJc4#Q`#Z@25eH+3aW}SSX2S)UOEyalIPMCz|Fgvk}(KOjP7O&fU9%h&J zKj`aWg>8i*6AXh_qyL_9J4{@!wdZMj+FhiDMR)IZ6K=FOZ(k(DB6Wkv-EjON55}4w>Fgf{)T%LLNV?8T;SKe{bJJnQj0u=^j8%kTk1Ri{fQZ&IJS?nJ z)lguyE$}<19-FBGC8PVI{(IPB^~n?Rr3g7|{sxjH<}*;MRjaXI&m`JSAFyM`j&g(y z<$R9v-vejQM%R7AKki+JG<+H_FJDmbEv=^vGr~GZFN5cv&oGjc_2Jnw3rba9hR)Z0 zt+cgQxbM%55{Q|L!7S!v;_%$u+yh`hmuIhfQDaq>Zjx2d(Us@{#9cv^;Y}4h|ENqx z<5UVe25u&V7*#03zc6BH)t$YTm)8J}lYx;@4sfZ2JXWvvTjE_9Gh8gynElvf`t#%{ zBu*VEnD{3{l#;wdtfg~jZ1@(ypNG7;cjj3rliRQc_=ST`n1jO`8V#-)d97mfzFL21b$Tj^JQvnbBeDm=r1KL^}c%$*d^Ky$=OSprSz0d;8>=xbFKOmLST zJeWGhq@jXLDzVmvrs#X+;l3B0s446wO%l?7g!^$PBcQ{5%O;`Y^QEt@S%U_Z z8mr1zt%3XrGJ$f+6p`FyGg1M@h;t;$dN-&?GmksTRRw;(8P13zbkhu)O!2S;q@p8G zV~Ar5Tt*8kjS971GOj^RN0xdMemMeaX=R8>GwYYwSZ>#Xba9c9_q{9 z+%*zclq-7r+ecx>S^ z^W?XY%E~s*HR+mGNNx`Y7O{w7&xm# zG9TCPV;1f%&{ye|yL?(;5TBX#WwhfpZsaQSn+-C9e6f;1B0TiKg$ z%q!zR&w0jciG5S)JIuKeYZ7@H7@+DgYtB8N%n|G|Y*+`{5uQIC2iq;B+|j+v%znM& zV_WRq_dnncJ&K@b6j za3XHo3JZKo!PN9RObB!0ZHv8imv&QCLl4{YxrVHfdyPMYqyqlUQS8PWHEvvV>z1$B z1{)Zta}J4p59yH{7pEe@EYNp8zP{5_WM;G$*Z)BDVxf);ZG8giwh)#|izqt;x0vK9 zlPAw&^uB*~Syxc$$FDy{d3CTT>pC*KUpj$Vko}uOoQICr_4ahX32q) zz?)EkEKSmBpSqZsG{ctBpJ&|hkDcJx+xE5Ci9E>!9KIXpg zWLY8|2;Tyii`?MU#hh*nJj|Ob7}-YhiQiw;pCxuEE4UU+Qg)7xn|AG*8oXvNJRO}C zLuf$8A2BpLTF{ZAz;VyPDA0ncpK;N0M@d=@Y` zuD|KHzIMc`Z#-crDxUE$?c3}91?o(EhnbP5J6rF*<63>~W~Z>31ENk|c*Ca67pOOQ z-3HjSb3nIAiC8ZZ7eD(Oy5fv4g!@q}mj(*?d zz;D&pp9CFv(}G}b_VS}Ijh}l+%O+3ubj%ck`)vZP5ib#Z!kNF_2sN|~B{uZ)NBBjT zb8_nQ>gLmb0Q0q; z{g6nE=wxf`A^UNaTLoxo1^(>xS5nqQ^$fF5$nV$28%B1pq-5J|yKwDxkDz-7m0`T`$yLI2>1xVNGueH5>uUO`>yXCZW zj!@uUr{n@)x?_DZWa*c`JYQ_;;YL!U;(b8jZME@p^-g3-ZS3) zMTlEc>=rZ#_sJQ2ji-zjzUx2EC{B60Jl6*emF0a$ipkuF%>nxXFIFfi;^G2EPj|ZOW9cIj(KYt_) za;g}AI(0({q)LQNc7>;kf_RzQwEbDw5w$&f-xnQC5*n2~p)y8-m>@3Ko%VwhxgltFE zeNq-#L1lPcj9~g0UjGXcI+5*4o1kOlbnC^r0iT|-*wajD?nAiEt*la?T zDc43;tsY8>?FbZmM=tC-JIK!9hPUz0bRt%0^=Q<%=9qh$%7X=$eNQRg3K!>{1bYkw zRwb(Be~ebQd>}qOj61uvc-qznjxu!88lN)e(xXU8Y!B>;#w-nFRh)GA@UJD&J56U? zVTBxUn!7t2(KD3NN&BtiGE`(@GM$lCKc+B`z6N9M*ng%oGo4m6Y+FJ?wEF0dBaLm% zeHnWw@wV}1s04{!ki=10K}1LM;kbe8i}>y25)KrdeYV?iIp|FBL2q9e6BxzGc@BF^ z;hdU?EH>`gv9QXt72+&p&bLDWv0}EE=>82U&huc?EQR8K9*e>IUeSJSnbx0AaTMP- z0cRUgQ;?<8JHYd(uqcRiE4~Es=fDAK9h{wjY7npbdP;jTtk*_3am@#o62$Q(;)5fro@~S&$ zXYfI_)FB&H|sM2%uX4 zCh4qyo5g`dF`#!2c<>kbUtQ=F0KBq+D1=zu34?7`pURq3CrhJ z2-q7k>jq$v@JPvA>!#jWa%Py)x3(YT$03pUfek;t4WL?mgcm#$uq^-j^&Iw<_EV-v zypF`}VdMmHGl+G*wm7v+nYgA^i(n^(S|Jl4M}fjVeFBn zIWKvyveFQ`o~Zh^A3jE>h#22s$lzTeZPQg?+HIc{{^IE+@vp_smH{l>Al+A|q0 zr5<-^;jjLF2A_@Y={&*{F7w7*lCIaM>X%r}UNWfIPqn{2f3YfX_zm<;Ef`8xt@`Zv zxnk)+Q8}^R+l2Bm{=k9ybk7ph7n_u{1@OODA6Av45FyT{{&E848UwZFyKHK*voQ}4 zA150lEz~dC-j^v~vOy61kP}wMJj9wSo26@gaseH8Snf$f{^-M0_mT||m> zj?Kj2MR0BpkES@P##Q0vN5n}09lAC%*G6Qz6C+6{ST5ugK)W2Qb%goEQIJZ+1j~b+ zjlkLE`qZ#z>KX%Hu)6z*oDm7;&Z=`lDlAX-JvQ{Dd0~ZN=;?Sw!TUq}(F+3t{3}mIm+(f2yHQZ=dOu=7 z$e*?f?JL0wD?_Kcx`u+K|L*kSV6`o9zCBI&N1&ZmYa4H2x^!sX%Vy83Th0l@-%-jG zTh@E2^EiY4M=rP2$=856b7N70OzELKsKO$DCUSwRyQY3GT@r=wh0TLmxdfe5=$2@PYtTka|PPEq8{6Fs&r{R+=bKxE{k;LljWy8M~Tg!Z@| znRIs3N}jAV5Bz6`lKzcma%Y{x*tjwAE*(+`*6=N;a0C8h7TAc4WlWp+PMyR2f$M)x zyUsT%^EGEr4D9xCxc5u2wIDDEnY9@nn3-ofhS#6`om&w`x0(V`+wc(Yo#dzRboAn$ z11xJy;T4OKTlZ_zygl#ig}W>FFhwS$angwsp22f7{t7W{_;-`tKL^U~i>r#B*VOS^ zq)V818J_QEsbUth=gInN{dtVRmn*+rh)HVqTu z8BKII;s%CkD7Oj|%?LI!uiw0p3kRXHFt;#bot}P$tZe##RS_QQQSkpi&X(DYdbc{`aYrhq~JhNt~b)THAZu94FMgu}W zjs~`!tT&OKJ$wJYnXay`Y+)dAGm}dK7ln2y$cQ}um>5Vp4)`ALA_#hG<4|*-+NJ!S znQVNeG%)$w+u11)u!3(2VN(F2TkbE{BLU06Cxo3Ka#1Bf1{+AWZJYRfXXBXyA$7iH zcZFu2*Q!-g#YyF92tokQ`S+x}IG&h;FEPHzLpeAqi^SL*^+pea($YTsdU7kN8391O zqTT0puezqaTj~Ay*cSg2-zd(%X;eR~h%&c^>4|?G8CT;ZC)^(M zP#tqJ;y<>#`!;0$l8H>PHtrTy^asaoEqTlW>N!&c^?z;fXJBhM#@3UkEb$)dp|WxR zPWP4FC2pQ97vj8pQzPa(7<}l06B9^qvl_JLZNS)+hf8G6bv(gfwvFR0%?nVjOo}I; zVj#>)qgkx|?}Pa!TDNJF4fMO!SJinD1hcb@evV5s4DN4`; zM3GEamNYa%S*c{|=&Y|F0C%hRBRT}K6GEva?07oq>9JB&6T3*HSO(S0q5#(56$oq! zW-Ahz@+yH|N=yAdWPNGIC_;REoI{jt<`z4IxXgPMF<_P~~PMoIrwYB()A)Is0}YIl17T zZ2+N^WgyU<2MlOMH>zm+>naQwj66+fs-^6frMv~G<>qZnv!VQAUEQ%=zlB=g*`m#x zyb5Ko_@ns#Nba4PkrDmWbb7{^%(Dhdv_JU7kEFi7%VrW}JR*B+Bdkyk7r7{xw940b zd-DmXkRphS(=*R=T!utU8{WQiC*TTrbj#P*n|@7eeC}e3@>q-kV3+?QeVJlbtoWqU zPha&%Z^}8%&TP^jLVh^$U2|KClOlczVuMxHwB@baF}9I5C%rc>Yg94LuiIeRK?eYX z{l_MpHDc4)BF}j5K43U^dPyXzF6MCt4<|171Tr~{?d0c8}B3>K< z(Z-fc9g9`!yo_!#p~KZO-dZwrS$vjD0@mFyEAr1qw1 zlG&3%Yo&WLK(}1-ZbVGHEpK**ANU6sw=VapxDN)be_9V;@3S-HPD}b$Nw8EtVg}hN9HzT>OTpCx0NJH_{~>wi#rz@uumu_>X~cPJlT{Ne1+xBATHl2{`LrC`?T%bqg}< zct49Co@&UpY)O&zwD2EJtSW@z4@SfQB8@*q9QTf+`OA^m^_BPSs?iYj)X$Asu}KcW zTeQ)eylFHS#HXf?=Z@Ru0ld_W=}6yS!xQ5Yj`v9DmbM^-2teol)sD4~nImdq@ze*k z_b;f>#LfyM&_8tYE-Zi9OcY{#zwcft%TTd47KHs_M(LgA@)OPFJeyfsBm3d>`S$qGx2%0J|!E|9(7o zK|a(0F;YjV)(sG@oK^}G8k0GE0Lq%9DJfkP`BY5#@0gkmeq53f)DL)YI`Ofw7F@FV zaArp!slz4|>FJbLYshch)uiLFy+8pi0bCuNoo&=R&!N&Nf2`!w?k?uoe8M^KhZLQl z7v^BeAWj{qd*Sh0s(04w(tGc$8u)EsuJuKg_$lbjY zSew4AkDu>aAugN$xox}tqm^!)ne0keR29?ZyG6uusN>#0@Q6#!aEPt%Zju(lYy%pF zfs}8HuA?vh@kd7PnJ$=g;AQxH_>a2g?5Rg@ZQl@OwoYC|c=#oXgT$a6AcTThfN}6L zp1PtgrANO^SRflNF6GVO!PM|)5DA%;yE2T|)z$H7{sxy=tULNVzNW$z(*m9HNQNSu z$jrrcZul1W;xseuGfPNB zNBps48Wc2G>lO&*N^B?a@F7GPxU953a8;+j&T84Xbn@@zIZuUU_l7s`MirZn*VH}t zBeSt&xGn16j$h=&t`#?lPFP`7fB$;gZpIALKX?6V!!USgVff&`e@;%O##dL^0a_i{ zHJ#q8ESm}%0AG<~6pwKSYtA|4QSF;;-aZ9~cJTsptB4xca^GM1J=L(pRB?Yh=RLMv z-0RtwFV{mE_NwGiRl|Ms;b2K^D$AK4j?KH#HgQuokYe~Hw##OKGD^?M4Vt)YKFdSa ztNwF#b9y~eUh=I8ax!bdf`-hW04=B5c6|oDQ0!eC+!PlPSp?A+)>BZlN=l2St_=(g z4PY?hV^b(7m?K$u@LMjrk+&6J96$S*g|kgdU7Pu{SP(usV_Nh1PQ=ap()Sx8M_bj2 z5{Pqu1$tlD-o0NPTN$t>l>IQ>w8hk^y9Rf?P*J6uQsf;`9;Le5#waQ(s!i@CV8x3S zp0oY|E1&byLcC6#>r1kG8^~POC3C2r#tuiD@C8ALKeYatMP&gc7j1aj=`N}F(~>`Z zmErWj?N{nt-w4=d-<$x8haPVJ&9utjH9DmX+z!8EIu$`k2(VCNISX*Nh;C~%%80ex zoqg3dDrkw^)~6*U`SM}&d+2pkq0P`-s-bAPMEAGr+wQSuyeGU&N4{7A;4h1c&cE-} z+m&bl^HjcQsy=vnC-6r~qN?J`?ZcI4t{{BcVs2&sw8w7e%TpX3`!tMWu-lX85yW67 z9ymACGBVn;iP9R3mN0Z@lNVEPZ|3knIE{i3HY^){D7f#Rs}~ zp&OOyIQFJ8L?ZCI%mz-9K|&Tln}kA--CsoV+U7rIZ0(k(0Jt<`0liO9)n=MVD@mg7VzE?C!mLXCCZ-Omm0M2x66@?b^p@ z)6>mf_H5L{_@JEumtc_BoAfb>-ph{s2f@s^Jc?e}>GYyDEJO6K^<=NG4JoFq$)MwD z28V-YG7oH|du3g5F*jF@OH1}_Qk~d8GM5RYD!egd(^a_b#>L00@;Gt>b3iYL>yPyh zmzF?$SfYE)QpKd{IH?+ZR+kwy_$m5&iSG2haJs;GF_-`*`vV7_ZFlJQFse1mQtHjq_zPo~NG~aH9&_!zl8Lic|BJZ+ zWj$2cSG)lJlZKAYFMxOoa~FsT=(RKtXDlqZ_6|r4NaoS=vXa{Ofz1gE1Tu12l*V)o zRl<1m`hv0{nejD=A5D_FinBNDHxxG)dWQ~#thNPtL6P3(;-2I>Xs%7r?rya>Ynws8 z2`+I}=Itg_>Sov*cQOcv*3*PBw)KJy6P8QKoOKiDG!GsQ zi+&{uR7ppVYP-}MSrOHD|CN&3)R5-Qn$0^zQw!Bt6~~|{wO1+hka{8M#tGb8K-yJ zSE1+9tHf%`&tLLB=tH26#?Sxv%<%oZFkUQw+^_#|$m|Rvr;k14Y+>iEA9|>&@Aq+A t5An~>{~RxP-S?C~H!Qrt%pE`K9jh`Aiap+VjDr8O9yQ)FRXNk|zW~vPRo(yq literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/class_trigon.png b/doc/src_intro/img/class_trigon.png new file mode 100644 index 0000000000000000000000000000000000000000..3f368fdd993ca0269d6bde88a857dd2d72d224fc GIT binary patch literal 9436 zcmZu%1yGcIw_hZsL8Jww3_?Ic8VOkdiJzO1e8G1SO@Fkd%@x5eX4gM7(F; z`_4Dtow>~53bX7!&;OkBtFzIn%CZEw)VK%)f&eKetqzZg@ZEuf1^>oOaPq;!RTnuu zcLaj45A}_f%0@_oKrkSX(hoI#vcKkdYifQZALuH;qzNr#&@!dO;=;fn3&UiJ3TGtt z*QqDQ)J)C~Wg(@v;Me8(Z2tqnmH8|wX^g966ck17J7dYo4Zjw3pRlwkSlXV{5A-q$R3Fz5 z5!j2cyY*5N#V(c0J->bTF7Dpmo|}%kw)Vib^Y*X6z`*0RNcwl0oMq+Za{E<&nwn&s zCY|^c6cjITt!)L#$jR4_)_PmrcM=qTX)<^Gt*WZ(?eE8A)2{YO+-~4~%)`U;?AbHb zLqlTW@!mog-3_xOnpq#+%?Lg^@;0;hNExT%%pEh^Kg1-)T~9c^y?OUeK5555X8d_h z4gq1L#vutcwf-#?CnwGaw1ki1sb?@aoNhG5e~%a^zoaC*H{`qA4gSwEG-i5fc;p`LXK~Grw{%Au1|3A%XC<_hCYf!7E7v0~#+c zFGbPEW7#3kpI;O5+{3W2uo%e_Ai8JLiGdi&;6|q<#6CVg-kqtUfcL|pr>9RzN#VUD zuw~W{KbDhJQX)VQQ&3vew!Ku&gbQTk;UP8Tq`^a~IPatuzgW$B0}F?c zkkDL}uYaAD&*Gu8vfA?N`m)f> zhG4jL3mfq)H5D^NqC3FZ(y}kRjui?hFE1b0)6BP!avatB>C+8Fy~8{YGc&VkPblUH z6CUE?&!2+o>NpmKwAJYf4c!(8s)OZ@Slg-60;4xxN;CVcG8L_@l>*i~I>_tn_^ zv9-0eJ6WQTbFy#og`U%}HJH=rb@$ZNHCtO-93moYL>#T)%V>ky0JHcVdMrZPsKd_R zgl%nYl)N^?P@kjIk0wkE4EYsVvktZzCnCu|_Z!EL<{#(rdEVE@cNqWg8D*NuxFsm4 zw`tC(@Fl;#o*3SlXXm+JH+wh@eHwY3NLQWaK(Eue{U=LHO9nA9dHfJ8`z8 z8}nU3;<$KtR?5PT3%u4n>iU+$jh6aTzac_14BbG@-#L#Y|;)T~#sS*wz-t*UVdf!9> z&&jHE>a4|npP#>-m>?O?743yda9MkcDJ?6Dj?k{r54ZnVyLR?1q0w zpL9W4StMNc)tvY5-n}&m`oq#<=;-L!*VnfS&s1+N;{Uemn1nc?H*c1gmv@)tJ&D04qU(kx{Qct)8&PfWiqP8Hnv0)5qN77} za&i)pue`9jYAP)wgH}F?HJ&F$z^Tu}R6wV%OHzwt64ZAxyi2(NOc- z)ZAQ9S&1tyF22+iWU?Me>iM<#`1|)h74bjJyoaPTGP^c(@!ciyrxiDCP)V|GM}Jn`CXa#^Aw|iwEr;9cT!tNWy+u`oO*v z8hZMB$AhUJqBC>z^A7CuFPBhNC4Tq*J;}9eObr|{5>6Y@ zv9V#bwVWQFo+R}2iQE6w{{3XNNatuAO&Wh&_z<51;KuRYOKPo=D^t!J~& zhM(V3)zAnF3qxmB$;DSu85goGEGlw6SQ4x@dZTUrX_6=K+~eZsMj|43dRo(C_rt>> zU73f{s=$@dXC!oVV>rKPNZaBE$H$3a#!)RA8HxSm_g8_NKm&9hf*&|r?~^yzgt zbk0o<4y8R#9q3PAU*D0P_I8mZ=R4n2b#k0Yc8hd=ApsC2wL$cv=TGMKakH^ z3(CuJ9*^f*`SHjU6cvR%48t;8=?r|}wu!^4n8BcNIW#0^*ye_LOC^_V0jB)ZGHWkCvRqYy54e_R561Kjg^&k_1I_Ct?lT?kI3X?(t&syY#kjP zhox4MSaOcHB?{@?J15*g6;<$sk z7^KCAj~^pLLeOeWx)QG4QeN#2K?fqnN`Ei&#_Q|RC+`(BM2q8M1au#2^gyYNsHv(l zv=F*})W`xYunx?Y!S9%9_;F)n106c8t(biBty71Y*{kJxUa|dytC)Ztu>>^y)4u~H zC9iz{{++r(h5*lA1lRIi%AGiYmo13jbLRglv{cLKd=?~6`Xh#_VrzO))Vb^sG zDj3@i*}~c~{^jLmGD=E0fJ0_toQ#vCq$FPV?Gd4YM&}hVYEeJl)YMcp;PSnTp*oW; zRy;hsnCR$&FCXikr=^jXl$Cv~_<=eXb8|^SK|#jE(9kPMEd|eVWmAs7fBBf`b+Ck# z))M~?n(H$l1nRV}bYJ`^DJ@Noh`fV`}@xVT-Q6KQF(>(^z_vG5rf3-3Q3d)C?cB7%&!f#E=XpW1IfyN$13mBcTO(Dn57)!p29+;ayv)S%cmHe6j@3joNkkxX3t zI zq?|%i7Ai)YgXFlEFM0X~2G+a&{z3IphQ*)r)49$-;pYcqIl@sGhuhVhgXF6Z3*D zsqiQ``&NSfa(HI-8z(a2!rjEP4M#;slT?JvPEARHHz0w54#%T-3ly-M3uPk$;O;L* zKJOE&EeTJxtglbTPaB9d($Zn5W)1^6h{VE+P5H< zu#CGUCPv4mQ;R}sm(x8h3=E9hmIsogD4o$@F-YB>n-(k?SJsjq*Z6px@xcSi`T6-l%vkxV{?+dL+G1}zRDsj1i5+1XctP~aSpo=U>r2bQc1zXHS>n_dR} zePSKr`s3geSSMKLiaYJ9cpn}Oqkr8z7doPPDVS|VR0}7Fxo7Pg#eCw%N@cuggl@J z(m0Le0mm)h8NT+o0|qhy7+xWfUc7dywy#eb^}Lf$6&hu7Qc__kg?#1*)FlUg1;8b$ zTt04VZS7%6Ny&HcG)aw(_ub=xiad_jWf&P>yKUiCR8*+h+TH==iD@FJpy=C`rFo>6fK8ZcYfo6yeAZudh0dgDvZ7^p>||BnMj zOHp)mbZ|@H9Oyueq6m8`%*NincX_$fI2xsX+uPgsZiJx}7oZLoFE57b7Ig`LVXMzE zBRF%GvrKTX2^krbC>IRSHd1Kg=y$e1Jnj7WaU`HQ5UzxZ3K2@vAAEYV_W5%(3DYCf zz9^E@+4*VB-#a8SzP^Ie^T;qH&mPmgdv#-Xn_61<8zpnIv*Uo<3ZYkB+}z#*-tMK^ z0QrNjqXJ1C7c!)-69^Ju4N$-bT-(yp637yD=cq3Wq(u4hY)e41ef|AwKURXUL3@K5 zas52W(s0_sOC6Z3s-yF2EHOPV4^YxCKR+J<_lB~=_iM`!3doGonV})5e5K^&aU%$5 zupU2t{9@1B(=)uPiVfhp-f@xt=lQuj?^2p{(fA2I6%Pg`Cgua*Z_L4!I6aU8933A& zbamwhn!uKol|^VdYYI3oTVAX~<&Z3o%LhOw4kp~NU?k0Z;CclTgg)T={_QuuC#+aR zbR+w2t0%vHu7(j=x;1oJ3=%@~p-h%4=)Kfbttz~p{Aam4pl#L5W+o@!0;x3EOfX_# zV@rYMf*BkLMngv+z}UEWcsvC=9uN>v4TnaA4A|tfC$4T z8i={hwt8@o0Ap=qYr8hrV4*m2a$eui5E2`UM@vg9Aq@h#_odZ)Q%6UR)9gu*)z4B= zFaXQIJ)zuk*X4PYhd@O*0IDuPjl#whtIiCd6x*!UqK-*m$x#m03>?x7Nrg@km^R2_ zuqs~Nw0S;YVPzE#ISw!K)6D%3HE3rI{r|>OY{RBWG}_5M@FQ~(-OI*C(8_3{qM{iu zUaalp1*PehKA?IO7-Fc;o1FG#>oj>HnT1MPi|#ffBcmJx@dp4=B&gLgPzkXd8rk?o zVs$r1(R@2B%OMqu<*Nk{4>;<<_8fa+t^(+PfA!zQY9BL}q5@+-pz! z4lB2|B|j_58DpvH>gv_qUEN!y+8R=S`xZ&VL2^pZM=u?>=r=MK`CVwcC$>W8YHDis zrQK1ExLNb@S!tnO|6(PPEi=`_hYwr*PVd$lw!N*cXM4@*y1ToJ2v%M0`g=(uBO^ol z9*mBRp&{+JlM`;=ZE)*?la3cv|(Q&0S2T4InDtUf>Zt3W#1m{Rb zL!&@VP5m8o+T=`?P6bReN{K*|sW)4I)w8sl9&;#~? zg4zZwY*zYd$n#`c2yd1sQLFs>-|#?(hW`yDr>t41Vr*0l%0}gRYK`8oy1slSBT}QE ze7rw@KaP_73gl&=6^@RMOw-6|Z``1|`5M5x^Y?*p>zg;dJw0e+V`Dz&-|qx#-z`xk zCipf-&0~o(TW3OKZ*RZ!##^O)=MFpj(^szqz?Gr20qBrbI0S3Dn;{_~5Fri%F}wUZ z_uOCUqL)peMRou7$P0886&1sF9};MZR?jcw+SR%t;E8tk_GYh2bh&Ok0=V1&JvB5m z6bxt$l1;0u0}%T`;5n~y_Ja^`%II*~D1VPIohX#a5ccMroSFhcG6F?(^-ocg)#ei| z=c~#1pmb4))fauu#nqLBrWo9WtEyVX>l=LNnY`Y2WHbsj4Gr;KWq~P%;y4~AbAwu9 zH*6(d2{<8u+N^!~61%_ekYqJO@u9d);SL$*pQ0TSPXw_ojoTOB%@S@FDg>ARnFBKm z%NkJV?p#BW>L#_VO}sj;S`&__iiJE6L~bwW^`)fH!Qb!G*(DpBMh1Vpd6s;$ZlW3EA5FHpwS@^3i0IxP%{m6D3#y-qg$47U z7zl+B8DJ~;9p-|ex&Q;-2TQhUJ#y5U+BaI61q5`4rce$ozo4LJTC4E}-=bp(K@GPQQFawI$RDO_R#avrcnrN~Rf~2?Ai4;-hchP!i+{I=X=) z7pa}%Uy*N<8Oit%A=3)Fp+rB}SlxCXZn&ZRnwogfk>)U?h|0@{pwzFLn3y#1#Ld#i zNz;j{RHa#hQ8k}`X+C~iy}@nkU4#>!!Znbvw?A^~ zR$!0RSh1$c@P51KRHsUWxe-Rr#S9M(NdyG6kNleBhCRc7Ru4)=Uwm~lZ;d`0KRFEg zO9PBL(zE9BR4i7VMmdY0004^TBMTc6iL7sKMq%Rl_s?OkoLBgLayUX*r%qrLljaK$ znzpf3IbvcyM~Ln1ZB*vc(&ClVekB9}nPe8fV{-YpuZeMIKy>uATkGFHPoa|ev0TyE zqaznc_i7)0ajfATnx#QPu1O4{ts9(90i14`N*+q1s;Q|VDwmcP78XL^Z@nEH#D?=i zbpj&4sfi2~4upqe`iRg)5YZ<9jb14y^=W(a1{E%cVG&$Oe}7%S2}YL*IuB*`5#5j! zHw6AZ6Y?L^EiOW0jevvqIoT$F)ki#-uL7kI>8BtE%_obIK1Zu)V6LK3nS96O-b@t= zCLnUY_WASY`o_jy@FHlMzI;mZ@^2xDMJee0`9^GDJHZVdSI{_=!d~ne>5!1_fBowE zeRtwf`}u6x(!e#?Js24o!FVx((6bnb3xRBHWMqVSyT;2`*mkm5=)l?C&Fu)7l}8j5 zZ~TYZOi1r~R#x(;Vn;!Mq;nccs;Q9#-yJ`g`TTW%9~HEK;RiC^7#IKB2ey`7)8y~v zA20`ZcZ_TndCzCFGCe>6jJ3fXB8ZbkGcz){f<7+4)(}moT<%d_th$5H)YfLacaI1n zAI||JSYhm2C@5!opVfu<1&x-{GkFgB*UHku*B zPaXIro*96v-hD?I0}IO>9OUlet9t{9^od}`5E8n&l#r8~Sy-Smh61W+8qb57z=s`C zacL=JrCEY`$;phoQPxSh)^AQ9F%WZEq=CJag3XluY_)G4PuKY#8^pKturxtKz+MDH zTU#4a-erH$Gku{NyDy{lX1(9}@27QbOuIsv_Mngk$TyR;A zv~Ke^-x!F;!NCazM}!JvVMk!LIh1s0R101l6>LF!gXFmaF0Hpemg4${^%i6!FP&K4 zimCV>h(uRlGkDE9=dkGsZJV@2jezXLR-bfgNZ#`ZdREMLG*G7J_dK88_5mIU%!4WZ58N<#A4Vd&{DhK8XX<|^UseJE4nJf zH(mtEwT+q0_8%od4QiAsCY43w_6`loHtUuw ze7=CE0fB*LW@cz?Y;5d$FP~0G#?y&XgKrx3n(6AtD*xy8!QYZXR1b<8QE9mM=+Pra z0CyDVo}CR;>osP$LGwLJPmcs!R$NlD20$SvFQ0sytzsA^&CJFo3QW@4LbE;m_AQb4 z1tPyvfD$OCQFCg^#seAgz_}dZvN=Q|{pit^XZr-rtPv3raOu5Jm80!Z8d!z2F3YL} z_Sk^RXJ?*A85ua+7sx)ysAp^yn$yZP%9J5R92yx(fj2D$C$ck^(@S9zfCi~P;SC`M z28Q6{NnBp%;i#n(kta`{9G#q?BLdDpmu1|4ObDmKvRyS!V+VdTxUyyxBA!9;um#1% zPrrZnsIX3l7sG>`3AHz*6mX&ij|5@r=!5ENBwW+Uw{IE7*yV1)RCII+O-;N&4Jm19 zv&SQME33~fS)7;KN!}T7V7hvFS&wOHYT^t(vJ>8NQ06_a@{__U4_q;A3a%Hi=#ROM zQbk}oBjGh*`68zk!K{bm^YimVRPy7C_B$f1 zxZR%tp1}wNMkwmD0I~NvpWW$_V8}P_@SA`@==x;t`7?ntj5i``=mZ1=0muCmx-cRB z=_NRN!$AD`fZEK)_R94G8nFPov|u|WHwb;_fNRv%)lF?|a8Op&ibYRP52YB+4n8e9 z@Xd~@Cr?0kv28$i9~zDQekYGlKtSVYq+mRk`|qYOi<~~crJ&-hQqA8>R}ED&TEa*@ z{F+2C+}1lYQa3MsGv6>v8Qb~I*Z|8EP3zIa0$EN@&W5XwjyW|P{9h+K&*Aoqi<$RePi$*r zqY4}%)3WjVuNMtZRvbMS||zAE4c%qi*x@rP{`V z-@wGio`NVMD#`|yxx7%PXh$YSRF)hb5itpCkU|dDJ7((VfzNFe2n5g0wO;J?^KHMMm@lwTns$*-)80l@5;oz*VZAwW91dwV}7L+2}@1J@P~ ztCH7VUvWXdL!wZ&>_1haK(XE60GTBC8(1R+Bd4;NsX2rs9F@p!#A&CXUZ6^454CBS zZpkzjw=N+x>XYna!jy%e6eX78dY24yX8)l#~X7h#B;A(KL~~ zkfON$K67l?;!CI6(PkP}MLo@!kGWZi7MvQiPdD%b12N7KlqN>;$MCH@_@qGO)dSdi zq4rDG&lx|oGgH?*N>;m1S(BSf2d7FIHs9ed;Iz_7K$jSqD0YqmQNL&C1T7`c35$F@ z2M31?-ce-XghPiVFSeckj1T=?Ha04>0A*!DSeK}(t20hrs7d*r+GrW`Wa2e<*bTjh zB@cWYA`!X*A)%;<50=|9*T=!hSaeRylY9DmB`R-fd;B6NCx_d4S>(~K6RhqUH#gv_ zM#rkK!3>#!w2mkGhmL15b|A-ch?~$>4C|*f>I@JBV%qzJ&Z1NT3x7yop0~L=Tn-Gc z6i8tgoZh!x1MAqKvpH`^@ru2Mf{%|cNtv3t(-BQehb@xSPJZI>81x<72-<4OpmjIwmCq-p5?07W_Yp8x;= literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/classes_block_iterator.png b/doc/src_intro/img/classes_block_iterator.png new file mode 100644 index 0000000000000000000000000000000000000000..2dec796a7dd7b21e78a6d025337780670b1851d7 GIT binary patch literal 24135 zcmbrm2RxU3|2O>86qS(@DN!OSq>QX=QDl#dtdJyoj|$n8Rk9_dNFmCqY-NNLh3v@A zUeEhDuj~KZ_x-=GXS|;0dY$KWIy*TWzwhz=em?K@IRY;$$?c+Gq#%(^07u2xk((g&_I5?op!;Eyze{thJ~&vJ+9kdHV~mEAN87l=+m{&5o$7x zeh<_;CaKCN?p>)7zW;b(c6wxbq%3D_ZK)*JN_R4+X?R(WQ$~d@KjOgyNk59c`8)2r z1jhc?U*1D5rN(lUEWXr|CFfQ1$%!x6zN2}^|K)Z5|9^voCHrAt{-+lo-O0G_e=sT}ye54SgOx9Bc$waj3Z&NDSN<*^^S_~5|< z1>wCc4i6Mm=w1ZHL`BhYs%KvQvm2KRJ|KSchajDd(VuU5RTG8*U!vmTf}*4ME==}t zYnGhaSXC&gjFm3=WJyDORHcYi8DdS&Nd)a9R&Hd=ab05NQuaKt`1dzB;t%?^Hcb9z zk&=?yxoelCj`V>Gn9uvJ>qM6;mJ~&t%$o& zxUe!mzBJci_(h^AbM`&)}zFozs8}w?Rb-KTXf&YefUU1Bx zKYxs?cCZ-i!ediW==NOD-?p16ASsENa^H!HuU})-GL!~a8oY5?kE!?DqqwxfM%%Mz zmxhz<7bf&cr}_98#Jxmz@813J(W92!Z_j3$FY6`evG3Z_B(L8M()#CM^BN_g6=c9-W#j z-{_l|P%5??e3_qb+MFz5dhOb)>+PJxE%w^J-$zY-dBk;X(tATHU6t2yR2^5IT3GP* z=Q`!v?D)@zndm83R#m0d$~9nPWxX@jkvrQW$DE>?Wp~iMuX0CczNM6`>^3f~9McLP zvenhurcuK_@%6b+>lOsf4mb7x`XzDw`ZHPK^0oN`txqqR^i>A_9q-aI zF~sfb6y0JWiHV6lHzB`$fJ2A1s{9Msp>S8Qs-xY4+(8|%n*D9}GzmCq<%Ht%kMZoMb7^>sgcddjzKP(~%LEKG7eefqS%)O}%Q)opRg z==Sv6)mg4-T0`1ty9}8C)i1Bjl?!kFtpEDricaAThHKZZ6}^3H_jja4ug0LvgTV)@ zkp1TS_wOkj6oG+(l{GbLS*mOyAt5A}u@`SfzU3W>=F-w+WnR=F_lN0}NQ<4_5$+c^;IFe+Sv(!H&i6{B*I$&&STDhIsgA`%o z?U$ex7I)Ta-*H2n#Y@Cl3`|Qq^5V*yr`Sw?N85wB%NFna{p(P8V2V=}(#d`rx-^`*uFtK53GkzP|lI;ak1uaR~+?yQ3;9 zDp-Ix{7Mf`PhMW$6r3UvkHrW)a@xInWs<}^7bo6L^6>Ggy-_K+uCcnh>asHa<`Iw4 z9a)LUkCl~Md>%gB?=a;Wlji;74is?IlYvJ@?oBhc-30wwmCs&e(LvCnq1i)|B`nuiR^G*~P`> zrA?1m*~*0Q`s%DQp52G$6shT%nGg7_%*@Ph9ezI;7IJlQX-<=);#`DKE(^Yu9$Vx7<^L{fBQC>8IBi^rk1xC(Z*N} z(m7DgBOSk@kgR9Hxe0XKrO zB;@v&BQY^iTUYnXJLgH`gofAq&t9i%Y;072roO{xWW*xJptSz|-R;G0bDTEiYy6`4 z{uVLkKi}S?@chPQ0}EH)zV+VlO6=OTb0>$|(~GzB-Y);UP;uxgC@FpAm+oULlkTet zJD459!1uJmq@=Vodc5n+aPcILFGcc?BHOfD&qLx~dSp@CsSa7(*qCYHj-L4Wj;PI4 zheR%8BW0`S8tCV}ey!G7Xq~P1&gqipA8ajR_gB@|D_C~qB-pJjJEHohyUmS`>QNm$ z_e5Jq=Qu7$)LWd8CvDkU%0x}>8yb4bBMz84B?N6UB zdM*CiPMV+i+2Ffl&$m){0rZmh_4Pp#ceh#Q@1>`g8*WU{Df1ATEL}K+GUc&0*MZ-E zAHZm~UCZ#-;Gm4GtiRg`J11ul)^c+*APO#~2soqj*5SC3kF?%A_ah>bZS`DS1mC}ZFD)n6j|-hYPr~zJKX&YCWljpUqy_L+$}FD$y@GaQaYf+yix;-HZgEVP(aHR(y??~l-~ZV?g|hW!tJKs~o-=1ED=K_qPF}H_ z|D!|t`dsI3Y%IN#lherW-@MKfdizf4W!{{u4n5%F=5`uL^~cYjWGEaTySlC#?Om6)KtT(2C*G;dg2Gl;sK5xDuIc9scXN+L}*lw{GIOlDKI z^i;MB%Wpo_`~Jqyw|j+!-_aIbmn2s?Z7QReGK+0EJwLxK8Et6GmMxi-J`W!7$!#N$ zU*I10FIj5rz0(N~&=u{c`(*z9{fqkgp{{O+56;l_j+_@^XL)(wS5``|Eup;~K62zP z3SZV6Ha50A&lRUao1UERn3xz@RaMoT5&%$%*i-r=tr=9r5ki+63Ki(SI^9>bl*6P~ zY-bkQw3k!8`Qf**{{FjVWn%b2nc_2&c&(C-CBrYy4Jj17A^XqFXxR@VsB^eK}{KbnG7Y8Dh1-(`UarKJoYX9z1cRuHd zA9|jmOQy=2n)}K()`bu7-$({KI-&E*_mHSt@6b>+Hgi~_LAQWvu3>r3^b#I3>vHh@8o&FgXUyg0Zbt}2d#ybnx#LlQctczsl^H{t!`t?PFbB|{YclqiE?~OIN z%a^GqCMJl^kD6;_Vj`ud$0WY7YM;X|DJd!FvB(2fkc=~ZG49L`Wo2cig9oSo{(a)P zGXF4+fPHe|heU5VJDX!?Ki4aM5PCqs*vd)~Yn657%_*Fu{F^`Huq*?QCRZlQm9aRe zC4kCPW4YzmcY2e7L*&^FD#(WHe{bl$CWCe^=rVQKret~>`a#p+ISLkOBX!iK&Mi-# zJh_}A>1XWB0WA1q5pXAkBdBC>iGg^8GQs=m)Xt|LJ$rU97gx5(F#G#{VO@WJ|E21& z|FdBx>|-(D(_K#h)#cvxD1ghrN74@y9jCqF;Gw5)7dZ-{{xKESb)Cr>tc8WqL2M(U}Zn_>G(LE0f(WXArMkhR%prBU>eB)dI|q~|BVBt%9MPKIiZu9 zCwoBxyY@w%-3<>95oXW7Dv35B>)2?w?Cl9`K(wa0u@3sI@Vnco?7%=p7SO&ZMMXtJ zLPJrR-hcRTr_j2~Zuzg}951kWoA&l0ORP9i35Y(0R)*78HPVuHL0P#&aAJ9G3@7@k zx%s{O_i0dM7FSm6XNNA4l;Q<%E2Mu35XPCnAw%7wb4wJOuCA^gErJ5yAp(u(KdMB$yA)ScyaH<-3QNQ&VFfa zmBQ9oE4Jw=lc|>?S2?4aAE2dxgIE?GIh5|cFmanMU@0zH2*$ohP0^mmnJAkzCNb zx#4)f4FHyp{~56GxzFF&v}x0seTri(Y1?r$M(6ZDeEi4&D1s7TJU7}-P{khajRdoX zm^_aqJCM1GUmx#*U>@b*2mo#c9Q}Y3KQ%RV^~;kBXKwy@h@)wXUNh8`lzaaps#unK z7HyK(@^R9?iHTogPrhX<`L10AMaC!8>d##(0sOp;Zb@Hk!Enxj1D7xZ=^eEWWjt#P zEurn1MsRz!R)2s0$9N(8+Qvp=DMrsqUH|&L4(p|pZ=sUY$2I&Gg!jrC?FH-Kzkh>^ zDC8QHetTs`2`YC=Q+V69ZTVImySH!Ou9PSe7#yq^IFx7GFYCYiU_EGITdpxjSp43| z*?RHe@n1_V?Ma4#v5OA^1e%>vVq=YL83MgU`$I!Rlg1d2074rrO#Jk~!vUAEpX!wW z3G;`3k*)b6_2Q$`(lRo?Mn*Ej>RcbsM&jE3K%Jh;e~rMBfQ@)9zdVuD8a>E=V?U}5 z!L}h7?Ted4;njX+xV2zAv##A+-D5;hw0Dq` zA3k^PTu-}yaQ&xGCz{5AuL0%XPtVl8Zg#~gn?UiX=Mm0j;@X!x6CJ5i?DNDe;#hlWwf9p6l(w4QyyfHon1wnUkHvfoR z*wvdicZ-~o9_`3&0+ON#Ra8=vRiV3aopul?kc%ajGC(XWn00s}fZlyfGG&9)VGhD)^ z)8#ylN)`x|Io0hx38`k}OFAVG%(cK136p(&l6H2d@v8|QivER~VX}@kx~U%={SNs1 zjvYH(CzLN)F{R@m8Rr#w79Fxnc^I z#00vNebE`Yxw*X0|CVg1IypEDpx`og(aE?zH3}~Qququoh%=GpWo7S$>PM6)kj=(| zNjxnym@iK+9U!4_Rsq4uU%J#Tc#4aQQe0e|&{?|YL9SIZln#QZDuHWL#7oD=0&+RN zpKcQ0=$)L*)mUvMz=bspsdjUTVaVGjwHzg5wsr5ql>|C=P zb|KEhm$$pnQNZ#EWROzh=I(Ak@k8jthYvnAd%SU`ga29-q@)<#U-qeyk#=x6gUa*a z`}gAJ{=0YY>Xf>j#e?qes|rTxBhDI#Nbu{|eBIsMBq%-sGlLDY(>2V*fBEv|%OYy~ zZ*0VxaORrE##35dpjaLYKb`Y!dJ-!uD_I9OM819d#sg%uZ5Ja}q}u+s3Gf`T^y!N9 zkQS2^nI!{CAXyk32jTmC_Sab+o(NyxE#M^~v9Yn${iQN!8UGXL2st3I8*Nax@J1c# zTbq>!NYXAG9q3vWm4SPB1q95|SDzb}Cvs{$qw7@e$kAsIb~*t%S8MOx$V7#og%(^P z(BmN`FCQQ)amKncUvDh#$p|1fY&uu zRem>rzE#OHmLZfybdv9-?#^Y-A!TdxS9J3&BtSXrf2JSLL31A}R#KF3Hbu2lfC33z z#P;B0E5NmOp7B=j8x|g(sp7vZzO|1PT4roRVvXisR+cADL&}v>p_@x%OM-1q9u8*|WE z*NNG=IkUD*72P)=@p3zN?&RU;uZ9A2;J^V$$(hr4L?L_Phhl6F{71B6Uz)Ilhcnub zLvqW`&KR9*v_S4Zp_EflL?t1Y<1sYZH6}3+?f%c7w*Fs(lF&KJFeafpj~^d6YxQ*ijRaWsr9}&?=5y`$K4hC`ZV2=9 z$6&cmd#`(RLcDw8k*Mdtf$uwm&p<^*1#GRBA3W_FKlZ@h8i0m4l#p@03Qi2vMS^L7 zs#c*5lihN1I>yHr2?~u0vP;BZtAP3AyLY8>)}b*I-RJOOACx0nX6B}sMj!W!c?hCO zv~-CL0Sp#4A4DqauI>7PPvqE)b{2 zc6R79YeINwspt#c0?rxtC>)JvUd~E*fQ0r49S_Vk+IxNJ9)QQ@aQZuAC@VNO-@3X? zEGz=BmcM@e%7;0i^$s-oGcApK}*bB82?cm3G>B%pq2(8QP#mB zUz58Mm4p(XbN_(@fWLKk)Q<#g603O$>jlOE^iev9UU%-?*$*B6tq+GhHZGLUYpaXX zeusdk^?|!9Au8F8zkc~L84@cnPYZSql(g7k>hQEQlbn>-|2sN?{m}Q=ri=yK4fU5U zdzXyLB52un=&Hb&rEV*PdJLNaY8I##1%WqK7i}5&Z)9q$5TqIC#^LuDwvIA1AysI= zp!-VDOnqvqZUF1;7je0DfBl`9(2s?qU=or&D(Ttc<+R+>Y&15>BA!Be>q$8BsvQ(Pi^UF1)Q{p zc*G!=Kgzw6z{Ic9=`LOP-+<9aVAfgy|AnHA0<+-#RU2Sx{U9`Q`RTMCT+BT}U?c85+XDj96V60*O=omUbKxdYr_0*XwSFT{=r>{Tf zpuop_g0Im5_btc#j`yZij@)YtMVK-y_7}^4Mon(=g8=iuN*6p!{QUfuSI{2^-Pj}i z{I;T}ajEt|kQ$wYhW81QmHolUsHjTl)_HH<)O2?zhKnte^YOj*2qqRJB0l~TK3@@N z5h2SEIvN$T*a@CkbjV~FIlMQfpFrR_aq=X(X9fT@Wc*_J;Ubr5V<+gJRN|}Wv9a$P zQ#{~{J(^(wrPp=$UZ}|ybdEwDY(hehAV?Tpy?P!#Pc^lHygWG`T@45&4piC3`ie-8 zw*G!Xyn%x@Nv( zZT~inY)u(ML+11S6OBLLIiC&loXN!}wy~m<76P_igil%QGM&22B_t%&^oC9R^QTWC zxn;{ieCCar>=8pXm6g75SMyw^`}9_D=%q|ekD}#EV6!{mRrwsvY2M!orUUlr8dVbbS0X1l)k|@a>11REoi~ARnZG0qozue+saX z6z;7v$P{Y=v`rxBKYwmONV5F?$}DI79e5*@ho7QV#z6 z(COAK9*FbT;6&+_xZH<@vip#TJi39clT&q9*8v|GI4@0VcBA1FCXUNgFPZ!NpA{*C-M`T>kIaQxVX5}FoDY!`zWDvSAKphaN)uQu%umoVKwoZ zR9pNobN_T0g>CKa)oQMpnYFxiw2C`pc?Ycw z1~_!n;d;1CMrUq(i-29&*V|hG_C+X?Gotr;d#}#v9wp=^Ik`Q1_xeHiTiy@S5b7u^ zw%EJ5cRHeRj62UU|AQ0^}P)8l}2a7^HSWC02{Z`+v+#T4iw07w2M zTB65r6bXU}VbqC1`@<&GF1WrI$E(Q^+j3mUaWv{{?q%|wJ5B2zut9JG@7|6W0U?b- zckg((x`I~xjQ857{REfM@RkhtkQG&OjelRS*~5S%)4ArWP)5e#=g}iaHoKJQT44pS zOViOYAWpum4KG3^I@c6!Zy1G^ogG`|J=2MHYGi2{2$V6km^VrY?$}r!UAhnlAjG7@ zheBEO!%;VZ*EQE)1#O+~zcjC$nhWqVK10N!3@x=A463HchPF`M-X4uQXpa~Insg0h z6rUQaa$v`Y*#3_}^dRR?FD!7YhC#;XY)>7$plt9Mdz!#@%-*Z-@nv90$N*s2Q-Fl6 zh0{1Dwxeywp)fbX*5?rr@TSS4WHFE;ZlfOl67kHc3$Z`=%F2Oi)t*RHjbS&Yfk(-T|+vaS}l0K_6SXi4GdGZ0?hcXd5R z4bN>}{U5?p?W}bLByW$uEpk9-YM`C~E^WCqgs=?}^4s_CM%LC)?)%V>{N`POgSx#| zteKdYEMQ+%XK%O5`3xM3!e)lU>jBnIz+RVC*?w5U1WZQEBU9(~G2Ar7u$RqVe$=T? z>RP4x3RIt7WB`p7v>PDTc&2UyCyLO7AnAr9jj{_et)r1Dnt$)~yL&`N0$GFS1}Eo# zFEl~`odRj4@7w?)gLk(R-nZ+i2Il?y13+y7M*5%?!Z-^@VQGd0005pQb_#-9`T8;? zJ$%IL2xMY{xY2fA#wj&1W~h?$OF?BMJE_U&Ow_c>Vb zFT7~3qUw^9lh@9zr?5wJ8yc*Yq9rWrOS0 zOeI2x0aAg+nImrvW~bsQCWONB%<(2jpXvKMTZu3PipMl?A?<+!*^a`nl1`u>^=&XP zGCqilBZPrt$ByCr;ZqLbcYnrbfJ{61)46BsRiuXWO5LIfA$~D-nvf1)6XC9ei|5my zJeh(a>zG1IL-QUgS-aGZJ;yHgqL*HL%>SZx?R#fu-^fVqmvlukLC@tg2nET6Z5MQ% zIeJnz|1!N8&eeVfhC$a3B6z|6UzX9<-MjWa!T$Qz*=cNUUIPMy9z<#N^*KR};297u z+wY7d5`m_ng=8SY1u~Oep6GF!of}UIft=0glXFkHna*BsyILE;LUgopFHfL|S}>_c z!p^6NAQqGp0y_an8QItnbP%*|>wJc47R1;F1s zn7#Dl$B+H+KSAoa><*v+)2au>c%LfWX`)MzjBw~eGAjFpoo?i<(6d=VoI%f;h4u36 zjgGc90bIIWhZ9sk{TcjM;7=o`z}F6vB~<4-{ew#X&OtuM?%1*1v$3Ax^_GJh8Vb~_ zC~fb&ygYbV1Mj@S$6Q=pqqV(VmtbgR8kUO@2`|8{qwMVB9qYc-x!ec{a!7zurYI+g zaX&9d1&$eY_ac}jjz?Qk@XXsSr~s!J4$=PifZ=rgJG(&&JRX8T#18hLdGZywj(48@ znroOexen?v_^5LO5(th81vpR!b{FoinFtbIS3`{RAHkA#&z{IJ+b>{tk!`{s#IOV~O$ms}= ztDAhu7eebpNg&_7dkA(r;|fmiC4e1ms3M0B9U_8+gp`_VAPO@bZNKvS_eZFn5F9Q+ z>5zkYMM&jPs|i?(^JJBe9GQ;S%D4cirVtJY2}gP0b(2^csvktpJ=D|{=&(gzYv+LG z+4%YQf$0PP?LfWa8mQ~ z^D94o+)RQh1(iomT6znNSKoX0(lQnnuRTG3MfxOO)LnCI6%4x^ zi7SO6sP3(W)>nuyh~oWeV~FL^UxcB_@X5zps)r-re2p;_kjVyki%1 zAC508_rP>x#>PMG+qVz=X7fw)rb96O-UHyFG4-SKpRxLSajXQgMJ;v#a0t7YSRzmk zFG6~Re}G*}@L3{(mZ_1wkH}2kym?c1fyF_wQIRL<8ra^W(`FPQ?f=8KnHME-e|)$7 z==xlU06+h!76D4|UwiD{P-{dMlCfuqE*11Qlqx(avs zAl^VjLn8q-8*B6nJs1UO6ZOAKq&Ld}Mn*f-Pm!*(XU@Pkjt&XgdHVF}Teh~pa?95@ zAq}yQl9Cd8mq^TQ*%I;SQ6SP=c)%xHQZE94o;{r*Q=-m6IA#f0R%mELxxLf}8vcX^38g(niL{vb(I2OhX(H zXo=>~p+;sIv(b@in7uzi6>?piVgc`a3V#v&?lRZ`(PsKOq;WfY3D{=<;SCzr zz2#XXhueDutiFao2N`A%K(GXmAS>^M^JMqvq)m6pBXb=6!83>6Z5sjC$mxf+icWL# zj5jcNI1z6^EpoW?!;+?ttpErN|9koBRUb5>!P13puJI^e>Qr@z^p%Pu=#+iDU zUZ9u=+|Ay3O)KfVA10?nwhz+Z`Jsr!1G)g{Jo4o-*Z~#T^`-!#I?c^IJ%ak{|3)^r z8Y?pj84QFYO`cdva~QsCoju@>+T~uQ)rB}evyH-&5iv3TaIgW~>-n5Okl-?JNv`Nu z=!)zZuMd7Y!5rTk$Hl2%=F8dVuLwK+xeAleVd4h^;js}hSeS~(uN3~FZ0MJHBT+3*8%)PCA*F$eM33&NFwo;qo$64Vuy0y{_<5WZ zRqw_n%JsUfr9={SPCpO`qz^_eBwEz`ub-MCo-6#0qiw%p4ZV*4?X0S*nnto4kU<$jFF6H;Dpif+ zcqfuh!l0!u3kzk_Rrhu}8+BMi{3WOwV9_2%#(J#$B19C+woDolYQ>2uB}Idd8!f3a zf3d@Pv#1hWQ!z)DTwU}sKp0N*@DIkZK} zV>h$dC!if7&TrXWB7`PIIA_=oj)~Z79TwhT1Vl;#!~)Lh?~Yu(P3Q~K;tmkoq%GW z=R9dJx5SKWF49MXUGuFSU;(?ly}i-wgphHnfKr$Mo_LVEx9X^P4;m*yWOOeod?Eie@ed|2g_@BC=uj~rpgh89e-q;jA z{1zh6u_isVJUO5@TSv#Oy{*dP8p_YnX7^#!8AD`&>u~YXrKP{E%CoC7agf-`H`Wz# zk7o-Z=EMP1lJP*xgTPblwdR(y2muUEK5UX9sNURP9CuPtnIq>w($?1Qh1-YvbT;gJ zzU3YO)1zn3(217b*;q*V?8vnPNf{(X0e$|7Okv9rQDpofiO^7h_-)Z8hGXth_bn0i zOT@;;2BaGBCKa0q@xuF2QPRLgBmx}5a4~S@Jg=o&K4dJM#&><3WsO^4#N&liGL!Q98$F_>A z35F=Xf!Iex>dDKvsRq70&+=XvR|Qq{_f^2G_kpx%eEoV{Hn+X~te%W~ zBlj`b0=?5OYa;zZ`4i*!JWzW+ph1qD5TDy$3&?AdFajwK))(X1A3W!96*~gJn=Etk zJQ-HA1;r5gR~hVzpr~yAju%geWYt#6eWWQo=vD}HD0i7x-sCLrk5-ubvCJJrNTL6V zw*kl=J$6hLhab_lcKd7s%%a}4bzCB!euxg3>xb<~Jb9w0O40pK2*X8B4?@B~oSc!B zRd8Bbn%n7dXqACsVU4eo(4z_8{$C<2`yd+3rf~1THy8xKw`>mgcD;n61iVfb-Z4^S zKfId+H4Gnw0I8w#Z>+myjg47J8!J5<#MHvf30>l@uyY8I1?!sNb|fNWl+YCkMDOx< zM#z&huO1j=aCWZJN@!E1aI5vO$I9Ud6) z1*dU4J&n{hQDAWsy2F-r?)z;o$R#t{nLR2imy+;hmr?~i^2rjXw zL4%%Oc@x%O6CN2Cr~7R9u(aiUVd!zMQ1eCJEd2St2aJ&r7UzP}_Ht7QYc{CH6l8WTko0f8_^V|%;f2%J$c zBFyichusJAoD2z-2u}AGL9O92t)<4W1Yw3idb^k;mVhT4kNw7L-FXH)xNX+5ce?cw zF7WA%4YAbFq=-Na+C}lasOx70NR;7rLL$Rt4g#7uxB1I@R7`?CFp!9_uI8FJ6%kPC zDf4`;owo@?1|TZ2W92(UP91BC7fM?X3JV(|fEIu{fnhx5o+7J>te5uMKs0qOXLRZy zZQ6giYyTp?2FqrvuV1}tQ>G*%1RR~$*DOVMIN~`G={v-GVzh6f$W?y(R#cH;XTT5P zf*4F_T6G#g%vuGy8lHiM4~|l$#w)=7*Im?T2RE`j+PUx-jG!qW=Ep^^-+UWi}r#JDuGuuxM|a}U|PO~d4a$o?v? zRYp5(kpAh_VhRO*U}_1W3`&&hEa!A35kd;CqOxs;a5AQ?iJC z?&(Q-`I3iNPXrWLSXipuo*R(sA3=sA<&cO=1u90C$`c|g3GeJQ_&N@g3_*v&HXt0x zD=KnTJ(nT!x*k(xD35H*-|}m_fLLIhv0)J!3T%*m1P~;GtLWjt@KrrM%;x6i*d_`r zS6B>~AfnkjqU(ijf?N=TqXa`s4K?{Zevs1R_D_U9wDT=mC_ib7jDy$_30uq!5nAPO zT>~H7)t6Uhiq&BUA6xYmmzS4Un@m9(K+@C~EiG9!i+sn9_f1WcTg^{Y2D5PW1<^VW zePR$>`>RGMBB^$&zkrdGn?&U2l;7Fv9~lM&OV=sqRW)d$!fK5G7o zLr&}k2wvMU2o{B(j{~}owY!$P9liyyDy+N94Wejvg1!@2MZ`0VUh~f|p2ctKNJbWw$Cy2c?`!CH{QC(gA zz6rVu+@1^&kS1O}6}q6*m)2eUkWnM8dd!nNW!2T`FuBO>hxNyJ0zp<7PSc*lbmFw$ z;OZBy(Jt2Ig~=vVwfXqhv@&_XAbL_#$`laO0P?(UGXy?3tjw@O{}@io1PG=juAEY{ z3+f#-4NFmFNfG8HXwrm)2D=qQp}kwLu_-7tM%>3n-N~>c0Y;rmPL5%DBN3^CX8cIZ z)2*xqLpp{qrS2ssC(}Pn;E*?R);&K_IC9RlUVem;_=vCn9d3r10t9soRU9y7$o2V7 z%2GX|0Krnn7!=o35rh^KOUnx`E{l})7e%N}n;v!W!?=2}MdU8uX356!A$I!0w}=Tq zp8~YL)c*}SsUL=nX_%N+CGF{!9`l+IvjqfA^E-3^<3!l^F!sMu)?O5`!DuBRRhNL( z%NWqh2GGm4sM^`RDrBMEV5~|Kw3UR0r;hMT%EC=lsHWi9DLWsQ1h*~&luho3|`_=|Wiz|)pD zHim>z1!xgH%nRBir$UD~=B4?vwAu*o@_(6F| zl+sK+Gbm#A7dl9-n(RNaP|!GRF;j#qAlMO=?1iyaTjqO&1Rx^0DSZ#@<7`ZbVZt+E zW`zF9_ij0xs>rgO{LED+nJ{ z!4dkv!^?}*<>j=)#jdl*Kz@iA;PdAvbl=!t_M?0C=B!u?>Fzo zjyKqX`4x&Yu<(fV11$IRpu5Bet4A*S1JW=US~xMTUa2VGZFV$K;JB`IA{rmjeFzN^ zF^|e0KT7h|Xt{R)fWRP76y7yW8|nAEauxy}Yb<79F#nxIjRiyE0oR>=fU|dmh2=JZ zOPx6T*cSdq5E%^xVYZZh?3!k1w6!?77ZepE@5l^Xn8+u$77;Qvy?OH#Ht8dT3fn-g zEHRq~cPBj|$R%(P%u4bARs%*!_Pr2aj@{9i3FjvR-Uq^E=~)9s;NrpH??GsE)^DR0 z>FMx70&5Uu_3LYx_{0&*LfgJQeMC0I#c~#}w`k(M@r?&)+|JrtV|~q_*lz2A1CLe5 z4Eq!XykJH_DR|MZrmFf6s?x}(BM1emmk&gzSoKIry1J#=VIf3)vHd?U>|a_q?(iOu z14>e3!M?E7mA$!lFcdKjd@!@Nu+h<7dapfd(wpR+JMr$FZ#;Fs<|$jjoSJ^8%b|)! zLxFl!7bU2Sc*Ps0yoLxyX&owOI zj{fkcad=K-h06WKq;Aig{$zp2m6dnp?w{SGJ5(0hq!}EQb%~g*-GKa-ZQIJU%=Wt* zqHh5RsI1UM%+{Tez+@G6Vn&2nBe&IV7)0THeZ~a~*EOD~9uK!P3gNAOc&%57(ga_e z+2pLdA74DBDQf*dd=Xlau&)|lSZ+zIPC9!aIy#!;#0mAc7r)2ThpcJhUyqyW9E+6D z(puQl9+3C+NMxOQcQ$4*+GEx@lyxzQKq*0en0!-yett8Kpy0W4eUSYwy;_TpXCl8t zg4Rf?Kmn;*t22bXxnJ^`w;~q?ojwt4kMq3b~t*e2I}$K<2ykUx&XP zc|t8pJ+@fK>BtNUJ4qLsOahK5Xnni$F? z60MMYG_^Buz^3Nrwvs^DjZlyv##IBPG$W~FTMF)zQdG1b#q0ytUv1B4HYD-ElGOWd3)d#qqGlW}1wW+l@^m#B&alSUxzJ&GAZ zjoU%0>Gtj=43#^FD_UFC^t=aZ?^AD)SZ(S6)c~gH^j>G?G&CJ+gVtX?Q@yQT$#|q@#QE6)+#gM7%pZ8vBFeH(%!2^PV?f?s7yC^B` zCLQMGrMYwXDgsEPXHO&Ow~(Rug79u#pAPp9AZCtsLqEZ*ZFn(56au}DaSrKZ5g3LA_-a zFG$Iq_QJV=gSedpWjfVGNxgucM5x0r3kqZqJb?&tAD96f#^}>SUUWhUI19w7!)J`{ zDu;5sjq1=&gi2s1UxlIJvM_Ow)C*6FdJ7rI1+G#B+p0Z&$sfAvITE49J;WF{fRR69 zmc5A2;hJQZ+kYkUn#hK}#Rq<0S9jr4KXy3Q>IqT=5}1x^hAy`{ZsSel#J!+(asAxD z7Qra4KR(^ZA3yYNWQ;<0`PJXQ8TbIjngm8Dg{TG6ykwbT0%+QT_Cq@%=&%iGslAGi zjlBn0{;|HE0>Op~w5N#2kF#GMe00$tL)bjKEEj$2M#>tM4>Ub0$8Yx zId(){uU@|%1PSfPsZ&aN-E>QuG2)Kn>2){(rkicu|BjHcv$M;mtK#J@uN&vWnZJ5rQ>(43lYkBh?X(wE z7wJs^pFsMn;7uS#SIpN2M4O3N5_HM^JXd`d4WOMNW3_Yp_U#Dp1e7`!0WE>k97&r`EgE&YP?)rXA%r-oEBH|$`0KeuQrrHn%gk#`~ z8*{v&lSont2nfJN z{soa=7RQVS>QPiwR6va@vWEySks)MNTVMYHx+qfGJ}{+l%25*c;1U{cxtU`{Q3W<8 zKa1_RTUuJ)a&)YM8*gN4>I;pS^ErEDT|{K$U9@%pw|?R`U?GUyeRNkMl0b+K+YZ+6 zjf#$L*NFwI??cUiJNE&53Kq#$)MQC(2FE2$=dx~ro`T7LZEY;DFIGlEQIQhAL-TDC z^5ZNgPV9vE41Ik|P*4yLWVThj9D@{htfzjagK1WO^V!Q@US;)W01)}e5BM$M1WA!b zFpYM$+YoLBSuz$y6=S+&$r!N@YLE-rFG0#IDtd@Jk;52+x~i(Av^3ByD=8{6QVM^v z#Rp%$-=}D~@*{ z5G&6aO-pl}=?dgI%x{NNP*Mg4aBy>nlbW$x0|Nj&!T|azofH%m)1W-708ZoG7PKTg zTU!==ef>Bw&$rqg8OlktBu0$7(9rn#`cjk5VWhaUGaI#ii;qExi-fc^+6QrW#l^+a z(s-NHMN%#L-|zX-k`i(f)SN)aQ3&lj?wpsAkum<6J)HIy$%z)kXfuFiko_&_bByZJNR*rpIZmu%=1O1zgtXFz#MS*SR zOHg{Y_`peF`^thi3TB%0)5M5@3$kQ*8$n}rx!y~~ISFSmA+_l|tWb8=R74p!ohL?F zTuL1$yY+tmP}51fj6pLnAI2dE}!#2O^w9lX}x>FIkfq|7s^Hd z{{5{+(g;5>_5j5jkyBPSwyk&zM_>Q!t5>H-MmWTGBAJB%;4UN>??9$}>oiUQ%t@+1 z?2<%+v#kB*=0TrlHSNlYB9?8uaL+Y;QE#{VdguTRBO?WDMrxWwG0z|*7?V-1 zk)u)hriqv$5?DKcwMjleGH8*=agazT@-JV$B>Y}dMR)fh#3s%b((Ku@8JZl1I#M96 z8T80!D!VfP=?<$>Z$YowPB2kSDOEYDucgO8LrHr#* zG#-vtn1=mJAWfo~B0E>fODd=v<795*5YNSDq#dIoVFZR#Tp;Gn7`(bFm04mrmLgYR zU^b)O!{svuR(}W|L(t-_&^4X)yz_JJcVCrTpcL;)zRq*av*t`~7o-Xmz#JSJ(lajy zdzj1=H3qu6LD-B(kfp#-f}Wv%OuK%X-KFS3yn_cNDmgV(@)!3s7WP9+i^?kMXelw; zPC9RE%Zunt@91a{(9Cq8y7k_@d(nF#^GlR&OT&9*Sb2D;(VAt=%-C?qTOckLn2ko- zm<^A4YLshfXla!Vir4CDYWibu^aH0>p{h+ad9S~&c6&BqP7>@1{aYt?Na4Z-3E0bo zbRoX_i>mLEE(Q_CYL!JugrNpgT>>o|*Vhnxkll!26I2E03>8RWqRku)>jBH%M#9UN zSb>faFm_p-O8L-#zPNJ^`1#S7x%`5HvFBRWh&%gYk{%lKOH2ac-57^(=bCP5lg%lc zXJ%$9ZA?qR=ulAls))RINr^~QOw6WC3U~O1q05kZX+dFX(2EJp(XBmCY+PgQ8@FLu z2r_~@_w$e-`GR0wezyjFmE_~XyP10XuR8Ae&J_y^Gcz;1=&uH}QbHQhYD|4ax|nza zh~0g2+*>*!Az@eY=)(blJDmgL=dQPL9h}G5q6(-C>_nzJhciDbqgoMKIl2niQ3|wDgVtSb>^-B6T8?vd3oC`C zCF6+45m1PDl>+hlzM?XXpG~A&We0wzIq8Nmi-!@QsG)%pq+mOZ5eCDWTUu^o{1-ab zRIc|LC9ELgtwwlWB=uc4q69AEG!w5nvz@}>T6;1h?mLRfX;PrHs)>g`PB$@=3v9d! zC%PH~?hy|klJ{;5&j~t=P@{bNPkR$0`dSr-2&#Y^-;5i zoDQNtg}0~?N0XNs-q|J+^u0ZJBOEaUjfe&>8W-%mj>QRg0#N_@bsLkIy+~uLxT!RR zZvd{qn#q1$dOb2J_rnKCWFsi?5+5JnC1_hd=)9aadVc;qh~iDW`i%x<#>a>Bqtu-q z*kUc&{`tu0XdghY1k7w;%sliX_@F`K$2aD6q!7j-WxCA}807?BAuu@NijEh;Bt(l9 zl)`)>-ggiVgNk_VghB`YR|CP}aAe&}hu^BU-i~HVXcKtg09LnUO}~SHKwEte=${Am z9Z2&7A{#K0&L%#`kncV~vOChO@9{pZ%PJ}Gqwm?Gc5BFX@0#if7L@Wf! z24ej&MsyyZ6q6fNB#Qpsz~v!03j~lwHWdB=y|CcSDiP(v)}5N2y^CcGAjdhwQ^H@w zG#Apacp*_ZD%X#9&bf^yDlwC98#`(~fsEjNTEW1sNBH>mpk-^hJh+Zw8Az;s;8MgJ zKj7YlBg*ojqJreTKAR*iUpBa8b#qBGA}LAv(i~zr(Ve^}XJRo%ABy)5!2z{;?u^rX zy{qu#qqw*Sc%vS`3Ju9^W&R}Ui3$uS_j0weDkT7{o-{XiWCb$Z^IOIRy67H z0udxB)M{Ubhlfjg1qTITEsLu6Z!Lz(LrXemHxTfJ_vG8RZ&57RXJ%*9zI;(-Rb_fd zG*+PHbE00WMb(An%cES75RM?O7KE%?&)S4@8yE~LE3B?P7!DvtYSAdd5XQSm8|Vu| zG|ld!;y;8ufH85hbAi)r_=!`Q)tg|D0a!`*F;Ru_SL*x5W$CKNPa2dwL<+7BbEYT~ z#|$W?FU3xFE~#}Gl=~4dt`+Z)fPOkQYECY_Ys^a_T@~-ZILvU6At%Ztf;)vD(GL= z_Z+}G0sfBxr$#_MJm3fyXlXKVovW>wPQ-_mtAQiLQoZ#C6F2fZ{1eRr@_gIpZ!rMU zKFS5lTMa?djn=xr@nwn29KLqTRDlCu!1B;{Z{)EnRiB=89-4CdRDs>i{JX%In({9| z{lL%ES?__nE(Pi<|JK$_Xxza&=U3~-{x0BHw&e5afAzCJ`JD!K9xFd7f4g{6efnzd z=ac_l12Tf!KA$$3TT`_2`_W`v!`Sc8+~xSZ*6rgeE#T-sQ*G_vW7j%2eh&%^Yy?&! zOHZd5Nj{&P*#jK-YSjU9fR#kuA}PabB`HQTPgR$?y0+fhWCdJyzmMS0Y}PbjZ3k?rulnA&>L2_0j?=SP z=Lt?X6}M5=%RX1(7IRFh1Ln)el7*3*4;Vk%^sFiUNa|Thpkm-a{Ko&BcOYZ-ZUo2d zTh#ua`V8!8SAYWQYI%|6IrZObgUxr!JfEJq>zJROdH{2}R*-qGJ;T;w4&cDYiIh!l zzV2tA?%cEL6XQ+A3q#pPv8kDWe=XG7NbS!lp;i(-l0u6O647^}9olaNcHr S`vG_|JcFmJpUXO@geCyRr6^ti literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/classes_decoder.png b/doc/src_intro/img/classes_decoder.png new file mode 100644 index 0000000000000000000000000000000000000000..228f9bf234bb0be5ee57ad83961a546f56fcd9b8 GIT binary patch literal 29753 zcmbrm2RN7E-#08JMM@%~(o#tFh-8Jf5fKfWC}brvQg%i}MmA*?MG9HTC=wY-WXmjj zulI9y-}m#}&wISjb3DiK-pBv`{~P-KuIs$c^ZWg*@8zSSbdrvSm4j zlqvZ2+=lh|?>(uE_whd)Z=KSzp`h4YM*e?I=;6(5_$!Lj^0Ml8qDFo>Tw=0YoEx8A zc&*w^;{?+5=?t7vwWf9RG?3Q4fx|MrC{8d}#utYPJkd5o_7;%%$VnVU=eu}D$9yiO%%T;sC znnsNK&vbKK`)~h|Djs*F3fL~UVXr%V0?R2kZg+b8`V1qNiU;|Hyw5(WH1Z2~PSqqC zrhh-i;merv?-vR3L6jHCKa>mMjQsKA$IVLF|M-b+qlQm1%M5(u|MNdO!QFif#s4>- zbRmw0e55x+dE8Mpoh-wR+ArUhjQjZbkPll8?xx$cX>4kWXKX>G{>~O^oNjgl( zH=AzQTeV^E!T;wvB{XKed)J?ySyXSwiWTw=$3l7U+se#b+4a$jc4us4q_%qtS<4!- zmW)0rDV*DRuY{Za3_Yw_XO{CqE88>U>U(_?lgi%DkDK)0xGXR5=oIZdd-m+o^75KX z?{6PDA1NGv{;B92(*{q2%7D~A^K)}!L+P3NH*QofjuvOO8@Y6qdN6y64gGk%|L)Al zn$8M;wyD7eFA2M$x;WXjZ_Qhu^S(2x-X1Ax?)&oPkx;@1Fbtt*6>~{I5qtJrRlGHkuAF=br+@v-90?M;i`+~f3q!24_9K9 zCJJBf>#tRQb|%!&Pkpa^%noeqzFZlL$?V7B;od<(s&4w#S>E0oUc7wS)Zy>vm!eZF zwY)f6+0gKq`(j$bRFp6)-JhR1J^it+U+qUGTPI&AOU)YH=J5vK&w{PE0@g-8^;qK#(6m^+8($nvg&W7>s zlyYJ@bm$PHLcIMb`Nu&aA?~rU?1hfg7XlyL{_|6{(9w=^?b_3)PL=%p8R<#K#=y+% zm6*66i*Ru7UbmBhyVvl!=x`i3aBF(#;{68?T5_%SZ()~8!at2VW*?AtF+Iz;hIL`) z&%=m_9adIWw!`1)?(IJr(An9k(%a#>d-v|4mdpN%C#Hv*Ok3X`X-HO1zB~JuN?TJ8 zo0)=-kB^d)a-b#KB);|TTN#fpv9Tc`Ax_LGRKHfqsnS{Kp-a-lI>q{xj6uk{tUH8VDimCjx)_hrHYtJtKd#LGSJTUnmf3D_wvcj}Zk>tyfe zZ8@DsGDeGiwjI(pH?Qfd4x7ih*|2GoVZ-zD1+(pUskCExIejPOKA2v=9{#8QP_c;$ z?d0r9QYz277A#GF56ZV27Bs42EGQ^A>M(KO@87>m)6F_gEA#ynlFkbufl><_4j(@3 z=kGt*l+G+>*}ks6R-Wfd?xXc|th)O8a>+{38@6oGY?ZR^-7qsVqn>dk0()A>wEn5Sx}S;KQWiVo-5T{Ta|Du4W7xpCu0(OfsJ$lsOaML!mS``S5XWdC8; zRTSQx9h;m?yqK;*G4-c4%&MoNFWZPRYa zaMOn8uk}8zcUhj++(btgA>}L)$S%EpkECSO*XUzvdDcclP3e`WXiYzC`oDgAd07mb z*7w;n4*c%os+QB-*xtv7l%Jz&s;6F{x_fu=oLI&(uI7zpM~pAi;d=aozwL!jxiXL0 z|Lq(a^3BT=Z%Vsp&|T(}l$1ol?>I&7_43=B9~v7&qL0~cAC_W}3$eTq_k@Dg-xJri z=GN4JD#a7tt5x0Q4|j-J?37-a+u#2+TJ7N*lqNyf6(`4;5g#0T&CF}%pFjIl2D01y z{<6bydPo5!wWz45VDaz!7gyguL9wK~g^Gvb?~N*q_3!`j+8|;jCHANlrKYCl$jHbX zPRZ+6uXH<0+zuQ(sDJ(Xh7zo?Ltm)o*u=zz9)@k(gqDK>y}kFKda#LE@L#Xnlar~p zyf96!%XN90`BA&r*l=dCG5X_+D|rmAuCDD4{kt5e20plN+(vQfwLVq0aZQz7tKh`t zLPrr45bPB4-4<=RvX?HgP*88#y{_cfuR@mg(?QXE#Y+sQ_>|UCQZ}9)tYs6vPEWR* zs;Vl*P6=CYuPyBLscMII?%bJcI~eR(aT{yW_TGNWJ?sbrUEPxT$^JDPHg7&CA;Ee| zx_aUFQ_C!~Chq$B`dsTinwQ!+`ve714w=#8e7wCWI`OY^b8}NXx~uDwPH!Wtcjd}X zJw3g$ii+;u-m*Wf?>27UT+!4Niru?)_wKKWCj$q*B~ml)X=plnkyo`bquP*{kn`sZxxNjY!pQ=esT-n^-lZSzL=1EtZ*(mYiFUpm_MbBZ&# zZ=v(WI3$#uIEtE#3aaQQFVxf2PoF-2{vv*h5}Ali#&PhV;_K{ewKv)?gTup9IDHeM zj^EX2d1o1GJ=%WU2pf_n4jtu^`FpKwV_(HY)!ouAFZ^~0DXs~Li`%21%E%!hp}i&q z&4J4|fpc}f)|F9azAsD%-w;w#B15Hur3}6N&VuWnzJbAH>5Sp@Pkc7{srXHR4Vzlg9&e$85xtD7XQ4%r&b+`bxNS9a$8G{PqqFfs-vSr zrBV^FEB)&#juewjgvgC2_>}r&W%g(K<-S#T3N%wIp+?yzwHhdqAt=;bfxC}iu=th# zY~{+MWhOSZbQh`bnL3%mH@=^H{pOAO^K%giE*a)GZ#K?~eZ)g&I(F>XGrfRRq{27jO72r@P@6~)x+!I;GCr2(n7q)1-H2D4HQ$d4@P30dx$c|4=sxfjb z+x*NnQGTZJQrkB)G;{)mG{xMay+F&fKFOyZP@??nSEZJ>=1(JCWsPQ+#jJZzQK`5r zjaQy)ICL&Nj-pDe!zs~edAgY`XUU(RIdfs= zPiu12Q7gH;yR#XToVz4!Ra$?&x6h>H6f*g$9ykqHlQt<-v<0m<#Ux5f=nf%c!^Qd2XU|qQOYwYJ3A^JHHdoKiXFncB z-<)xEZGG*!HEjhBkAcB*q=(Ssf$V{G5)u;lMMN%ImR@f!5XZiwuIKxBVqxs~j-l@_ ztMhF7y#oR?_;QS2paV%nESMVG?jNXsM$782SZI3(Xd_42G*Qw2+Naf==4%Gy-Q^L_ z0ZIark`6pqiaw*FLJzcIc2_x8>SArMQ7>g3{_^ImszvLQu9hV<76r5>Y+QEQ?L3{R zVN;_W#WMCu5AU-H8T&a>b!y>M-qHJsk`vCaC-=lTT=2J%QH9@*FW~|wmX}-Zpkrcr zvi#VNI|^e5eVu&E=w%YP>c=aB&sFpKbLQ;X9u)l{I-ebte(~{p(R-*>-p@{{X zU#?|eto`b>dTb_er+C6{cCB9{p-tm_?(_=hX&M=1R2ioku8y`Bu6gz5P4D-YmzP!+ zMn!+d#L(1qV+oG?tDKyR$xkCAgQKE0Ju)2#-(+lTJj7mQQWGo9E-fvs zk#Xg72$$O2Tu&e;*FymaY0mvPW zlroUhAfD;Hg+TTscJ@ct-bmdYk(Op(8ND-tKL)6-7VUTu;0oqpR!@ELB<_SXfNR&T z9X)#Vl}YVx?ROS6t}B!56rNkyzkc-EGCn&CJ?fLWPBfs8<4L4^_e%vC>f2&glV0*A7`w*Vq&9>a2wbYwC z!63_gwu#@J;lUqnViooVsF)Z`jsxzA7Edm z6EH!0^5jXS7|GLj?i?lk2wg;cd%D~P)tkQQTim8(Ykp2Ti%w5ZGhyG8V{pdFsUZJ~ zzJ3C!V$ZG>I{Ip)Uu?hAL&qU3{IB{bDQQR^KOPFCco<~Xx3I8~0B{jeets2nq?Z>` zFL0DsRh>*}&o zu}PnT)s*ZJzxtiAm)RTrG()*BhTuG9`MklZXUuTliR-hF*j(^Md8Evs9%REovWA-+b5C%(D_q{CFRTl--`o$!0j!UVkiJlh#Da%`0wDPQaJkdv+si$$|v@EixWJ5{m zP4H{xJTueWP9qc$8WzUvoA65a!+pwfTGbG2txuo>0QAX5)lc%3lI0_XOg2|kR5*=& zpq6Q`l&w)Z&2my%a~ujqZENe(+}xvBBkE5_Q~uGd+&d5us@|Z2Z`--^3;xE++B&#f zo$&`~2^vcRj#<8v0)z(1e?OO5yb=lS2BN|yYT5o`*jAqFd6U@=DW{`^%0A>P`ZV(` z6M6%UGL5?G^CLP%QK;TZQAgw3pYh1cHl}L^0wBKzj&WICw#RcF8yiy@eZh=vX-jkn zZ>Kvw{$fACIJvmEYzOP9l$Di%TfWpkJKJ>V@e9zp z*Okw>sHQLw5?vwJBKyGsrQfH#Rn& zd+;8o({Eu)KpX;%<^Z>(BL?&t*0&LE1Hvwju9x8(bi_gZR5gx8XMI` zE!t9)>~G&bh~MH4<>ch7?vfX93LQOZGO2{zH2 zEZQ%(Z`-yF4e*&oH4c-2pkQfP**btu3RcmZ-bF=H+Ap7g66?1;#i~eM2W)!Sx0Ubg z6P_-dp`nKJ?(`h3K<&3~-6DV+o9}{}T9aNdFf97oeFrJ(Bx|rPydaapH6f_9PXSQo2*%r)A)NXndWHA?6%^RH;w0{ zL1h^j9yYjs-5XG|^0hi6mA$=vj*8RFT|IymmK{6v3=Km}9p&ZM;q>t_a-fB2Wk{oS zG>ifqsApb_K63f3Vcyb6OLlgYlfFJiOMK(UBqW}syQO(>)}S?0gp1o8d~{9MuZD-^-Xkd-jZJD6kFqcpjK+vcSo-WAu^KlYU5|L|COj ziR|leU2QTl^U!!C6sDD`5>E+aPHwKcM~R5GT)xgb8>5_NT1<$11?+1iu9Nsp1snym z?t}*o(;YCQ9XNzgnU|I(Yq2*&(eapZ#Bnl6xuy`aXw!uZ>h9%baP#Ju0*6T!aq9yV zH<~kyP|0!Oq#=RaC<5)T85R^tuN3FWo0fuR9c8LiO{{-$hhl+e>VTucQ$^bLmhC&)+1byXJNF8*HpF+^i zefuY*aXF@8VW>H?HtF=^OOOy^T^9a*_}{iX=%cg-1_tZ5?EZpQ@c_8%gy$wbAbR_qGDnul>xhe%+_AM ze7Ur=G}n1i^r@&h@MYj+f9*Diuf@gEeba_qXj3R z80X&VqJ-SBgl&5B=bMeEilh2RM{DCxc+GXJu6TKPP-$jd(F0+K61VYW6)`J#b)57m ze8tdV=_y15j-8P!{QaQcJdgO;d#+AI%S9%}4eSEs+#(PkNSt!74C;;@wXJ#rs zeey;ROKJVx-(LwrQ1`$115l74AQ^&vrLgvqi}4hG3Om0tLiPl^oo)a3I)|HCk_sdz6EGqsxeOvbBz;}lo%+b-&YlSCC^%+ z+0u{6$i3+-QHK4xR6lE_i4<`-4^V!bgMwCYn94ugyEBUq?)zsA1Z{E3~1isE0 z?9%bs*~-$=`>6d+&d%Si3zI{!W5;Q@YnO^$jsr*oaBaEwuHEq=9u7S#>lryYN;+2I zIB-ddqsNZnW_D5h?I^AVocK}Xd<@d!nNV&4<1Z|4EjzyAj`5MULybO~*Bq!$xjKHq zMp8l-o+qkVTg>shGyL{{uK*kXu%N}DX{X%gzHM(00k=2*FUqWt!-OF!=$e7=FWEkP z_`vsq@7?V)-7Z^bXsT{IlO2yQgs7g_Wac)N{Zdp^RBJ}8siDE3%==&6hTda6`TIPv zZipHNZ93(z&8g8FgT1}-s0yIMhwEIbiRV<09zg*G-ZLjhM0$CO9PutdDUHgrz(RiiLwf!~e%`J;1brsb(u)}#~r*QI)eCE!o3w>Nh{Tp^GU+RbAWsfPFy z)YC`dXBFHTq#BBoebC4zOezsh+yDwlh85W7K@JWNFp9BCc2{~PCJ#tO64C+!L0Fe` z=i!*+H%yI<*UOwcw+YJ=@l!-dX#c^3p1r-j%rsB^a{WX*oF>oPT|0BeSAx9+EM>W+ zzMcUdo!#B+))*6;F9YYIRO5`_gtg{p;sBv+L+S>)P%cc0ZCbEy^&FXK>~pELaNZH~ zYg9l$0D`~a`y;5;!lw1^5V&67owaCpSu{uMY@(c=pWQDgm{qcP5bZgtDdw0u%-sx<>srswb90DpfvF#kis!Xf00{%!k=(tQF&w5hqe zX#TNMR?9VFF-Iiy=#}j7dBaAfy3Z*0t7Op+@V)}O6 z9Ul)6t2wsOTxpH)j`GtLI|}j8k5^Yu%M^JjL*f1uauy2>=7Fm>G2?q@_dYN0+q1LG z5H~#(6T2QOOYJ>ypx2{sB8yJz+w^~|TgRw);TC*%X?y!_a1N|MxR8m`^LhKfZK}2R zJBnS|g@m#xN8g#WI%z1rr{27?1RU(uD}K0w5ZCT@-E7Kk4Q`$lm!4RRV7fKYdpc)N zq06!aYHw*vOT_eWv)W5-5xcxKYuDfE{j_zLaoVxN8ZYpuqp)eay1VZ`d`SDqMNu?S zHyW((5V)ZFi`(cmDke@I^hRfWMjx=Uu~oyf8=ILyV-}$xB_2;UHS7qxv#m0o*Kc&b3W zm|kDt&n9Nw|8*DOS_OKNAX75F+>i)J(qetzP&%5Pt`UMjPzQ}wYGuwq?!*aI#(z!j zVp9M)+?Rh2K4Mk;D*>goCcR4USq(HT0MGbfDs>TOL73v zV?S4p{hEwx569$>7up@X1CnCdk@>`_sgQxo6Lx zZ%>nHv~z;q4-H5cQIRiC#WH2gSy)(zwTX7E(JARp|4a=fj9cEtcA(BJX#dHgx~tu| z*T#&iPXRw(;SlV*919qV-|%G3_^Ls+!I?1uG{BEsZXOKb#AcZqZVr5QHf(#YKhii= zAGgHxKvsnwfiA4*)*T%c1?!!s`vtztElQTj=<7*#=c&>+s9`oJNjzciva-0J2t}hS z-nny!(cwLn5q!kYj}O^JEBc67wo4)jQH^T?-cc^nSBBtv?wp^5aps&fu)yzM_8m3$ z@i5E{4=TsJ2}C0OiQll1)YVn?bWlpdaY-K?^+g4Z%56o&WgQ#d-HC|Pq1+j zdAJ~8e9)cq^S^&0xgY)jijFmiuH=!?{(jQ>uES>(Fwt-{lDzHk>CxUi-bIuyV8oPw zmptyAvBCh3<<`uVpkc(uwL%st;I{|80$PLtR1WPN;dT-jMC(*V9&D14`} z7~(EVM`dMYhdy%0ga!xSPfk7rkElu3^H~EZ1qfX6~SIDf9bC)5vd!0z$X=pDi#Skzeg-zw&S^T;LJcpxi1m9Z{hQ5bUUq#B&4Mc)0 z3&z(&ws+NQzie6fOlo^BMA9Xc1$R$RLHuA?^mF=zb&p6M?H&$85IRD({pdACKbCl< z+Fa8iEzq7GEQEEK!OsfyYfe@BVPq7ZkWNxO4cXk6jtuIX~KJ#QpC3 z+YNzM?w1D-iSFe;CBkuJ12g494>+?lH#-r~;jANc#Y0Z}}Ux--A>i;}EYnww3WO;OG zMRce<>ptI%hOKgp0{;|eML-k?QUE@K5=^S=DgxQbXQRhzZN3UIvyiCQAr1%`g+F~N zWYsOdo##><)bXum&t|W~ zl0Yl*c>P)c?djhSpR#5yrcZ#3abr6?XpVjR)&WP5ZF&yGf zPj$cqnw`-F)LEDc>(QJb-WSOK2SEeRGDRQ@u&K`OjGQ+m*`cccHZDm3MF^P)+WbBT zanjZhdAAoj#W9Erb@uls58Jxa&nNl#`(Lz;h8oF8g~z9ndF{N4ib}+;j~9D8fC?YN zi2}DJRzc9o^=QU5w~Y~%K!(eo2z_Uls(oW69R!gh>qYmGz?lwfn?u#^?CCiHB?%Qc z35ST!?q5jz=ME(27i6tZ-TD|eGU=dM3aX18^ zqma1U9fyxxO+Mg$C*a>__oGICEGfB1bP=rlg`t=4+T~OkqyDvxUMQ_iWHC)XnNshS zPbJm?v?bGyqT`VI>+B>FHsRKY$qVpp1u{!6dT#aK^QQq?C+g=&Ti#>)4rfg~f5F}d zTck>mwZZ}F?&(P+D^HYPPAa4b$|16xI(IG!T03qhL>AdgVvK?z!70tak8;lb``qhj zc|f~cSy|JD)#b%sAz~R79sN2hs~fwl!A?RhJN#-LB+9)_N7nz z&vOf8MVt&AzJx3P_UJwUTtU?7?R?i>46D0;s>i=G{r+MHuDH>T8^_MtM+avIG~k-<#k$a5XNVjGqUkn%H%yikXiub7z15)ci1LMtt{Vf@GO;grGwH zxc5y{cr8p<5ABuL%Eo7bDR?9%CT6H{X=Yq2tRfUtM&@3I+E$M6ow51$NK0 zxTIp4HyS-^aOHyq;ju8P2#vU);zo}4&Rx5-Ug^rZHSp zKIENwt0;+l-0VmUUYZY@3){x`f7INGWdK9qzlWXSTF@t)1C`tljqQ+fOk8GWtZB^a z*WlS)j31JP1s!@L{y0U1A{F5?NZv=+eAmP@8G$U_t z%g(MGoF3Ic0KEfudT;8ax0x{O+nX)-p`IWlxUPPc9(k}xc$wHuv&r!<*xe6zZV3_%#M7)-mJc}l zNxi8gXbFtN`{6@^Pk;QlgwjYfZYX}a`T4~EDE;`+VQOIOamOhl?%r&D>kls7`R7j! z9=O|-^o9RTGL9nm{rhd(w^x9TRl)8@5TqvLVS4&uXkK)XFpS{F!k}~mmfJ}IACltx z3#|tzKcJ~p^^3lCqwUe`E^}@;6ZAWFd`5d401%65y_RRqfqj~cFu~mXycHB8TyNuj z3f-Oxf8yT2Z^ZRR9KU;8pny%zP~&Hy@;#&?w{6|}0b7|O0HC2ASvSmy`i7b$b?M|Y1F zE%HLtH~w&+3Q6PFDAxE3$lQ8B=twZdg18WQp9C85(+E;O0|arJ>+-^Rqehq-dj(LQ z8X?~U$fj=IB|+*p;2ewOomY_`@yUp?BmnOe00M*V)&VSFQw4K1qm2mQN0A?FG<9B> z>VhVNgE#T#U5CD*q5I>&a|NaD_eIv7D z?|QEMhug@x2E1>*3|UeVF-9jf05OzVXn6<_399^(mwM3TJaFBXxN8iVI>kjl!I16N zfXJaiDJ|obnk5n zs>CM&p{cB{ekl83eX4`(-^x6Ch0`?Zdu>Plm*~_9IM)<7dY>8ttAG3;ow0LuaSd~q%ruwBhbYBqeQ)kYUqHIHAB*Hn!X*zG>x9eFor@gx`Y!6VTrlv+)BDrwz zPhHp$eh|>W=WSrJz(laJv%`+#1-a0}=m&g(qmEOY#G7c;Q2KXEyyLX-YhiQXsWY96 zIvRv73ETe0_ZJ`Fcfk3C+)Bs-$bP>Uy9>z-ucM}JKoAl@o8&r(0*Y0F8UNV?_ zL7ak~3OY2o0etauhrFCWfB!07xWGUH8~pr_w(eJiPL&$N#n5fU{jl;-Qb)-fba+tK z2!K+Gg9i`Zgwg^MKM8?{OgE5F4V<7;`1eB5-#nrMZSFxwdX0Em4y{tfXzlh^xn2)h z$U_0Ny`s`$ASitTQt4+cYpae<5|NPPrVy5DdP;|F^c8+txTrZRm}(;8PoyZ`8Pi2< zf<*pFrOnSLqXSSRDqyIt`2kHG;rkcbIleef6R5Y7Bs&_m3{xh+%ZnPJ2&JOztJCUw9nhK#;#63;mfrxKBEGIB5n zsgwwI7>WQ2*w23V_*EpeBwTtXAKb&E?7tDWQok_&crL1^x@SD%LwPyT3pcY%eSvqe z1HtPxYu4~+Ww{eD4b}{8mPJ5+9g=)}W&O9K_&~)lTcfe;41bUUT773%SCDB-)cPSY zK|$`ux9a^Abo2d2GWY<^hBZ z*`d=LRnH-fm%a0(3S%s4Pt|@Eg_uv{sh0sK2?2eVvojhsJux%0iT(7<%$g}e>&YPzxt88k#qv-hAv3cUY7_K+qRS&_PTG)M zV@t~pc;xtX3aq=BpPM#rj7Kq=Uyuy>U2CZo7}k?*NF4UEvIEr)ka&*#=PvpO|Mw}U zIm`>j9GHfYMkHVqGcuw;^ULDYsSU6v`R;F0IK8(r+2Zr#BzcQoUYEVTK?$4_jy{>2 zNCp&&%DJbaFHf~s!gH5^uX(`SC-_8jZ1cnt!#*+V^%uSM|9wM@b8uspQ8fvaiI_F+ z0j!56&zMq!iiDtA)SqXkR3$!Rqf8v&3SuK*k~14>+$X4mjU*%YBF z1DQTNdIH-*ivV+PK@vl4OuP6H*$41HLg7Ipb< zybivM$Z^ZtAgkFGe7lv6%|~=c&=MF8v11_F<2VVR&@*iSs2lW9-8L%)+ivix|1OsCFdaflRSsq!^xc zzWt~Y%rPL$XFA0$d}Utl?z)zifv_q-vYqu@5U7D)dkjyDy58#u&Bl%J0o{?d>>3$4 zhZ-wrM~hqLiSbAHN>CobM+=g8!+l`ltjXQo{gu?&e7Hx*!;#02l+C`=i`Uxa2m*Y#P`J*@Ekb;Ts%YDAU)r^jVKbx zS|B&DNIMCE^)lf1KPd-z6SxnY!wu>JiAMv6gi%_0!6=05h726#81fQeD5cP}08{zV zo<6I;(m>v!WSGH0$aQ6DC$(Q~F6)KJz}Vp3mcSv%?9;RraV}z~_h}&AK)4MUK>5dy ziFJQKTS%ysjFnLs*TzKu$@cE)>9H~AlaksEDd7J7`%scAJ383G5s*lFntZHIsGBwo zodbhGfq=$LoJIV@tC(4xAIYx0GuF8V23i7c_>EbUF9hWJe7hT{fs?;}lW;t+4S38a z>w9AWE)8(qNM0QU6DgOHuU`W&hV=k+O4rm>E6&^@2D}dgb|iyzuft{0ABzbDjqutr zf{?-cp5rQDgVU<1HSE*M{KS(iyMSw_bzVB<)Ya|r=xLIC-VB0judMs3Z(kMPF+*$aZvqBt66$=H=atkQS_MD7lFUL1Dbc@ATt?UC0dKW_@jc;gDYV zyhB|z12Onb;No~V2!~vD`w1K42y|=CI;}#JXld7L$JMkU;DN^w5gvt>A`V>nT&z@~ z%J8Rj)LMMUJV7r|<6(k0at%9wM;>PoqsB<8zQNE4wqWWcOszTeEhxr41dL*$q^;OB z7GKzqpg@ZUcOIM%0;5CxFOv1T(adYsnDPOfDXU;pp7Y{uFtJ-!R(la9KrDth;fNxf zCerGKXEgX4980G8l4aOzap2-GhsbE?%F?7Vj1z1*llr97pcTeL3@UIO_g%%rdB{34 zoBrZh*9KK3qH^FnVD*HLUc$kKBj|>VV^MdEqywc4ENW=&&y(h3N4qRf+gzX~gl*WfIYDW@f`XYn?{o42!)kmc~{-XHCCm&*Vs21`MzRG8{ z2Nbzg%GO~ohJ3ZVF>7@cv>8_VSDQs}MdDCQ{rz=JXSmpP6@XL)6T#OuW@u#O0SODoGUB-jV>B*GJfjC(kjSvO+xlWxS8Tgmw{N?c#&)=_ z%%9x#lN${inQowhFF0AU@Udtmd$mj@TpmhXTZkKyT0wU=b6vU5iGdp*<-jmkW%oVH z>mw0z>vxz3_!rbK^S=48p`YW>p=`Th4I(g;MMum7MY|hUN&v%JYH!iMMfZQ z4%)7_ZoLx3OiMW^E|8B3XhT$TRE!9mWFyFK^8tqkR$2@1z5_&^D4ha@J=0`v>8N{oC_7w^W&4mOf-^?^ICh$6j1J}OB`C4;9 zOUH9e1TuvxFb5GcLcl;V!+vUYws@6@ZGO9tOElXZIBGZ9M-hWT(W2mqBVzHTIT2?~VHCo~i$&bc2Do80`_$947HEsh2q4?(_-< zcy;f6b%y$d_>uE!+=Z^LBi{<^uX5Yz*gHzI2M!Co&m4BXI=bkh)9mb=|F?EJPipCv zk^}ZIGgM|0ztl|56|?Ft+Xx$1-QhStKRuY2V0Gd?$N*>xT~95GQf)>+sk;!ULV0h@ zy#g-;xSz};$;-<(4h@;wH8wSMp}2s(VX{~5>{(izW<~7puKs>6XiZIbf7vy?HaK}M zMsf!kMn>S7OuPdP?m=u5p!y_npP}%PLCxITehVB|=l9p>%jxDhH(MCMb}OI=4o7F={|xWhYo%tmNjS~j zV%)yH8^v9)Cix01x1yDW8@<1Of9JA*LWX(5jHax;d-rl4KD>6T9^NZ4{V9w12>PFc zIdDO&5JVn@g;8V13E4<}n5uI?H>`%oa+)B7LBH4vo9)#3^W|uC0+@eC;z*DLsV(3Z)Mu zk?)T4=su-TQXulZwDZH58Jr-E*r{vPZEZWDgj528lIa<|)`Z$#1jlug3Ud(r`=e~Obhj;IuJrt09 z<jO8!oZ%3|N`k2QM8XnYLdx!zrW(*bytu;i{(VaH z&o2B<<-&#g>FMcTJhweoR8!jqldlvfoxHUIfkt%IPQc-Cycz{=FkUfn568C)GRghE z&n$P}TdfT(w9CrQ7C;VTU|?X6m>4rN-!*wdL&H!#_oP9D8KBa7V0%-PAmju$DuYqSm{b&Jbr*qv7Z)K3p3nkmX0Z=y_ihnMA1jCs|+W??8?^w4hgAV%I|zFZBCX`znN1{l zg;T(fbp*arJeathzao;_A};G)1xDKMLuxDi{(U>7D3b4nu;nQseWGxQduWUF(mfa* zVn1pNabn8x%Nusnwav|%#>)QOnpdv)VV;}`-AshH890WK}AjNBfiKm{OU3nH@7~rLjOV`&=Oc!S)qEb#Y`d*g`hs}we?lGc(EJ> z^ELJ}s$SfySM+%C3?~=Y2lzmH7<|Z_KjI6U0if>8PduyR5~_$ysMvk*UXOUu>z*UrsDw*QY`%4xTG5mBWw}OHH^yqAY?ca}eemz;-{QtAU(wL1G4a z+L!&Oxd|}oGm@5YkW*2+4Gj!VVD+BiVP1gRn`jx^BOcT9)J0N9*64gal$KX6%Z^}` zBwP-(_z|PZ`~YO@wN_CWkb?cYUQ1H}kyX+`q10k?9swx_7ZEb}1L+#Qmv1S(d99c(43Bcb+Po9t$?Ua7| zwiV7z+z|T)&JEB&psTHe)+B3c%7sX2Tt-F!+}G>ZuXhrI7-61UkZU6X^-EZ8u;#i| zMTSgG*@9UiX}ETNe*VBSvI0Ogxii&REujmI|egBu58dY_5cN}zCya-{S@!BxHifmo{j{tVf=i%AWj?8*# zQB*EKJU3ro-*Yx3e-odSw9dewN1}YAGm{jp1YBUOz}Qh`dOs-kia zG79o&Yq0seFbD29`_~^5C?&ReX5o$iftlOg>$xA_fW$#;vCiRPT3AYGEFV68JTdUb z49MmNX5U70TqMJVDXZ_| ze^K{7KxDvx%nQX&X){3SuWoh8Atlo+@fH%C7Yt$H82jh@eUTp#2Va)PgK-SLlcv;D^H`N{V^W0@7OUmzH0?C;CFT44QTl%aCU#^iMitk z(JiTvBn;ZK>}mvIl#2L6Xx4aZf#$hz{xv{PnKOZh9FUgv#9I_TCnY3MB8c}{eOz;6 z#ifP=39J^YUutW;JUtZ)HNTGU)Ok9G>a`Cz4_Xa*q*4%JA}osIdz_t|ZV?If$E*0$ zy{?Fm^Ju@>fTTsR=XD1I^~;yp(B8{1jD)l-C3q4NmL)(K7)-t1@Z7(1Ud*rnI0HL^ zj31y&isdccU}MK)2crN^B!lDOa7iGY9M1kDX6vM=xE|Uh2VUHA`LY2bhrw1sY&MHK zYsYtXjE(zF2N;jgLDisxX5fy&6$~W~O%>QWh`?YchX%#ZT+n|1EJP1%O?n@B3}A!` z%ZP}GaA?}#zkyDD#TH6UY0#BDNmGO-jC;Xu^snO*p~1Tkh&Kh;3FxN?y&ADfo(Krw z?ncfPDeZYTb4q|@B4Sb+*^Q^3qAO@+u0QCtv z%0+w`8|W5Zck(X5O5)}Ze%Q1$3+~Srt~Y1w0`2#~4}EBAB8`^3u>y_!Ks6R}&!Iyn zOL&YbQB5#UC!?ymmAn`0%a?QUYG&$vVqtxKeIHQ#vG-*`vB(y zISWtCUFoGPQIJ3uLv5Asw4#w?S6&_vHZ+@`=p$1-Na6XRdBiuE+Tys97dIg0f)2Ls z>eZ_l09Z>LXo%%Op`jeMzSG|^vI3uY4-d~KL?BC1P#|*pVd9y9WeEuh5MxD9ySSbO z!HSiSz{DwdvDJN8X9mE{c$VdWBOXv8Wq7vJMr%LddCUzW{07yZvETZ?8L|t*n5g zj1pHXBB{{m)=y$?f)t927nv|=LJ}>gJ5ZbXY|ZH4=Gw4ej11WF=}6rfyKh%A<1~n1 z0VIsKt!yL7eUvf}rPIG5fNf=9AR#t_+YqBi8m|NbC1HfPG=5fARu&*7B4G{IbC5(Q z@-R;%uW8_WK`zP(#D4UMl>EX_Ac*!$P}Y&Or-Ud6n6U?M>_9yqXv@p4OBL~jNuUSo z;*_#7vjkIw>0eEi!wZ<E`RPqvg7?Fcit zqhOZ)`n3zTFA-+RtHdItPhNWhCIelkVMIyJi7H1BGr_%meS0y9jHn-W9D@YM2QV;F zfJqI|)@IGW{l^z!@puR$mvYRQ$jb-f)o$M6=H{LoNDM@een?O>N_h#qow13&vv6N& z_62Rg=UqZx1S+f1Oa!n3AF zRFYAmToK|P?T^;hkCm0w$emDa)x#7q7*i?6o8q27UyqJ~c~M4qcsIYh*70jxZj&*} zu}0$~Jpi95L#lOmH>Mo?F+#K7O6E?%A>*Gt zqXI^R{lfx8s30rrRyQbk&>p+Y%obFG6cRK&3~8Q3CBxa##c+|WnV^BWxj!nOKHd_B z#o}CvC^qg>Hem3PN2T8`u`6$akQfNIWFtJ`(IS>}N_x6MsryDE)_5o>AHW3+GQ9L>#34LWyxtWof*#LqX$>Egg3*hWq z{cRJEZ+IMmm~t1kI8p7#Mp}drGGIbtx)l0^F7OWgDU!H80p^XDYVqJGe!enkX8wxx ze`V#Qf58s~W{@3dH2jOWlRUqYJO-xPCiu5AZM_TJtT8MB(U=dFTNsZm5XVh@8On+XZOk?dNw> zbc>&E4V#$Cj{hXtpZA}_DZ%K-sRCr#GVOvd-e@wN)!lmsmosgXa295F$@F?!v$3YdFDsev~70hkWHC^`SYJezQ) zMeuH(!?xVkhd?jLd*Ws@Ul2H}OL}9r$rf0%oVF6@70t}J5evMBA>tCiXF#(`WQy7& zPjVFdfLVe4p2CYPoL(kvqNApMu{RKBWd0)Ki?f27IqR?Lip~?P1&~{jWB(B2C+UIuP>b= zGxS*B2n(I|9w9-&0T@%sFj)X|w?ee{A+N#${7D4PR_u_fv~fC7IjOu&PMDdQW#=X4O66`Ddit%gu?)hHE@n$1&O!U5iN5fd$h8RecA-QOlz=T2hjR@I zM&5-pFtx53^Fh#T^k6YSUn&DQ8$(s&u{nHyUI3W)$5RYIKr5s8|Sj|)pas40a6ECHIRwsOh!2gWWo zdXk(yviiG08~H^=6|Jqa07y@Re3EPrnG(iqa4Dc2!nNRc#AAR`@2;e3K~jYT?~#}5 zAOemTJnEua4&<4`4zl^&=-}m0?SqdxJTFw1|~{@I^l3*NQz$KNFJbw zCq`s+A>H7*49B9E=x!h)hw$Y`5Ov}O1LxI~vWHXAv$`_6O22K}gRCq;%(gSKJB_U= zf>TRo2IZ1DHEr$eNCePn_Ln`84A3XBxqN|M@svrN3p-I>MutKs)c8JGu(-H53W8)& zef}FO#CvGyB}DR?AU@%R0~;{9w^btaphsq$s3hLcK>!^#-W_~}hf@E`I!uKE{Omt| zd>3vQ&*}tbVY&teykY6lk9Ugv>xp<7)dR#_*JJXNcqHWIAOE2Q%3#N!S3SVeBK-yI z@?rpO{K1`&g!(tH2kqLaH$f)VDV4ZjaEyNj#C@JXI|PbJ+)Xh z55(|vCBlP`FlU6am582949w6UNVLYG+c_<1c=K^_$%4_NVggeW=msO~12zW4?~9%} zW+Rgw!(;QxMda<#oxgu;49`K~SrAhJjU&s7{9u!m!Au1{)e8yhw_qd$zzmI>5pJIxJjmj@#jBHk$!?2{9 zbr78oG*K}XLUJrc4y6)tG1Bk4#OS1GwJGIXshJ!~!zOc8s%vSTsHE=ahx>Ow?mzDP zaX;?IWBW&^@AdtBKcDyO^nQOEH`0K|!!-(0%5WSCHm8&tQ|qu_<3y6Ic~Jx&i;ZqN z3WI3Nqc#5{Ems&}q-9dSKb99ZRUTUtT3rU@8a#BUv&!p}*4EY&9pm)$iF)C)ycw6a zB)Izda}5dk`x>WmfahV=n5{MKDOwqE=kQy1!5jRa2ZbKnbGf%ikKrpcH17Z1b78`# zQht~-viWXGc1bopDYK^FT2Q$9{}YFK!H{!5+9VslgY_e{OUu%B~c}&GvZ-ybhOUk z!4eJ0{J}X8YLukw_z3&hAWu0hVQJL^sgYc^8x`w1TtUnl5+#?y4b`BT)uXQb*dz*e zNOR$b(`j1z*X*!;2oY$GqoG<1Y&64I28QgSe{sy@$qVY%AH4!%8txNQL9RfXlTAQ0 z!FJcr2#h7dYQWiOPP;m-u7NA7E{%lG|CST*AsqOQNL#+Eqt)Yon_>YZj4>|q_d}vL zKlAqkrZo-{v*Ta^f5J{g=!@E_g9E_>twgl$AO<03nyjgMy8LPEi)Y_m`}pIJ%{YT( zl^~N7>FJZq=B6jLbm7Y+p{>SO=9;#g$<7|iVz?}x{OPCLlr#5v+<)27yl7wC(uWfa zdIG@Dk~D1CFfl3`dME4?_es0Kk0QzorH9pO9yd<2Ub^%|dDCOmL^C_Pv!$v5Xqm~Y z)$JSe8)igbw$qI6uoTbUmqSxgL6N*9kY>tfVM3U=*NW%#P6fzt$ChgZ0g~F_% zjhh`5+TbClFZ(^bPz%=L1dJ2UUW{>!??9*&+gm)LB(+2w(LZQn<~N1>)RT16%nSi@ z1?z9IE*@zkC-KBcTnez(^3o}D!d&*PW8ThyIhxU#53S1r2 zf*e&&rW`uj(z&4L^VzNbdo<#IN`!0Br`?~ZClcrY7XI9(=4Uol1@xd^#bUr1)^u@k zscUHP=91`Rc8!%U2(J1ur2E0D-c5AY^Dv2a(j=~*p*qD-{g0XvwRT5E^>=o0xl6v< z#>C0qP!%GF-ht%aw zxZF`gcEoL1Rh9TS-rnkl*Vv%VD7|kzuG_cgaw6;=IARCfEZzOQI<=eR{8f&6ai9Ns zl=B`i%{_mUF%r1rvY8$p9>N9V*!xqdjDW}p1B4)YL`KGHSxuq$`SR_1jTWC!c9ows zm4~$S$Fh!rH1f!ehL2If&Ed$f?eqLLLCFA{^f(M>$T7S<0_^Nol9q4EE*KnLC^kiV z=7L=I2P2$^0v-j^N1tc=#L#3`V#43wO`5l~v~*2p%QD<|o;Wc{A=PBfg`_0!A9Q6~ z|8OzMh->RAXGNl__qu->9NfO8U=QfjhXsZ2hco;E;Y3GI?>%fNF_V~Xr0vI!>C(f# zkL-ltfVftqyQk5|w}xXavRkt6Xbin+?g ziP;&TG|{hv$bJ>QKn#WvPrSWzde@l1!d5TV@h)c#Z5ra}MU*F_JBzZHYpPXlno{5G zW^XT{%LovU&nM^+y-0UJk=;#Uy=mG1JYdxq#V@7!P_|JrTV1Mn%7(7Ey@*^3qnJ}m zRqVDg66|XH=1&+~cSt6)wy=m8FknDrBsNqO;N8mm{P%Q{S`majJSnX4(G*^KaE8k1 zgd{<-d087&-q5hLtn3WEVEZYDgva*c6xB1uH~u#y$~zhcA!Yy+-@w2HP@cZw`wV8! zx3q*bDF`k(u+_z%1i_}9ItBA18KNnzs=Aa2`d-1ucdQzub2nVAkER60zl&GYUy9ZL z($S=s>_;}uT{GxQ*U{OvbLSoYfv{3=-*6;>u^t-;-uDeBK#+Xl!uNcjv0oP0xVXsB z<1P8EX(k1mns=z2%DO@r>0aH`H2G*1Ni#=h=Tjg#z?~ijSj4)Zps2_?_}nOIJ&7M( z)xm^>U)uc?T~>?4Knt}|$Rd39Terqaz5xM?{1!pF`-X!_Cl*}d7&$g;b5^;J9{|@= zJ}rHa&H=W)nu1I6S2^8%?GOH3i6QcVr}USV3>LEng1N z8OcmlVJ~oSre?fG{^JkU3swWtZcnd2T zBQZT8ccOfP`N=nYwp6<=E8o6nx zjftP)eH}VGY+ANprqtKf*`rvZ&e~>gYWBA7(?}$K9I+jL!ll&LNNS!}eINA8aZBL773xIw$^d}eC<#)w7%hJ2DX+J)9gp;>uXBi=C1qUo=U62 ztfs5`RqpheGw(A9XzW3Z1zEpT#%C;BzTEW~WIZx@wN`mcJ76lUl=&u!W29<^NLpHQ zARJh^72u6}v&(<7`WNf_$X*RfqJhY|XFqfJwd)%i9O)5>id+H2=xf#z+Qkt)M0%99 z%vM%*q%15eQ10B;&^g)2C>o4?la4c?cXTSnBt{qSn!N1`dybeBPHAKuuCyO?ucPx- zSkH0p_6me!<{w*2H;aq$BNpdxnnT_;31a_tuShp}TSL|pj39M0`0r^fmLU>DX2N}Y z@T)$Wc?BHiP;VO@d6U7k>lBBYB+iAjmTij@K|DqU#mLA9qobpJ_ZWHAR-~=Gw?PsP z%#qh<6PC!pqop>`r)y`3o=W20*)CWRC*9#BtEX2=R{Mr|3h`-cDFH5~kKI)F_iL5c zE|xbuXhnx{fRgAq$ok#kAgx0-8^!T(@BaOhNO3lDKZ~jMxu*9jolIR;Dr^#{kaI1A z0~Cu1(@Fbjypq+hB`hS~7qZQ=tx0y48Up!0;F|#Iag0+Itx!yT^+pNqY$Fr z1;_$2@)oyAM@<3vPKb;|C()Gt(XSs@-`PF>^-JsAhTCCaa%?6;k0uPc)EnY6pMS0<@r2^Q&z2-I4?Eo_&E@2C0I~BpTdiJ>R;TfIV3-{L^Ev_ud_?LAee{hO ziJ~rn8ux&pT=$-xZV>K!5fMm$JNHRNZ1Qm>XFb7RY1Nkrtq6L^Ztf$&RQr+IjK9@H z48GOJueuG;u5A|Av4I8J>q7UGJpGa`4i>3K3Wx3t8 zX>5Ce^p74rDmwF+e4+)~5^}eQoHpb)=J~&PUCcm2VGRKNG+>9j^73ZTZTL4MI;`b4 zTJ#c1dyUR!di(gjXy2U3`VdPi=BPDhZYeL55#oawl_l^H)y^)Y<0Atw#VFuKoI}$jMl&TscW7gOqZ})>XVNQcZ*z z3aQrQ@|89-Ytl&2?*mXjC4LtUS~=z5T&1VckeXXL9#q4ov*3S%Xxe~gf(FCH+%1+^ zU;#19k9Fer?TU@HYn=UizdOIHT8aCYYyp(G)knXgXH;l)q|=u!St32HQr0v6PFv?fT-Hbvja`zHCrsw5tBQXHP%WWh@dip@oI4WHMGP7pH z63jtcpM7^*U)Ykcg0DF}nWL}|cZl}orr6e$`9W2)8C)v53Hg^nPN(OoNd#+kL6yQV z#C?+_V7$mK16!r;t@^*12W6J29*t+# zRIJb{N9rR+D=z6bJm^SGAzKSSglB+7?FU^Fy^^ekXyg~M5IhNtY4KtV@e7e(#T+!S zj^|Xx3#$Vp|7UIOZgy%C<%6c@E9Acs+l;i1h+a_U0BO=Ia3Q4AL~H^$ zfDbKuC?!5;pB#ZzFws2@?Q97rl6cb$^0qKT83!XkAF4VP*PJ;I+;+8hLgF)2ZK2vo zqtFGRE@BX=h#2BBYNL#OPcE6pD#6h;H1^C*(Yn%};x4C)b2K9yI9EjDFrmb?Xupw# z-hwZRroaswrV5zP#Hz1bK3WzSShZsO)Qkl+$}_)nBH^KG8=A9tLa@xp&}QLtaM zlANChht4V$u=Zd=0=NEJjBMHoF&Fc^(CcdScEfd=i;+Sw71)uknAmok4sbtaBGr zxP<70DEaiZ<1S5X4+=~+o$e_wZO=su=lhA~d_ZC@D=RAr`fX^Kb?)5$g%|g3d}Etd zme4k*rpq}aF8h)zQXK$&a>?bX8>8IX#)XRVsd7rV*pZgN8#N{{nS2!k;1A>_BDaWq zn4iCYJP$8o`#nUmlym3ov*sa0lOVU}9J2QCIEwUHa`&!-|Loq~brGenzo~gM28O}W z$0UVl9zc;@6L_!!qf@kDI!v58p=BDQef+|57|UZRv2A z2Ua({n*)lsE4wt$CAfY%eqkCIMx02VwP)5^$5QUroTEBj<>GZ`D)NZ zWmDy874{=IH0Zejezc-D>6m8flrigj~h z8>P&xLCp-vzb>CL=-x{$me+LKKW=b)qay9y-9K*s9*xJ0fVr%4*c2r7Zu zN~7WV8;h46uXF0->&@P9I;rcpY#mW>;lgkpsK7R-5yft?aeUgY)*`;Ra2HiTSLGyc zto%ACCet>wqeExv6CexZ-tqb7ty`5~hiA$&M~e);+LB$=8PYvqNEshrkI7;yK{pkC zBMnneoSbVHYVUOh!^6fPzbidL8DQXbevr0((3?}i&fD%c28I0EocZ8+@cEX*VL{R8 z{o4;8cFj?({;M$v8?dr=daV-Lqwn>4(~Afp;j)5#|A!U)ujgvOTk+Vq=zGu2C)e5s z7~+KygrAo8UW~G8(xq`Z9+`JKr#;_fx@~7%X1(#9knS}hcHCUkOXEViOT%VeaTD4z jKYpBW!vFq^ch5Gz^_`|7Tc7qGNwWTWzGa5_k{$m6(cguN literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/classes_input.png b/doc/src_intro/img/classes_input.png new file mode 100644 index 0000000000000000000000000000000000000000..89be452bbccffbbe352f43ba60ffbd646d8aa806 GIT binary patch literal 17065 zcmajH2Uw4N-#`AXXlM)VQc)2}%4+Y0_M)jFiV`hNO3_rLfp(}+Ax-U)iUuvCJ&AVO zey`JWKgaPLzu$BG|M%f`UAgM~o}cx8zt+cXol|P`TR66mNF;gUPn!d z-)%^miTDSNi@NC*5{aRf_&-^!2m>dHw3DQvtYF~z@Yi=QvkyIgsiwOwzKzxVqP1JM ztJ_dH^_~Xp%Ofx8%LRKB?b+zqZ5*9!EJLbjy?2ll=*W-_S}FNT}{eXQ&ZE{&dwK;;-ODG|MM$Xu}rZ* zUoePCQ9VLO-~=^aPy@AOHNLzR{@-7YeR`rD%h1eE{Nem%hpQ5G`qKY?l{pP&NhLBV zQb#ji2%_N&Vq#BKjsM@i+-=Glz|>x}nTpET(_$x6K+}kkly7M6>XJ&>4nwJm`d|)g z#aqprsHg-EAKvltLWWe;oL)zw|MX4_{`R`kW|u;6EE7Dd~}o}Pr> zJkC4){rw!0D-rZEEW`k8gYXz?K4sOX%>Ub$%4uzFB1X@iddz(mP8u9J=J(@sR%=Jc zbN9rchF5EAKEuPqBvQH0GP#P1%A(m_!IQRz`-(H}#l{*AY{t*YD=I49oLkzf-#1#U zD_z%RzqY>m=isGpM<@F#EC(g_uKJ(09NJ7yW?*ROc+cIO^nrwgk5{TedB71I}mdHI@$cfLeFk)=e}}!h7byWfB(g6 z=gysTIm$)7i5x%3CFjR=#JP7UlX>TYo~~{co^W|%&1gdQ*3vHO0!p&k!0GL6Wf7Z_6(+yR|BZX2fjj=}46mpPq=EEVOwS+3#|+wY4=M zFpvU^kZI}3e}!0lb$W;M=TpyrdQ7U^5MiS3o;#T+VVxZKV`74ggx9cqm$_>;l-LMa zDm^_tOG`5Xq@DZs)03%H(}w{ zv7ul^4GkJ>_>kme-unkE8A#)O6>|Ib?Mq2by*@tf@bKtmat#fQhK2?b$-TBHF_9xl z#yc11&6k@%}2RTJsM%<;fZ{8u7#YWr>9pr;8N@N+$2A( z-s@&iQ2)%(JIPZaOnQp?`YdnWykV2Pux-gl*64*9jgXMg)0`ZepPkQjjE&zt)lHus zX=3&C_NE}s&d!oZct15iKUw?ccm?xr`fcB7nu>4SAm6lUlhtH*{?g)C=bj-WBcu4^ zZrKe5r%s)cY{Y}kEX};*ZF_u@)8xz<<74GTMe)D;)dSz0YvGyfc@?sL?AS5W;kDY^ zEC(+SDo5MU)$9}#W4eC*x?MXbUQ0ECW4G&M<#me5KUGy#)C>&w72n@3OY>;vSoxV- zfnnuc9#Zx6^prO@=f+4T{Z9=nFVBtDw6!r`xNu>-^EoGv%(YD|XtAbi7~sH;C(~(q{x+B!Pw zK0cBnBMGQQDw~+Fd7s+Jv~%}vm0^)1M_6+$-d5k?Q>q+sWoBWaprxfn9B$~qpeKhyC@ zvz3>ZTd`5{@$uP>(yS~mr=BUiM68R^Gn4B$*h3Y6H*&;I+S%E?zW8+q$;!zoJd#_A zfA{Xqq&xBP)LL3v(LbYjWVSFeGG=6EDkv#YV6(Fwb=f&MG<12YS7v--g75fo4pC82 zr$9$*>+266axF6KAUQcXS)D(BJ4^pb+S8}hBE~P2F}i_YzanZv7zOt2qbqg)b#{&$ zk6BGs($b>kJaVZvT0pI}z|mM)MMVLdDUgyr+ixW1_&|Su0G`rLCAep$q%`qPuCBno z-8**dAZeDw6ciMwjM9(?L`O5PzLgl=@&+T&iWA*_44eMQ@W_buXmdi5%K-VymoIh9 z%;-{vdtSO+3(C(w$cb~5>^jGEDvqiAa7qT}TJKwL&-E2a?`Lj5J175`mt0i{Vc>R| zAJ;|qVLN#6;PlK)>LdMZVG$A9+qZA?50SDlEOpy44#itOX}`yh>s{MO&O0a}CMJBy zSWHsVFl`?H>mM2tn6<-%cH|ffNJwm(8~qR{zmuuQv*z>XZKUbZ51fnL`8MzJ&VLfz zwqwWr_choy^beo5bpPOZ%;{m3mC6Ub-Zz8pX4}&5{4_0Tec^ z`}>%WEl&0vaw#@*>dqtcU71&SaQLFw#V-=>#vIshK|w*4_@se>0aC!p2ZxD;&&$uh z{^$|+*|TT6=Qq~owB3IVu^+O}YZ1MB_ij`8#?i-?Gz ztHiy%^yl|?hprdgp3*!IA3k*X*|~qhn1PR;`a4ZmbRZRDHBNj>vYeW$tGJoDdFqQ7 zAKj0j*>I!%)ngy0rls+VYcr8V%}au4Sw$-w8?&o@T(4XqBTe>9Tn&c!LIZf>T-F|NfD&&;*R*}RY0UF15l zg-6;m09Ex>SLo2#SO~BG8gs?QiU=J&eH)&dXvjmRGixn$-~eNBaq+F&w-rvEV)#<% z9EB2oc4>NG@+isL#&@84^FGs;o3PprU*GKim?RUX5J)+IVurpo{pZg+tfIA}V^~9j zy3?1}8fmWKJTe?I-ixT5Let}I0^MJ}RCjjn;Fa@J*3n^#iHWhYv%86-X;m3OwltRP zf1%i(I;&#uckQC`Uw`)G)<<%O$!#oApy?{3uwWlBkmOM^#C%t-5?$P;K3qXvof`91 z`;o;7^ZxDo_scVbD$U7qmbTjpj-nFOWNO9bx&Jy{TVFqj3e6_vzVGnGFPm^uflPQ& z!cB@?_%@M~Nz2IOTh~yM0x-FUoqNO4s}*qO9J^lB;bi4mRgu%Ni*H(4S)tytCHrb) zP~>W4 zG{YRDhQ`JluU;JrkBEqV@E{BiC#8uT+s?`=fGSGtDKj%J9PMEIYfX1I8}?z~n>U9K zJ9P(atgk9*Ycm4fy12P*CYe?Ez5OL&N|)6C^CzvPrDgOS=6f%T&4ml0s2aCVIA#`M&eZefreIKL1as zAMfbsXp#G`#D@Ib(oKv!(!z&3tE+E3I=*}US7G1%RWrSBj;vc{J$R(tor>))Hs8B< zuU1wl3Ljlkavb}T1h8dR?vwC6%3#Uk-1+k~qH(k-!xY*VF6@0>P>`CELc&>fpK6cd zm8-6=rzCaTP*PGheEg`2x{oTNym+jmt1AT0D&2c`+RVsk$F^SrUcP*}yTFkZ zyQ!`C$~jZktSYZRzqwb-WCa8QxyPyGhfQCgoG$s4t52@}nX*Rp!n6w{xW6Go)oR_=`ppPB+u%*5g6E$ zB&~OhBVHxr2hsA-pRLcG6B3WOtsdp_+Y=od6922v3WBrdMsS<#$r^*XE*X8Qf+Ajr;x@KnK z=US3dv7G8BPuAsG*D&$$eC*Ay@SGv938v4vx|fG9f*lp>WoU^LXWE@ROsJ6!C2R{8 z=tnNgvv&DoCr+GbO;w_@wYMiK0~%dQ_fIo3vpmn4v&1Q(tC3ezqr!`-;Q+S1KCiz9 zaK(1~sxTHs%&L-f^w_afG(14ls+V?6Vzv!T@d*j37r(y28`>t1{KCP!E2JHqm9?kH zOccbTHQz>!REclx9&6vbcW=Cuhp2>v#Dym@)aOY+%^69{eSbIJiHe*~EV{`@PEOuG zHYT)~U?49~Ds^b;LVpW9c4d?#ym}%BjOtcoKH@#_YvfXvCo`s*E-^$)Tc>kF<4JGP94g2w<(b1>_ z)~F8MC2k_#;nr-*s;Yy{35SY2XVMxLva+)J=awgrf1GXZ?d8GisH>}20=%SVWCUU3 zztpnXs;H@hfr`h(#f6}NL_hz|7F>m{&c{TpqoWgmmO~Qm*?8_T)r)G5dS=V{3LOdH z<$BXdn#Ns0&)H!b?{6PI(3^>};w^85hi}q(xqIN5>8lhFQh?AmoJCky@5M>7xTc%I z!IVBeKHan5%6&OOmjKm6GBbCd=}b#Y(=5z#0*(cPh@|H{-2bP~Uky#Ue`4ZxO3KdH z&V3fgw`-`&sIJnm@KfBpc{Bdl6~Waj6YEBRncBj__pa*E{PiCl9_|OMoRrM`+t*us zg$f1D%gc-ZUEqxyJDI5OBqz7!yGH))xcW1PjavYD*zpTU2=4EB$~j7M9DxjlO$Q+P=N5E4-by? z&v@$j`-5Ly$2@M?vLz+M;7$60g9n)#8ym;lGqoaS*+Hulk2pu7=NawsHy!Q5hMoLY z%yQ|{C2Cq)C7{c;XQqc1*FY%m#Ke%Bo10T_x*>i>&uBBMznAp$colW-oZq3Qv+DSi z;Sb3*11aXE?)+VASfTC;e>nmT4Udfttxi>_d3qkbdiCnAYnH`VC$^q0yhJY`kgl04 zdFW8h*Fxte3H7?VI#AT^;wwTx;YLHMCKmVpT&n}wKg$`onRZ8IXXpKkLFg@^Z@vEv z;(X~C83m&ap|HL8yCYDbHhA5XuBMgMw=Hg4IY$`CB^|FUS7&FZ=h8GE(dYp7&f;jd zwzWkceYEhiYY5MnY&rMwA$t0C^}^Bm2+o1w;h@*ACD=GQ)3NpkEXo3~CyjC~=w)PN z_L=07s2I2^t8daC^j>t@B_tG=(DE%yU&x&=mZ*-}$+84V1q&j;#%+Ip>}mxNMQaC# zTL1(v?INP0Lf*cWdG`D{K^vc0RwPAeoII)WcVpf9;zfE+PR%ptzI?}!?+kgqMNEABl!hh#KY3u0g2cm@U z*k=-e*;1cBt?{8X)HLXGesK9&BjCqte}2=SIdjJ6@A@C$W3`BqxpH)1N~klnb#(;Y zCNXhvgn~qcnY|lvB_IPxhpnw`K+V8TSy`T;`iL5Uvbsy_CZ|y+oi1Jk{|aQ}l}#ba z@a4-@DGGsm_YVQH60ohz`wzn-DGyaFSO4f}@O26*e$W%VFad!ZP zy~}dy;nC}5WzzFMyBJY_4t&~d&I9U1Xei4*59R!MpgiQge5vT^bD4(A$AWv=~W<_N~kcy5i0FZAGg8(Ft7WUVZ`L7Cz{a)lT#Y0C&M>25M(Nb34 z^!P*qIcaHrf(4*GB`uAdo}OOXdy!5+HC!J16j(d@{{3M8jb$obU0vea9t2N|dVGGW zYiLnLO9GXvmwnLn=@S8iq*ltr(X~)T$iu_K`$tA@qMAbiVq;?i3+9%8-*DO4*%|yR z6|zQ=&$77px$NxhP_%6x$IfTbMa(<4`mwcr{;Zs1^!!d@;^~2ft{3Kk5fKp$bJm82 zhTT0q13x-)K2vvzCkmaQj@}FA@P_Qg3qGaboiZ}q6B85Di;MNCN+F>BA0w-Ipe{sm z9lL=t%ys-KH2|Z-m)BX{ud~nG$7`YVqynIV%U2dSc7eU^({-8{>nbTJX=rZVl-v>m zR@>l)+Kaw`U!VxW?LByl&E_Vjo%cS6+{o^*#Q=vLX`iP}SROF*s{y zYn#`1&fZ=TcoUV^j-%txR3G4I{KeN=$*f5^v?Cq5Zr7O9I|%VKD{gIVE$`yj!_WyT zYig9z*a)d(ZHbxS*L1sg?_NWhA!+{h`PAM{x_32|b=$T)dS?TJZNI-23yAj>@Jo68 z-lWscmVDf8%ZnE;0B%))lujkf(x=$&G{W~$(sOLWNuU4GL5uD}uJcm1=7o8wnCG+= zjiZt)3MkYq+n=drQoXak@7%uHaaw?D`}W;!_iiLYWmK}a7hIh~b7bDSRqyArQBcd+ zP(!r9R&&m6+csHR_8mXKnA~zs?RjU%lx9)zG|F>N)_zS*P1HPoIoeV#NBy&B`8Srw zl22=t0=-5?M&7!0>uKyf=L3-YnhzhIH(!>MlM4z7sewd;4ZSr}(y3dFVA5DLhxQDb z`}@xXV^>t-SUoxQ=tg?FKxk-aD-_I4l$6zI@V~wkDB&XjkAUDPxuiYwzRib)h7z3^ zFcVFbhg-_Mc6y-Zpi93zq@bPR;#<+-gCZj639jSRBR)Ub!$Qh)?vwpi>cNQ0I^LZx zFgZENv~8QgTg{vRoB$tR-vOL=@O|i7WKcNHa@wWX9=s1FB1J8VN3SK>=Vn&zU|m=O zAys>Rz`0ETl?>&Qx;(ha20P1iRAG>$Cg%u8aRYfQAlIm4K5Zj&gIh0+Xlw;_v)~encaG z%S=pJ#hou>gM-yhedUkVmjPx^yo=<{iR~oD0$Cy7zXiN}`||3GyubbU| zeUSvDEzF$ef`_36J5&ZjM4F$!3Z1*mb4Jmr zyt*$J0xlt9^JtwqMH$yr2R&%-vp`h#<|G+Tyb1sbo2*Y!H$4SDvhE}6BXK*;=fmeN zU5d1>3AP?-j2$UAQXH-WG|6`z(R9B!OW+bOgTq-#$GrugJ$n|8l^z^^f4AuJ5G7HS zzT0fuzWwrW1M?crjrxfbwLvs2(C>;gKS86|tRwE#*V4iWJc!RF#JSnIxvCM@rdmQ{ zfErcxvn%)V?63xe-hN<#e%In6AQQn8@c~5PPnPw)5f{fwkOA!60n9!%HMLbTFU=U! zrJfv%54&OR*20U_w}aGufACDQ1_``dL<<#;EJ$ymtCJhg6KFTr~z8+qkxRh zLhnE&KY!CL4>PlC*RFn0fAv$Rf9SZxfL6sP^CIf`=OOtJ$cB)-*Rn! z{5oFqY~#H>@kg9_t}RZ|pdp#E=IB0k7vN%MCWG?J#?H>SckdQdnh-n?Gu;?5v#?+n zXZ-V9@vDY4NvI$0Nnfz*XZous79*APzI^#YsJ4(h`P@sYLl}9PSXn~?0!V0l*bfUkGw7&z4=+5M>sje2YZ)RKc@p1zXjohRE zIM4AD$UXQEIo4YIeXjSP-{@Z3dzV@G55Taw1xU)bYu6?ep?hwZIU+6`=sXAtNf1x@ z_ni3^6&2l8ESZK9{wIx%UuSEK;|5polV67nPf5a-1Fzp z6G+ed#7-uw@zzw5rmEfxi?RfvU346{++u8bkBCUR=_`A6 zZSCCY-^onvp6@?|nr2RA1YMbgjFIy6sjxebr5iOT4|Id_J#zjV58vj9$OwI`t=&Y3 zguu#;83GTL0D`UQ*u+SrZbO%HBi-X2Gj1|8a>@n;Nf*Tb=DzVaMt38mE=c0k;1l6o z$MkHkugw0a#B(avW@%RkbS!4mi|+^BnQi#sR}Iu$1#!H!%`gCDCvplZM-2;EI)U!Q36u1)#>tpPwL$lTwJ zRYrhu9JBz~9^J=+s*|-^RGtYxLWMLgPFkGmBPyXhEG7TH>qko6U!ZucJ}l15yW?xI z;pP>Pm>ZS-|DT z=RE|-1RC3OccaTqk8>GdXD7rNr(7kl;^Hf(Xt!)pej~nV*jw&%Vy)KddS?DbI}>Kv z9 zZ5TZ3XS_W&^~%^s2=gkK%*(LKG?O*Xn3@9F@gyW9*vUS-XG{e#RscppD^xKIs;aV* zAylBai=F6coB(?#BCA3rkNY#T+dd&=OrU-z;V3j22{}EQ>Avg?D z>FMb;Yin~Y;pmDswzjo+dYBi;=-k2?D}aZD>1mf>Yqn7swBcc4v^Lh(RT9p<4-*bw zI7G?wJ6^}M_NSY_g6iy)LgP53V zn3{)h?(M-c+0m2)g@m3|uVF95qYxiN@wGi&aG?&Ox;R$S?yQXsJ1D&>#EQ$VuG#Yo zKv}^FGTw(jq37GTXJ~}ue5Ge()OL4wi$Od*heOML<;oR7Il1HyQag7B(9qHC(-%w> zGAr;bHhmLwUU~IdXOP5?EIb@77m8?HbE8fIoNRtUK}txDxp&txAN3K&_joJc8c1uq zFwdUMd81&(7$>`>ug(?u`kz3z&Ckn@oK(6O#45b!&eE!u5J;J&f z`}nBFxnezdZmfkuxaVFPYP{##(!t-oZ^MR%ZTDH0msR@&d6Ys}uEf#Fvwgo6d`Nxr zb8V;vV_cI8NFJex;#9;Y=m}psEpW2xE<-VUyvmPG*cYv(9?k>{xcKFDwA*E6;*5gn z)>`_n@9yw*__?>Dx?0f(`=uN8@6rCszSdTw;Fybc4rkBafEH#A*@UpUftm*C#yrdnm_#K}qt1Qgf?aI`r3k|5v)P|nPm^j-I%e$gZ09@jy$u@X zo-d8lf8plvVa})eD&7J0)G^e?3@;dTo{|5`-O2Ee>}^H$i;1eJkOS=@#6sut<=}N4 z-IW5Pg@t=bdepa)J5AcQN%J4OU6MXDG{nrsW%kvMFGIJ;|F3MRvS5~(m;TQ6wY63N zeUzpG%`@!xlM)5LHMYWq0*GNQjZG~&e`{pmjjX6h*c_QmH00?od> zlJ^A40mO%AX9`aZf9dbHf+LzwQS6Z9Qa7{pI}H@O!f(pECX$v{;&cqRY0pF)OJXt= zk$FB7!s}=Cr2qR{Z{tptoIk^7q4NeYEek&E>`qr>go*uWoAjQ4c^~ymP3?bcqLiNg z|D=HERW&uYKySp%*ClBK@yh*O(;xDIb`=8E=krl+jdm%J1e|ii5s5;l9=%Uz^Ks1E zpi?O;E2n^XOVphTglcjpLM0bWA zR6WVON{gen%uC;1r25Co+VUY#aF@kN)7Oq&3_x|2H#XBUf$v_T`z2&{)APJjo$?F@ zz0LB`Qt+GDRAfzF`K@1D9K(63Z*9GE%;PuL-3JevP9%um%zyL79xC7mh(1wX$iXDc zgFC-N=s^s!)Cp)H2>}1%$X%TMX^+E>=1Bhu8>YU#J{YuwY7UDV+Y_3XR_5{h+xw#8 z;)8N)(-cF)!?nPl_V{rp9#GI`!gJbK`_Umn6gjWe#pm7PZAQU{VNZTLD5}5ZZ#lyr z$sxG~R@!6>kh+eZo+7Gy9(s(l=QIgVu0qu!ES-Euivy=$Q$xh|M6Cxtbs24D&-WS` z9Ua8NRsz3FqpLrZ@?eOLjz&unezo0N#Y<%GUZV0r_^HESTu}6&@v%b`JNwhU_7<~K z`Qyir^I*3_9?5i5->U{ALHReaq(7| z2jX46ClwUP(7}m35`KaffeIi3rOATWk@bbG*JK>(Il9YzrAYm=BTayk$=z>*M4DDHU;JI?Y;Es-U7~H<5!|leQ5|&W znubN8I2YLd@9(7{_>NZ|Rr2q@uLITgOvpfLx{;G30zRue2<8$&LB)_#RKx~4QIDCc z9R=p#E-EU@qdy$=E-*WLFI(^)Y%V*mCz+W8$QqF}-PJU;v;qO+Kzelz41zGETf-m5 z=FZb9?ManF6woY38yjbLsnr5FDitG7Ex2RP5T2`o;Sh14VC(4*NBVAEw1U-OOoU&M zb`v{%xE`}V{f^iFUhxaK+b-_z!BF|WPH)UM9U#p7m#b&f5)4kzG>N-5=2oB1&F;TS5o-Bn|#NCwbwxDzA2l6SMyi9jVs{^gYs)O_NKL{CfzjfzrpamjlYrjW5qR5a3@{H{Ud zzkuaF6a>1Ods4@b$jR}-8A3WQ`sfF|HIgU>yCSk{!$g#nBL0@V$cXlbz1}mSk>UCf zHi6-BZM=o;0C3P&%hiOPujv$y@jJB^rn41pbqh;Uf$A*XRnNAKk($!d@U=vBN&S$295NrlfSkVrx zKRx|H&TJW%DmZh%vOEa-AnX{TCQW;m9sf{Kw$$8w;_75KGj{ho95Uo=0^tOAUE6qV z5+V$%nL4YGU=I$Cj_Gg}J(p*9gYQ|{*wh@ZobB(g3XB)CCLe7{j*8$s(pYlznf-^v zsxMzSP|Ve}w3M3e?@!Ijx()NLp~N9#3nH<1t_cBTKor7BRffMtPC-FN0@8=$arg3s zGNE|@ff5fT^lZ3~rmVM7Zi8X$kSgI}R*BKc`Ye%nqCyY{X(+lHLGkaQ0(^XAh)uz? zRn^nm>i2iuBYI9qJE^v?&rc-1JvR2v9TKV?fCB{yZ@AmoqsDi2kw|PPM?MFMM-J(z z*X%Bca{|UK`JDV5+$X7{y)j?40BzwoSwvV2WX&KM$RJ1ff3Y$j_frPpZT1nKRrLc@6hyn>W9g(sew&5gb_pfZ=++ zBij(>5e0&!z)hKsJJi(FYHDiIBQ=eSfgP=@gJ|p`TM{K{3A;k!cI_Nq<zj+T5M3dS z8Bu2L)$$bDcN)VywxP zeCJL8GC72}RA8d{ez%Yiq7*DL*XEhL{lJ7xO5HDV$7xD)b8};z1r8q69gGJHCb%Y= zGr_b)Ez85v!%y$Ct5G3(?kJHy1P`;p+Z}c3C!vt$Y&+oWQ8nVGLJJL<5mq^&pm5*M z_AxBx+#!zI2=Oi-88bpWgf3QKP!b&RuPP8V779+*qWw&@g6V8p*^BY^;fbEST`f18 zt{`dzWxb)}bKVM(uD;bg@#DuJiX(Cr+od!M`3cO8vM^$Qp`DOkK^mg>$PJ!&c$66| zx#9i$tn`@J7VvA3F*N{$*g**HGmF2@)V_OXymIZfCoyZo_1K;RBO{w(DH1u&wD=WI z)_uFQJ!%XmVm8n)A@7MfwC?2CW3Ke?`x{|XTpp~YL8byyJ8i7R0qvGRG`%RG#Z>>l z8(YmSc{v9FzN;G>w-CJR7PG*Q6kB@Ef6Hxi@nXcYXZygoxB$4eTZm{!xETJvK_-uw z8K`-Evj2u@SY}N4u83(OnMtJfuvnm?&(dQgon9wn`Y)Y?KtbrOp`lx#;x#_3K=!OO z?Y?y0t5<|H)C#few$1Op3P$9M%!*wzcW4PFfc))%fEyARsFZL;R#p~!jnEi}FRcGu zIi(TfyLH4@PL)XIJA2N+gjYcVok-Q16}gZh=%}u#c?0on?~_-rO2BI0d!ph+qd!^@ ztY70SGRgq=Utg*qeW94Efz9PS^7qQ#It6bJ)hAkY35PuoUhLzO55(Y=5SR{KH3&lD z=Q-!_na@PckUDbdTP6Bho?X)pQYFgcWjvk0Q7A^Xxp$u^m>T{H6+LOOV``~HYh`I> z2!=fERu&e*d?68JEzhw_^jpzoC8Ihg9R~_3#arL<3k#`gZprRBbmRyXygGRO$ior3 zQ<>KsC79xU-93LTQAsyeejXrFh}^s- zegnirhBXzcGZgg6<@PQH&ck##$uIr(plSt`mP#Sj!Nksf8@nXG3pSnMN-2LV(TVww zAbTT*WDTqlL(lJNDq%>i_y783uC_ZT9#(m8xi9VR%$Lqt)#q-Y&Jm$g2}wyi9mV$- zd&}5C$LewNM9Of(fdMdG4Yo9bcxGyuj-KNQ*jA#%Bp~7uFYWbGxho1VnS+C)z-;gP z+l~QR`ntLbfXdvlk5>pu{yfD#3CtuBZ$+IdFv|`O`;B5O4mvNh$Zo5Y3Ck8fhAFGk z4{VK_D7Te_rS`Qj&h7FKZlZ3BBlu5*WK3DpjXL6_27VAG1zwkPI3)aw>OUmm>guX^ z;sl)mTtxGGr#p0}g09Cf5b0vzK%(A8w74V>ORSa#I3;3w1!$t8h{4{FE6htYvw7*&aVA? zzG%l2aM4j_1B+}@=6TSf%#-i#+6bQoV$ zsKpKK!*hN-`dJvCe#At=bQcUFGNLvvO)GS&L`%(|z`%2Y8Ms3+Cra?a@P}FTizkXC zpp8L#wY>Bu>7Ec#DKC6Ld2B-p8bi~@cNN$BAhm;hV<5m3aWe!X*iP()fb8a&Q60i zNqB}Zk~-_6k1^DU#h%iQ`O{_xg1vA|_UO@~YR~KPB+<@ zf(b&l9l6_l&EqV~eXb+WfOCVWhTiD4-5SQPvL>>R{8Jk4%kK=p>n98m2^GSA=j5b4 zcW#VhWdH4qj9o-H6P2HwL?jS4)|P>)C{a7X4scr{??T63fM1T0SX`U1v9SSHVIo}J z>C?e`OtsX_1gZvHK$Uf@%gQ>P!*=XPJfktG3sDVxQ~ueyEk}2}p>Yjr=b}ueiEGx7uW9HzGdfAZLxn#9n`;*z8SebS9*M zL4b_O2i@2;L?cGfFIE4^DbMMCGTdId4N^!zNFAN04}?r%3zJ$iH13Lz?JCy4+qJTN z3k?k!sqEUq78LjpLg7b-6P>(6qZl$#k=do23uk!$`rQm#ID;39k7t8{&5fBx^^kua zJMy!n`TctZ%uwT7mdEF+gBptC4p`o(8L$HOM$#<^6V?3TLrb*Z|jxa9t7)Uku$YVq^v7fw<;`%@mID zzVc8*&8S1nIVCrj(bw0P@Tatsq^;+OtPT-(fBu{vXMhM^Asc3A(TB~980an7XI=J^ z_qBE`h#(&t1RDWj90PHQ$KCxfI5kzu;EFeNc0}G&va)CZ_n|j!hBZjil$F1Hl*{Q` z5i`W}8;>6g217H1jD9?;CHKA3`o{-H7>VcvTs#tdy4A$}t2opyaBg%8bv4JOJAkBp1fg@E3aZ=2>dJ|e_ z{upubr1+!wX!;TsI*K zg~UFQNSiVA_Zjv_w?s~vm`L5M5*Z7iQ7RhIj%y1=0?^IhGc zsk!@aL@ArUI2BX^k_$wl9FwPtt94Zk!A?4v7mWiq90Ms+Y?~&v= zxC(SZT;h0$@XvqKIpoABNazOFK}&aviZXz!!8gWrEaJih)cZE{lJTEEUoFor`@mQs zV)BGi`14L|$ump7fk&}*{X$?l|yb19?m&)Nr{jH7AD_HSC#r=?+MU%oN!UaVjMiDE5l-PLhTd7E1 zIR@EeMxcwJ;9#_HcEU`@E+y_1;W!f^0UVm^$;rtEKW+lEWC`JpR`=9R3N6%6@8*Vv zTk94`SCOU>akwy&nVESLTnK>;a>$U?a5OfH#u3zK2p0&!>FpB4C7pY@ooBx1zHs11AsxU0@>v6Mxhx z0(FBf04p{gmbPTnW4UjP3lfk}B}E-izEAVR{tg8+sV1_Agf+1^C4mc4NHd9viJ_$L zg;`6w_c`4~AQ(7*2(1?}Lj`PTRQNDZ6Wn4w{2>u(>N}K*-D2cceYFVj^|a+=sukTY zUvz}eEN^AClL+6C;8E7W%IMiYMQD+5u%dlPdFi_QF;S&)xGO>uX1`gAy^eI%tFAvd zZ_tmGpfDmOsQ1Cx+#|!VB9n&mHo!koXyw-DSx6WnBpYI{0H^}kb&IyoHa3mTMJFdS zDk;@umwh{K%(?LMzpxB(kqAg79@bvzlR40N9Dyh-9^oCd1dvriCjnqSdS#T3AUW6z z^JvxtG60SvZc5^abS_C!pzW#$5($iFrwg|1KmEEA9F$1QBOb4ytILeaOo#?hd~j(k zC_J2w^jB^(m?b@Or2m2{$m^gaT}Lntb$~dhXqO?xjUWIiu;+gk{)Z3wNFfmpGHjsk zLT6rtPAIVXhDS$hTMbE78-Vt|f1>6e460^_*jB&eMf4)JFYhYpg&)8-$! z;_cae?H)Q{XJ_YrfJ+rGbiMWVAni`Sgu&fLOOQvwgT=FBLf53+=NQ8KxYR^N+!6JE z{yFURXVvvB1?N9eqCHikq2ym%xX_FejTa+na?GRO5#t~Qpg5jI4g>mRJ)CQzDiilT zv$7P7jahMC$3H!Z>Yh;TAe2}MCL)81zFLkOV7P2Uq*8J7j<^*HCl!T05L6lT-u?)2NMY))SiE_A;j@}j_*}BH)b|A;aALMF?WpCHQVb> z>#i4y^ofJD{(<|5~Ve}9IGM)?1DyLcII_g@C#_ddI?qns*% zedE4H9fm?U=D5>RjoyvZsAOxqiwI;)O-13V5On38KwfxbOaT?HDdTuy2On_lGP4Qa zghsdPJpnhjS=KEfF>nYNC|h?0K{q>+7#3AhQ;mn7`}jS=kGV_OM?YbE=SY+v?3`kh zTdO2lAq!?cQGh*Xhjlf!UT^QqwS{xVuA)*WzOV${LQqQT!TY8r7EZN)ixbYZFR}Gb zN8w85Y$xM?!$pc$)LCPQ)^hwZS2lm@yikh$>GZwCu(R%tiEobO`E*F!|I0P?{{~sK z$r+>0Boet2@%I93B1d#;C!n+H#1R9akDH~X-Vuu|k5~5hVVxYylEpflZx0Th6{Euy zA6(1tdg4jkE1Egg@-$pxk%jW9Uz0$@dJq}5b#_UzSVW|ta{a?ckMePk1=LV<9VsQr zQ-MDUeGDqv^&!Rg`K>;0yi6ed|NmS41abHucm9#~y%mmr+7_xb;t9ts;#11Xe%_AU zd1~Y4?7jHrXo}Z^I=|9Zo|_v~bP(2&xT*+4Y?RT}Z2UpHl88Msre%SS;EMm_Zy)$2 zbYf=Pff|B27#enPWPZOxL$&tVR?a%RZ}uRa{?K|*mY+(SUo}B8gp-;^+8f%psN4Me z&lQvOURA(pt?g^5H M$|>a+idHxN4;MrHa{vGU literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/classes_rs16_block_iterator.png b/doc/src_intro/img/classes_rs16_block_iterator.png new file mode 100644 index 0000000000000000000000000000000000000000..61a4f1887c3c1f12659dbbc1d2b843cb5a7218d8 GIT binary patch literal 34523 zcmaHT2RPR4-}lunO{JoYQduc7LW(jP2+4@DvRASxqC&_>8D&OB_7<|TGbo?Bx`~9r%=_xOJZZp*$Dhh?N`NDY#1qx-QJB6}> zb^TiW2_N&lH2kvR=6O{s3S~hyD8IaP8s%Q|Wk9QLN6S9 zw)f8i3(Zv9=*mBfx2EQ7njDIoW+TcM8`>Ni9T+90q@<_@JbZj&uVh>w7;X%xkS_ec z|N9wf-+PrwY5jiJZDKTR3ba(@H|tMRiU0j|oQZvt8~%O&>V0le$a7T z%H;q4)WSJ|S39=us{5}-G`kNiIaLc7eQ^DpV^T78%yk=cJp1+Q z*FS`Jsd*F{m$`1B7jb+#H#PLrmP4#C(A9NyoNTz4RBY|AqU$!MyUDWlDUSl>4vL6Y z`7xdf2?(G$>$7L7b#bGAXm?LfMtb_bqeqW6EIQ22vyN})8eb!z5pj&>?{&HSdwt!a z|DT(g#C=MnN{y!c*v+Nk*d>E|9-*c3Pug`v%~dSw-2z*nRDDB(QG4d0U@pzIr(+eO zK(ah^Gp?g%l;CIK| zZn5?Lr*IMe>+Emcn)qT~a?GHSUM<)3t^4M^hF@~cQu}^)S8iOna%D#%cfHmvMW4&@ zvd0YHJ%4p{(~~DpIyq$5@0Xa1;ih5UIw1H0 z-^HbooTH9=ijS|pzi#VO9zCipTeeWbPC7hJE1vUWmh{pxGi&&oZ^eJCw=TH)&6~TI zUYxy@cT@Yuw}Q$}=VhOyq{EV4G;h9s4eKbn{p9J>8n2y)$tB(mmdq$AagO^rH9uPN zLZ0oZpanBN`S)PU5JPI-HZhOv^V)0@jN5kaejpXwJ@W0fX-DC++kZyhr)!JTP)R1{ z#>+*<88ycpJa{nOan`cHZnQC3HH**f16RpHS&jbz3p+alJpOA%w{{8$2w)xL%&Dep zt$4z6@%pb%8P)?IBuz9uw;x)+VZ(~jwzlAR@8q%IZdzH1$0|@WGWw>aaV;$^g+yPL zlk@xX%G_#ZO#9yb`^SzQi?SJNr9X8m0KdG?&^f2y6mjwV`Sm_~1z7g&qqsbOzHjYT z#;^g0fq{V)+-9Ho78Vxz-$jXUS=xa0PjQ%)@HnYm8^A8}j7M^^y|GbtXmUtQOzgar z)b;KPPre&ppY}C`X5E@H784hLCh9EmaMzKt(oz@AJF{z?oSe$a%JObaaTw>QHCGoq z&40?&+o$X(9ed{R|$U#j* zQ*m$2Mn1dc?(Xg@*@o1y(!nf;4!ITG{-f|xe!o-z+ZjBNrzdPU3>w4UbapbCn3zyF zl#|crTlV%h$IH3@oRY%z(DLZkyw5yGj<8>fc8y!a z_P)ds7$#)JQfFS$k#Dumh5Eo*EmKpOw~r59kd^Jj$_zPPRaF&mRDBP{P3#T+=1YyD z6LWKO9}|@}o?kZmQr|cfNVStgmt7MV*UpL}&M-1ElK1*`GhWuxpOWP$<)rpZ zJ?X?;y}F<^`#3nHvWBaC_F@kwCnu+8XaD$K{@|qZ61|H~weK;jKA9U|^P-GI4d3m< zCa!YZxcfs9?<|Y7v@~Vy7W$fj=6E5eIX-OrzE_=hnzP^IpM_$(QH`^Hj6PXeycQM~ zzuL1{%a?eC)3SYWQOpJx$fCYE@#6yCI@aEPHa3q8o$8fczkY=!nxT5Vd;eY=3&ymw zI2^Zs^LyDEtRQYaz8G8&t}AS5aX!mw-u8suNWGuvl1D~HMx5V=Sn0_Iflm1pHU27Z zx)(}(#n%lD*PoV+HB?tZs|G`e!mt((CtE%*XHDyEjz(e*Lt;SyHJhl3I)# zR`}3XYb^}*8w_~QCxC@Jl*i|zRu3EcE z>v#YA(mDa37Gr+tAkO^<54z%=X5IWQmJ+2)iB-68^CmZnBr7-fqpmKkltraP#WxKN zK8y2zCVTuuCw@jcXX@4Mn)@^A7aY9%?Afz3b930%Px^%N^Yh;qJKa8hspqg)aNb=z>y}^$ObP+0N0y|c>6%-UWO#jmnX1R*d?o_=l z$LMl@zhY`?8YKMK-gEiU_=|IXWQU-n71=C{{fL{HvFGIERM@$c_OivezP`SrV7YK% zG0@&Kc&2bKm-yTNx7q#M8CRf`kxsdP>A=68k%ChF_b)H|=RB4y-pRQ4Lhx(qB4nMn=Nwg>{)$U=egfTG*oNWu3a0#BrGf(C-ZEg zF~9xOr*xCHRMToVclU|@_Xiq&#>5=NBAn@d$VE2XVdZ4|B*#?E5?`^XeJF@6#r^$; zt*Pqs%8S4QHD9dJMR-jgwJ+75FRUo>v(HiUDK5U_oAo56sTJCHvXGGnXUa0KbYr6#HlszaaP49I^KIc5d(*96jGekf9M`!2m-NAjf>gwN4&M!V8 zFKA)6X7ZH`&dLG(kKD(PAFpG$P*~wyV-El#^OJkimMvACotl?v`}krNJh650ExIU8 z)`K56;08)cM8ALke(=ztOF70$yN+J-$j=v|lq}61E?Jn^C>JSG+1~za&Bk5wnYtHJ z?)WhXyT`|~?iIKZqu&t1c_p2cZ?}pH2`reW$8^@VB&k$aS3fwclG@eRSCwbcW7w9; z;OXf}b3~2C#c6)}Qk0mR^<*TfKOS{yYirQt&!)+)H>*%_&cC|xO(7@z)a~QE293JF zMZbr?1Ot_f^#*Hhr>6G5ukyP`*VHtu&o)Ob+@Qo6XlJ|T%^p2ARS&y>urL{XGKCa) zQn64quD!PP!FAnPnlHE+&vv{B;L7b{$4I%uV z9v)hyE-OqwrQdzHn`>h6PiIeWucVmRJ^iQl^V7rGCT&|>ZcPnln0JbtJatO7(Eb>1 zQbxd>fq`NASG#!dQFRY|LT_!L)!6#p!q z?H=@%DDejhy;fLZYT1TozL&YNYZMAzeRZP}IEqx{<)uZwrYOhRiI1u3dtKy27XvJN zYmKIy`rqxJn;x!fO}UzpnOS=`i3Qc3>q(%T#NF=UVV_s81SldRA~W;zCSJ*56Lasf zV`C4Yq{k{HDVNp>-#KvBy9geP|`qU=3jr(2MJ`uv|i=T}QzlMib(4M-*=kD(AxH#1ocEZN%dZpK;I2k%@)(USrUIm7s zDFOE&Mp)7>o=DdHs0(acDnXEz$r`t!k7CgUP+($ZLD z!_K1tUdhtGxGU`uD&B&W`(wA7Gk-=qtKYuefC~b^L>-UqOKDb4QOmfqc#HYK0fG!3 zFx}Crd9**|6QJdXl&b>8Gu<1DXZ!Y2K4%-10}AEcSv)~$OI3eyG4yyvb@dBH4&48D zteyV;{;vN1n(oSnD@b)q&&bdo_z;T~6B}x-s7NDh`-{>w_Pty}Qu5NP8|o=x0DBGX zSq9Ir|0uU^-8y+^LGb6%5M1g>aVqgkS}CZG)ero6dG9RPyKkZs!&{jduV$K^YSWxW z_gcScQ$yQ84`%5%NVQZ0KMUFZq6J)k0o?4pSHKsQL)*aM9RBmz z@81H)LGXOa~{ryk%i!~j`*9^6# z0gSKE)YQC#y{2exffk+xoP1~I`?{sMA+C_)X0`qY&aqw1-qr-&3< z`7>F&$+#wwdCumiKzG2e>r%|pN@l2OY0qnEX(i^V*sWgSwd+VNN*RCTYn!2p*WjYk3k7&Uwk_Q#G&*(nws9c}n2 zJ*xG`yRdbCckj0G^6~;b z<=Kx%$6Z8+$mzS_*zCE3)$o1vnz*<)T3T8ybMqz->I3pgEo#HyEf3HGCgq|iYF z;8n`gr%#`wG!B&4)Oeui@U?_~84Wp?qL!20-PaW9my^SLpo;Kbs;AZh1d?^vHUnxJwAXNwjj(?4M3&PjByv`g+c~rcI0|?H{4) zkK^T7;(i!K@6=;QwHMeN#`m<=%hB%L`|#nzjcsX~tel+Qplz8z$oQet-wJFl@ARka zK6@KorJ0_sXo+Q@&9y-9c~0}W`dh@9n3w=*?uCZ#?Wyv4Asc?;S7%9N zT`(6~HGK*_=#f`K0{f}k)2mCrePgh*`y2vQqmdMD}e{p zgEp3vtq?1{yULd#sa+W>l6*o@(J5R8kS~wZob}@;Psme1C87{yh4RSjytJUWW+Z87 zJ3YM&N^e#`T_~0V_?Y#tPyR=)=Dtg~9RF(YoQg^?+Nq9-N!>GEgO`A}zI_?mH~ouQ6U{Xs<6GoTzT$-MepYhu=?= zj}rU!?R7Ay(++SQ#@=>pRsngRTUsFz;O83*umr7bG?zNnu3e)? zZ8iYRF;^;#4X(~HX~UiVgdo!kb*Ftq1x1p_p-P^Ht)rs@SOW+Ei_iej?4@F&>29|% zOQQmnfZAZqz+b7GO^uDEuvZgQvskFyR^mG#Gn|u&L0i?$ZdKT*lU{ZsnHiO2fT5`u}T6Qg)QX&l= z3JsUWHQxGfiAskXmQM`u2@w_A*MoJujna~tK82nhn+c#rzVq4=^Cub#)$ z#L)13(XFW~kgF1%{Fp>pP@lkHSCal5bmZz;N5?|t*I+*cOyFYU+NW{3=&?1A4@qPB zTDfyI#z@907w?wMsWSPF z_(nu%1o^Ju+L%K)(8yPzu&^*5GbS1u2}47+`)fCM13`k9f*IX=@L-*+tgQX*+pFHa zwlgPf4GUk$^2d5C;GWTvH|O3D#nSd`%6U>(Q;4-UFTv85}gX@n0R@5E61I z33Ue>pc;q=?eo~J--aM}h5+VUnM6L;-`&l?-~-tJHA)9^9J(8~@kchWNNKDZ-cz!n z$IWQ@jcM=!a#qVp1|#@cHsxemh*`QLU-Q)@f5u#RqR=qEn~BNq$&(!bk$qT`g2KWk z?iWv;JPBd!p??2Yv`X;@TTtCLf6g_N9`CL+`kc*99`$HP(Ll#6{YiUnpxx5uX5N-> zRj+J*)cEuLJXYV|cpVu3!uj+2*x1<4S=v7VbwCHk>we(k;_}CG6LjrIH0*SRpPxl` zCi>6ZV-Us7Vej%aH?H^Z1i;kM*7hH%J7Ju2qG3aG76+HJ^C6AyLn5P9bwD{p2Ut;K z%`f)DYvb;thAE%M<09|OZQ$Zc+xqnV{QrPJi6{T^h%$MPYw`&Shh!r~!oL_fZi5`x zG)&`C_~Zc=lOAB(UwMJ@uK-`+3|P;UgZgKbVz-bBLE}@7iAu;k8awTA(<{02SfGcX ze-N;OE%1y-uOEUj)T)r<*ny^CS>Hrt!vxPj?c?U>uPiO4+`fJLtT*jlwUkz4JBS7s zg~i3i>FMcd1#X1t-zdh_5K*BUJ&3LkggpZR05>JtL$av(&!sjNKIa-sv$mEP1~%QFpDqK;sntvt-k z+#TLF++YR`>U4_oB-Xzr=o(5u)u#-dESlS6U1x~yP1-s7qy56nG0)fgtkhmtHkTUZ?P4Sz2|{q^x1H*O@W z<#3qn?%_{MtxGc5v1`{^Y*gq|YQy;Z;+B>?8X6jaIP?@&R@Uu1c3glG59Cx@*CMN7 zmX(up(WVf3G7!l)N;md4cnBo_eV`WPQRRGwpdOrW^;3U7jI0q@EHqc};bFpdvL;`k znvIW*bv=<2`TmfrxC@Gk+C18UB%upeGMM>|KWd>AP_7l)Qv-;$OlLKTG#6~N?ylG% zGXIMgm=yZCTn-ImDJt7QXNf4bO$EgLT(d6|U2pDlhWq*WY`z%6_jaP7318KgJT(uQ zmn^2?&p8D8p&PJ*M%oL}*`W8Wr=lvWs#*(ne(l<|D8#@hEa!ShV_XkXbVL}UOm_FEJKCO~(srU8UHz9~Yt;GZ<0u~k64%Y%Mb|fxW z`!VreuUHScQv7FQ_%UAI@`{Sp=u$yP)oXFzIj!LlCmnc*NM5{r&U0ILPt5<6Gk;G_ zWqs>}ZScOixd$c`k$_!trMYqHjCXsrqUMx};sF`?ACSKXz5@*k5LNUEFHxMuLMZ{sk73~{!Hb8M6 z!Vpb1_r^#PZt5x_~45HQ8eS(%S_hD0Ikpo-rNV&+=UBsN)kco z5xhOkiIRDJX6$>&F!pis)mOe7cCg5U@uPeT+6>YF4Kyh)WB=_F5~726s5rle-&g`{ zw>{sARsFT?8jYp2SS89VXc#Iwkj4QV#K#!n*+MuJfD%(b*04GJA~ zfj~o=1O?{Fr!0f5fMK+BbkuZoZ_(~(g>5;dVz;AIkisKygPsCik#H1<7^_H+C6)tJ zY9Q@reP2+aylB{0p2j=mUo5@>>1Goh&uWN?6fFG*0KSmO`Um48P8ov$*FWQZfW{0X z1L)94`B-Sg|HMxxAJSz+Xsj@HCjCH z%XsRR;b-jZP2|OQMqz*RVoTqF#$n1Zgcoq-$`!+)4USKs+>jpTD0|_8HhPz0qM~Pd zIyX2W&#&c{PB(#smcjqf9PbfPIQsPX^z>O+XbK629fd-W#3Xq+%QHL6yo zN!w8({I#ZOM#et%F1(dHs-&GL&-Q^{S@!(-cN}4w>cM!XkUV@+Q;)(6Q!8JDwxoys zjc%=V{dyUc5miV`xotOc)6=`~xCXY^l@tV}9ae~0kB-2)Z=Z`nQ-t1-J*>@8(vSjC z+)Q?wLRf5B&`4BFP?YS#T4z@;;5%{R1Vzn`9T-2lWqRs0?2}VcR^eZ;JGf0+IiWSD z&f@LAsjcN`{_5l7GrKfDnr}VuxG&c8H|?H13TYarh|p!+2_Cp%N98l7(sjD|T zE*<6I@WQoC!aZ%sZ4zCkKX>jNku$N(gy6o$IT+|dE;F3F1vJ^cb*HZ|EtW!qvY|f%v9?@Q=g7>fyg;$L+=P&<8w2d0)X5 zN#{86V*~ov3s{s`sFrx0U3zE662BdWzVcl`p?2MWWC3O;e}dX%Sq~^+D+dhD0GriE zoVse&#sL_M9w#E5zYK3xCQ^g}tDW;=2FTg}4=HkMm#rp@3J;%fmF1;*E{NWw`oQIl zQT+%>{=dUS&D}e8lz&XPJPTC(?3j+b{_WGJDLPf&-%IbVf-QS<_%lBwK?&^S*@-%? z=3mlL^28Elk&7Ti@NO_yc(&P><1HJ-2~nGtW`n0A6DH`tyg2Giyrgwo8Mp1-TL(QK zhS;hD=X^gFTwN%jfaJp$>@xB6v&-alLS-e%4YiDrD z*DE{}g#Z*iQ1vf^>Y19E;UYG{d9^9{xs8S<=2=o2{9KfR`@pL@y1Fq&L`6w)m@#fi zTvHep)Qg>RE#GpDfq{Y7ZZ28K;H284dxRMD!2+!Xt;On&0)7r)yL1o6?sf=a=mZ}c z%wWRv8NQ>)$u)6qZbE@lv^ok(fI7_pf_XW~g^|y2+ugf&tw%e;@si}B5&&tvMK^7B zs@hswS?NZ88!yLnT}MYXdgNQ_?{k|CFzb(u*4@LUtR(KsD|9W1U+!%2~4Z;MyQPeU)Z7C)vWm6LG4aa zQBg!9f?{*ixWaeQ(OrNz0RMP3@v>2H5Dn?-O{B*oAs*oNLsDHMBN4p=7htD1U)$d+ zPRFC`p--3Jmev3@`j~(~b!Fumd!a+JAP1_Dcnh4M;f9pCZM+;SwUb5W>FGcYrFShY z4bvaFAtzcQ&hn3t#=rAC%t~?hO>g<8p~9;jHp+&1fcJ|^Qw>+Ry~J4*kA0m+qmTWs zPsbV~PCb;0ErWxgQFKd>y;{56z1LWKrT~`#lnlbu4NP^?e#`}Z1b7Rd3#=Ys zIp6)_?u6^f$jFFD43ewxAXkADMjt4N+81IvxNg`%>F+2K20e+0$%#X^E| zN|$5YA{MLg9e;plG=s{CXRsax7wxQTa4=D|V7QK}L>GV*F5D&L0N{lXwVJ1)=|4>> zz*fV=MSp*PKGRRwl6!%KHf-ATk@Ia^+{L}bH_yzBM#n;21Whz#;20>ZEWQ?ND%N4L zPpxjIsNgtCGbxb-nUI|cjJ4|B%S#8aKC2gICoOK?e2y|HC@6@{{dm9vIieq1CzLa1 z40j^d0GwzE07jNJ03Dr(qu~6XQG+-4*38V#8hMF=oOJc7y(P^Ct06?`Ovg1=J80>M zQwTQqq+Q9lhmXzxn&b=4+qiyxDdG^2;jpzIBui}vtL$?{4tBL{Hf--` zsE(-S)Z4b5#!lrul?#iYP)-0sc=_6A!%f~5(hKt*5SpL~$A2!?Z`gC|&&cM&YkqeB zO=L4LmpX_4NgX zgp68O-qAy4Bl0Php+TN5eIY$#$<6O88BSPJN~@~evF!8@v#wgT3P}H%u-#EqJ5n1> zL6EOHtv3UNG`i7-g`d?a>KSbB+2lN~s=h%|;D!6F!-d_RT%X3_7scd+ynsvr0jabu zO3m4MS#ju4Nh);kkj_A?>+&j~_iMg=sy|lC&GD&?(}VQc&zxuU%^iRiBxe z83eQ8gOL8glPAO2FUO6cyFxf1&k$QBWD%ZRG|V^HN9(1f>tyC{^P4W*x`Deq=`eAy zPKZ5F3j4VF$J-}HU-OP(QEx*1fFq{gQ(rOU?c>w@HB~uj^4A}^ZZPnTHwsVcut~6> zj8=d-oWF1Z)m=XInhM;o`LajC>0bel*$*K{MO%{XMAiSl6|Y&P#BH zv-F)66t?3zK1UV)%lVv;k-BCjlJ>Rew!oKsB`C32^cItS7l}+>u2#13Y7GZ4GK_ zk?4fJRA@ggc6k$#(x5IIx-(RJ)0N{*KjSk}2=X&9GV(<31sry57a$iJ(}B8i3PL?m zXYQ{J>HYv;$jNDuZ?uDWK13>5(@Itt{n^Iz=%X3g*%jyn$d_dxZUJ%4?b$OrctQYL zJP5>4z_ZG+0NJkPag*RcWLxLV#fJ(BG1yin1)I$+XF#1MK59a`2 z!!fA`25HTgAHM&_E68s~8-S})9ZZCdXlrW&WUy5G+99F?VY2z#GT7Mn-d;3k={jHo zNwkiBJb99IVPWYjVw6LdYea~{<4+8_ul2~++4~G>_{#i(qZxjFTY=s}np9P9Atx!( z!Ti5PNyaaM?1L+9`AbCdK$zNur|1|M8c<8|^+RbT#g~_z=6*-%zI}{p?1mynTv>z& zXJws8RMQB75}GT>VL+l=~cDdV)eAPy68+9b|h85b5 z?Px~>#D>m%Q4(MJ3$_jm3SKeseFJ9P{K{MtsKxEYivtjNTa8O#{D*~yXS{k<{r8FglJ-Gp+zaYwjJJT>qL||_Dzy^ zGykpYr)6X|p?IH>liLav3zl`W&lgmRzP`S^{QMPK@C4DS-~jTbrlw*qFvd>wZnlNV z2yr(LhHdU-R&K67fE#$`2JEN?;{$14NC4s3HA~{ygu2 z@$JhZ-N;!X9hZ=c{@61-ytyz;rKz)1RC?$TD9~jRRWU;$C9Go`BV!|0vptxHRP1Ba zpi8hRe?@HBzkfdgtP5tEdPx-C2f5bVy{ma`$0nPHBq*I(`)72Fr8Eq%iRir_*Gy!ww(D4#7Sr_gjf` zB+0RjeHX{OdxLt!fA~RRLDo}sq(=$O_GS@eQF2KE?* zq)SOD9r+D^XB^Q7zWJ8s<^v)k5rCA?P{1G7IxkM`rUV5A0VpBMD2CW4XffpQ=%gfR z=xUbPV>|I4GR2TC{##MAzUJDGcayXXvGTB25KWY|)V|hf7-aj-X?dW)t%IzL#YV(V8TO&lB z8zC~WYZjk`stX4t4B^J!8GdS94iB?i)Xd9l^Uer#N)r*yk~`{?w_$n++Wxu{Vu318 zGI45OK-6Mp7vJ1pXH>P5T|vU6mfi)>EZ#UiEv*Ufg||Typxi!Emra$}>S7ejYIzSw zZAhVbaC93tZd_WLH#crge)ffZ17amEXe!Kpp~!OLnbr^U;U^qd|L4#C*H{|aE&C~O zqJHRrYbFGl#bUD!>ym`OtJLabUkx7@7k?}qmb7&$Qdf0Qs1I6DmcY68xRl|0K5)+fJ2`?1z(5Wlg zb=w*xxUZQXWr1_hV^v4aBkd?&wHIvcA#3z$sClwhuhmi-{{=-{dE?+H61zVA6PV-s zvzd;^72x7W|2USk>TBDS)?8$3C)y1n$A7gGSDlFOAsGOX(Wsgfy4*UmG|g9SlV6LS zgh@Hb%cHylaRf(fM781h#g$?*9S85P3ylvRq-ED8*KN^V{;wWO-rY$}eFkz4JhP9& ze{8Tl?B?38g1rAn1kQv4%~K2|9s>6|RH-E`2S=hjLtUbf*e1dhNS}Vk`$kF=o7*ig zP|4k?(4pZ2i2?_4Y0ARb108Ca%ii3PHy$E zTMuY7WSj}~LH%39sIx{8%78B*Ho{eTNmpRr9Jd*p2;RaaR2^i<Ij9Mo>@_ewNM!su92BC}f-mcbWMOri5@}~M zWCWnJ^;@^LnO+6m29D{*RS^t{n1JQLheIT`MY>Vnm<5pmCMOT@@H|H00eqk1^RpXj zJp#F(Fm)1&K=coJ8RHRegfliEjD1w2um+#=>9rkK$>Q{0!0KwGw9y6tqxl?iP1r`!mp9@@W4F%?#6^I7O)(s8SA*38SkVEwk1p=k9LRmq%S*zrveA!${oex9MI_#Q=;PCi z-(j-kgxZ&H-@XCGtb2}u0|*>m_$9XX0F-lt4$zlrMI7yeQhR_GE^%lsy?$R`zX=Y` zQO)Ay79!;ROS?=y$FT~x9bqLd+l?EIVCw^|DSL_kNLcD3;2R6dJ0$T-h>iRSI;W33 z2NHhY0ZstWpr5+~cw+$v9J#s+9UHO}DewS7;DkJFmOI59=?QlC`iFy2W@cu(Mn}_> zKA{{?Z{4~T39?Fb6r<$9tMVR#d!^9k&zY))VKhSJ5UTrApMw5Rm|t$ zh_SJoz+hz%H03!0k-GLoBFJdE6W|N$DgzLm^T-k2VJ`AKKxO_{(zcQ-lAn*CABH-_ z5nRHCEnD=_u#qg;?LtN{rUsR;tMf4caW&WUz2g!RGdWb10?Wur{rH@}em~V(_Dz-N zVgY-fhJ<7Sijt*mUKYfm~Aw$OATa^==y&s?@P9T=MQny2qVT_TiuGo;+kCpp)Q%^ieD(Bc#62pR4NXHlDU( z-MNpQ-IE07Fl!JZU>*^BEz9bgB}tS$6)I!sjzkBLL)I+l7}9k1B7p z%YAx!ny?Pk(su~sM~FC4l|rcF%P%^5{CE($n4x>AfO!Xu8v~Dr4_9d+3VqUPE&y4b zSSz>7b&WQ4H7J$M;m7-@Ol43|hvp;2^rw71pD?Cl~d#pQjE6H3ddnV`?Re(&* z3zPQYP;t=&UZ7rVqUCnM_9kgkY(^OvtYqUlFE0T+?n2OeYe3Pq=zV`#5MEmAp0jsi zQ88fBdJ$}-9K?pGFY1>T7=~i<6|#u{u!09ueZ-=)-bYJ@?Ei=|{XXF`Yl=X)W=2+) z4zeCdU0%lE1s;Dn{Nu!YX)@1bg;L)j--V~fZ`b!e6bU;OUU0r;91CF zNrS8)4p2XK3lZT-AO=LCw-$1aK?Zn|s1DjZ09p*3N}e#tDK}n`e*M!onDGJS-!5?D zYiUOZ<3Ik;2d5Q3%~G$Pg;D-&3J+?<)N6DuSi$gy zB9h8$%n^~e8e+F0s~qYOnuzW|gVlc5^OvR8LMZ3?9L|me{hytp_>2JXc@Rw|vFq2P zTMcgCo)17;-1HCct>67Lnwp(qQil)WA3Y#gcGR|p_adFIgzZLR!2OD?M1kAciLHCr zyF&w%!OP$OQY~}~eo-XF&W}$_+!_*r{qjr!02T1BaPdE9E07komm^tc414I?-$H@| zsA(@NYrN?n+@dJStpny*a*Co({h8Aro4<+Pza!KfuP; zpVE!B(SSgXrQqTH71a_NBGlcd*#F^vU9U%rUm#CO!>-_pwq~MHT;mIkJQG&S3G4n+ zpe8HbsVCTA#a2vd*Ya*6X4`4~XZd%tT*z+Kj>_E#;L47pc#?cHEE(aJhmsDJKw<>& zU=~0xx6uw#XaJX{1}{5C-3m7&w_)!`I4iKBWlY-I&3kSFmD3L#jt4>V!~^jLimLo1}yUnW?b+-G3=%7!XAtZcRe&)X29`^Ws@|;Lc<4B~hXt9dJP75g~JZj>#y? z2*V0C$rdqNx?_d}ZcsdmPly?Sx4peR;G-L#4spK#=4s&|LGnpxUAg<;QAd%Md@BQ7 zh6FS?tev;R))lv>F=9db9!y#}Kw>gO1@oJZ6p>7WCdT5WITJGK2Y*RaK9?lsF>o{y zg@n0$lJb$yugv|BI3;GZ`UiV z_m3pwX(C9GI%2C;A&-fnqJf$iYRj9kc3?*h#jFgM$i*)Rfon z#XS7Tl=6>N*yume*at?OZQA5LUQNLjNk=0gy8y{02+_5}0dT>{wDUwBSuTin)&?C3 zy|EYkR2E)`9>B`)U+p{W?CcQHc}$qF2sd_iO*w{BWuZB~1o?I!24)i?p-#w1m+(*^ zieOO2;zs;I*O}9QX)_fSRW$rWYmkBFTrAi>+NfT@Z&`><|E1Ui>-URL91g2`oWz*1 z9*LEJjd12ThnC%hUqLqlzz@u+niHNPFzlotGR@CbZCam11;YehgcE|{;cYy zM2bP-l)u|Hp%K)lO?bDW%L}}9$FS0#L%TqWWtARgm3dkUDV&!f8ligsWgjL{kvd+L z{$0>@zM=bO=w^%Zl248-ngP%{Vf)JiquI(~SbMNy)vD|IXCM@R{D-sa4GDtqPec;p zl%GQ0)dSSQ2;%1mH)0>YeEIUvBY$Xnex8Mn%o2=fyBo3O%fWjx84hzrLIkMUK<1>+ zxw^Y6U{>U;FTE!+XJn6d7CWhW1(M-630b6}JWi6)Sy-H9<>iRep2Q1oqw$15`ZoQ1 zz<>E$FQJ#>xrtvs2)PBq{C!}I5XtDjqv4kK$l9=geq4c+2&v0(Ex>c>ge+s?&VPl? zhtZlYJe>S+#5z43Wy$KeOQ;K+v4*S%Ah99LKzQGgMO{G@jk;%EugJIp2FK?RReAxd zfauTCPBAet+>qC?94@iZ;I$YIV@Tixbeu|<1W-rE+cce5qytE&^z7NY_cHGM!2zwL z|HuN6@ROybrEgf|{rjr`_l+3k;B8>i8w=(wDY##M!X!avLc#Y(aFD>HB1a&oR5J!) z32QO>GnZeqF;EIgu;=(jqmfsCoo_>twEsJ*K3SZWRuigQu;-uq%fQqWWZWVGSqZ984$EDhgLmnbBPuE8$Vw|JT%p{gI3dms zn!g*H26*5pxAscJzcF2|&`btb@u!5AVq4Bme=!%bAKT}=FkXFIsEr6;2oO<--)dg6 z=#FYe)Hz>YU%ILYOeDeR_}<^|QB>rV>lY5jHZbK_+1$K?i;D{+O9=66LZAVgx)5Jz z7r7xzWI$jOG8S&NIg8`aA<3jtnYsss#mwgZqWswKDs~%ruiv-f#|VJ^_@;1Iw6%ATqaO9cQNgSL?{M~3&XX0*`kAfG-$ z!L&r^F6B7<(rDC&)oa#RAo77BE7eTh4PXpi*n==uAq(&igR=XHMG<*+o0e?fs)FEqn7iraQ8ulQE6q-iBKwY( zX45#ZWE*Z3J`aq%y;enD-Ua=UqJR_q91E71ElvIwXFJ~l_ zVsAm(*iu|vOjd{OuTLv>?AQTsY`4VY62V`PH16Z0z#Fx1+}MJz|Iyb+HFSWP`5nd< ziCqm^5;%D6J-9_wOpIdh{D;d53eTgX@8N}LfmfwxWv!xsI5D7^-H(f7K@@KrJw0ay zoIQG&URR18g+8{l5d99Doe5RO9o=Z`fxgY+MhX;VR|KsAN1$A+16$Dkp{TH&>9>Q` z-MhtV;-LGl$ODHCtw95>!b?DHz63L3BchLY@!CMq*5jQZ8NLF_g$vm;nC}2SqNAi^ z{vXz`H0K{E41WW-cUSG-?nx{&xacZZ{lKfP;|)_>Am6@C{)5;dHwLXeB$zQ1zZOa& zbft1!YNF5E#>OiA2=r_n5up(Y7c*gmWH+hi``FhqAKo`0-s(w{Vv`&blfoDvmA8TETbFhOC0|`Ma3C zCDjNZ1=0-_lqbpa=RGQxj&O2HfMeer@0NrlzXE%y8h#o^aNVP$nLQWlL=+B6+S=x3 zxA0h;thRC-?$Nsz$Nza56bnat=<#y|7cl{_t$toha`4#2K^`7R%U`5GDzwdZUcLit z7{l}^|t3i9&L@7-I8 zuid`lIp7QK5vzb53g*(nq@0wjEDPlaLJ}~QkR7_{;NT!8gvD4kdLL+eKg1keRwkyPs2Bs+f4$A>)4*tAS8OguKr(>x4w)Rc zIk>lh6o@O;2dBA`L?xL0zkZqU*sn81>$mI9En?CE3th)dAjJhPNi_H!rS|Lx6cjXG zR}_F3&>P9r5u|bE92vYMw!??ZF;b3>R35B($CImgW+l$4$ivIbu|NuLB?Vbl>@Uo4 zk)t4xW)M?S+DYb`Trv&5Cr*Os?c?Fu4s?$q=7JGCC}1lopgSw&ZLcbei?6~n&9m(F zl8+C`%*{>Btj7e*>Gl)@Gc&XAt@iog(cLhb1ksJAM?1G}-n<#bAgVUSo*c=NtjI!v zjCIe0Ebj0AE)ydB$B$PbEudv$a@Z8n7mG^y$=XCoIKgcW_U&!<>b8&K3;Ei9x zY9VV4wsRR4YGS=$5%QL>+a5rRBSXq$0s##l2xdJ7rbriqv3<_knh!6Tqfq#XhpPnd zkt3TC{N2T(__fes2dVwxtfa2uDXye^ z{P>YVfy|y~Gqeka28Du2=TZoB+{ilvfGY~0`C&$W2>vh3jyLc`(qRx#PQy=1G#wfm z+K4;myq33(RW70ekCeFKq&*lL8*=}bgp@)FT`iEZa^ZC6EEV9ZdjrVIJ`8)>X|&1d6N|L2DseX7!l9mcv0}FyZgGf zt6PgE-pT_^z9QhQLSp>*&rgB4kDGURBcdLKnM5+(!hJ#jLYq|eSG2s-?MJ@jewcZA zcVN$x%snE;I8|r0UhlHANjt%zopg zvw(RU|0uE(Dk8ef+ti*v6+h}P$pe=S`>*k1T z0R||mcnSnjh8={&!sAb=cr#sKe^+o`1OA-Elc3VBgCa+fKh8|QXO9<#2Xx*&KSQ7h zIdn$EX>Q-4L$L~~P}V9y=wShDLY6^Etqptvzxj?pA30wLT*?BV2MX9;Mn*=GTL)2He=V zL++F4{goGHtvFa&*M0u{ng3{5k5EL938ScWzdYvM+UzUjKQE~yUs=KYc*vGX$2-F> z6i&w&ttaQgJ(H?I;2Ab_iB=naS{-jEu^Bq?s=+8^D2z*XJv>%Ldt38wIqa@@bgb%% zdRN7xj9VT%#H(m^Z0_QhLApDVoAHqaWuE9dn*j5URSi-#N$Dp?Y}mTB8hhDzaf_rX zVg+t?N%*w+pBzVy1m3<%3dT8+--h2`&nU0Qhb_~G(efz!Io4F9;~kOfqMcuzto~Yg z#B7#a5cQqnzu%9`$hdXyi5U5QAM*Vh@JTw}E&SvIS#hP_$CTUtUT{|o`2nZroI~nH zIZnZQs;y2|*X_cqLqS(;Uve5QLCr<^&*2C?R`p5L5BBr|nMIr+Su3yk>EE9&3Q_L+-lduPb4a-Q6v!{lG!Sp4YRW?YF<1s;S= z^1^F>QNE?V9k>m?F@Z?#Y5%VF8uDy*kP8*Z%~sJS$&m})VsX8ORwr5HJMQd6*@gXh zm~-yr&T8TVXw{HN1s~&ib$fA+e`zYs`3*#E>?RDA;0=|6K~gA49HZF+87$4GW`6B3 zy=rXCfuRT-%i%;y5ZsL*+ENhY`2meAFBNXBQVJ6F%se~_gBgiN zr#jDGxkAgs%WFdK3=0N?;{~|y*!cKebaJ@39on0hRUx#pScQTsoIZ1A1)^7DQ&WyW1@4J|D>d(Q1PaR%ua!3qf;+c>_ z%tfgbtW7#FEC`NIB82ut;u@;YdQ6vez=nUXss>>LxPncaH;aA}L0(dt6nIEWWVq?l zl`9^Y;x27z*$H`C^2J#nkt^!PwWv+VS-2JzE#B@_K`aFj&lS#6OP)8boNR4-L<^zw zeIFd;7_aP)jg2K64!g?uvfeYK7vWyUt1+0sWW@C1D#}Pl(cyz#Oi3R;eE9QW6u=B; za%^U~7;>;}8X2Jb=MS!=U@G88cw2mG(L*b_5U;i-M2qFs)Vy%?9_FGI3)brSThrsb z8V}r{HnPLA-T0in0W35nI~l7I9EJ=HLiiw>sz>E@ik>qaIg177 zjv!cE28w?uXdVQNq>W&p5R(j|!-{}I(XcW-e0|Tt3?Qe%k-=;@CAi&lv1w!TkZ<2X zJVN4uoI54P0418(z;Llj;n#vI?C59#_Oh=J7v7B=I&6`<;o%I3BCMl)g02G~&yB%- zsBk1SFoTga*F{9!UjX+)>yt#awZPb*rALns`~mY_&JQht;e$j*&zvJKu;yF&-eHP4v*G5CJN#AA^gv7H5eeq3{Bx2yC$@YG*Yx7;(7QCQ3gN zv)GRB5kG@K#7KdK?2FJ8W^eYLJV_7r^BkgVl+q6$$k89<+&bhikdV9wq(eEarnZM5 zFn|YyO0;mThKS~TETEJk*zJoXR2j4tBpAhnaBBqXkyrKcqavjguCtbb!8(KuAXwpq zE(!hF%=5wzE?&Io#so_Mo1~7DYybWg*p*oSXCbC)gO#EwQgQ8-m6Ey#?ggKkh<3mS z^0aFv$H&P*ZO988CUYpK+xs;u^I^E3H z_Bag<%@|BW?RIccoKd(LVP|-2(vF^4*~JO{W{pK5xvv)H$oXxgp~5qGgA))*K6-4q zP3xjxIT?!3sonywh#38zr$1a@OX)%5csf8 znVF^J)@i#0jEU0s@ zqS5c%xzisfe572>>y z#6%~$@k@nMo*q~;MgSN%{1LOdmUedWfIHi${n7dz;G2M!>gnr~cx4UTaeZ|lcS%Y= zfCnxE>f#;@qEJ(NR$f;_nHt796ae2)BRsL;Jv`W;fRTfqV!oF8MgX%F9esP0OG zH~{Ve&NEb0>l+!_0&AS2_d)=>Ok7P(E$~Xll}+a6<`|XG#-_8J5|>0{IWH|u&Rp>i z3Gu=&I?zna)nz4d_2jrxw=c@(dyZXS9S~R-aX#@=B;Iosu=VqoFV~|k65wgL47iTO zE)Qk}yr6B6tQ)G=-SY?U6&H&jqDU0{H)uUT;4Q6}87Csjp`JVl3E6{+!D82rX1%0EEAPer6R>`aq2RUxz;?=RN>)%PT6n;>&To%;98V{6&P=-Fo_9 zO#nlYVwaj(=e!l6|LZtf4c2N(wnjv8f~?I?4YSXO(>~L$L)ML)u9)&il^Q_UNo$Iq zeYJ~rx%+-doKo%hhf69iWq1Q>oK{t(Lv~s09_vHIqQ}g!eZTKgz)3$yak*e{zYITy5*9f494h-U z*$*cuWxS`MUSf5)jZGo~s9X@Mbd;Z;oNE>sq~v%utMJ=n#+%Tag>j_Q1~kU}xvq<- z)L?$AeVIhJK#3q{{Q)l}UsByUFf^p{I<;V_zNY4-wRdm659eF#NivIy`K2w`8RSqd z2wHgk9;oH}4{^&+rRo)t_U~sR*HgPgUH)>uj#U`|R1XvK)jtnZs0& zu}%q~QTjD6kah~3-O$MBt&(r{WN|dqPDt@v?PpteIluLyH_c+2QX89=<3^(v#uFilSNqFGhqfQ z&c%jfUE?$(l3K%oHTMP4wxAr@giTl~7C!?juQRx)}?LU+WG!6jBAqlU8@71@tM z<$x@7|HTWP90YZ0N|8e#xh1&T6t=zW2}dvs1r*Z*^kiw4_WZegtVVCGXx>4mE5Ap+ z?Zqd#foNltmgHT_{)%Ok6cFz3zkh-8ZGC;RrFu)Qd7|*2 z82?rchn8uEBq6Cxvb1QDC=6kcX-FZX5)zfdSSqqq5*bU8CD}5TA|=}E+f2#Q zXp`#qxH8{!et+EeANM);AHQ>cbBxnWed^u&^L|~g>w0dl5!|oZCFV*gNc(?)-d=s=UjhV;% zmHDR?4cz+;ji1GNcn&okngjFiJFZ%}@+nikii*lYL_~yFeg*Y%;)TVuX{~`y!CQNY z>j|uFGAkH}u#4e5c+8z_1!%hy$2jyKi~J20mvGwmA3X~3s7_)pWEAlpQ}^kUENh6K zr|IcaSW9cbm4q?j!q}2k@P4SUOixEg+n8%d|BX%RHV_6wSx6|!Xto}mcHMCj#Ght9 zIiYC`0lO0I$UKq{=0*a=uZUStCHl}sbNNP~q{w`>A+<;;8U=XZudd&ctyQudgtL?c zi0J`+++$pI=FFZ=kG*wx?+kJ$KBI|S^YhQ%NcRE4HEqKdK&;Thkr1^$#0>!d_SRNy z-UD)IO`4>E??d$krMn|Ynh+jV*4ARGqR;8THZ*+X$f@ML(jLL?oC9^<(U6GaW0B2j zM%)ustDoJgJn9i|x+2biRCX87KFWjjdby$Tk(pihJ$&#Wur|A;doxv0Qd^le#XWUX zSXIv*#v`_*VV}8@8jl=``Jojg)*wAS9~yIk4=2W6t?`{xr=q`Xs#pfM;9Q_HVmCG&C9Aq_9G03d5tK z>?&4PxPti$c8FSDlGdVLffe>aWO9pAB<=X&i5@+0Z)~S~7WSw&LHbiPt0KDIrpf97 z%Z5H|Jb1ux*W&x;7p}z|r$8fzkuXzIC|fUme0T>APH7Bji<;x|`=FjYlbgOe?9^FyDK8;V^1qD|grSISOQoV!Gg4u4>RZnPB|&&(@BS3g8;kLcBx zmV+NCuh6xNR}udMuxa#eK=cEz<8*`m%_fI1X8^lV^tHs}W4aB_)sC46V*GBUW7SsT zs+jNnS###WyO?LKwqN{ojy_73=8kd?S5?iroS!U4bDKViIQSd}ABwqIN3n7Fldpl*hp0OAMf=mf2>zaH{OR-0t4W}I>Y zSX{j_ZZM!>wSNAO@*ic+P8%?E5Q}{5Y|Jfn=Qk5$-oE-tTfn)_pbYch?*F{GEpS&W zRqF}%@!-wi{^Ak$Q|aecXtsH?A)D)f&9O(W z{quE=MY~G*i5^eNRtWy*pR@zaFLz`!nz>0AVDQbvLP0RI?s>~6w7z`e`!AmmEH>+& zasLSu>cbi;a{V&`1;Yi<=N)%*Py-wd8|Qw*$=WX4x2odmQm$*#$y&Zdn({0DiDxGX z7|Ne58$Sr1nH&7yAz=N44UEx zI5=t?DQWhZ)(ibNDWClTP`Tb#H@QUlpkAZ-&he4*&j(pe&A$boRGz!qi~w)7oX-2R z0IB$rgq=IvLpGO%oA{q!Z}Fv3$%q{`bf|B1bXooBZow#_S_@hF+40MuCh8J?dIu1K zgG<;AI5?pvql(ZbA`w`WLoF|0f}jVUJYz-&cJg`5a{w`WX~BRE3fPEQy*{C#J+O&> z$XTCv>+$1G3=1sCWLiqfpLO}APjz+u$Bl!0d2NJ|Bl4&Ep`S`n07SO0%4R#H2`i%D}|L z?-H(Dd5XQ&&ri7E?u3{j)KKvPG#k2)jk#A#BdFa|>~cDT28C0^7A0-n+TyRWGGLIX zbGoGONXiiC*GXWBmPXtXQ~;6yq0EBN9FMDt>bV^9ZC_ZJrSX!|mq3&=VQfS~K+RO~ z;&&z_idjHg`MK!s*P5Da1-;!WvO`9V8g(DVAQ(oYO~Vx9?!9}P(+p~N-EkWI-A7dT z-Bbg`D%xc;nlCeZ`$M2iK3RZus)__~s;VMF^%vv`x{_D@Np44SJd7F-t18!@4&ZX) z1&{I(6)&{(gU{!%D2v~{v*c|Y03eD$yW0_jYJNA6tk6ye!@S+k$~u6JUAvDK$YlD9 z7yPP>GQrIM7xA|t(7O+kraXmT_SqELL?^bFt!fzn`C_DHnt^^mVt>H_gKJS6S{hMA z7UKtwdWvW%$^ zM&dRZf=7=Y9W->PFg8>y!I97kknb_?-}-Dww*XR9fqQsoCew)0vIvh1!1Nyf3L;QN zn0C6xA$Lxq9s-|0xn+zkyStiN8sOfJdR)1E(1{Eux{Y!D7{d@Ex|?+Lf&2GwhwjW5 z0Rj^%{(c|G&<WM|s@mDx&jp}A9UkuG=f{I# zslX7phZL@UePuFACKWG9=`=P5Xo)<1+LXN7z^jhbWh3QJCQW0jF&o=^A-LV)XKHO7 zLJQ>GxOcSEJj3>(%-So(=>ni8kh8HdAw4Qy`~b&Q69JHy^FxvcIo|n&S+1K>mVRQ_ zxjjJAEsaEP!w*wcexS`!RZa4&3u3MrvfG<3C+OBl_~?-!rGm?AYVzQ=G-4yN{$y)& zHM-ofx&S!z-n!4HRG(=1Y9yc~gET(Iy;r;tjmbF_%{E$j+gPN3;_JhJ@SY9rf$oLR zy^aCgaSvKi7~3d-WbG7SDw#Wxu}cE$ZPac3y6zB5D!aVKZSi=G%jQ~`n5&b*yGaqOP6{yHb8#L01aj_ z%i0>xbw{uG(usMO97?pShS7Aa-{WZeci<397wWADb6J~mrW0#-D>88axB#lk{Og{* zh|9P|IE##>Q5x~obER?8R-GF@uOay4?$HtaiuqG!D+0Wri;%dAiP(fwD4wUx3<5+i zqP$Wod`-2Z_pQ11fG|iSyJMwAMOwPHbLR$MbxeKOwnK+)M~)on@(ieJM?FJ%?5L|T zg)0kPsm3FI7<};R)vNE{v869!Ruc?0#cAz{iq!hw4O*O;C!|`0MaeyXzjK6_!8x|O zyfy=cDBx@XA)2=VTBR-|^qo0IUta)fKyjNT?(QQT&NmPjFb=v<5E7u92ucK_?!J`x zB^P7nTh#BT&3#p%dV5P-%AOp^)48uf7n53<4S-}Mx$o(V7beV+g6D#QNIcCr&ss^0 z>YyYyHSt{;R3!XTv{qhVN4~@O?=C; z0fW881Fib)w+oF$ZU&gd;!uBEu5$bQ*M%0u?Bxcgg=t}o2*9mnyDxOWbZvc zv&0NL*j1qmBwqxS=?=))2Xu6J4qLI!o&BYHZJkC}kRM`kdm`feI(%h{oo)}?GDp~q zs0t@0q^%hr`;MOEJnyphBNrOUfxy;tY;8|bqo1+?L_tDEMn##iNQ;Y$jlntCpi$lI zcv4tbTia#!%Z{0xp5V`u6-5>ylv2MprMz3k6%`f`4MM!JP;f*{DsaD4c2r+C%%Pq% zs+L9wY_&CyaTA_;wPnS1XI4jIt= z2pt!H;er;80N74<6wE7cAoiC_riRP`WpcQ&`3O-kW^@_s)cp*Gp=~rX4*BtOsK+|H zI{zYucbn*eItGrE5L4)ZeGJXbEzc<2QzP{C`_uBcy1A(>t?z1mG&VLa&Jz6lBp}L; zDmiU#u#QeTHzvlwS-o4gsg#V9K(0>_{E3ux6bd`(UAQ_B$?nzmjsB9b=o61--xh~L zFDi2y@WNy|%g9rwrhie&+Md|5G7n(7gOO_pNe$ zU|786d@5w`u|IX>-TMqzBh?V~q8C;8gh>!?=^UqDAo%)O%6ajxuc- zcAVMK?#Nuq9i2JdLs_Cu^DB3+9x#%j)L&m|7QRsZnwY4W$(;RLDBXFNR(uT2#g>9( zIRZlOUE)k$R(6oPC&}EQwTZovrjq&>-pS>Tdhq^hadERlFGc)blfSRYb#G;FW4=*S zKWZ?;EW^u|4W6+}2Y_!Kaa{9=QP>Nh?1h_}y0eBd$ysJ?CcpoTfQ{RkuH}Dy<@L`8 z)sz0Y#{bjBo-Xm|2(XV7a_4&Mp1iQiYWecz4z^qMt6MzR(O0QGWZC@v8wY>+=s`-J zXL8o5tzjZe;>#80_vR0pZvQi%wo(R_78jf5geO+uJdBW!?m=#U{p zj#GK9Lmz(f4D^waIM3l4ayrkgqR#&1Vz~&afh2-^G|oJTg9X^{U+b>2F{c5N-+%l# zK-L_lV(wqRM4DGs)n@8E_2EO0JnPU`hgQunGwYAMf#JI^OI123?YkAZNr%AV{rn<- z8fbwu6h(LJQnk2nNX^LO$EN}V2W~v$^23wMAINx`4HL7w==SZ~W)>E^WqndrfX${M zMtgV8w@DYlc}RkVu)5)tqog}3@L+022{|kwR1vB)K7}t(n^I}x|_w2&H z!NGH511^#W1?|{E;i-i9DZd)M;0Q3|reO_7!TFiGLxsIqo_KvXtEXW8pUm*|Xa71gL`UaWEI1VSMd*$sor%^`@xsR{%s}!b1l6GN zH+jUpmq6->M39Cb3DU3+10JV;I(h8!_!^h&+{*G&Iw-j`y6Uf3!6G5Q+2puw^u$ig zX32sf1qErYvqytzWwBkeBq78AGm6e-XV4fEAo>W%u+&G7B%v!C888}#V8F6FDJfl4 z(-=HV?d%Ss%JVy28GD2l=NSZ!scw&Fq$r!wERaDk6|Qvv3Y91~of{zrY`dZdp>t19 zON(H#S5=+O7Pp*P(AesiSK0Rf$Ik~}V(zhbX9hNbILR$f#zmDc7X-Eg~xTx4LHL7qbr zAYmx4%W$gAsgF1e3n53*`uV}co6)T#$3{Zj*hKF-W2kpyqT~6AM35AdzzZA|Qf6i> z2nh3N*PlugIK`9Sn8}W8HjwhuzyH3Ewt}qvUtDtxJ*&#pT7*kzuxc8|oGxQDGB!p} zwVbdrfm48|82tx`!b$U3N{VrB1PTm1vq__q!;c32E#!5Md8k{b{T_9d0|0y4tqM8$ zIrK+#cB-l+B_)BNp)!c7&Sr$;D2e5K^TCrQg#l&y*k8rN5KgO=PJfB&h{y}{%mOKi zh=-DYiuUiJ?(}T;Cb*|STF+T|{Jdv8d}z41Kc1eRvOgs2{ZaY1m)~iIbgtznPMfd$ z8XPd6F(c~SxxJ#}Dwr=a?JDf5gVr$*MmhIXoWL?zP`Q`6xD-M(NnTQTbo5T{sic%EPeq)v?5R<0`Hj~s z7y@H=!MO?D#0D-Ib3l+_N3Cfs63WQ*w}Puk=7ckxdcZa+ia`4WdSECyF9bKe`;^1r zNZ9NY1*+^0ci7tvacHvMJ?0|3Pb%oQ#-ZaAf|xWU#R#Fi9F%}L&o;`Iqj2b%=PYNc zn*iab?Ax9D`s(`5bTZaXAf|#k6&HIWIJ=+GS&dw8Eu0lN38phnprPDDD|_8-yc%dr zK8$nEpX`&CLwwJ&8R~H?!f6XJC%r}F!?J~r1hR5C-f-yP!2-7Aaah*dcj#~)E}6*b zuNY-m7&7=kySFCakL}#n-qQWPM<;fB4Zw_fmsTEpy<`szwh|r@(E?LM%H6v{;R^bU zfuI$Xpm;%qwg)y+_El|yKup7Cq8RZIvmh3_xU^^0NF*CW)`*8KBExFbP@NQzJ?2Gh*iRK2oZ6 z^kQoLm%3l&#>b>E@_oxB=M8N?f7APu)L!P?mLRp;Q2>j^l*jhP=`%a|;V}-j4qKL@ zY5wkRjB#@7}5w6(O3r;qed3$uVNR_pp=XL)hLk`7i$mvXP2E&l6JnbrEY4>V(wDx)8* z9X@<`zWoFLP06|C#of&07Br;Kw6M4XIItFX9cdN4X+5VQcj(t+7r7(lV zQ;Did-~NuGx#C(Acfg60u^Hlh*q;$B`5-g6m7U#N4rf$EnScds`>tIxcGqx+}_84ra!at%{5DnJbgGy#}Jd?PU}4-L+U+6V37Cd(qprQn;9W z)N<@RW209N`75r9emNfoLXm@Ld8=nTIW40hk`>agp8|Afv|z!}KN8XH_Cxb#^m5QP z3I!P9*Nm)0%uK0WNE0&{P`Bxquj5*Ok@{@)+Z!CL_4n=H5C1o%Py1kVo_2{l?4pWu z-iJ-7t;S6@2!_JgeWq5W&_H*Ab;EQXo;Y$Fz5;pVuc#}~O6jZ~+cx!;P>MVv64OIM zyAZ72y(0NK;Mk15rx0gr;>IH&hbdql=e~oVG`%RX0(xOmZ^<-{SV zOOMM0%LPE-`tt-y)l-~7&VeE`2L zs^Lx;qDd)?V6h;Ly@w2-fWDVK$yTQ*uc>h?onITiM5J|K=*w~vM|;KF`Ld8jBP@Cl zs*@yk!OFz{k#f$ndI67~sI~-Pn>jKD~X7W-Hjql&dtMUF$I$3sQ{wK_k#tU z{pe|lz=w@rk`Y-8n!37YvR`JGAk2A6wguGdgEOySbk3t#666=UNJvVy-ZZ|wm@23# ziWk$c93;8=W#w=6sN)5NLvG`ob#4*tN96qD>J)V$g``FZA_;Ypf*y?p5dh%X;okGK zG*uC_Q8eV}HnB6X*^m>wH|8hy#i;oC+2i~4?Hj=B@Z!d&YqhS-jUUNm#|-+z<)6ML z@d36}-RPx8`z=ikV@aWt%OgZWBO}0d|DHiLFkPbkC5)SgJU8+1PJ*yHaCebe7Gie0 ziSd|ieK(co7AF|du7)hlvX!IfG9Djm;x|IeqtMBSPeg=gv2Vn~$$YW~jTouNjpU;C z4=j6jsxuw1tX=$Zw*V|*K^Tdraf<;g7OhZze+ zcVQ7n^5U3W?q;22>3gQ=J(e0~3HqlXtNzICY`vqrym*b9Q(kn>{;%SJ3jdf*n`wM@%EDj&3u}DFcK`qY literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/classes_split_strategy.png b/doc/src_intro/img/classes_split_strategy.png new file mode 100644 index 0000000000000000000000000000000000000000..d83939f6894d72d44675bd03ee3caf59f3e0c969 GIT binary patch literal 15437 zcmb`ucRZJU-#>ns$p|T=5K2RXkd#fR2vJtDO7=)b_DWjF8zdGfI@~RaT^s zQDpl)kMp|j-}k;B_kBOU|9sEK6V#s3?0{B*;=);p@|I}^l)YVv;+F+v-*62x}mgp$0D`-6$ZYv&`omg;0RmNG1N zJ}cO(_Wq%Wa$3lt7rNmotX0vMMr<0-n7*@DvIw^k45p=P%!1{?hm^^S!rYfR#1H|Bd$&J3T!;leqa@!^1Ao zC5wCxtE-`mw1J;*nwZs^2nSILS}@Wo?*8`|dG}nCcTP=D``^8*lRCjbPai9t@348! z`TNJ~H*cOy{jgEc{o1u_Ob;7vKg`e1ZR`u*FcKswdCsyd4)A3wYNr$s|pOssl! zWoh8YkI>7X9-5AK=D9D=I|Y7Nn)z^$m6g?B#JrXuBDYCWYG`Pjj58+v<# zx%0&(hPm-BDoIJneMYY~-Ppjr(Na6+#fuk5S2}Y|sn|r715M4^gHNcc5=54MKJCYk zAN5Kc`A$ES3KdX^l)G?&hiEGGbh|p%&h+)`SIx6$@kHp`v-AaW-+Z`#a45l{OkPK4 zQ*Uo?uKTnZ;rHf^6mHsSsFvw&OpIx5_?B348+MC^SpRqLRHIz`uY1)EH5ut;K(gM^Y@lGQQ_xs zL%rg(G&KHoLzO)}ueX%3Du*dVY(ID~N5mq#%4edxu)v}*UL&KtFxR|p1ErjSfkDBQ z;gd(5M;M2{fB&6mZfU71#S_K8-$2QCZAF5KSLOlHwD9};9y~cBIxvumm6coC<1P`M zlXGz8_a|8~$9_3VIgSJ8lXY`0e4gkjKB1%(bn((9tFLdaZQ|lOxn;|i^F{%-d+T*{ zb$2;9INXegNbB!6p_J?M{>yFj>T0Ntj*hC4QDR8Q?c29i6%+z+47+7y9^Slp^IdcE z?HxOJ{=gZKpTy74U*Ix!j-THE4~$~FuCDIQ(9o2xrJihrL6PkiR@T|^t~;AHZAwp1 z4+#ko)Oe_d`#7Vmov^ZGWgp3XOxe6HGHrR;%U?DvEsb)bduGKjL7FZ9u$sR9mWi*W z32N%<^4#c|gCW?Nxclnn; z-A+r}dE&$gR$_44{i2glyoIQ6nrDW`>oN z$Q!4Wd#aK2WN^^zXJ?)O6Zg@AXJrBG*F(3+j*H|oy&akscK9mQTjss><;#~Lp`rdS zUrM4la&0;e{E|X9ynFwif?9uPf~J=+pk^>`|HbVQyUuw zV`F2ocb!KX(4?Fq0mpRJ)EF7q_f_!vE>|*n={D%K2Nx8G5&camimK}B$9;Tc0s;c2 z+H{T4fm?fu9d4j)=ouJZE@pJo4Gz^s5q{r4CB5zI<8_<-N<*A4_1Jvr(xvEo_i9_7 zYOrqEvR+?bpK!!_{O$Vy3hupkbb#K36 zMw^6rE#u>-Psz_qRf!6I^vLWBQ-h^*NU8Tykyda-p^ep2KmaA~(dW#U?CX8LYuq*+ z&yOo9QLp|^T9Z3@l74YVvGZ{7%d&eE#l#Ys;eS2hN9dcIu%J$a{%B=5_!LFYGn%=%F?5lCttfqPxg$YoBCoZSCVnj})$7zrKIK zEWbjKm^Y1zn;@*`+tclWUB=qw6&0y?cz8-&C%B62dT2#NM1JM{ZHNaZSUuLSuiSZ4IUO<;xz+?iP)Pi;+kD~;pEAi*&^n2OphKt>RsJ%_L-H+ z?;@|Yc8k6P9dUUQ1ZNfDN#&R1y2pb2cO}bVT*m+ZpLq`_y#H^Y=RXk8TYok@qV9d=GInQdVXns^@5*pJZAV}0toH^KIUgS%#hyKTNWfui%!^TBf2OaX zu+V9Bd4Ve`$FO(JN3PB6z+FctB}G+K$YtSEeV3=}E^ zyOM-OvQ;sdQQp9S>!{nW@Y}aHN_oyP0)KSAauLG##VwvBi@q)6?9|kh+?6Yb+@*Mo zjh;Mta>R9j>^M<=L}P8V2@OPwDd}Cfona&ZazhLW`02u>%X@&sYaD zEiEmsXr1eLXJyypCr`{8Vnu|7h5b@e_(mGy0-1SbS`9RC85pRnoSbw*LPDHdx4!M_ ziu)}pEzLbt8xe@_43CJIPFh=D2VimJ>L^RG$U$PCVG-lWlP4b->FIIOGI8l-%V3)8 z>FFh_MDe&U{;?_?T3cN@*!$&+sih?y6%`dZ$FcW@A}4!_nK4QqMXq-%y{hB-$|;EZ|a2g42~XJ<1>OG|G%dNm}!t*xzwoVe!Zfo0xH zRd|p;e*7T(#>Z{Lxy0##Q*v{2E3i~kQd70FS26K1Dk_?qSV&BD#EJhxsRs=)+Mc~t zP%YLE)2nTQqoNVtvaB;C)_AJUMH948UfIs59Dz$OrMn|ll z>e^aL;{5sZ$#~-5zFpiQD9C^KF#Ea<+bTj>1z31_KS^(>tF3*6&nof!d%$m|_>irg zU1po^xpTn`90#`V+(`rIn&sLHOv%h6RgrkiZEEzhKx|x`Q{O3UGIE$=)M7;_s;e{o z9%&rP_g(z6r#52i4g6fP@7gL_tSar)ePN$vcVbvU)T((0_y-?8mx6*~esyV5QVX3` z*Oh1XR65@!N@Rvau}rX=+8EtslnYNp4#M3q!j$Q6Wn(e~W5<%xPoR8(DKg2b%{ z4;WosTx4W-smBLJM@Ji!bI`JhM&kHT7>Y(l+@C*xCLdpGTU$zICWDrimRh{ndQ($V zqTX{?vHh2-$0zR0*QbxVNFF<;JLcbZ1IXI8Gnax$&dOqRc6OHXSuVLy^!xj#8zCWd z_z=^}mv4k|931>4yB3s@vDentmLQB?yVjspSh=|)04A2v*0Hj_GJZ3SS1$wkjE;_a zwCVD3&dkg-wX`T&TkpM4?h}ENHR*bBsejr%Iwt0NW~PvWf};dPDC~Q45Qym8w<(E|moEqE zV}$U-is-KKiHXmJHo5?-CLPa>j<`>4znpOA4izxe{NiF&eLX$lIMFT6$;I_Z`|0WP zucdrfx1}maP!f#XNAI$w(*xl)Fp1(Z^NEXZCZ<5C%&=uxSXt#kv_xEf>iFAjVP_A% z_It!>Qg3zYEi)Z6^YCstAaQZNg^lO^rbP zM)Jx=HaDLM3J$LN_;CZ)Gv$XfXV2Q*W#%||At*7Cd-3mNlt0zF!R|tv-9kc{_p@KU zI{NoDCf*fi=UXu`G@CbXF8hs%GyWtAG_d`C3AJO$$!ZR=mQ|Uw#zWkyn#yTcnEMY+WL%bt3+m?>%viO^Uy zA?{TF{=Gad9b7`-A0`>$`_yRqpCn^n_+L9F|fBwI&9Sxm!0bStXt zdSRhU#1HFNSAS4~{`gBLWOV3F&v(3ZzMTH-*)+H3+Nw0}+0?{@Ag2EO2?8j6q83Mv zFy}bVy}rI^uFeuCfsJfzn4y7KN?iFmI>)uNZn0fS_8NKlWX!PCLwp-Ix6S?>kJOLOi3blJd?j|5S5{Y7JFcyI{~7OMLp3O2&G^lX?KyB@#A6rw zxy1SV24jb`!&tH*g*F|7vtu1#B$XJ1BDS5vZ+up`uw>U^h~0{hzd1T;xlPt*TYY^! z=h3UXN$w7o2pU&`VS-s|qx9i!OP;xko`HechkN^>n#hB%9d`H%l*Lq1QqrH9Q&t6R zMvfrhPf9#7Y(a8Qhybv2eQ3l{1CuSzO&CtZqS(o6TF)jZcjnAS&$)4b5V)gPNBtbi z7HIG6(x}ytU7_aY<|ZWw_l23AXn_p`w1}XXn9Uy(kKF(xKj`RcC(J?V?cK}#U`MiCD(onLT?xt z9;Q)IQL(hPex#8kgQAuL27l!?8OiH2PqDH%8wk~?jkaZSfSLt{vhAv>tfT<1KH@Y;EhQzD>o}l5J}4{_W1oecME}&lTN0WxGBQGB zFu`QqdFo#4*emP7;y$0i*RPLVb#c*xUW5X@5_O}wxmoz|;aW6n$-@CqA)rm1-(?4e8abHBbUonRB4pds-#T{7PzZ8mJ5`IWzYTkQ@C3I+@5KKFXTJ3-Sf`kzF< zf)8~K7+*!l*iswcx?Uc9`X#h0Uff0#{|p)AV|^d}uzT;`fS@3yRBubBIY8kbcUSheIr0KsnO-?uOP z!`XB4_Vx!JN?qd@PCRY+7@S=5%$X_(XqnuGWnPk)hhTUi*b5LosP^~s4LPGPKbWsL z@|g_R$ApB3S7Uxyb9XY+(^o+rK#Tm{QfhMnGVS&~d-QDt??UP#c`13BATyb1QkUr{ zTIq0gT;{do36(xQMRwGFMfP6|4jS&-wQB|{?2ARiz!mINlJs9Fva+)J_U)UJprGJY zNI`kc0}y&R+#wJ$A_rydY)E!OV(=2F9EVr5PPB!k-(x9t3@- zTfe>%Ai)GP5jE^hdvHr56Ert!)&al<;3RofRY)R3nM}Vrlob>xL32K1yIcHuaR~}{ z`e9bht@!;UNh`AL3OJj2j(j>8W7f*d|N0;${5dJGmnKktbBl_CA%_(Ic2#7x5Xpb>q6&|88rY4t=i>uOvVW## zXYFV|aV9YcTG-K{)6T!VLIXAxl%MY$Xe)H@;-AUB^0+rP*8ty~a4@u8jGV#*J3Bj* z$N9?zAoqpxZ%Ru=u6$Dka^shkEx&NMs#hp8nJ+3HG${~B$aSK7r=zneS&I5wYu>+K zkG+f@tGLd<@lz@(v}+A~B>;;F*An#VY4=z1vO(=CUb{`^It?jj8JCx}JDZ!CK~G8l z^iBW6cJw8mVsL-&OK0(i`SxFqlK6OS`8V^$ix*{5-NHwLQSv61mLVuy^X2(z%BWpC zc2r>M?!JFfC#~pf7X(%Ui*ofe^Jq4 za=Lu9VvdU4+$y%d>9w0f_!d#x3l}Z`>#N}A3@eT)JCicL^W;})+nypOKrVv7rUFF( zWT3|0>%BH{q5;K|l9km^>b}}vNd@@3efMrU{00imvg?LsX8a8e4F=6;mDySjv{*1O zV4uAO`Jb0*X>L|wr+xY z1EN=nyD@yHt*l+;VPSU{({>PZ2ta(J`!a5MJ3pxFi!Xob_oCD)ZV9Nc@bE-}5$dwN zpns53!)78~A>3x2?|FdU%d=`c| z^z`-Hu04;6V#ZZAW$GSGNt)Q~swb0wSQ&PVnVDJtqzZcLHzRP$?ZBi*GcWt{bN@y?8O`#2vvlPT98VhL#q# zyu3U(T6(F8mkMM*K9ml#YI#!G*qHs%*@jJ&-8VcQnx)dki#x7fy-HmhRZ-Vq`Zl=j zRm$E#t(dH=EJ2~L8eT;fmz`fP=Ewaf>+L^OsQ+xrg;{J-SH@QUTJCE+;mi}YPG7%^ zeJX^{)@ym5l@vRajvrr;;b3D6dlqoTQP4h0N=nH%P_p(gr&?8M4dXJ@LYIz^a& zf#V?|Z21|o3kwTgBDBQWp~xEJ-_4t*pF&}QKL>h0;|&NCi9sQDqsNPd6(!A)`3vG^d9Y5#wePnpJO>aY3`AEv1L5)+V!iZ=HiXHY!O4ioa7fnq+pMUNg8z0{c>1nrs zK&nCb%F<-Hj)O>onAJv#WW!>6r=*=bc4#^}3SYW-k%jeEWaI`bYwO#<^3T%KqahS# zUnq?a$ynEd6If3yEG}M=(5(4{FRc2?yswtyZV$K>M!S3aYunf%iE`xz%E z5!RT#Ajk&0U;;OHbUekKvJr~|H+Xl8h}Np>9%nxM*YZ!RR-P z0d*xM5NXm51kvA#YwCXOb`TP*6NS;)25XzBda>fzym_02d5mIyHa0dmc8}nFI(^q+ z7lldkTzW4dM@7rH{n1*@Q`mz{JW{dHddX|zk@Zm{{|2`lkF$?~@g3$b$d=E2%$0=z zV0(lo)Ep;zIb%iTkeJvGo+y0F+U6Y6~Fyo(~)cXi>$feUX`iQR_|-9C2VGcEk#R5af0r%!ho zzgAIFVj;KyYgfRY#30mdMD74+n@!6_Br{ujZ%eOP?O@LE5ZMH@%sgtcD}UH1lEK9` zYGIW>iU3plfpPu^^~pvYI&|m}?ukppjG7`D#iIMqvp~6bmwHOX#mAF3OtBpYu!xQE z@`B=V;j`3TV2gCbe*G7Z+fDfSU*zRIYriDxIk!*Wz~J`XyPGJsj@2S+o{> z_W-diP7RPAvy2y>6g;QU5X-UlY-+#LNiyoNAX^~?a6uo>kG%h+19hTieL0 zh51cZs_`;}zlJaSHbWtgf&zO2DE4lA{7Li%d1}Ahk8fRu6xRD!aMv!CSFc_vDfOn- zV8ozBfT9j|?hVs7n$U_HVaJNu&+7|vFJ@9fc>Mjv{VXHnOp=UudO<;fmRZr&A7}Xa zVI1%i1tyi0_#?D6k2`0dooe`5Dh8v9^ioT_mkvV1fXuwaU2>%9gLg&w9N zpc+ug6>=Aig%uWxe@v2%Dt74ON7h5sqM-tV0Cw&hg9!lQmwno2&In(dxtN}jp#a$e z0t?{>nZw%kAAKAf+o{88WzmH+8i?q`#6~7sDmf^p^W%w$iF^kRMB-_Z9wR=_AF^Jb ze1D*&;nLH8r3JVR{gx zy{WY|=-xec=el4B#2 z%va!Pz6Hma>TxKSS5SB))A*ijMuLE*Ob}Op^~Oz3Li?w^uYXWP=)i&6o12A%eOIxs zfJB7>s%^i%*+NWxd(ZZ(7X-)Nyqk1h{o>;d0=bVtK?QKTg~J6iXWVv##mC1d`tIFt znHnrHPwl>Z`NGPQ(Edhl7 z3}m;gAjV0t*rAZ)+Nni?7mUs8+u4}1EN+1|f^);NwTG%p2#P)7~KD?T&_ z(g*y94sE=5?;aU6dVc<806s!qS(z5pwFWCa&#vb%V53~g7 z66)oZ6%lNAhzm2^%0RHCD&4|wuK z5dQD`n9G+g(ID-!O~#8e-=Z-iKhe(CmW74I5A=<+R3I0L+uzQ7{``WCr`G|!(-rnBmMpPeV>y&yw*Xg$J&GEJS0RJ>j-P^}!WMqWJ z#*fI&PpHi_w6s^ggUOwNsQ$jAdcgeWQR<$gf2L7W*95{_4YGDx8j`SB~I1P9|f{oS`oA4-Tfa zvb4nPz2Xn?(Eq6GxGMakCjf51bg5wO8?|QF`*nAx9%_`fz=pXr6gBE=ZV~g0QzGk) zn0aLY&10ZpbkZLnD{VA#$%~94Eu1^WcF4H={4hZuROstI5_~|UGvh!Wr>A%B?kTDQ z40>r286LjF&v)@*$h*$YSmc1x(U)2-FdWXk-V=YjxA%N~W8=<8S4=775T8lXv2YI4 z_cocIo3M%a_U&UtC8&F^Cxva-$*)YnNM5sTx+K?! zo{w+q{^lYQ&u$u0KBCmmLnu`@vx{<71NNGL*G!dPYvX7f>!$J}i3}vm&iu>F5P3iD zFMkHPDm;xa6XvY?FG)Usy|xY$EG2k`#^05*7?m%fkdq;L3rh+RDAcJHBk^B*O{VM8 zL&5c@hD9^OF~O@dHdLP*7u(mM-5Wk4f9A}K?uva)x$6mVtnPI8gJ+wli5}|M&pUF} z{h+zvkCi3`4F4sb@UJhD-&c=gs1IK-cpm1xH0M+<>%F)M4r34qH|d3Ar(H301L!hE z)r|JO6vY)`b{S6Ydy2*LuCdW>{(38!M}Z>_0~!M9yW+xg!(&$K|Lyv-&!&iL&n{&| zWH{ZqcP|*^-dW#9$QeEaX-_NO*wEC`Q3r-Jc2)(gjVDmEk{BP~onibZXMfq=zQ0VL z{YH|t%v?cK(WNuqMF_wxqk&wypCCT-;X~MxC(KRKVtSFEf9vkuAShO*uxSWC7#IQ~ zBCKmGlfERo0~v34DE<0^42Ix~6E#_f?g*-r8XSdAIgj#hf!(XtsWX4ia>NXc;2Luw zF(E0FnW(F&Nx<9lTAC;(ryc~d{^8-XIafceW9Io*4V{q*a~;#M>WO*+3m2Ec9zTDIvv1nej}o{JsR$Ymtk}BY zZ?azV!f;`8FTUUSPw}_33@LFFl$4aouzStT%}I?CJB18eWVYRU_%ITTq7upqLOS!G zd{?#YDyel!B_Hk%>9@CB33PwS;F!pep7l~?s*{R`;K~<{2 zdX}*7?Qd4@s0KSAcOC@9%C~Q+kld?9cy$WqS_+mIMENWWQRfl0eFg<|k&%(3UtUX) z<|h6MfdL9+Jc5DHieuqQ{1eXLFh}^S|L`YqVd4H?HxNX?dY}*IlP8m#2y&32x$Nxy z9L3_K%Yj$`xe)>O-UiSxkoS!3^9NJny+jUeyj6o59D48;vbo8Xx<%B&1lf>ipk}yM z*!f6*F(PFFXM-D4e>;C~sV4{YLP%DG=EDsOVF%0l>mwo~afL34v+LHaquTvxQVb4$ znK>D7fZhf88Hm~#f;vcUVT=a|dN)aXd-2bY60e0r3W|y%mp^WM<36omB7HUoa^2H& zs&m)^=ZQBzG7L1mF$RAI)jIckiyiZt5Qy2}Z0_ z%6*Ceszzw*Wa0jw6cqp%;J%1IC_~pXGdFjFn0>S-t5nmFe0J*Uja+}3OMnIb{P`nn z*DYpgWt9T6an_^N7>Q0?Um!Zq9EcH)+gtb{dDnhhkh;F7n9l419tR|#YOE_cB}ZrH zx1i-t-#>C+ymZOQCU@jxA_G7-=x0BKHK@??s2qT;sj-~$DwF`I^VG~tKwh566OE(` zIj+Y5b`Kbrg(EQZ2=Y<8iyuf!ZgFuPghKLk$h0H?P%VO2Q#cm{g`VqsB+s(v|1UuX zp(!s!^$ZzrL0|3XE8a^Zgj4FT09>fwu@e~{r^u*Y)=K=1`)>c=@cnMmE zb@S$$Y$+uEjv<0WO^}Wqu!H05&o+&W`~bLc{n%~fzKV_I+_!%}`KW%Cpz9=x%q=Vs z0p!Q6_G8PzyZkm&@cPv&dbKxyk#sp<;z$7(b?Dp|^1qEI7Kw9l`4(zvACm|o)nC*I z7N!bjFnDb+OwlKm!z`?>zk1ihi3Fg|t^JL|L712sDjDc9N3l)V^638kcht;lE1YiS+ zgQP7a_d$h@L_&2i0l-H}@9pr1`=2oZ7GLc{UV;_!^Z@7&Io+TD8GlOq>8lL;MsTaA zCxSAh?F7xA7s^95pz4CFaz?iWLFVK;a*Tg3)C^4{#blJdeA8(M0|SGljg6wA;Z~TL z$`Hoy%=g_E6T?1u;%ZMv!i;D>#inv!U&O(~d1ZNy9zBW`~*nY&_%r~Hi zKrCdG+?+fxl*f(!{D*X0k4 zBDOo}C1^58+RGI-Ay8^=FPKKXzU(M+aG@&_3WzvB(_kP-s{^V)cFST+&eH? z5ws54x@JvRSfhRx$%|Vw;K!@H4%gfCb z?k)G_g0!`5i^gaA`p}|bL=kRekjJ^E- z{JHw)XWOZMpZn!2b6c@tslnNRcHNKU$Az4yH^|%tUYUrMx^^XSIWr7} zJ9LBBN3Pswh3v2$J9e00nsyf2aA3)hX^r`%B{KgmdikRgj_zlS^|OM4O~59|r_uq% zl5fXAw=}SW2y0?(O)nuKq4wYiD>VC2jCwM`0iAvjimgM&hmro3wR7g%aNCeDZ13wc zP*PD1z&`4Ciuxpv7((B88dT&WhrW+?Ro%@Z=dHD zHsIlj>X`Df$WH9@Sz6DI0)M|63rQ90KU<0^fziwxKR?ld(w z2jF!J#5sw(f2pCh{MW#(;d2<4blTe5(2NG~22mxLqOf^wxb-lD^WN>ICnfa^j! zkwY93XtNfe$7X;2&gO{%f+1je- z^9evhGV6#er2vFL1fR*$2%!V+x`D-jqyqW26)HSmM~*4E5XY^Au?sW%I)Zmcjvl37 zzI;~xR9cT!M8WG#a+}o>kH&n6#X5VJCN?nbPI6!by=e&qqON0!yCovr1@G!DBn=VZ z)qjhQME&vB_wPf6iUnymYzx8mNyRWG2tz}|G95X&mz)&jD_1~^(MXO#Twg}k<-8*@ zAcp;V(ZWwCH@0t*3qVm{$E#6(Gfy92+|j88ci#TtY9KIifJT!hM*F9Z`fu%PBGwib zf;hpFyGOgbyXWVp$rL0s0Y!hS1wD-$mxeyA*R!; zD5#5#YmPmO>5y*ZO;5osL}9UCMOpS0GTAwG9t_Ic@X!OB#`p%%29Kdyfy^TH?}Jy~+L77!e-xA@<>#i|^+EfjFX=zJ7(qf%r8iiMiX}^c=|yIY$63+T@Gjlh^%X74;L!EN^GZ#%6L}< zrzAu*T{{;T3{m9r+OK*xPqVVZw~oc(ojU|R^I##f&srhpL4qPcrA%%c)%Nf?7T@q% zQ{ZOUILR2I0r?g>JiZk5Pd&yAgajB1+MXAK&moo2KQR%3q611Oyt$J@DG2q$CHnoG z(a<@_DwYSQ>nx9KHXNZyXTNNBI7#0|okB<6`AJV#nfI~tMn*`Yt_Q)#YkWEKuT3TH zJM2r+m&_KYi57nBx3S*KA}O9ywTaP0yZONnR}gL)tHq==O6v;-HuTAJQ>FP?TmGAi z&2q%T6|L@JCtqWt;|R>cxn+y^3H^PmoB`=JBF+(Pgxxje(CG!MpYEo(w%wF9Sa7Dc zpZQbeL6XGv|M|{;o=9C+>_6|B{12+mzu!Rl*WbwXH;0qiG0R(@x5r=kye~{Pc>7NS zG31gyWELIGGg~_)kEFQoD_zDEMdTcT+@4LB6ck)7{Q!rbCFtQp9*{?&so3;%%UQL2 zm+93N&o{nn7filp1mCS3?}_qOoQZ3D`m4xwrJ-zLqNcjK^PlV5@V{Rd*PE13By~@o tIwfm$IH0T8VM)WkhBrUw{puQFL(fqaeDa;p+DlNr>o)5CkDnR+7_%zl-1%L~tJ77Y@Dr z;V(i5C4FZEA^nPd;UsXAG9btmL|IN++x_ios)v!<;aQtWWm&I`a$cF67K)5jfS-_% zF2X93Rxl-BU%;}9R%q6S?z{Kq8_Vl9Pvb2*UWZ82(%VG(M5(jN9Pb_di|ww=TUF>| zT0C^0P)v1}92Z~ok=l2bT-^2bLnS9C2Ze>5V`Jq^+LZJ;x~%p_#AiO@>&fHOn(m^V z&dl(zTD06Om4@E`^G4tC#-S+yUtL$%Z$4scYYTe>{eZZ*xY=~$3#SCmVQqaSB?3}L zF@NSep6xoH!rJq;wtJ*z*Bj14s;jHJPCK(Y=hi&Dc9vd6qODpQKE%{9hX(b26eekZK9Pb@4< zyI%A22?_?*)ZE(H-JMxojryL%tDC&2qgVEnywJGr$N=3QSY0iSq6puxnyBJ8sC*WM z{+`(JNWs>Yr{?*eb4*N3LRS5F1%{QazrVfwTQamIO92bg-r0#cL>jjjd(bNs@quu+ z4tp!3Td0D>lN0ZXr+oppZrw7fdCn>NY@(e^>Ldmcd;FE4x|87IMHKQ*+&KhQZ9gU1 z`t4gRikOJ#Q+9US^t35!U1g;xI|X6G!EfScV`bq}-rFP$!q#%m&d$^{G`cC-671~k z!WDmZ{tVzXKKkO?;X+yzn4C<9!^guDX=Y}I{k|JFZV>v9SK1fxpM_I$e9Fl9T46UX z0Kd2SnV#a-WUs5xQK4XNB(9zLxYAKkSUQu@1Uik6c!66McZ@j|p`&Gqgg59>SUwb<{ zBk1Yr8Si)sT_B;CL%O=UEE;_O5%>=mKBDX&9~n_MG<*Z)7_gbh0e6lZ{BoPx{2ES) z*Z4~6R8OqlaaQ5nbgjqs0hBH!l63PC7h{9h{>|Y6!!}}?n=w4Ac$VF7l?4R_bMx{B z1_t8x*M42qKSIB|<0V3J@#4q_dE$_e5KS$uxcm3-7gtihr#SS-#xt_Aw)#FQqRvEBX$37WDm$H?9166Az@oiH4)&+~;!v}* zvxNSAeSH&UR&g8OHA4~-sBoYwk`50KZ6|BR;eu5$*ge5Uz~sRLGGt?8ro~`5yPzNn+GgfwfngQYuZZmk;^N|hhmSvV zusN%Kp99=3ECQ{Et!lc%Clr%6KK&gZGl( zU>o_Y2d}UE`a(0?_KIfgeOw%_ot@oNYwO1y81^gSb8{By|E^uT)@;I_St&Ssq+s)_ z!B6VkxpNNFjW|juin3?F=mjmi8ok!*Lc6+DB|LYOl)M(ZnP$%7<1Zur_4U35%U@jn zQeS)UF7oWS;S5*ZGyUJcfBdd1dPrjwgJ^D7UVc8$i65LTC@3h+ye%34z4`Rtab7{? zO6#-HQhaD2F}F2FfV&X5iH{!J3yA;Vpf>Bj)$vO7)+>5pA{03lRdB=U5ixL$BR=lt z&Q4HvHplskwEor3iyweQMk?$WpkmUBipY3*dB1-9HUkCXpOQi!a*^&FLO@2=2HUu~ zF(dmaH@ErQH+)#|0Qha8NyE)DlY94w;S!Xf^MZ+K9H0@)?8YB1DRqv$$6x|57>sq1 zqR*znq6hSK$+KU#Y{x4|Uc7k0Cm_%au2PNqr=M z*azjfYeR`sRgUIJ<4jBF=Hh!l?6+%ZXed2+&<5AuTVZF2t%HV>En*=dq26*ET?>F;CL(HLE*MOnUK@d(Lo3>s#oQ}N<>6t;rT8Rz{fp;C)C#gA~2!vq+!g zJyt0xmO8Kf^N9COpWJSmbA9Aa%>JFeD3DPfh^3=6IwwhDj>GQg{fV;ULIX}85wf2va+NMBC1s(XuF@o z!yHI!Yinox=D-7~61W^-kH>M>)UGF}9IjSQ5$!I{&u;?4rsd@1@QphkY?xs(Kg$ke zseLRgycrc4NlQ(wprbQXDX`!(+iFOOZatnlJKc{O+!tx@=!o@bc5`yV9G1pdXlq}_ z*=S?&^PcxySzR3kdR$msY;dC6O3Tkbc^FyQRL`8{U7~(D8YCVq9i6nA8VR6omE-Jr zPy*Z%wwW0jpe}J=3)@id?CfleK6yV>6Mb;tzA{!$Ov7vZ_2h6nJvSHNuJ6jz;?`q( zd0AQ9+pa5(fN6x#S3-7Ump>{*HGhzQi6B5p(s%D72IbblOG{6mT3NxV^gmn9z&U97 zALD^ec{rTiYZ@~i8kMnh9;Lair>A%2=1o#dOG|;{&!wfk`TBzTX5DX|y$w@(#7bWj z*35=|>tFgakS%BxC0Zd_)BZ%4mPMwyS$-doq?K~5?m3o-8qTD3m|0BL9Q#K0?D@lLVxWsXm+W^Nv6H(t@9(>CRI76mey7-ZIz0%)MQPVOz& zPlB^|KnL{q_s`uwn+aukyx5)Ul$k2-oMl?8TWItmH1t9ZR2l0dV`Ju{-M^s^BoFbx zG3b>%#s>+(AteySH~9k&}~4gU)y@Vn<)&woYneW5Z)o&xlO_{rmFoaM4Hj z6_hh^ijY-+Y$$2dz`$o21`yAaB+G0H&|r^0ltq>$#hbqDKM_12a#1=Qt~1-HFa7a z2LaJ6{YJ#j^vRRZXTNG@x{?K(OUiAAoBR7IG;=OXOG_{HeY^nlt84BlOWFtLf!sl~Qg0!Ve$VKJ9|a%gN2{oR~18rlx)vW_}kF zO2%Rd`VGDJu(^PA3oL6sj8{LYIu~#`s5wgrQR3dVHN@3xzt!_ zX_Y{K18|jOWCV40cLN$Qeg6DeUsJOggg;h5qdEZFi045W#vC0TO#mk;Z^30_g;^ZO z12LPQJiZ%E7lbQ>Z{L2?+1XhOeW|@5}UJW_C6x%3IT89u*%+boW zwl&co$pt?84LBIA&Gij99YKKZKv%s0(TA9BOgFuj@DPY*z7ui0zup473oD8EV?_}F zsFO)jNUIGAgSWSLOk!e4S((tz`V)hPmmssIE58n?pjg1+EajTzK{`Be7piSLSY;5d{7q}OQ z9N8!+Df>#y6_bUuvQ(QuwL`D#%v7gy+1lC`TMuzfR6AdQ{RJ*3x@lZX033I4e0)`0 zT>k)s7lE&@Z|~4hLUK8d#iI?XC{JNyuntC54mgOqwsw$--@o#o=|ou}DQu1-0ZEe%8m2S3P%@aGpGQ5)%Y=&GJVI{)Gz{kVY`By+tNcbBl|zIyzJ) zKD$()(bCe>Ux4mw86Kvg2*<;{Kq?0fvAkk5C4>QYOz#p+Ow9wzGvyQ4F%8sd03qcy zZTgWpJJV;+qL-GIR9FTR5)#l7>GMCgH3zpMYH^n3d-B@B{gAhWkmPM0xJ~(R)bd#o z)JE-rhtqM-*%FwXoIF_jvc6naUo)M`XYA$WWk!d{Ppegk^7E4;^j*d2B4N1#K{pP&Ca7guw=&++v9JU)bF$fdcwGio{IjJNSg z6p3{SJPe^pN&H!vnXK&W@(P#(5Q+p+^DUudG(oa((@kOISFQ8E0KbQYhc^LEVYwFA zXSS%}lwz5fl$3he35Yu@%QBNfNj_2Pp+a4KhC2hM9Ry;sPySV93y&OhGDTh&EhKmj zT_Yp3A|fIOU}?B+WZRZtz^BfDw$%ILT41yb1k%{jf-5gCe=wh9f(6!$?Ccge1R66} z+wG(juhcfYz>gT}5nouD4e|l}p0Kbm04mNFpefR|fCS{9KD`cbgo9v@&bpsUgg7`m zx2*m8f`wp+Q1bOkKD5?cCe)xf3`jx6{yW}p1B!M8*9Q_-XVhE-G_IqgBNl)I0s_=E zH3L{>LmK<~G?ccn<{Yp?R#i39XxJ2LTg+h^;kj|6?~}$==xkF^0Ej;n#w@(BZ58qI zWqMH&Z`a_#;o(es>{SN`2mi!G>Z}LvZ|eF)1knC8A(cFwqkNr`@*4owZ(Pme1_Z&q z;1)A7GTQSSM`J#z>G@U9ZvPb0J+fDfUawMOYNTPsSr(EkVw) z=9KSo!Tmb#BICLUu-3XBCw9hU8a>ApMcn-P>uHQv6(VD7I#*mcrwBPQa%Eg{I?4Z| zx7k$KOw?Ka+vKIce_Muz%I|--Qv&^9K2`5ypZN^CPBk%d^<6;a)2pjDYCHdlI)N6c zs;;g}?VQ&*8m!E<1>}N!K{PNh@Xx}60yj7JO~VS+>of>Nq=$ct8n7Bi6&PGw2ZWMH zh5eNAJ1vaaOmi?8I(`xo5^Q6W>X82GmhUh{>YE5a~J;t->R#>G*BE9e8~iFe@wR$Sh- zy7ELrg0Pq^g+}k>q;+$j8ijB;LvMe7GbkK>w>6`Q zdLIVhH7t9;otBp|}-S?{q;1&74|If^}BQqOFI zWEww-GtJf0*m2}af7+!`61H``51SF!d9e8R0j0Tli9MDVUPNIMDl8floGNU27&+qx z-&C0PNdD;R!bTFIUU0sX?6c$8z)u4i{|5CHZ!r7vf+5UQJIQ(~x zsn;kcNFtj9LWgb;)kEjx8&zwr9nDL}%XPlE9`5b@GGO>TeDcBvRH;)ZHU1RT&IWZc zct!!MPF^DBOP8+5wH6V}DbK;nVm0TLe3MNe90$kd-`Op>?rwLfoMinHT)$k#i;equ zW0dT%rPqJ6jV5f~U-DqsY9583OVuNLxIcUvye3&Bw(!4WusL7T+aSbcWMq~<-(X|Y zkyLu9P+-aM)v-uPR_594YTw7u1B^_@q<({M-GtRQ{{IaJ{!0k{d($jxJ?`LmZwgAp z#dvMp;KemgPD0RQfCiD2;bOvdC5TFhebwy#aeN4^3B$9$Fox(NQfU;P63Sb z!$<%^(VFhRS{fSC78a=1Xr}QiYc8pD>!s-L4iJ759kWRJM#40(5r$~d(a`~=EQs&X zAC8gnaapc}=Fw3)@IExr>?jmA4h45C|MzD>iS1}9{rDvi&v2kAc>JZwy4(2$1ts2x zPBZS0AG2XcWI5UqAPQL_XuSJ}gx4M~^|o7Unsi{$>gH@4kRct_vX-W%Oj|S)zxRQ| z%48h_;sBDV>dTjwi3vs!U<5=&6bo(JTU&gNzvW&hCpQ5lgMTU*oVp<-ba`)Yuf4tf zuCK3TKwuzif{Gakgml@^-;l~e4)x;YOJWE*u&M!iUdr%!P9CQM)fa-wUvmfC5X&cx+agQwv zGcVY&o&9|d<;3`ShsjzGqXyqQ%2-MRL~{4DSh=xEC)Pp|+~ zR$5BYsivfq78|P}fAtgYq~1gbj7|F+8~x9pKd-H&^)Wh{6b5J@X_QL`-4!EgSu-9e zE3+b5+1bu8#JWg85X0F6EDNbgWJJUVP@i2T8XpxL;ciiRqLW*PTie@&{*b@ULF8g( zXLloRa%$@R=O;au&_KXt`r6uGfhqa;_+nsB(3+YUhy1j(G#CTM$8P|R4-O1aUKE0< zmxqUk3=@209(qX`LrO{t&hTo>!FAwUK8qmNLfN4`Mq3WKT#!( zMx(KT4WBV2*f8!Q9EW5B;y5&ja>x#Y{=v4hAwa&mBbC7ZFe^z#p#y^BnYit1fe^Gc zHGjjXYR&k?34-9`W1j`!o(LSy6lpy+@HA#&VS!ixLA-r@_+k3*?(W{6!4Kts%Io~i z_vC=Te_#NLAKkzF=MO80aflVDPP!p4jlp0v%?SF_sA`?vJ;=v#qeI4lUzr@HGXx5k*X#@oQX&h>B2$c-px7+Bx$oS0WEsLLDaj1O-LD|4gE>4Q!RSg6 zzPE(xbUxggCprd=(d7ygXHXHFE2Dx~V-EmC72x;wmP@XT?S(Xs4;+%!nxnP4JLG@7^&(L{#j&ct2hASDlwAn3?l17v5PJrG%08!N2_} zoOsXkZQs6iNXQLQyScf+h>}R73er0AOPBlwpL8SFg(pGTd@L@;-ulu=$yJyLgo9Pm z<(tg?)IsG9-cGODi5;9oY-%cry}f<16$gMXj0LePLqI};uYUBB8alJ8{cLaC{`D;v zE`QCQ1<2i5kqDR$slI}|=4nu9DDL%t@}B$CMJpj zi7wO7%t8o*HBVh0Q24(A&jspE45i;WhDngwCSc+GezHKY&(TgggxllgHf^wKgl$*= zs(AJ*1%{a`6V-yR7{%Eb?*T5r;|CxNuvn&(_mHqHmth;SOz9C{@$ONqxc&WG21Gib zmBZ1_A093)HvL+&+uJ+r>0Zb^8D2%QP66pa6+9-8ng|yY4jDV{-N1;gn|uHFahr*j5J0s)FTIS( z9Ov~J*ww4>Tuo=CEjn&)NJCv6JH@MJxVGRYy3Grrx=c`eZVdNVPW7X`Pr14s33Z`` zJZd@`E%VY{ybCn4ZzE1@E=B3enUQ1PVnLtOyI#zOs;PPUGEAu)n>kACgp=7m_6_bh z+rl+Wtz}Nk)_|E_(U3cT!|OBj1;nw7`$O@G6cttNpaH!)H9RqeD9hiME0i$}_&?V} ByJG+V literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/components.png b/doc/src_intro/img/components.png new file mode 100644 index 0000000000000000000000000000000000000000..6c16d7e5060551f1ab08e4149f8a6688f4836934 GIT binary patch literal 18552 zcmce;1yoy6yY~sjO0iOkTXA>ywzwB4ZbefxxJ#k9yAx<}cXtg=(ctcG!DZ6-z3<%n z-MM$}tZ!yb)*{Kt$+4Y%_WnP=|ML*~MM)at4bdAoI5-Sh83|Q5xL3@u_jj+6Vb6%f zwtBD^R67}MM>sgl-oJnFiAL;y6||E3 z`jvl(40f)pO4zGcVQs?x_j9;t{>Gj*w}td!#_;bEtKj5fF(+HzddLEEt?Ne~q~XM6 zWPT(BK8oV&LCmj@Qay*pmUc5zwR^Y~aj;D*;Tf{g35c=42&0y{1$Rc=q!ADjWPE`85sm22|A3{5x!cQu5pM ztpyFKzusqVYHCVKN&{uo@Q{!YHxU|U*wO|xp%S(f0#WORE&X>Zr+#kcer-u0*ULjW z2$iw;9Uv*!CT3{qGg~`m!iVQ}f0w{gx}OQQ754ljA;D@w^zPmNy9@i@Z<2p)X_S_) zJ^3kQ>u=+n&vS`~mp-d(7T{_xOP0|?!e#6UczlR_+eM0Vdt&4R%5o9jGRO+k$S7o!|`S9*T-!$9lnjOL$J+)}8=1zN+IA?4_4=)+I?1ajw+1 z8nWM-!!MQ7+S6P(*iBckFH&UUs^u zG(B*7`zAKNQQb zI#$vUSq^RcrjJWq02inCJW4;oKQ0Lbl&wGnm7M0SB{;BOj-C_&Cb9k>Z5Y6Zk)V<#L>s(>W?I(Gw?9 z6|Y5&2;Vi}?#3G4dU%L6i>$m`^%BeK>S~idvpA6NatK-4K)D$kMPg;5+`xc!UH?#v zw5?~ZY!}NJmY%Hmj_qtTcAPuU`-(Zs-3;Dz5v1ltx_I#i{n}FxGYzY*cS;SYr;``S zo^ED7==pvA>jRy!yJcfOUn>av`&aSb0?lW3oidrN>x`TQ?b5#G7sMHP*tIx@`|^5@ z`X{r@IfRD1XQ5$M9TEs#Z2tj8F`lb;VtBxb3(>1jqB>94u5u77%8!(CjVu5@hF`Tb zWBj!B4${|jDp(W|C~(dzS6*@Ch=*KWCKQd_?bzU{dqquOb^jtn&p>|fitHX*NyJ4JSesU~_4g7OAG2Xg`pD4mV$ytenXxg$Z z@W742P$dh1MiAf`zM5(`-Wq)%sBt10E%muw92ZG3G0)$uy)$Xp(g)0c@fB7g_F>+> ztFKT4o(KnN*8ND8)d>oO^F?S_41+pVHuV~2SMP>UFsBHYqv0{cz=odl-NhU^LG&hx zJtDl=S5<4oZ)0w_U8#rL?_-w*Y>PO&(*9i1@{u(VN6(PIyvkU|Xz|scw2Kn-6j@3Z zbonq9xOjZ$%0FC*vz7&&^yohxfE^>I`mQfq7bKaRLT`l4fIcgAMR3V1;-JJAKgR`p z!{QN8<$GsazNeM7=D%VeubEkJsI- zy?)(Aq=zj(AExz_(U`>$N7qf?dfmASG04v-!D)`tAr>|p4$y$F8acS8K5(&EeV(+} z1H0_#%)ZmY%t~Xaf>;K&X;>ZA>HJg=7LApUY_Fqq(7w#2U7M?a3$71@(|RR-Znc8; zQgUxpF{RPQMw$FtA9fyjVRSs8+HFJZn`f5Z_Qm9pff*XoxRCchV1l4&OKTX?OGFYy z^MU_RCkbt9sUfP-^&y`B7~4(=jpH*mgEeeEjg=2Gy3E_SWEx8`7gRmZ?Ol@%?ZWkZ zyBk}^A8ieGHbnzX_j(;F7;+(S(L}|lWEtPy;;ZjbI$;0fipI|{dJl+0>bw-aEbIC^ zpe)+J6xx$s6WF$0?%!~tY|!k;=98>Q35A}wdLM7-7Y_%GBlINR$icLNUOPI1RTHDu zuzFX;U}VBE6!GL%+|>FG1H7|pexFjJ~p-WiIdBnWJdrR*q$Q65*Y$vhmQ zF~fJw5j%I2O}x^r>%aYK5kd2zG2k~Y!!qnrWQuU-_6?Re9%OV=AF#f8OvVk|dh!zb zj*E(n66ug;St?el+eGlx63u3ZX$@&~5)r%+eI~drEjYE*lFhY)&Azd!!hS~Q z#k7(4S1`fV|9Sm6s7<;LUqh{a{POmzmChtZs0{C4dz#Jq!U5aBTPw6P024XMZj-D|GOCjeNQKm9xCkgk7!84Wf)-M5^+!1#UxgdZKzpN zLJkc!ARl;NkNkEicO%tmU!qcow?a=L9?IQh- zAr)UucO9Ipf2}1M77y#LKvUWp*IDr^%RBOkMDF-rQ1S*p|D<-|t_uW9FF(pf?H5nmW?VNTt%zU`7D~jN$aHl&OX=}AF7FnmTfP7A} zmie`mSca;5M<3ma^;6hvUuX^4a_4+N-E{;Rk8M#rjVFcC2tL7PmgGgTqe`%fSKnin z%53}9EXkX^_hea|{pPXbns$P=9!E$p@uAvgqhh()Ls}pEjeo~tSEJqbXUTi6godv z8Ixmn(8non;|C$h*PEO6`}vn1esxhKboR*Fn_|4VjYyE0WfoA-dcrBy#{HOVM2aeq zQ1e`qOwl_)r4ehKPlkuhDJytJbt?MIIrS`;uk^rZ?cwrzTygQ!{Os}B2ti+Z_|%}@ zHRVe~9X7;ZHRTp}Smx}9kOQYl|FdG|$g-;TN_ zF!UQ0IC(vW-^kL9^5aq3Kg0Uo?Uf4TSxH}voq486Z^v}87aTQSGzD75C+`v8ss+vw zZ-6s^%={&;Iev%yp|lA?(be1G&I#Fw4G`I+?0lz_84zv$C$xv*qiCp|_fxEbm+1S$ zF2y5dxt-fs1;#5|IT~FO8_&7|RHd{tUX*v40ZOR@eo0(~W+?I!jt9ZaBOEAnhxtA| zE7@qe5I`TkW)S9o*53Q2_wk3@dO?UTrK4;bu^TGI?~)>pePg(7Mzp6`;JdVbc2@;_ z?bfKWoqaiLo-5| zchft_r07*hq7quWjQLp!i+&FF9?8}86Yya`dnN30fXz#!jeMC5DEraxU|5vhj?+Ne3cxer@Y;?{dsWzbEDTh5 zP%U)^*mZNRDPcMhYd?*!M#(#rZPQXbk9m?xvT*v_8^VM(Cpe(8 z@*hRMf(A1lS`Zb2G)Uy~KdSuw|D^Ii-z}KkI$ku8IKi7!`YLCQlI^-Du^9C=wT-B~ zjK=$>(x%v6`-rBoW$N#(@FPZZ;Y9BXJjB!fh$Mni&efR?4jymzZ`yCVn9XFUS7hoq zkDKTN7U>+K*>+JJN?xS#6vvv-k+I$T8C6^5)Uk#G?Ich8aNClvW>#ZOpBk`L=HKySg0qTbbzP(*A z@eynwWGK%YtNSkw3wQmRITRow9Z$=wl4wk>qPl*2euz2MX6rqfMKEeIyZGHAsM@n% zXykl+%g&NomzTUC)l5JL2XkH9Hv^su%;mP#6G6}(Hdba$Ql0lryD7d0idO^Ovma4! zArNp7_C9Sb`FOaXvpp@Uk|>(!5DGkYacQ1)p!OkW(l{y54o>54wi5OZ22}V`E+hC1 zR-uzSTt#XUw%&>f7(WHq>Jq)pw#8?V3bIIZ&mYPpe>$qZr&+A!S=|++cB1eq=FLA+ z9A8_kq$0?B&=sn%_3b$5(~h0X z%^b{fO>XZ@p!_nf_iLw~KCMWd|1~EFY{7-)VW3|K*+!pj+!n-vsW`_pNbzZVcm_j>3spx z`;nf~7OrYR>l5A}2hBuRH*vRPc*6Mm3cbe+`N0@i98lQ`_`a`cghCv1fS#&i>kaY9A zHMtiL^@dF^g_^3F+i!P0SvvfdPfg#um*-d?3U;I%J>$oafZCQF4TDIkJdSyjhqa63 zw2tZ)zf~;LLT(fQQnP2{>n!|OK(MDat;3>jUVDKg99QT- z8SQ@vAip70^8N;=0QO_$??f*1Ve`$0i{i_Odz@Rqgjm3}Wgy_@6KCT#_Mw7@V)xk%N-%8c;!&0ysjn3}hVcqz*0zgmkDlG#~NH?@8y1&{Tmu!6O- z6b+w9pEaR_L}YQ3qp$OAPbY+zTSA7iT!ps_T{oYEeN3=te2bV4plp7tksE4Dpua>CNi;mA;{BPVq?e3C%;QVdoO&Xui#2cnC?5= z_G5pr+3w~n$+v(IdG@02tZ4GBm7N*$C)_GT&E5@sbUI(wPL1+6uvK9I3YbP`#fBX= z1{UTm4Jgap9kZz7dq?b#47`ZLLIc`&t_r3g$yW<2QfD?mT;p8WMJ0=h2yYo{*}y_F zYFv<^>{?w9hu52@AQc#V{e&w2s}eaFhkK8w+i>}F(|Y`w)q=h&T4+efdrAycT*@B4 zw;f4O)u8-Cmv!NGG{BY)Czee=X&o_O8g%LNyBx-Z>5Ui!H5T_#CNfW~I24x{INaVv zugiwQ;*y_qG(=OeVX6C_PWhW^m&I`rIxwKk#9+jr6y(QKNC^wRXh>m)8laJc{6E0U zYTc^L3M8_!@7LC!@O!-}V{ytUi}hf8M1!4zB?ekKa>~yP|xzSQvwU>RjQU-y%>1P5e*GdEmnHDLKJ_ z@Cz6UmKO{#Hfkmz&>&}@9(%_SDW~7PAscEs8rKsrBi5Cs4(~)b8yh1ouU+|_>%7Zm zf4KnHNW%_X3OK(Ip*FppDwXE*cX=79_SFk8T#mnXUOGy9LGv7P&IQk?SAuww|H|(^ zs?(ki%G&p}oa{fY1_Hf=e9^9Xd-fpBucZ8p|FgX3=p?O+64N;9S;v>G7Sv>2_|I75 zYLfDxiK)hCq1zl>d1ri%)%_2MVOI+4N&z#Scm~9}eI9e&#Xn~Xa>emtKYwjbV>IWC z?TFYck_KP)1Zi;^|CU)24Rys!DmV-=`f4cbj}0sZSG~yhw|oBR=flX>Uw9$7>#abX zy{>e7q^>81Cy>&%4u0-ZDN|(~eDm>x^J3la&rRk|q)rGtUY+r+fr&zo-xsL;EN+Cs zh89Q>WR)!dEI4lV zvo0q@CY!(-(zcTK!mBliJb8{4*W4T!I&+5RzIud$Tg1cmafgwn8<)SduxyQeRXM@Y z)RiX35}36apIC&nDAUx$OpUP1xnt#Hm~eL6o%wIdsGKLjFrn{7?Aq0_J$lQtk32i+ zyob|7k}wG@v#+)ql+}Z&M?OrmFVco^L2*M%LS(coJ(=p$c%K9RlqPGg_z1Q4beO6? z1U2d`DXk%mF8UjBoWG~XV~>Y$y|kQ$9`S`S72nnLZte^`|9orP)tG%3o*?>n2+B7c zn7cx&4|9eA8rjG4qoPA2308`{$3@Emjb+Y9fjeEyW;m|cj)IpUV2>R0!-hO1=?}V~ zx(-&lF+{6OiX|OaRyJQ`&4x1(*O`9^!C+Kcx|ej*Hcn-w5xyjHZEkmNL&26mZT7Fp z0JLONAATDkwj?oAtRUKLo;TXJa5GaU^JNWTRH>K3;DtJ~-!FosB^1-k&9D{u?gY<} z7dv)yDLD#h21?01Cun8LpaiS#aO|yjsa8{#IjQC3UitYIsSo~t&_s>L{X<7&JpS-y zVtFp{N)ZHnpjqUP{323U=67AT(}TNO7G;weQiRdx>sIRfY8E2WIh)!wTuHBQI9+DRe^Eye%@xoW2F%H88Se2t(zmP5wcUGg?FHNwG$kM%(rYwH}|w8!LIUhb30* zbd_Bc1!O`MyJK@4dn#{Lc}s~a%JqIu?L;qMeDFRIg`VIjEME2wLXbl822JsnW1`k~ zqh}nk5Hdw?A9VJ(0bE!B{>uBiPH~M=4H%%F=-nZbXTJ{D2Ergp?3Rn(fcu(Sh+Rm5B&Hs z$^u#R`MD{f&R8U|tMT6?%K1nBo&wZ1vJ-jImKP-IHvq8lr4V6oAO6b}l?t+pSce+L zHu-QM6cnx(hyL>6$a%rIVk)Uq>1It~4oUghjF%Vl7Fhkh9* z6RO(nz)>2x$FZaBk>EtKre6i)%JSb{KbHZ!U_i20kw{^uyhEu2kWYsLRZx2@--|d+ z6gjt=M(wGvMwMcsY*OilkyN=(9`SJ*EjR@*>LlL?g?A50<@|ZsBBtkP$zSrPTt^E7 zl?dYaA)yJ>Fw&%2e9PB?>UxTh`zTCt^Qv5dLJgEoO0F@VIeT&#h?#^fcoV9sU`_kY9tT(gkW7-K;gSL%TP9tPg z{*neVZC{oMEh0g@TBqT1AAN z__HcW&kkVMYi%^s%|ifL{uFGP{CsyZY3T2zO^;(h+Myp$;ONK~Byz?P`#ginruzm@ zUqa$dYGgI;aJ=XXgVgomm^aQ&rH})iZu0m>NfpALJCtWh$mPvpjy?@h-ot>Zd8=^P z1DSWU`UL1v%np?v7hvNlgE)Hcl+%uDt>`h?B8m9v+8DF@4y$8CTY2!Ln=%>eCR9SH z5l)X9+#644&S?FwT!7SLktyt9n4c!YQoC6jO2rTw@wxbTb*{^aIyTPzHL>DFP0 ztb*V+kSE(4!W*E&{B@r_gF^gt>ly{L8K{iMeiK|!RJ(<0+hPQl1yo|GqAybyvOA2y z)Kfx0O`iC@)nhz-kY6(|m)*h|2*r_RH?k)&uNv3ga@eFahccmC2qa`}D9B`uH-cO* z)xOR)Fq!lSDcm~XEVdJMJ&~Vudso$PDOb8K96KEg#Af1qPmYnb{5x9Zz{R)p64=&) zT(Fh!KyV7%JjnZfo@gNgcxMZ3Y&E=Xb5sw>Ms@;EE^Z8sK{RZ%`_hn0NJWj-+nFRV za#QN_N^+?v-sct+u%jVZP7B_(n^j}%AxQwd$dP}E-G1xDtBce9U0{oWY)_3`j4RL^ zjqbAV$~m{;i48}Jhsu7F*(c?kE8XOf;}**C^?n}8d9!%A@-n*98GFdKglQuw~& zUjD~}1m(UDMM71ROq6VY#b^2g!EFU;=3q>r*CpzSose)$wg&Rz!k~ zt8nqq=wyF2rE^Nig6P5bDI%*r{~IkCCGD2fiB~1L^D8)Il5~KA(Yd{y^eNr!Y>aKr z$;SQb4r@oH?X0F3lM`MPQRIXwQV}5|F==$r^wXorDX}@Zb=MPwd}GsfH)eLzh8DBz z6c@6c03u7OX_QfpG+(a0NqOo4dtJ1IU*CwzuKvMoeONpFqI=rJ5kD_8MLYr(3)qi*|SY)AiQK2Hlo3REIBm)%VVC{*pJ=jT1DIGRh393mFg} zP7&CDxwZEu0SOy}D`TE4o(WNsIB&wSZXIR?H!jfW6ZO@k&Ib;sQXZZ@Ujue<$=y^b zwV{`)&+|`cQ~9hro$X5pS6fwjhXOX|Q-^8Lld$zkK+Ilyfz^d#5EMW{in;RiQYQlIkjfTM1?d9N=S zV5IRJ{dLBmuPw>I^m0Kzj@taKiy`Q-gn=r{Ehsq4Erw~M0Vm#D>q?I!MfOM^iesoi zFn%?!c5B%bAHwJox2f7{Zkqj`j#)Hd_E6yv*+;7z_-*T{!A^aX_p0LTsmxysoSFhb60uGOy3lF+_Mkb1P)`qrty9`acqADD;3MeM;h55?;!mp?d^yI8NymLK~iP?qx4# zBkKy`yJ+5FiD^F8QTe6E)r{Hfmv+6h`M|`II$+p;KAp39XC%&Su~@*d9}T1KKz>gF z2SbR1Xeq_7gu0a60#GMnhSkdUF-u}mW>sJZq;!MaQ{(_yit8oaP?o!^ZCl^qu8G5S zbur^3Lc|)GF!zZHvQwd-^W}rW?Q9mvRZqSWp5Rlh+n%<^9rI2m#D}sA@n&T(!gEz} z9L4s-^ecicy_ro9MpL2TEG}gKB8WSGCeeH)qW}m)fheUj)F=oL+(; z`~LAkVxQ+Z`?Y}q17vh^p?WpK5TKQyzM&u6t~DTw*wRDXFjbG+bz1OQs|qXFaGJ2} zh9!K~sD57|6{`04o}0kU=j5uP@)nxy;%|?lvATYjWu0RHY3IgjSeKg{95S2uYMauP zb|-XZ!xQ3T!?>Haw55H0CA$CLSyij?Gup%NYW(_!uVc(H^5wMP%+h(lzEi+brBcOY z5L8CH=?72nXA7Z9s+m%4mWO{?ReU^@HZw4fY7rLx_Eo>M%n6uLqUeleCy_E^j~0d7ErlzTmV3r~biXjr2aG*={^>73YqtWN zZ?%pJ`#7fyV}<=M<^l=xjUlb5A=&@wEWB4>R6QTc|61KQQLpKlww8+utlEiRG8W^S zbyn*z0>+R#wpXo{u0$f2Z&IgyY5&2Jm2rL?%_JUtT~?%Hjsk&pU>x=9qG{$$^2`&5wCrkJ?+hg#T)X1pWH{lV1cDZ{JwwxdD0~mk z8RK1+Jw?v4SBUxC;U~#|46R)mO?Vtm zV<6G%NS$7QOqHu3VmMf6?`{b^Be1nLW`vL->@Ty1MW46@st>|{MO_(72(1w~Vvv{E zSZlT#xwUuSa9of8-07?t%olO7uNi8~m-vt@LU zOeS+WxIcY~f=uT`tWz+sl4+`bX6*seMn#}2aDf7Pk37pG9gHZ}>^Hl_t-o@U@q^D4 zeK_8CS<;)r_*Y1J;~v4IPVFzh@zm3d1#N}Pqh;C#iwz8=x|Ii&VNB7#ozM6Tcqr0P zF<3PFfFUv0rQ!IxN2hEvzR0t1wjL?bKkaX-R{8NIN%ZoOX;5|}|oRr1(ev|7pMf$P|w zI$CwG{JqmYZY;;zxaw$@*K#`i8zhdVHyzGan2gUBQdC~4wheQDs1Hlb3+x}PWb~l; z(jsuI#yRNa`%A*oY;v^0*Dc>yp+mx+n*U~@kQo<<4JD7UIsr-i!KtC(kz+DT9EG2M zblm%%fu(f^N$cZ-s}6sVQbHd^ym>t@nu7+7yX;KY2I_AC{eT^Q$8GhF^tP<%u__W| z>|Gs59NSGh+nrs%(dTBd(X$=VABk@gyU(qkLy=Ibqj%G&OYbA0gLvH~nte-mRARtU z5Wi>0LM66tPk(|l5HPwBV4XgrX#AP7T~T+k6a4vm-~|EQY>khnfe`HHaeKLD5kZwV zM^62b8tZc}kGXc9ks6<-L}xqolTO-dFh1$?LeZwmkg<Snt5yYWxgmqwhCtK<2}4H*Kkp0yk>2({6!u&4J(G%r88AK%9vJtF5EI z!^Sz9)xMn6@G9GVhk8Uw0nJCpv^MHlOr(#DFdK_wc)hu!+b%d>QhptQ&dKDXOy9Qo zhy<%q%~#*?bLb}5aILf3NA|O?mCm_3xE&hTlZlLtskgi)7XY=NvrV2J@S-IO?AmBwh=#jW*QGBbz&8Z%r>8f3J_Uu~hfugi3^uDFsm#iLw& zd6J!ws4%SY~_9su@4W;nd!<+oaJn-8EBx{ok?;CdKd9hwv60_k5{97;A*Vy`Grfw#5!|e~T zn+2Hc`%K!+yczIV7`eZVemOLxTkN-_?^h@rMI&@7EQc$ zbQJHBWJH2gHu5)nAa^LFk08_WYbqLdQ>Mz<`2d?pdior&2Oj$ivhb@VtZr;7T3g^E$aLwX5PGF#SnCp%~Q0H z)77jmoc16c%o2^C0bWpSHddw#kQuEL|G zs-=n^oge8T#4Pm@J&VCD!OdncJR)+e{_420$j-P}K)H84VkF#oOpl=HxIygI#^#6qhWgiGV`mBAO-%Y7H zZ7NMhKw-ZxovT=jKgP-gLDV`VIB8iBbU$_ulGU{uTlUN)TCrO{&#`WeVpP`%B* ze@*M-696Xj2~W0t1|=V1I}to_0EKl>N|4AN9T*9749%}nsF4i}{R+3k&%9w#^xoS5 zcmkf&oyeDCz*P#}-s&}48gJ=vA_j8;2I|g0MZEU>+NW{>O?2~DLObol%IO)68LMZ5 zS03ms`+}6O!b6A$HRq9dcIx^~| zdfZ*CrQwrhrhoTF;CzaBmfbd=o`at6=4l+Ow^B^-aZvs)*^%#*Hm2Vh7&-Y_DI{z=9+ zxcf07l0HSh$sy`h#(T5kN>|3TbwmyQN3JWM8!XrLIg(f~ze1|E$ zj#(mg_rq7SxJ-u)lrfKX6KX=Dh?zY!O671QCHnPPG?q{w{LXQY;G{Aw;34;7jjJm` zAX5><6y(5ta7n55(CXIClsiYTBfwg^_qYeRr_tp~J4J@<(mYUW_=*IyDhuU7U_Q_7 z<*~{gek)vG3s#yb$Wo%A z)a4$b*=4%nzZuYN@Mb;!Rq3gw{5H2$3A>B!N^MP-1O_v&%xNtM@m@V*ECHBvP^6=h zT)T#LmYLS;%51qpVa6!CiP;+-Ac4Yo6tu<`H_=%0Js2~yfmQLZm;4E9Sdx=#V1S)t znNEg}LI$ONSnIrDMW8Cn$#pH&>@qV;%;g62nIB*UiOM1!a9VfqjyI6};@R>(?? z*`B;$m6?~Xnz2DtYq3mLfk((S-%PNM63pCq!~GBr3iG_vper%f7gKyMY> znj$M<%VRM?74bCe>eyE_+fs)u(l0C@O=5O4lKwf3X?vs^DOT4T&==P!7XD08tH~tX zf)%GyX1=}}WEjH_!*YJ_k{mg@zfZo%_CwkBKW@d@iWd?%*u*GZ@S9yZgzN#0kD^*|cnN0DW^a!2?i{4NBWm2a? z7m8!Nf3nUqpaOx$5qwv`*HS5o?Qf;K>V{n#?QUcnu4P+Ujn?)i|Ky`g#i@d_VS2+C zk`IO4-(G7XWz|hcnlO`vSd}GaokxZ zE@)>@`Ucs@2;=)|9mX#_G<89Az`!4&rYFB$xAl0Wk*9SFMizJfMO%W--E=jyFNV+d z_;~+UI{P~X;5DU{DYX5HW7_VeOm ze}pAjCu3uA2x(NBE*yGY^sM%R#$;6gOQiL5fx9cXLgP zg)>5ZU49?RMjHXRKVtBzTauN)6&kc>$an}t7aCot>&kl1Te0ZJH0}`>BFbcowhoEN z{&~vi^FkFCrWs%YAMq!Dnkscj#KWA1>AyyF*Sj*;8JZ)s`xXpGDNx^$+jX?|6vu#j zal?(!bOi1D4VmZ5Y2s4MqtP~#tY3;trXU|5WP6b5HSjSLxat$Hy{f!XLql7Jyz(iy zlgGFeW5J5jA|ktmku}dE5SK(*$7;$w^y0;Z1uu2y5wMAriZPQ!y9{ zSP3;*cy0A3ls9td8{F(!ae$dM04$16&^3K1oS_tHt>s^Cw&zQ>brLFevG1$1vnXkW zftpv^M=b(HGzURz^Bq|2O#=R$cX@tK5X{PYkr|QW=7gL}E6^cx4>#}iHtp!Itf;0g z5bEA~jxs)1L2_)rabI@mD+Ma;;?#VS87*nL53^(T8QtT#z|-L=RE&p5XdLngs1>9l zoXjJ{t}FlL+7M)FdzZd^^5MX#HSyZnTFdHY({I9cvd&TLB=d@+rx;vqcX2~9G9O7p ziLdbYs{1VmpX;vQwtXklwQ(-e-(KAh8r>b)>RibX63ZGB*QBksy#{!3Inq>-p`;d^ z%yBSlu^>x*5f}o2w+YH`wcJgDT~q#XmqwJeh6yI8v{*7W%-wt3%tZQG>rxM%ZX4WE`K1 z!7m|RpC<@DD4KM!2QDdb7g4Qj(h#lv(TP3Ybq9?{Iby zIh>9Ng7i|mm0xadB*zxJc5tl*DrYyEqoAxu8yfOv9#MOJx;H+983R7kT6_7M@wm#g z@5$nD;_cL8nVPRYY?OM@?Ne@w;a`#*PJNcqf))Ds!m2Y=Ltw+QgZ6+a7+i7bX*@Pn z82IPSHiuFv;K>C5%5ph<{xN|ylC#qmZEv$(x}Fs7Z5-mcn(W2D$xgAHW$t#l1neHm z`t%3Gb)sOB*4&HT&kWwXk#%p{Q-ksA8*t4X9UjTRN}^F*x z24zV0b?j`w{>9T0}eaaq`hgn{%p0m;YX}| zRNG`GT|%4@E|aU=ycieDnq1}`NZv2>)(Wg&bittt4a8@5v-vo&ucl&RLKwLnPQ<3iQ1^D)cxkB;>(o*VR?~(raj(+I0r@6pRf2tRU6%}i8WES1{ufal5?oxL? z;3H5h2Q2*QrQYyQt&x7Y^|xQvGVIbmnIl8USd;a~A8d=yxwuZ+!)(fgCJ&>mngmU0 zJ48I0)alw~A-NT|7V$XAm&Br}2GK@*`WRLnJBwI8v}2pJ>x&b@4wbaL06_+OdsAe- z^=AAR)6dcQ0U1PSoH%nFH_IeYJ!y%Lv|z|fucpAJsB=A7F0(6VuaPkmUU5v=RQtaU zi>eg)`EOnvQj^1TN&siWwS(4n{*E)$vhCi%UNi_8BEQ7u*W9`{{L zgct4wrjBY(K{g!Bs=pmX*S5BZDKg=Krwm~UZLmB}4~<&4vax8Ne!w_7%RW0R*2!06 zOwt}wjd;7Puc|Cv34_l8kP){i33qzKGU0Y){te8xz_QQVZ-E35yV#^1+7F$4Hx0{l zA)+MVD(ytLufnTH&804v*X~@fDif zYRgzk{k|4z-)xb?j&s*8l2APJ@-)R)ikukEQ2RLl`ZYgzeMl!LjAu;ex3L+EZeW_3 zJU3$Oa9TO6;-%?}IWi$3t@%Cbh`jIF7hq@4%lQ3!{_}in@Uy|xPIsM8^)y-_K zsi@#8WJDt<2EG4+BImn!cJa?=Z2k+&45+#H$y9{{*9&MjyYi#sX|wJ}{g)tCO3J3G zm@f=94?Qi~-T)qrRsHxfwwtYi@zZ#FuhTwFYtXk{K*MC=G9qsaYkMdD965?YfgEjhQcZ){M9X+slFu8Kf z`)~-U*F`~nNtx1x#Sq639RhbaxYzIg{$GIMD}jjp3b4M~KvbETo-f$>y;p5u*sq&v zdJW@UaQXm65DGbobcI@AZk`4w`{XAnIZ;238;+Oy!wK=03>62_7x@xe?*7j5NbP}! zmpG&((SaXr)R~Hl7loKa!>vtt9vZvup**o2ys;0OojnIUBUxgBM)1iEF3wGhbDI1~ zM&YxQp3~^$hGv_c?qF}jhycX7u=;ZsIWqVLkpcfI?^vR+!P^4@Z=kKIbbjis^v0h4 zLNlwkGi%i8%8+eICan#D>nNEl5LKA2T4r9wzsEFB>3HOgo``UwfVC3SZx#IBY^%|$ zh^TzsG5n)K472`aqiKLOMGbRGDB1?WZ!1TP6-TuCk@u^{yE=O%Et3GI*ZzM>ha)QK z`-o+94CJmvE<}Z_%*zBerI#= zrcdUq(G_gjyN!!q#ALRVb(I~ihRv8ggi|p*-+xAdoQ*9FwpLC>O|tHals+8j8@M^3 z0#Ac!-7p*74+$CrMzb~LD1DbKrE6@d_ve=bRx>*@?66iL;rkz;w{*gH!4;^Pi66TW znTCDOIrpLF$jI9@jCYQ5Gh_i#-;Fn?4hOE?nvj$6CdVOjTh>dO_W?+s-s(8TV&n0( z%(fy;aS~?7uU9D#v_m>wnV7xEpU6K)eh3!r#4$;}7-{}F;_FULvC|fjD(W|Ik{3Z( z8Ss0c=#d#cLj}41{d^OLXd1DmqP;LDJC{*}i=#=HtTM*#cz$+?8Q z?Qd;a`%JVav6bBxke^rMr+ywcq8^btf*jyBvbb})R^;69*CMhWDXRUeQH;>y?B>k5 zABH0;Y0dC@=nq8)Fx9kz9cxk zRK3E^%b18S{o^Et@fy!)mH>4QHWf>Fa0EO--p+02arq}EXXI5AE1pKBkzQ2)HI!zV zo{itXYe~{`%-}=X@t^Mb2aAgHMbEeyKbU-5i+P@7B>FC5`++KpZ;X2QU0BO;v5E*n zF#1OZ2UX7n`7vXmUC{@5nYf_*CIM~j9w--%Hh+`*fGKwNOuMJS3RhKfA-X7mFwnjP zT!5LYR_UcwvOC7j1XsKmnr|@DO+=_Y`(->Mow^QvS3jE-I&bZ9Dvr7QK%nwd(OLsn zE_^tkShF@@$QdfY7W(*PsxC2?v zmnW8=#$c8B)GiL(&Y#c#iKW_Df`wL{sgG6`0`ydhG;;q*v*xy740G_a`f~WOGzI4!VwbX0Y>?#mS%F6UmUh?w z5%~fJ{kWl#jEjGjiijA7FL<3b(HSgR{xK<^tt0csWh|Rv#+tR8!;R(a+fzYR$v5O4 ztLEU>xtyrX=bQX0%5yR)YShr`bNFb@JAAldC13PgLh{s}^q=20=PNuNRLIfBVzP5j zVBMF={+e=fv#f+C{e}6}FEV=QNN&IDSq=`5BWQ27m)HtCH$*eSv58k-dW+1;%e%U? z-=v3$TDgm0OFXinV+&|>XODX|pKQ*i+`5m9gH@c&%OLM$IXS!X$xHi|vg$liGmdgv z(=(!7UGBsZ5k}MdNhCh^CIwnB2R~R%dHf0?e8YuPGcgoTeb-FpWRip2a}S zQ?GDG?ys3}=fga|I<=*723^QxW(I%8qcaov?fOFWeXH2J!%9TET2CW#nD4PSx9#o) zK@hGGNz*RpOkpIPW`xYPgyl$YxWkxh~DsghMuC>c9k;TDpqZNhK`Zzk<>F zK+MM0gYdrRRB_lG=)0MJbpB0q*>UMj1YE&3QgJkLYJV!H_NU^kslZixg3yJ3qsL8_ z3%=&!j=Ozb+;%&X$%I~Y(&RE=4wL~6r`?I(WB^5n&JXWeiF;=KCEGa8r=4y!7j~B( zla$UAVXqRAv7MxWGH5PrcA0Kw36G*ff3{X$uECDP3W6Z`fiCttNy2DuzsIU%GLOVrKQ>Nctg0P7b4&SotaZfD3J_-_hrNrqxog^)T1Yv7i=|VILIIDgO>Z5Cp+r zbjp;FAP9mW2*Rb*MHbx(f*=Tj(3OdXMGyo*5Cp#`8Wuqi1VIq|o@iJEK@bE%@Oz?R p5d=XH1i|l#hD8trK@bGL_kY*qziJg%JKq2R002ovPDHLkV1nhfm|p+@ literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/fov.png b/doc/src_intro/img/fov.png new file mode 100644 index 0000000000000000000000000000000000000000..693a49e8bf97062da3517626d531696a7d70e082 GIT binary patch literal 9712 zcmcJVRa6{7x3&ij?(Xg`!8N!;aDuzb;1D!eAh#u2n-uM~9OxbFL`r4G%pdBXcg4QE~7Hb)goICf-A{eC^lq(tC0? z=9rvyo|(o6juwX_kEI%>p|8*nppspngc6OnOGN_7)*5qwsD?v_L9tYXH2*h^Ho7-0 zyI6WYxwcS`e3GdZUnCWWK(Xntag#OF2}h@-J$1)!nhZS>D;qE`bt$afF%`K}D}3ru z9H4?Cu`Q+Dhv&l+s~Qt@8%S?uGx5oNuH@y9W*`~GaE!uv|7nC1;*$z}i615Z1_qHh zSh4r4K`SFKC|93H`<~60By1q1=Kk9ElbUh(?3o{G`+&pJ4QZwOyv}HU9hy#T_tgBY zomt(p*@QuvOzJ}=w{Cu1K|@Y0-9WI>JiU9i{b2pFGWtB0$eeTB_z25x0(-gUJ+TRi|NKuR7?Oi7iGep#}>3^zVbOI#-eB5OmUWkaTABV5T* z0>X-zi+9EFLD{w{FKq$EUl}*3{R{k+d;j_}dPvXr)%b=?`g60Z71Sz>pJOJ|zZ%!B z3uvbqX)%^MkVBO1%oN@I2Yg#%e_-yjRj+oX@mSz-Qlebn4e>ZXxeHZ&TQ!!=nk>4v zS-5K~_&WF*^>t#Zw=Hds0rU0Gs^@Epj}GT>+moC7=vJ{MiP`Aupw3$^=YcSxXkV20 zzC$Z%j@(_*-^TID@0*X*93X;-_HCEweoH4VmaL^YK{c1}Q-lisU4GVs3oF)B{8m#d zC6_j5(2%aMlrYr%GcJ+SM?Vq|k+gglro}$RrZAocb%fiTDx3WxWl?G>#kVDYJn*s` zIT5`WLsg-mn`#_nYQA%8WrlKJnQqJu6?T5Q-XmeW9 zc&ab%C=R+IDAza=3gW>H!Ne%Lw_ajDSMg#=rw@j1~XZXCf`~ zvjnc-I<_{GhQ4Tfy%NMdAyOYy7H^@EaA8+)S$X)eogNe!R4xQMAKDCHR#*T3nKH6 z2c(5}?9tk+Y0p-Ej%qMna9d+hQqHQP!yfm1?!1l6T3Zg1yk!sziKL{g;ALTj)v5mN z!5jnj{;tGCM)x(W|8R1jBR=PY$Jy$u0Oo6?&Wky6m%2Gx%zJg>=N-%Ig>r=+V%@9Z z5$VI+(*DLrop*j<4Z!BM_YD2*U@w1WOrFc6$ZWV zq(Djyf7_r;=C0a?zL?_7BqNy}-(>v!?(pUZ@4aJa33LI=cd0+cWvK*PDo6a^&;mri zc&rkD$aNG|twSChUX9tW8c6$o`!l0C`ZejC2**(&NhLJMw@G=0h}j8au^Oaz8QkRD zRp7lY#B8V7(@J=SZ0+MZOrT{Lw0(N8!4ls&VeWYnWX8!UK@-Q5Sjk51Q&DcXAiS+v z0t;(p>R+}Wnib>Nljt%1ysqoJ^MH*MT@;-@t%TnmK1%4X#tHm+U<$Nzfg8%WveOx1 zJ%5FOtqj>Mt^_YH`*3xnKTR3n_r@CzVLFwaQ0(_%sG5`2C8GWmYwr zbdr>D2LJs?onKwm)4r*qa~RYd!i3WebjG*ojSX0^s!dInC&cKU&Ahs8^}4c?jQhYW z>-dx5XwiPiCZ5lFQ_a)tD16}AQQGKuCU(bT@KIIFpzYin4bxjQQs(8H=Ja;)U-9RC z*)w{JKCb=D^vD;Co&dYGf!6p6I|OQ$RHC)y^jJ37p1HzXso+*#Uq|M#tY{c5#ngc* zeDRp~yUSFd;TVgd&-a<_DQ*ESd;;u-wM{t1ts+xEUpTAZAIO*YdWB2bhs`2GHIj!5wcwqpm2nC^UxRb?!TCRZ_DmPjKPvK>AvTe!vgox6o zX{W`<+oY;yoYbpi;`fQ+y_2A{BqFJnuy-z$P11KhJvH9=FFlk(U-1dH3{E*Xz9XId zU^Q{Yt7`AMZj5SZ)_t`ykukS!C@onWY_B$p$Q%NDA_DOSzl#j)X=`5xjjfZ zrz^5i>}n7Jx0N{NY&BbSQhonb=jDC^HP+x4?Z>*z#?HkJSfNDq9$W!6_EhLfU2bB? z^!1Ti`%t6+{#YQm84c}!E9IMP?8ZTRwraN(zz+U$hW%dk_}s_|vk3irfA*1SBPBxe zixqV{7Z)DuLB_Eel}4qtVSFb{JO^Ux-J|ZBe!VY?$D5pFanj{@Ad}yckMV)y&d!h?rQS$Z7YPvG@M({Q?Ogs)!e`?TyDjL7MW)L79O*C_N(Wlc zPiITw3OL;bBsAgFZAkU1bH`w>?T<9KXtfg$pY_ghl)58 z7Ri`dno_R1_y^aFZ+_#eI>BLe#Oz1rAf%4*tT3Oak5MfBikV0Ox^z`+9H)^DyVyyb zjw3^I0|h@FUFT?DmJkx3knIM2dI&Io=u3hTyL6ifE=d2uNND zb~;4j=@#^=Ka1V9%;L#im+L2w$3ZwjnZ$!ryPiO%=iz_u!f_T@il&R6t8)Lwx=`b53wz42;HXdf)-b#>k$#=8{}uNnK4mA49T55|Tx z@~CFy&=SzRm-|D>&3yWYk^6_aTc^?=ViPrndTzrizEqsXcI^`I5@ifDQo;-RIHI<% zo2ASVnsXrvucnU_ea3x)S|iyXk^dAtZBzO37y{#YagnRUwCeS}FACB&(FSY=`V!V{ zW-(FQ;R<(YY_-T{n=*Tt_;=j5nI$b)wx2FQHA~QIerKTB;Y z-Lx<*kcPLJH>@z=gXU#`Tsg=*h&RjnlZ2+v>S-Z+jJiW5CQElXF)$Fx#<1?ZTAt7! zR-$3MOaw(mt+MKX!9D{iz=mnrm#Cs6G~(0Ga(%h{8x>T;*0AP_r*Irs2WL~_qHO&6 zV1(d^y*8!!&u$n)pkHbhe)Jir{hW8v8KmbMn%3$FG^j{abI$`g2^X$zW)d+UnKs?N z*M659yi5KICZ8au~^uWMPpVlo-)$BH)p!iiwIji5Q zv~5#nsDO3$eb~-;HqR3nV9)aO#>(DOyC^FzAoYxTA%F}i2K!qBC0ntuT7B>jOYN-k zC-!D}JouwWssb&c+E{e~4p3$7k&$5M+4$j9skPGPJl^fm6eKV&iXY4eb6aVk{%}z9 z3;9dYayHxAE+1DxI9GoLOAjX7@x=!$o7A}TDa!32fxs~RA%%Fy&1DZcvVfyv?eN~;>6fwW9qwu;KNuU z<#L?~&I&9nV#A)Odq1iP?o1_eT^A)1nqeKM6>7J)$1%G?;u6cDDXJ}7_{^Xww4mJXEaR^TgA<8%-*uax`g)w*y1`o# z-F|fodwFxBvA~iqYt2>+a(5>Xb)Hw5vRM(l*wT5%Qx+sBrUnu$Z8v>2rhM+eoBqF)S9=?cYg0J@2^RHt@B{gd$(%d+wO{O*S_- z@euw-RQCAkIxdJaU_f9X7hAK9J0krf-<(?SE7e)g7`H0G%mk&s7T(|j+fh`)2sA;d zleK?$Vjd3jV;(L#{4alBBk~sWBzXPB;_JyuX4Yr)O8z3LGD@ai#3_-(t^bmdenD$s zlzNAD{oY1M9KaWtC2^V3~|P5d&-v#a6qN@JH?;9 z#K4<&f27`1QM_7s8Ce>9whZQ6m7nE*7cwEyEEM+N8}6|?P19cftRm@gr0i8~c7Lny zw}bae-P8E8DL=xLt6!ZN+)4hK4(r=PTU?@!6%c$;q4SU`yj!abiBnT5JuCOyd5drT zMy%YO_B~GMFa`RV{D0*v)DqO#%RX5VyLe^uxg3b(keB)jF+Cr_aVc$^Vwwao9 z_GF(*{uZrju!=cIHomlLG2lflc6$hG()RN0FOSp8WCHw zK^SqRgE(nEQ?s@r9dyJD8Z}*g5*AT)UPiP~^M4L-oVfop&Zms-ek)On;3%c+m72Te z8YHdUe0LkERvQ_BD8f==+;-#WdbFv~%D2!3OC}ew-X1=wmD6iSXR;M059eng*a5{# z8X_(G2Wqo!^!AfMy1R(-U0a4<9>L6g)%Ja}W_#BuA<5~k_R)63*PMfvy#9KkQ>{It zMEYgi^hAhk7PmHgwX8PR^yGMbiB&RXMy=Tg?vdp{#eVue8tnXA)WX8zPYwBFkcXoq zs(gH!Y3?~yYm@t*E??fdd)@R))dv}nXrvV0vn{3EEx){@{Cn5c`61@w%&~}l^C*9O zJ_Y88_={R4&xrFo0ld!-f)H`?Du}r_STOSMbXOogkwYMfPPtujr}!zL0uY%&6&*+c z13lAXlzJdH30RPdfpK3AJdCKjF}@xOE!VP+JMk%Zq85fq)L z3>tA<11l9PNyCY&lABfW(DF3?Z)S&-Vn|-?bN|ebcxKS=JowjKBq>hpP(qKwUv{9OQ`uMju>P3nf1N9{dUhdm)ts$F(FA|7kbo`yEDN?9A z8?=U|ckQTY9DaC|*$>}Nk5Y7l_%RkHjqKFv$n!chx>4l`(vPCN)_@73=JIpZ2VAl^^*97K*L#hTFim&H>tX&L!pvW>)9g3Eccs{a~a;lGg75Ize*Oac$J)`pxwFtrO4Rdg2 zxCWk7Yh^97$Y0MiqggbtcOKn*FP6|+rEZPaR&8ZVZVqVZgqjjaEd=|8svIR^vJ>?Y zz1~Yy+p8Z~H9KF)JR~I9PxiPA^xY#wcTe|5JvMe`y})U=!!9N^Q%@i8LBHR#+2qHQ zlvBA~{Y6^5I%){Zd0W*BCFsNMaoH{^s&p=Fa5035M_=DP;%zxa$%wwtuhk`v*Yv}k zz@Kb{_M8&x)cLZWO){D7C}Yw+Zf}kWxYi6@b$R;iW?;o+Ow{8RT~vkj2hjb1SY9zBFi7ly76&F&!3 zw#Ix7&#us&v0hWKP`ufH2nr!;rh!Q0eO{LuTyXFYixl7aQ58n;-kE=RY#H-O+vDe& znykV{$e@?`y3{JX?o@YNCFw-rQ|oh`I;(gH&_k<0z9zjnhzk<%|2*5cd%Ms04+b>} z^h?u&RNgw2Z6f|IKxi0zY-wnnE&gwJ2$BsQd_iYk>Cn7j!oi3S3eYX=+w7Hu6{U=g z*H6CQ%_C6HS~R#sd6>& za}r1=F2>S+CGCDAWkaZ55!$gcX$_#4q)sJ;U*EoKn89v-aOHGWOmRBbB6F$Y9K z3hG}tob|;uyW)e8=YYcsjL-a0{;C^CYoasl`Nk`X00VKp#D83cT=y%QW)i{_xeD4q z+=GVcIVV3td=M@@7OoOhbYCGQw7Of0Of5?AumT{*X^@%&J8m_n*Sc2;o30xhj(@>; zpV*EWShe^17aUn(K3(!P}UJ;g>6_P4qBI!;t@R=Q%?PKEw=*QD{V z?Mr7{DT(ly26<~W04bzwtG1$*$nAtOooW(7=Fk!~@Rl&M#sE=Cx7(tV6%XN*l((*% zp!MbL-gPVf_Ea$Y+q9X5%;LfVOW`oUUr9=Noj{11&gSv{>p=aH3egsG2mDPuC(k@L zK1fTI4h!jgBRy*{VTh5X$(`>bE4xq*CVU#uH~@(Bf9l)WF~><=4yMaa#QLB5j%ObH zC-%cnGE`a3KXl#yq!fWZ)`15U9fR>#By3^a+A2%50 zX0dKqlPNb+3k=BgewYfSui$F(*?UA*?>G%9;JCTUkvH${%(vB!)nZg}Y>r|cu_R$H@~)}{`Y*Lj`*5H`5;A4ZR8_^Q_lB1#fyO1bNZ>v)w?Vv=^T=_ zoH3Elsp)@UHdq6GsXn5^43n5{DV_E!^rnQ$#VLw98@Fff@cPf@XW zK#HE$Z?ISLyPtzo+JwfEe0~Z-EV(k|RItCdeNB(o@4Knu!Pq_+5QssRsE8N&WE+PW zyjD;iq((ET7pz;j`<_iA6;Mpnu#W*T2C#h~xF29_0}`C5mGYf=$B*0l<>nLD9$P0? zj;9>O;=GC5WpIz=-zyF$&42b&ObzeojU(FzOJ71P|7)%CP_oW%U(Q}YEvcjSfCRxNmwQRZOfxg-; zi*Dv!=6p`uk_dfde?3+#U;C=-j?Q`ODNI zGNkH_cL*^4*GQ&=QfO})mao^=e!5sNE&p=}vhk*qVw0I4&+pW~1wfpxrOpjbu28QC z0!(anUUKbwGs{wcXS3m1&^118Rrl_Sz?pK^X8<;S7WlIEHb3a{c&qXegnEBtuKlfz zd$iu`pHt~BMt{z{F_Cu72dv9DX;|s)slKo#hUp`n>N~cw`++G&!Bj1hLyz(PPF9bC zOG{sLIhb}{s??!e3(ZnZAP-C`SRl%OB;6^l7q>J)C$Xw8zU`_t<-+-H%LKTqdn`_J}i^h!6g2YjfwxlEJ&inYOR&JtI9 zfaLCPDTY?(SIp-ln(GDkSvE(H3hZEAQTCQq*Q=gYl!3Tz@>ixR?hCi%L_S}~42o>D zZi*(Lzy~$OqE#Q5VZ7@%DeQ*cf40Y6-YK7ItSog}FK6!C<6tgtOk}F&EZn?Pb1J^;G zSlmqvLdy|^APQ~D)W#&dw7@d+o@N5X6bP{Vfx42}x}hasTx^6~NrBI^Xs9c4zVtI$ z**YIx8C&(U83*9*fSH7eRi-NJK_2%ugQw`-SMZ%QqOhV+32BBS$&{BsDMVS$9o;4= z-o4uZ2vv0KeQ8g5(i84mPGtk2{^@FhBfT@rhm#{_XG0~qr0kol-{0+P#mYGZVMlKQDb>O_{@N9b;`y2ufX}Q%!!5*IAK)K z-V;7yBvH(xe~F)@7LgOiDYj8rk9tQ@+CXX_+-~=P{}t2Pr|Y2CzoU=hewnJuiztT1 zw+Kj!=$xrz1qV0@00l}Jz!ze}x_VOry}pWkr&sx7<ol{1{^!Oja}WfA zN&dGN;7A;(p!$(a+_u(5_T&>y909NH27%~}lLOnqp=@h=eD6EOi7NXQ2r?f7E)#bf zZ04`)1P++%zS)J!B0b5{DA)S-?td~~eJkjzJ*t0X1LcH*4BGE}^+qHD^TrQJ*=9{% z&^d|`+b15ZR|BOI>8t*IV<%!SJC_cLmCuQi>?F`-N;TJZ0!8C~-(_fp(xexzN4Ili zjxH(U+6;GQmmm~K!6&7Y_XF48^J{>Dc@itD`JytDZf*QYXB8)z9}8G>Fqim67|~)w zF#tp2%wXTY1}Y!SR~&7&gF~W}t4A2BKp;lgX3J9}=)k;L#V@A2t@;yL=<$B6}h-mU}X!~=ICe^l%m(J}v zaPsL7CPrX(6S3s#aF;mnUqa`uVySwsKZrHvoBWsk2gm(h>q$9Xy7Qx$JwI0|4Up|3PGqXkT4y;W9g7>cle(hBwP*U{rVB&>W5Im)ya2~pVTfyU^!K#shdc{yM!JqxJh&gH*g?qfDCVh|E^|iW z?z`=FP2TQC6nB)ISme$4Ks&M^&{Anfu=AwVV?g0sFKb^6)G1QgcW@C%l*F`GE*m@>TsTrYWHmj^JFP2%q5dR1w+si?$mHIn1c;&(H7+|PP~8i zV9^)~^yCYOItbF<=OsR$ui`^j=)B?azl|Oa=^QuKovF9D`Ng-CzLz_`H{*i}rFPm9 zifHQ;rrNxgEK2D57p_`HEjA-=g@0iuZf&dEN0Xz}=&QA%fAt>Ck7qY6IFS3F2sIzx z(osH5jaSr`eWlqp!Eic#g|F(|c-%(0h9zBWAAzla&+L;~p!x0wt)x3Ly~F6)ZOO@s z^fleQWpU$6EtTJBYT$LX&mjyAO3d$1U~tN!ZHM6h6qqlM46hc-s~)_y~!bclH?n|rq zboAT-I?7M`hReF!(J6HpNYoT zLoIi{dDGS}dSp5|)EP;f277JH&yV0+cURL56Ey*BD}MH0U5FVQc)j4dkDoVo9K7}X zwzq!yMSZmvKsjxf)#gp|XBL=<*i5MvQk;y?K-9*}@-dd~*uKt?X)&o(g(3M`s=aZ= zt9H+7>hm)Y+@@K>N*%MrJ-VD=Pv+f=poG1ffYBA9CBScdei+oIOjgmhF`7ZhQEf#2 zyyTMXpxo``4JGeEok#RW+UZ|{?f+KCDSReekADfH^zIqBp=d<%c^O@%)ysm@A_?-V z62YS!>x&T4n}->DN_+z9nZdXU#Q&$H`<1Ho@AYE4Z~iEh#4vhi7C5MKGU|6eUCcHI zvH9cWOASTVWsXweCv2?&rvH?S9XN0&f!#YF2NZ6ive$C%NKyRx@DAktSp@pyb2#zX zt7c@NQ+Yl?k>UIiiF@&yf{Sy#VPLY?ykk5NDIX!P~5GwI23ocFTL*P z{r~-lZO&wNXXl*RnK_O~H5K{S7(k3yuU@@Y0Ly5+dWBd5e;fl);UgZQ$i?s%bVsnB z%d1y!`u{x;Qd!@SzIsLVN*a9&tnpcA?m_-$^q3~$)c{ZML9kVWh}hikxjC_!)#o`*0JLUc-BFP2O?cnBM|#4E zJKBG5;Uh1dPC>K(_tjbL269E;|2}Mf7(my6U;Xb#gFmA1OaA>7{vqx&;mPmgfWGzb z0FDIAzNo-hnT|pfHloO*n-x#(izZ+D!saJ;I?0H}h41}wQJC%>4prAVdBzxsGY(@H zS67H5h`pH2|*_h!YTT(~}7*5Io?3zT-e zwm0COY}0bMqxezP)p0zFyy01G`*uqM<-)*z;w;X&bH;Oh;0=5hL2z{pKBPA8u1@fL z7}uMha?ufc;9s49S#Eb#ym{DmcWane7p$WaE5Eyg^*d41Ic#J(RZL*MJ?j*qeKUxL z%?KusyCK~;l$hxJHR6(HG%M4XV0D++`FlLlCCw1>pt!pFD`HG^A;D+9|1`Ahuf$)? z>vZ9?b7i9^gR7o(M;{zV_^x?SIvOD*k3Hk>w*2*W0}0$T&SiT1$~t%qtG~cBe24@5 zc>eX>gW5OlY3ABn-q4zDrs0liWXh#=G9wRa-gW8JfYd_Qe-}J<|E){XBd>4$_SJu? z@LQ{XsH>43GM~WT15HNV%m*?&Ek|Rb06N5~QK;{4G;`)A0y{js4gUgGdzV@7uNwT_ zgIr)2tBnJ-{_|l1pC8vm*~e#GyFU)-6{QFemX62vuHRB!oZMy4uX`9fb`sxqe#SE4 zV(6hm*Nq14#kZJL4-jj{8`f%9=|ZRU%YX5rnq%=pt!g9>#Lv{du?sXRuoi!SP;1;) z+w|h`?70{|Fh&+Nsp=OeGaWhDdvEUt5MMt(R9@9x-z+^ryAbY%mfFE-`R2Th^cvpKmNIt&(4M-|;S%)z?&-QPBTS_N5dX3<@3 z);%3d7|rW%2-b2|HOFs$@AT;=){mYKv!#bEyOOFCn8wggf#!kLe00L&*Xkma3H_+K z)-o;m%h%ASzb~36RYMe7)je6AF1g1i)u7{Djl{A$;hW^i{AE53(jUvW9fZvXl`kH1 zX^aXQ4mvEU`wx3vE9;Jr&H!)FY6RTKJ{0?(Qx7G9mI4Jn=2}-bcu0X$h)c@r0mwwD z=(U0h2^vKy($LrxJaa6KVb``4t?smu_d(tA7-|sH8d*Rf2$dSyiHx?i`eimEnJza> z2LqjnS#t32m#A|BX+SlIZg~yGG%F4QDeB))MBpdnla9ELpZDs9f@S4!kTXqiWaf~~ zu|i>@^TZ(p#O8@#TU1`ikoZ7Zv8o@*Q~5yp55l}@5WZgQbAYO8fQ*4Cwc7r4`4O~; zGm6G%Ri6311kvgZT8z2B?VvHfUNfjJH~C)u%6mu+qF$jjwC(H$+IbLHNLuqW>X3Mv zu)jAjiyf=Qj7~s>@;Tw*qDr~PnU|cZ4WqHv^Jmw;r3&rVbs6VFsp!U+E=ZwK!AqiJ z0Ekwrs6ouI0DH6+_urZkImwIIxL8Ca+!SlJe6CZL1p(Cio5-_utIOZ>9XghEFT3WU z=I=?1m#mCvsT?+=)3RL)!RHt9FYvl@%@nLeL|xUSQwY((qo=>~kt|Gj z_ex(e29hz&s)IOEZHnS*3QB>*vqq(z+N;d>(o7 z9O)CNe`rdiEqzr(OC*`NHhipNE;xi%b>WuVM&G7i(^=|BAdMrd?#oc{5kx4RK!-lB zpQ7QW?tP7v3HK}8jznIO~JOhkYG85%& zmeYqar$TrMvY1jK#OBs^b|tzj$rHO=awhal2->6}1)mg}=QS#{0DbkJP^$D+UNwPI zszB2h0H080-cH0oRP)9a$uzooz&34rz#<@|DMMy+L<>AGqe~|1R+TmM>9P3J-8;r+2m7%;4oyEoXBsW!th#x9fl4j^?YtN6Glwn&`pEF1`%=Z`s6 zOFH!6_#NE9|A8XR)K^cL7e&fZ%2X5oe%m?IM_iR`@Cqd4wojmtlrXW&On~8$C(!Mz z-?%>qV~2Z~XXx(5p<6YAIdUEvK(SQ6|AGJ#)n*AKm>;&gL{5b$aa`8RmG3G5DpN6} ze^!eTLnmQt%<;Bb^q??lj()oLNpxl9-(qmYLt%1{js@U}aUU=8Id#J!>E%^CAO5#^ zFMKyBt2YRLkB>k8ZgXQQ%@Fy_ap%*?0rvLxwz0FTKADJw??G-43ZD?!iO&9W$on|T zqqWODm6-R$)D0{Xx9Io)UxhyxT>OQz1{OERVijOq3}*Ub`FI8e-d4lBeq#5dKkq6Q zkt7QUq$L# zu6)uE97v%ukh7-7Y;g#;simbbM3PCN)DWhx*jb2Rk2M%ixjXwa`LTd>W1q`UHsTg^?>krQc`e3N$5L_9bYG(8sp$i-o-iII}Hr;Nwg%9Do zo=84+&{~pINN8N#8~AdpZEPwG3`l{%`gskG^rbF;iBb*pQXiJ>3}#IRZfiACn6>DH z{J%XMxDjKSW6>R$Dkf*z<8j^s_!yUBi$el&$Rzx7;D5G3cco)*V`I8Cl*r4^XNs`r zc{~4c<{_)bpyl-M4W;>Jnf>GS$)otqiuc>$3l6Sv2Z{;f?8-XrDz|TMO0|9u>*43@ z8q_h2$AaLRMtu$JZ*w~kbU!5i_Q#7=3TJjg@5oRPwC~vNA}9raRuvTZBlO-V)j4#4 zv%Oow?;&5vrzu#&B9qG!)&JtEj_32dO!Yi*ZoStwr1N(5IVTtmyHGTqwf1|`>O;rs z=03D`eKAqM!~P0L@w_8I0&=FKUH;{{c`D^@w+bWwywa2Z_%j~|8DY*gHI`K1{IGGt zd951(BNR~~sot~?b%#^8dsqAgrEDxmmiSi2skg=c*X@tGm)B68I)?NSki#ECxfn8K zE7e3d(r?`M^L7-s{fw>8S*(C;(lfD8EsSKkoW1?6(A~VvU#rjjjH-EbSntHo6Mv~g z8hjt#czJoX?v?%e{*dRL>3fG20CUkcQ%g&u&q>HO8(>X&bZ;cIkozCec~Up z$hhS43~o0DmyZ)Pr@V8vnfcF`PI+GEyE%eRK}`H??N_v-r;%t}!W)z?XOy?mFV7OE z?V{KckKa~2cL#~NJ#gx}I*D?viT?P|#>S#(ciaPCo<{tCX1N`BoHk;gALPG?3aonI zGgO`ree3*rA8SB7EuN%aET4?&1B>}&HE~_Trq`75N29;)3FdH)=KqK`nk|q`{;TEe zf-(Q&?lF>5u6VSQxg52uaA9q8Sw$cHQ`qxQ#X znmn(2JvJeZ{Ld)LHJ)@tRXkl<%=OKC(4mceO*T9OMPUmm{oD#l*+S|;*n&>uelwpg ziQ{Uy_*jX;W+JTYxd!06v&vKt_%%TGS+{CNlARiiH#Su)@41~?8UqvytE%mc@_C2A#ze1qgAAQi=yjP8 z?ZfVT@$Ec26u(W)jBIs_uD>egUAg;(2pj9NC46{+== zqD2eS7LRVJI-p-ev&y%a%`S_ZC2quSwJmgeL>mX$6BV08roxaK&_0{qwn~`T)&XGS z#~f~Slh6w+u~%b#9f~?%YZS|$1u};fq(Ee=b}fAme!y&X7CfE9;imYldrUx(?8H;! zB8TRuO!VLATO4s|^v9f@iN3|3n*dTDNGU~Htw$_=?gw3U%iUV#YTajUoryd-Cdo>v z+gMsac9xKb34UGYxyyJC3%A#-AeG5&Hdx*Z-wC+|zBq z>!XpUn9iT}1gX9-9-l>kxbMktLzg?t_D*M^c)u6*Hxv?a*94t!r-*<)Nbe1(Sg`t_ zwibuqiNt;8=(2o%&L7F^HQ#alZs_;ITPI1Oq(R}`!P5^Sjx42FKGl~?8rjVd@+EU& zh^J;D^t4&Bz0PIPBzk2ApPdB*k zlwxCf_SuUazSw9YUSCo~Y{qmNQd#7-m>}_j3V;1J0rKw0AK?MRPH6cjEO>BoUQ#Q_ zjFH^o(0n3~-0n|Pq}W5e^M;a)EVL=|@1AIX*n7?f^9x~Nksm_yQzNxcj6xpO;gv1c z-AS)N7In6^dit?AX-t)0ZO0BSQ>sRPoZD(;^nFa10tQ%Aq<9OpI|#_%9PQk*?w&)t z&Pkk2k(>?-)#)@6I0+)mM{#85`RAqA&Mn=_}kE&Z?(L3?v-HU6H`Y^z`4izLYQ*5tTj z)BQY@VgA#vk-a=_Q{n;{pfzKN3`QVY2#bt?ETT+F;Fa_{JbF3>LPZoi#D;F5lpPy7 zD6yuf1||1n{^Xg>e4S@#IfZ`|Et;?bjha+~c!F+hGecuKbOS zf~!@8*C&r<*&E`-W_*u9PCi(n#R6b%kT&TL7>qdFv~6rMb;!#bUU$UmS6&h!J3*2W ztFA~J>o_5QRcco9md6uDhw&QjVSn|+efY7|W{%buret<;&ED@c>W2C8tKFWhnI=_B zY>Ihsie<_%wF2+K!imMvfkEr}a0M2SJ7o3w_i7)0SkIW_+SORKk0*&=ZKji^m8Lam z%(z+DvOX|V%#v3z&B0>f`1hgs^uYHKDhF?L+0a*^7~zxl273xv?;bj())3fB66oNjaya)RYp6%{cmzSP7_VzA7j|OVjGMEO z7=@QQUZ}(dqu_3Q;xv;}bm(;5o|mcT=jPz;uDn02SaF`qe42QJd_-_keZ5WOWLM&O z{76f2@U(dV(;zY^fp#$dtXD$3H{So6AUv8#$OeeL@_;MncTU>`83|j^z8ETA?F$iN z83=iDxO7~2>KYci;jrk<5M@p48k&Bazab;f$Zd7EV3l6)c>^j_$?kV}y6?dH1eGhC z>5&Oc_1*nYlKC&>3!cN&!?2*`ld}=Hh}2*C`J1mpTN9}5*;o7*2CZ!=!*;zzpQ6*H zLT#9Gl=}ix&aE9Nd+U4bbxCRH>6|hr)0q%7SW@1a;o(52O3dz}nyWu_gvGD;uz%>N zQ{$`fsf7{tN>WECxQ1LwSDzMZxuF~v2YI;zlFvfh1(3rmd)^T`@xu&!+H|?7I@#OQ@@~r%+;N5}Wr5#ALWZYx z_hwI-Q~DPp_GZeydQ6$M*#GWT7FbQXuYdtpb)LjSa||rj*?o-2-^f#{BnXq8IDIwP z(#!C30E(h_YBXVg+Ktk?So~^=7JhSNzFk!Zvfto>8|+v{Lvp5|CmsY~hSbU>>G>Wx zNu5@X>r3Ab^ocSRmPFF*FjzX{Y^eN$>A`|f(*K1VqC9n}f>ZM=FpQz?$J$z;L2YZjTH&ncC}%iTmKzdZ|2nW|Lh zDNwn_-t|T<#uh4T13!%<6Z3fS*0FsUj{U}7a`Y9~l~QDUV;~xyZL;Zd<%dZlDQM6q zV8~N)oL zKJNKH(Uye-FMaz=Y5aWQaC(3K&gZx%p4&Wa=QOb|XK&AR@2h3?QcL7~Vvwf`BOX1W zk;kZoC}w)2cC55qpN$gqB@X4CaCfwLh2%5|9=h57bt;q+MG zz%x=VTl=$ZRu;>iYiUBizDdkrlb%cK)x5~!_bV&1lNDIYSk>)t`b~rTob&OImkYy} zLa4Qk-A;F42LQP<0idZ!Xwj3Bm{(x$C<0?)u~b&I5}39=#jB2)q@h-z@%rH<79AisPRc5`v?d;YJ+JT`)4H*3q)Hj{`npzE4=z6jI z#o5D&#bLc1gz-8kGDFabZl-Lau(cvHGno-&d8w;?DB6q3*){z1d36*<$a%4qEKy!= zarakV0#*PcTQKrRGJf>O;El`c{oBB+$Q|>wEAxeml|l(5?RIp}#y+(3igtv5$S>!_R{QO3S0HW->7^N^^to4R7iJv&8Ny z9Aqww`uN>QFJ8|qxr)`|@K;R;=+fXKrXoWQO>67!Wj1*>MA6^%34)QQV(~wDKAwjA--i1fy?Dpe`D{a#NXVv%`t5!P zuiw?)N2(bfOT;^4Z8@;C5LP0?p4p0Il6kJ&y2m*k0Pq^$gB{#*D$@1x%jfS-W=aXQ zYT|pvyj?~K&!B9FXJTyMoll|$8;UQx>391tx6ox+-0t}j{%I=x!gK(aTCMiaaB6Ar z`D@Q2CK?6aPKApd;6oYcrK0o~3A|<>-TSW#;rk8<$|Ec&QEewyDgr44A;V&UKiLJ0 zCb0d^$+C@B!L0&i&84xP7j^5Gg#*NFy_g_5T1zE7%;O&?)aPTGw+CG>3_si*c20XX zMbBo+1sx00zZ88xXd#hl3zEe@VCgM;A4i9(M3N$PON|;zK%JMelpYNmMh=!ch>+#% z9B%L>J@ayR+Ly_EdCY(LT>Je+hghr#UDYwIbTTMGH<99^@WZdW@y~g%JfqjY(K5yS zDFjv@s22WQgMdK9_IZZqzLQ7(4+8-$*SL1Sn^MKRu{GJ=pO(t(VWgS~7_``JZ|%)s zk%*@@n9FI-2Q|>jyWAj|GvVW;-SB+3=lY$Bm$*81UGr<{Y2PeO?1qf8?MhShvQ>2& z@0G%6gSotJ>pmYOvcUG;eC_J+U&BJg{X*q*wG|^ykVic6w9(a6d9Te}31*ufjlSai<#C zA8?`o>0pdx6&uYI2@n0|li~BlnwUR=b=P=2>UH)~=Pu4gU0c?{r}oUMI>YWBUvD9w z(^vTAugxcFKY$UiefItIml0VA1J8q+uG7E~Sjd4}qnR8;9hWp6VzQswpY?ku2VrT@ zx*tL5I-gA7Yk_CEk%B5}(zGezktot0OsQpaNkzsem5r5_@O;Vm&3}y}l%i*m*uybI z#;>PXs-8@HxL)FShH>5}ZNcUFdcBE#XhJji7nAS0U>PH@N#B*(Z)s_|DYsjRQr%;i zZ@E7$>uPs(M#xj#QIIY;Se+>6is7N7!6R`^)daOG?sj>9&098I%dPz1JS7)$Ptw3Ud0}+gzFF%paDzT;7IWza|s$ib=cvdCRhP zS)p=$A`-AGFg@iIG!Xrkhj+i^q2K2C`@x&uYg{Y`2gcfdWT`jNCBXMw!ZfG%cSzC8 zP76jB^H$8=C5h{?p@=m#HJ6t;QW&{urzu3x=^|wA5%K`OH8kC1oIwTceZmyF=B$nN zJG?4BT|vM0V9Li+5Ik~!^V`H!$^|9cn&IH7P@Jr_TIE}wbo!DBx+a{6-!si=J_y!3 zP`ZDaxS{lo$zeWgRb3q%KQg#Ii}xQ5@m#n#^FG=6+Co;e9GT8~s^fq2A&7c2liw68 zIOtUfRUBU@rKFu&|LySf?5q-T34&thWDK!5vILf(Q(HQZ`skN5ZE?TVj>qj)zwqB8 zpSh2}N>%H(M(va_eEM+&Y{CT)7Sw<-dAAUYh@FKZDsdgi#H4j}5_j_rhSPAV3w126 z_7?;_zXsPBTsto0X2B#AyauH?MoqCUi462u;ugl-p|j%n)Q zn|S|P#U2y1sE@}EvQ4@nD5@T}MqoUWgd{zla*)fig?9Clil!z$&qrm()wM#O*wlh# zjNxPt2=y=qUVd24U=wpPu|Q{PkA1Aq9cO3H{v4x_^R1xR0QbyCr9q5{B9?NMYqeu# zDlQzbYu%284sLKsMMWxZaCnktW_=2dRg}wR#7BlWN-0|O=OK`FDKj4RSwc&ir;%BR zY|=dBtu$4tBw*}&gS`^z9~EmpZ5@S@0<#%jxm)1@>~AYqDB?G*oRcoD ztej#O+~fnF)WkJB>C|QL7-iIDbgUSo_@~tdmxi+K%eQMUeF_MJSkFd8|Y$ zYvbo%VyQ)))ZfFGQY%9(QvVMNfRtzpWb4IH%ApEQkP1ed5qD+!kef^A6mxRtktYLD z?26IeBg7jlK$b3hpX-{FHi_krbgBU^HrG75cyb^>uQ zrN?LH|+>KhOM{3AQKqNpqW8+qDozpq2)*=Dh#PJrapT zMYjxTB4SF8`rc41=knCNP;dL>UN)97x^g$eL_im2+ZKh$%-*1)+iFH$C)$xS@wih? zEaV2bt4|%V8nqhkSFl@Le3zpO1ZHQ7Lm7_xNcY%u;I}8|oCdbDqkeKb9yG1iFgoAC z?9XGXQob;TaVf)uZH`GQ{S>aS3Jz*Lg@?^+?|gtMJ0f->F`%8dI29*AnwgW2U_XMY zo|sj`py0eB1DTqRM!0W$A?@^bQ!&AQGqYjsol=%~Wu9c zs{Vn@BqYX=ip2Sb&pTV(XxnL(x?O^+aa{>%MQMk;Q7Q8U8?1Bn**3q+pUz0QNe^)?MW*d_Pl{nh zluSvg61qy6{s)1>9OQJNcqq3R`PJj zR;1upm)D95M?I9F&Je?nVdwYetY)N#4y=rDfysRO^wj;YPt%nemc%5N! z%m!sMyj;ig{-3<8o$vpa3}+szbWcyuDp3(KOkt4t-QT6*|D6b04&dF>554#P+wQ>59u(n^p= zK#A$8Np0Ib({H`_;Wg`f@zzN2rS_E@Woe7VuO_+#Aq5^n{JgNcCikSaLd*^g$iT_1#{nx zYUD~hiXyFkZAgmuNX{`wgV~j~k)J6DYV4btT&{{+jE;e#Zve~?@a8C%k1Lt})u-xz z`R@5@kKXQgTd;%J`OA6m$xFhxfbgj$c&=pAuG#c*QGLbbrNa;e1%4=xKUZD#P1!zh zpB8qdyV&I{sGv4^sq>&E4IJ<)${wxJJDL&Eb(bmrq|fgwkO z%dUGGr}4P)%S4^i~aG&MNFs1lS7Kbch8!-uI_jAl%Qcyh_DdH(Ck1>rcFynJ#^Qmah?^>UftE4iO6 z^$n+zCiXG{oN>0`1yQEKxVH_cm2&`csHD@5l0aSiR|0#i&#Nw+QaBc=S!}|Q725z6 zm-sTP`h2t|I3fYru#_QuvqOa)U#;UdS{A1iQDy5(nqqsW53}m?0nHoAgRQT)M@pIe zsU(fNj=R4<^Sng0Ht{|j{%KCL%Dcs_(mAHbi{*W7W4@oV?%Ls$WErhfZ`)^E&AHTM z!#W{x!S>^u!)Ebk-zd(<`FB_p1URS^F1yCEg4cebU*sTw@z5sv;b1zlK&$?m62y^{?mxL=-Jk$YmVs8l1O|K zHg;8sGr{aPlvEm?`dRWk=EHQ(MequvvDrjnF`1BOm}V*7!dUhIALh;)JucjWc8rZZ z^5C~Yyy!Kj>NNa7g}xc)bVWF0ZEIWRQ8q+67}w}GBbV0sh{38|ZF2axVa0joH31Mf z4SBcZ+JVbJ$hS;Y8a}*Vz3WVU)E72A=b80ETJYkZ5)oF*TYa9%=YTkrj#}#DBav7)Z;w zw1!H+eN+P@mRenCq4URE{S_?g)l1FhJc>p> zS>)c=ji>WJTDQ|kZCJJdGWtwZfD1BFALJ?m?5F!WZre-U5H*79$j~A7ud6M1|cS( zntJ0{n@uTIl!x;v8d;3g(z?ngq0GP&o*gJ4D;osn4buJGV1MCkWZV?-=MUNMKXh4P z*cdG9N%j_>O1l9$6%d7o# zuGAUcO4RP%YgM15>jv{FAn>)v9EP_$`}Tk(r&G1O^d~?~O<${DkLbs^e92DgZbjwUQh}7FK+X?jR&bFAN0|E7E3bbJ^(;c5rKkoJAUOPzL5ct^LFk^9zLTj%}G!W~rLJ9$9D~FSAEuN*xB%eCjyj zFH_DOjvOP^Jzq&C!$v7r#t+Vhx$G*t*fb65ov+}j5D*S#g;7P^^kNhK!71ZIc39KFWO1o;vNGL8 z?*@tl^QEq@s#5C*m|xYFHduX}!qcGDU+q|I^8v0qQ zQf*B&)Lih0!DFSg0fT-T%!+V3F#b5V?}pskb18=_O+0KhJ}GPspdD1*nm2GTb#y_X zuPorRYKj+k$)T5c;_y}-Ah@8-6guNRZaYHl?WR#uswndOv@JJpx6(@m@la>PXH+%6 zcEhxx5CWPh7c0>|)u7g(=zn(F*y4yIub5uibE<5N?syQGnzqXn_kDBm)=;&uG*Y7! z>>^IMgLX}^F?I41u_G1y{e|a-%k>neQeE<$Nko;^scfDbw57pr8?TokAKoo>9<&!& z-@`+T*S@{u8Tl*Tfo=JNWLY%m*U2+)Y@a+%NZKTf&dN)-!pZ%B_~o7lJ~vLZE&Hst`nb5*ZAYVgMLO7erWh*1@1nQDhmMQ(g5S1uN zp+oL{*AJXPW9QwjqydPfDAE21ZN42aDnWA!-jLat*$NHe?-dZMzzkxV+*3&5#`!(gQkY|a=eDwXyCEn=|n131~QmNfV2nRtVgM>J7cvLON%JlDQKTDqz8`T}~| zub>JWfQg%k%J*+5M8PhKq;M<|vAM>o60(8=ZdXE-H&lxui6&(-gGo{W^Q(Z{)G2W0 zKqhD!XfI{;kTkzmMO?`DelFmPD}ELaU29Ly6beujP(xkeip#qNjwuQX*N!qQ1yfZ4 zIO)AZKoG?-@pBJuhGd8^|U1-M)?}iDATZRiJS} z8OFmw7cxyC9O)E8i?|3IfvNUd!wYH{lj<>)UKwAaE}uph?hK_MUc$Mlv+Li%hHA-u zXMR2NA5k94&}Vcnd2a`kv||&c&G5lEVEP7ypl09%Hf}3J1WF_#3F5p7Q(!&#eK$sA z0!8naS?omDd>hd&X+|Ov4}j^a=A=syTL;@ z_g-%h4WzWIA_^pFkoB2x@HjyclGC$`G6UAtfs&R%W&X`S{V*6nS(07}=rY;4_yJUa z3@#@cX^U;vM!H)$(h|xNoyaNTVy=K)g=%G&3>I}#D3wBjR6t7w)xxq_i8M>%oNK%! z1ke2EowzkN6e|#0Sf!EwwpCO(u3p2eo({ESS4xASLYq1tjY@@A-#Ua~&vP0TN*}o( z8Ha<1(;JjTjElpV_A1!QoWDlDN7YETKL;dX*^OwH(htNEYijOyBCMeEtCf`APba%Y%(bSY#xGMUq*1gcEe?rqMm6uj zMvRG@+2jGH^!`){-%KAIV}b)5L^KdEDo^;Crb&H@W|mBYWmw_`=K*k>L6W$CnSiQl z*`16SbwXYMl`;*--w{og5b2@nme$irAWjAS*fKG6n#uO7vB@NZG?)F(|p@1EzB=01`~{$E}-I6Zm0BMVei?yqw2`&;bwJWsb_h$N1aObN}4xAkWgxg z3yjdFp>)w`mdJfXJB?ORFPy9WmI!gR&w}Pcnu)qXi#CZ)DuNdU4hN}_MoobXd;yg` zcj6%Kd0SMHQ_t)x=^xByq#`gC9o{?|e z_1=E;Gj>Wm9`^_!fuf3Ec%&FuzEA)s0?0dRUcVXi&h?vbL$JThB4)G#h^ePT4&-Rh>Jgjf^qk$P zt{Yf#YXz)RUQLwDOqn!jn9yagIsK5adN0*+`E9zyT|KkxK`LRWi6PY?S<94`Yg+N4 zh=*05{puB-sq9BnWh#7b)L13uPbTz{r#P@8yZ!5eSUC(zTh!rE4Q4l%*rp&Bj8IAa zTz&Vm>94udGpE_)#A4SKKFxd5PUALYogAJ1r#^KQx2 z$|y6pP5@+6MS_s6*XLZmU}(HWf=XeA5+Y8}mAJb^$`yq|c-R)<_4`FvWm+~6YN#ZM zUSoVQ4{Iea)dmLnV0^v(2?B4>o@P0h>)-ln8qF+dFEBF6#!sz!Xd1NVI(pXVG_$nm zt(#oJToD7Qv&oE054v1#My#5?rb=usC{=nS#V_6uJ$xuTe2`!K(GAa$HvTI~N=&|J zvfL9bDh&a+sb}gGUa~g=a(MYDzxn;DsL}Vge6XkW*0i8u`Y`VxmVH&cdR_0ER`&dh zxW0?6V=6%8TJIO0d$$2qe}Em5ufrSBAXie~2jPeBsAL5=NZ||1o$QgFN7tT;mj~bG zuAXMwsIW>}y5UB${4s>QzOJpgzV1Lzz`l#f;obD&^WdU`-FOGrmwZjsPT%VvL{5PX zdtITOOc&3)6M3m@Mzi^~8u?4h(_Rnvk$4pc5qyhE76xp7+Fq9{NME07Yy1XR>T<06#YM0+d;x#j76JgASZ$<0q}93|BZj^^X!$1MKEU@ z#wRv!^r>iW&whbDJ-pfofpckk{>L5i2*;seT|oj1xSYV{zm0tucKtW|{_7XqCDm); zsb))>k?njU1}O^fn z6#E-$RTrWU^Z${O{*b}jB5=wC-q1cz?!}B|b-m@m8)0GLDWWFw3@kW|2QC~2Z`{E% zYngp%%}d#d{KG@bk#S!#k>7JV3r3I-9F>fJdNBA`c!aAGizoyXF)B4{mS~L(WMz9# zIF0K~V2L03Dp2ZUpsFsT{6A@9|0p<)f*cshk<*{zpcFFUL$MzqTpCT9FKzm6ZkF5d2_gf9(=@^>2#mga1>W^`Vfz9#jEO zxmn-x?_?pJK0c!wr}fF~zZJF9|Id^Lobz7MN6Q|BKuVRoA8=woDUdyHX+ZgZDx3qY^5Z5PK};a#m848%amd1z4CswxJiH9o%ld%3tv<~;D16k4Soc?_DHm6!pWzIi>YV79x0C7K?$(jkiV;kR+ZwZwPej_AX` z^?yb~FuJd?WY=nz^e{PN8U)357V+U=4J*Qf2NelF27vXwDJPM)RY_LG=~ImWO3)q_SEnFO%++W z5UX*Hz2Q8ec1AV5peZ^9%Jk9{YkM3yo-fS-oGA9}u`;PN;n);ZSS}$_k~#gl&_BP& zMc|gr8F)^h%+B8Q_yVUNrjRZ8?mo2MXutog`UV`F1Gd=7K}L-z07q#R(6KDf>$g14 zAM9G)k^i!KqS$V(NnN;h((U>%@@KBLF=&8HNrO%*feH}xN(zsJ3N;dd&sFF$*KzZt z{$5NBDS%EUfDG}*MWwj>2kT0u-0J;2C%@$oYLqJkUpnCu#nU*akXR#eXi7JM2txR0 z|Bq@ZFlp>w#*{c(iCm*buD?Y?1hNM6GN8kT8#ggFxFp7krG`(v1U)FAW&Y!G77qaV zsD`8$g8%gNqy>4m6)v5kQOggvkXx`h@)jnF%mN)ZIr|Xr@$@{J$@8I8i4|9cLO=pB z=A9Xd+GwU&E_&`56UmQ_&`6}`RN+704Jbo}DMU_MH5N9pZ*p@seO|pFOt&&|cwoc& zv8nBjE+o;*l=n)Y8jRd}a&2A=R%AC15`#`J2;+jG&Y4F)Zjw1utQ~CNbPl|Y_QI@y zDpfb(V2%fT--WYdrK9&ORG}%vRI_0|oe^~e?8{yoXRn;&BH$JzfqXKW>+~C zr4T2@Hg_E4dxovWK_6q+ef=3Wv#s$5WKYDH8*D99szQMDgo!Aedg>8^348A-9|XyR zMQU9(zr*^7SDZS!ws|^Lp^BIT8i}^V8{STUhy2D* zPhON9pzZO$lkrwBm$_m#ZQdXX9$P=V2}ye`Gk|%NWO_u*TZm%M>jstcw2FFHna}W%srH!T3&U zeY~m9X(vH?ayCO2AXN%9vlqo=LEqqgyjNMWbQtVJi1~gff2=X>tX$Y4vy6xASCl8K z98ji>B4le`rjiq7@r&ct$hu<;Qhx-1{EAKGl)`=VL4^bElHwUEzUf0EQz&4wV|L9I zM^9r;<<*ymPIYo!wEYn|yppm8(ltLVd{W5t40XGgOTe>#<-hi4SpDcbUw7GjsT!P!2!g3^(E}qP>`;VF?F@n;$kKzN=%IyFj@G_ zl1&Bf!_8OLcIe>#{LntM@Oil$Wrexf__>$umWZj+MUKR&Fo^D5rcnh_0qX zunJ#0<9~5=mqR0JQ5vWXC7PZYupulVf*0d)_&`8LkU~hr!S$Tgc=WQw-muvvY-I%= zT2!Pv zS+aqH`ey_CDR2n6!WM5Yg8_jPY09$Za&fKrS8=h8sj2Hh^H;C6=f=ZpR#ktuRvMd+ zW;($&0&KQX#|Wt>F2+}W>)m$%WzY8*_`EtulIdSf68TInq8cThp778GxarMc$Dt!DGqG_fdT+G=unBjSo9`9L)gD_)!uDr}N@VUd$ zi@gMfqgUTct5BqhO7Ox8(^4kCI;TUN-Gf7s4C&Z2Q^Kwy)CHEWX0lH_0mD>EKFQFY zh&JX)yl_l(Ot}Gei9SGr#}b(wGzKwHo|q&ACH4AViIJO>RUn$`7|w9s-m|-RFq3H} zj^Qev7T6?E4P@vf9|R;cIKH+IskP>ALq8Zyg?uH!CP|$njHI-{FRn(B4(euvy#GSn zFh7s=T^rvctX=~#mlnXL-OoR1t4n`sCmIFX!Fp%Q^3SNJW`|ud0twQXAfLu%S13q? zyo6+yd6{$j=6)P+HtB;yahRABS@wS0nY&f5VC}-~3tjI9>|j$NHqvG_Eyw_^7w**+ z6CN^(D6t9uLjM7ln{0+l68gSUxYtA-5)(1Ctg?A^^re!L?@CYLPs66_hg;ggP23-6 zn;fc6<`$v-*xb!``cQmIOe!QwDEpkP)`$fmzYPn`{`wa+VS`%CT z7m=1JT6g%Ylg%pVOTtYFvqw9GxfzY+!TZ?^9r)!oZ}4TOPvK zcmmTck3#lQg>@WMqmWZ`f!}kQnJ?*3W>z%A7lmh>56B8iS?=ms>1siZDNStQ&qzAl(yPXO7fx z?jNy-?w|OM(VvW1Ivjy<{Mm67=TJ3F+>!LWd=PB@RraAGxL%(s1PCgR%S_86|bXCW~v#*0Ly#$2C}u_yiGeYjH|dicqUUm&Pdcd%@9@2F?D_*!ddlZWuu9MToL>QK-nLz54XXpl)d^X z5#}X03jJ1iFBXGshxqDDleC~3ZTxce$hMpZ5XZy)|3}kV2G!9uTR6A}cXxMpg1d*{ z?gw`#xD(vn32p%rTn_Fof#4o2xZUCX>i(c83eL>1ZMu7}^=xy0G3}W0;9aR_4<5{d z(Eavu(u2U4-=bulMDiorcw>C9TC02mJ@GZrs#fH`*E%B#gV5-=6Xo~NZF6%H9xFwK z8PETCxbhJl2#F5_H#d+ErO4&p=S6TAlob3m6fwxsNUbQRl2z$?C=u<9G%Jp6h%8~Q zsKW}X)AvgPLf5IB`Et_}SAJ%Bxjxn6s;qc=jZ7X3j8gST_OzaBwaO3G+3mCXt{~*j zr@PBN-|pe_jk~8^h0kmRv2vsQQcR{Xm3@f4wMuI^Z=HK1hnG;dr~RwqO4FA%sRU)w=m z8+Swh?sQ_=@jz;$q=F0;HG9DPprx(ZPej2&S<#M_HqkfPz0WEs7pcl=91ECdIex2$ ztcFg+>issPq_MAg_s5BEl399`x-?2=nK?Aa4xYw+nppARG6VvQz>2?VvB9$J`m_+ls{P%l*ipO)-ao1-KQ zDc`PCME`_eAFw&jgxLk0Fnc%{DLB(j{lmv~8u|QXj=d7b%xtQS`}4*|Q;1bwV33Ok zhikgw=%098wvY&fGM1gJJw}@m`65})`M?ybe51i>Ub;{7nG=1xNk3kY#=aK+IXh?)K)Q>zYB`eecse#`qEXhOrU(FYQg7J@9p*$MWaWK z?uQzq!ryhKHDJ6DRS3wz!dBFJhdHf9`<2o4N)o{z=er}K&!B*VuFai;t^igB=joGr zMaNCGfUA(etp@jBZ615&_q)`|I&bU!)n~7p&wm4x)?2o5eso?UqKaIY#g-4l@{_#v zLb*-y)OT878pUI+&Md+K;x{V3wR0#hCESEp<$b4>VdUCe}!A{|s(#W;i{ z>K`onx+5w+9QAzlMRc+{D(UU2HE=QucXRi|bA7N_MR@$Bie#rX@VYf|fkRxj?|Z4{ zutsG{&~gZM7}by6yi+^D_xecu!F~4f+!Q^+Y%;1?o>Qie!D$&EklRgCnOeuvV2Bq8 zp@MdxDNRrgBSW5kK5U@|_H6jW-4~0#VzTIQWsfGdF279ch9gORPi2rnB{5#AHF!=J zePvl0{jlaiYCM(a5FQ@h_HUG0-*aN&KJb!PF6@b;ikHOgcv-bvIXu#lK5Q&koZ2!{p~oYdVZ{Xg>14? zJaC#~=LiTdvmE?W2muTG9bRt_FaU2~fkZ~EM7vUeIdgvb2kOrCB`$yap!?O`PWs{{ z;w`g0&tPz=`yUKT_cO=p8p+mn49hN((LECi@n@!_VLU(jB&^z*a>K}ESo!xz*!i=v zGOty2x<5fW*3K?aDe$VBKbWDli1|u~cxjut8=glQ!SD5lOruQM%H<1gB2IJ5kHVA) z++9_9=M#HUtHy)3`}x)@ z+-vGY_J*WhMQFIKH5+Uw4;f`j@Q;0IKUU+b6qYPnkLd;OsINUB>5Wxy6d~K|FPT-*U7x(zYeE zeETm0Yz*xV(^H$cytwZAd+BHc-4}z~(Q!(LDm`^z7GTb)*(LNStyfLc?3bBWALn z&finekWo=w?x#h3;_-htZVm~`(rLz8@0igA`PRN=|&3~T%7gkB0%qpW&p-ejksB-b

h$XBsFMh(r~Z{N!-Gj)z$yCcCFxsY;2UFi-zawL^vYs%9ai2! zP`#HtTEz#^WMBzy@_u1_zK;;4NS?S-*nFn>V&D$bzHdnZwZIlzZjfyLpa4Kbn2Cf1 zWGnT{^haI)$+9xn5Fbuo>~;$ezM!s8Me8|k<+1vuMPUk7NLoavQp8Q5aJ6uw+xAZy zIHKFeEvDJBAB|EKR90qA{l387*Di11tt13|HT(IVeC=XEK}H%nEWb-16H}rPVT4l&iC3{;B4(b zak@wfF*28laqYH@J>K8rZ_nlV7t>IvuBS=Vr^~({%qSkek(3-9stJion0O_)v=8q~ z`0}r=No>x1`ssOI;`Sg;qmtb_K%dOl45FP9YKeX!vMQ>NNHH^^b+g4?xD!i^9A;DlqrKO z&VxFicWJ-P3h20uSfq0n`is{n|D)4q0d`UgU2JpX75#=7CTmG+ex7$d{e9B;f@4Nf zyrEy&)nBt2xE4sYCLwYr zN1QhKd_nu+ObWQULk}@Hg)kn_5}nSeHozs6+-BXKA?fJ{a@y!HKN_Ly`UQ-Id3 zKU#2?ly<$jS>ni;n)9{G@V?&X;F|8=9vs8NW13Dty6_v>Tk?w){QJ!1FZ1zwlo51z zBsyAt{z{c@SRb2nKC{6eHHo0Xzv`R9#^7}GIi2125xFG6YlL4(#s8Vt?rLEvs zCi|`DZU~0j>RmcaUi`Gz)wtV&qnDrK7qG{0F~#PyjJp#OH#u|u@dc<{+{-2?8>wLx zwt(;aQ`DX7d_ZdQY7D6W(}wgVn`caCtA^uJTyr9J?9hrVnF&eX3?P!1tsC# z_2Rp^1tK%DKu$e1bbo(8 z7ccJ;_;aP^g%IlI9ew&3^d~XAa9MmLX?kjPd01FjYY?bkmv9Nh4g2{E+O#eqFH_L! z^>Q~ckmHzFpZxqwb51<3waR2x{Z-H~L7i51sy2JL=|C1(c==^I;m0hSWa&Xg9N0GP z`X3{uGT6(0C^MJ}PgO`TXS!w0W|zLu4ht%5-IO4@{G!{!`#X7IrUG-(=JtJBk}dbH6+ zt4~LlMmZ}aAR6scL^irqc=?#uG+O^Z7Y_X{rdluIAAesx|X`HA}2qE=6EXZGb@SJnV zs#~+PssJueRn(*pdk*5FTdt3@@a@aIX_jt`hDl!ZKR02ZSVAM)iALLCoTurWTS0O$ z0)2EyJ&E&Q9g9>)eT+OdvRX5t)b!(a#yAjiWw9ybkL|V9Skffp@6FcfNG6{R6{(_s z9y_d;uWdkJ#0qb#Etd=K4kg1W1XCzt(?g5P+a*C8GjlUq5?p6R5BVrK+MZS8&Q;1P ze`6Q!YG5x86AvPTx7|^>!wolK4($atM|Ko1Sst!vKkMI=CeNB*?7-M`5`X?5OfME` z)@w%7TpC~w9rJk#5129|_h)4bDly5+)s$BrLP_f|7t={160Qkr+BI-#6~*-`v{H)U z#b709JvXa`LZqZu#uW$XA34*N0=E=pOdm6ET2V7o>_@F`(X9H+k*Ub6Pp-5oF9+k% z>F##g1q^aNpv)JgLn|xlbqw_|hlCW{Ha?4l6041K%nYe}vctl3)1XC5*_jY#B8vu1 zJJF+bcS7S7(a+8k!jo8z2c{xlrlL`t*Hc(0+IGqr8(8g&N8|>8P|!i&xM9gHT;}N2 zMvK)e6GjGj8+AcUIHeuBAxPO=b%YAv?T_7OWP+R%%TmGqr4X+-EY)ntpzQ|T8bBVY zTLVd1#4UV8EAQY{?w?0D10gN{9k@#l`3f-RrQ;t#nw2=^qJW_}4xQXKRvNxu3o2ZZ zW|7sz93t$%N_BK-HIZsyS)=$OC7nu6x0)S~IPN=9(rd2P@qGomL*waOMg^B4*DX4@&DT2>7&$WqBsWl=V2&)P1&g+P%l{ zAa`arbgw0+!OQWs`h>+_li!H=0d|P+5a9jQX>%f1!%Cbw0C*wHfOpTt+B%ZZp)Cmb zGMOh91NQ1BvbaC!I}c(*e{!1j@3qGD3k(z`CMGWaaqu(ie|wO82FNI=Gpn=FEwIpD z@30*nt?v5pA99@S4`tal4wEK9bR72#xA&&Z7)bI1TVf_De8#h(gEMluqzgX%q(4(? zJ!8_xEDZf`K6gF+K5z6m)AidtSZ**|4}5z$U2jhgL&DwmCJB5j4;GFS)jsuoOU7;!kTbKVH@iM^L!Pe5r>8t3| zwdfAv=DidExEb0VNj@aS+ie)i-(6NEA^s940ZJZ7^nu^La_+-}uX1jpF{#{*p!Ch}C{rB7Qvld$M$g;0QALqpu(VdK{s;>1dQTd& zo_4)4g!-s1eL5Hn)@3>#!N^uO(E(mN{`sB0cUJ?LDhU&onOx2knX%s%vt((Vi)SS& z+s5QOX|Uag(5?$Xz7abTH0}ma!vp6jWV2IDEw`SU;cS3wFygatl_4v8#x&7Duwdj*;BMJ&M3E+QB%=JZ`o1e|% z@sN;HW4y=0k1J2|QmaJkb8%W?$@8(qzD_qBFQOhhJhYaPm3rh{TrHX(2^`;X-gq{K zK60LbJKm{5)&Dd4bL-A^p^~9s2^WJLj)5!FKVA1-9wxL6ud6GzPjg zJ2^#Ngwyai@DM0GA@wASG#1N#AuZU|3z`x^q+A6OL04k%P>UE^-@SrltR<=uFIong zR2M$S(z4}+elP2VUapUJxa|#YY=D!XHH;%m{*=vE->nH$ZRRzr7SWF)^?4%dgc$Z* z^uLNkk$x+RRODf4pa>+O30-EjLaBf(ILQ&{RvLH8$ z50rk-1yN#n^`9vaf|(eg?J4byFD1pWbW>>ItFR$OCEE2N$N@9GL$*EnEbLJfmBunf z@^#83C!g9e-%iA!v4Vtfn>XNz_2D0GKw|#e)mf-GMq;m3##hKx z^(ZK~kLm;h(s~;4_!_iovsuEweY z?IIBg-SYq%cP70bv9j>HkKcixfaaabSz z?YTMeJ~*1Jrbs@Lii|V2u8W(QQ7S1Ztve49D`xYcOkLlvABYUuxBiw^Q9%VZm|O4n z9G@vp7Q2Sal(O$d17F^@f2geYa!v_9SviOOO zmesRwWMm&lm>+iaxB6hVM%gJ|&j^ z*##%RIH9jYU%hysqi9&6Nj1dI1M)${a)&o@U3Wu>q6efsGs*03gCVDyd7*l*DIlzj zw_^%rmle~y2+_WfN&JL}->TfAiXu^hae2o~r7pLt^QCAFNC((3gg`wh4dSMu;#!Z| zHv?wRUJE$2o%;f}_PS$#|2nv#u@z2OJrUMj&W4{MA1K)Q?OBlc9tH@RsL5aDcR$Gp z-OO2K`ffa=Fj~C+5q%MH>}o(D414~UX;rB!)u2fpO97Oq$QQe>5Px}`?}y_Dguj6Y+~zYL|990_uMfL%&NY#4r<)>y=+N zHa4bHdBW8OztVuj$ob`F34ll1I6A^fN3UBo=}Zcq3jqeD_{A)pCQINo=OHv@wl|vE z@q9J*{$<{zV>zDDn?$X^=XdYaC=zNS>3L@e+-uZzs)m9qsjQ5K;}b0LQJcz*w%w{) z?-n1gtXaccb}v`J2p$l6mps)FcU(S_;IMQABc-t|Iz?jD*8v_BR-YsmqugC67W>e|L}@#IHH-dP3_^T-gF6k9`#; zRK?ph`ZxC%d_+VhpEHHg!|D=Uy1d=ykGPf-!}lQwP~#jP?h#j4SKsk~tQ{AS%*@RC zo(tT|birg~=@a4xE3LYBwDeJKIhw#5EOVB-biY)~(9Wdhya>8sFXN{x1x9Z)w=7ct z8XKR`_(`^*g^DLH?{7aOz-mg7J;BDs*8@g5S?M%`lL&#TAnP}{^GmF?(V+hVyL`1z z*zs@HM^S2Sc6MYUzax8+-ahge&9UQ^0A#fKl}@4Y6K3oBiw%wEo|oA*&0>vjj16a+ zahW&WWEWRJ&8S+hHU6ZwJFm|F4D`I)D|2*uTF~B*nEhqFFOKwA8mtAs(>?ssh6@~TOvn6u+PQ5Tfx65XB%k@DI*9XZHmLU7P(LD};@kVY$2Lv2C&DQ8k z2A<479SfV&a=b^S@pjO8hcsgId%rVmrOK6p?;xQW9tnx*+7El7n|TePt6@sO81`$w zaq8fj$nS~F{>+|9?`Q1mYrs3{@bM82O}+khk6Y;ekBZly*9i8+K1j#z&h&*T;SmW` zk>Ts9PRUBmG6F5O1xQ~{2aB`SFV=R}mXkUBz$ZdF>V3E)J`$TQeE$q!J10fo{N86{ zUcj*pFc!4|*Z!FtH%g4ugGlf)B%zU{X-j7KhtCYy^%qxTtk>(`59qKJoSWipTWGYE zC`?cEQp@JV8Dyo1s8GSvn@dBFUktYrBS`lzhe*p?TU$MpJjYv)<+q;@>xLYpjk60sN%2-kH>j1|qPX$Y- zXxg+!vfzH2mHOk5msknnyAff)<&bgesIBI4ua zC}Ul{_q8Pep!|CN1pVnN4}twST{{O!>R5y|xl)!9g0+1VD-IZbvFjgVzeGO(A&m3= z`@oedpDIJ@pHiOZ6V30sU+;RL%wxYg5XZX_x%iVtI*uJ6uBy{v-EZ7=$+YX2m6t~V zVR))O3qU_*GV00!jJE9FSLW~Cm!b}=g4HcT7d;_FUC-)(5vcDK3Qnihfmo@An5*Rn zFvWwDj z=kSQ|nV+NU?M(n8hrwUC-`f5{XlwvsVmyOC*&reUB8nC}v7#Pypam&9rUcYC=O?vD z{7>0Qym!(6{ybp;iuMx+=P!`yhCcKFrek}gJa6|P;Pt?^^Vk#k)d`_de<*ruwRUf{ zPSgGCUH8;XUNKYmrS$6Bnog$=xBt*%Ca2ZM&9~RPhMtQHHbzICAOy;QEX{rGMsozu zz+;Da5`lsD++(Xhg8mBwkXZw7?Y8ajjO~X-NH(LEJ=T4;so~+UKg*Q&oK#Tr%56JO z4yN*_*7=*PK{ka6q}xFeB&Fq|IMx2b!vAhj8m}JL+Hd;?J6?|!s&$*9r+|7bf14+& z3~J|uz31<~1zdyPzh`US$47xX*G8Ri6gg?^|E~qu;#Q5K*jVq%wXf@xwE)(oz-^7w z^&b%ibq@Q{AeLg#EAo%-_GG0KUJlOyT+mXjfj93CGRb#~^4gK28pZ*^by1D{n`I*jp+oq?SSV&%` znArzlhd_h3Yrr_$O;TvP1QXg=TZ@e@Q@`nT-{_tGUYm%u(Eyxp1e{h=TgyFUpP4hd zjmev=lq7N$69o#7`G#Z-Zf&Gu=5<#$7L_&TOm%f#IyyW!2Tc*64`ma^_J+-A&8jV@ z@}TJG+xN3T)&NChspS6oKt#qD1UH8BTTx<+DvL1NdP1>)^Ps_I2;GCYRy9sc{*(0> zFpJ@~l!^dqg(A&ZW2u79-6-SfW;f~7T_(RPjktSRsu_zni%i~yassI)Z9PNEiPmd$3C%5N%!>gc;`AG83C^6qj2`J&@;!nlDd z9TotCrh*r8!<+3a&nDY(ez{@=P`!Ic75L z6jgF6lYv0Y(-%<{eq@A3rPJk>7(Y3u9qO^=uFmXEsK6<2*Yx`RF!%8+-fX1WpOFXO zs<(!>3~M|8Qe%6?{fB6Gb`E}-Tovc(`=5o*;VCn*B z9@Y^)7=?ij?`z;DY7^92MplgWRWNKOeb4|_!&dmOhUYfG7Y526a6o@qTy75npQ%er zm|0&R?+Zi96b%%S2jg~()wW?w-9f;JqphGH_?-#1$gNhM^lk&g62{t}GK$Yl+N62F zI)t6Fkc)?2m`YOL;S5NW_WtySJWo2lu`n~^yGV016bAvZOx5nQM=Wv$Vo3hwa3oFW z;=N&7Px9rrI`v2-T>7vU=VwoDWS~9{PfoXcjf{%Q>AJ5NJxI}Y?)vXgjUy9TA)RR} zUhsVP5mZZk0{48^{R+B0-<$%F!ILMB9m+;Vq#podp1x=Q&3n=Z6qk&H*0gHP7dWS! zFaCUb{mt72z_&Dx0OB~X+r3WXxN}@p7eDCZk{8SE)%7h2k~qAA>;uxCJj~SHh$Y9@ z0{zR;$j21V^c(|V0i5CIdwiN<4Xh`Z1x-;B?=-sa;xa@pvUx@`2K?l&m;WVLW>;6ktZI5ZbbYCb(`=Jz% ztqWT!$@7fD3Yv;@VUTd@O$QMHe7NeYD!vfd=y}1&xx(rzxJ=8XooFnLxmc5-uq9rY z-9Y2mExACqGHK-AYezM<4~|+^MZhSkZ5ILKXo;1m4lSQE(EJF~O--KFN32FLSv?vk zpoPNN=-g6)8v-tW$K>!xTQFy{LDAIn6~HdjQj%A{kw7+hlhv8#>SZb{t^6vwr~RTZq1&m72(az&8l>}M`tG% z8?iXe;rn15H|@d(wVCN@S)O4ua}*`!X!#Y&YKFgUAegtSI?>&Bt0mRR^!7b4VSOJ) zn6q^VPgYl#$YNb!*v*MiDfv<`TCn%QM7iql-1>Uxza-r#heuaFQ)s-|zsZnMkl3K; z+x@RU_M@QPjFWtNMzzol#bo{fm7PXRRlMj26CS(uVMap3{wW^kUKregmPKY+vtcft z;3UOdp49naUW?I^od}Kc^u`rT&w3)(*bpY)%a3(|JhMn=h12jq-^3NrEyg0cygIt%vE`H7X2Q)EyOAmj+QKDR5>XK6ZqI9O@2LM8pRrRC%6 z>uob3!1B`zAJ^z7UL+_ji!TCJN?)UCnODrjI#Tuv-)dm&Bu@T5m}gQnkX-Lumz?Jv zi9D1HaGJpWn9(Z-Cav;&=F;)7pABrjH30#tL)RV-kPL6$0r%bkRt(Fo_Rr?_bfurS>k`Fpv+gEQ1fb-@eIzpW;+q0$*AELuPu#%T3E!VU z7o8y(NV56z*K;R>jT#-kk4};Sh6m@2COToXSf9c9ewrLMA{>v1s6dlp7FbYUU!J@y zevf^4C$mlHwO;*Oy?Ks!yEx}R?`U^(>lpZJu$Hl{WV&<z6yHWrP|n7O_&8e{;4d`ntv z*vBD!iO8S(WF(PoCA#`d>LoRFJ>YKQQuFm(IhhKvB+xKAG(M2qwS%?xr}BqNqH-lo zi1v5rQ3=B%$D=&o)OPzTB@l_up+!0IPi#)L@xtBHrtbvGJPG$Q30wOw)rxg%fMkJ2 zOZW~M?&CjICL4LF{(ty$Be>r#=dALK-@5#fQLw#l7M4a1V)Xrvq?%iK&1$3(!)8dN z;j5ef5sCCXE`YS}jN=QPS{ee!5jHGx1Ue8YHv{EffWfB#WOGUrN^b7%5K#-uU~&nY8Gm9a zc#vA&&_xd!Ygb!1H)xTAjZLgl9|GF-VAAAZl33{OwCNwo+17BPgq`0R%1_JjgQOVN zBJycuKnB|3F6jHie&`Fzy33H&;i(-pqk?81MxEn^^4+8ZmX1ik)0vyH^^W$riBJ4T zr`-!S!HxBvpuYx8Z}(^VewQ4&F8sG7%ik`kTWj>?Wb_ETaP^8ez05fK`(bF5b0p2o zII~;rEH=BK03b|6IGAXzOolEEE>Kgu0sza2g7PIMn_@NaGZDWn>Udxqfra>48ebjEM%MR-xBu4 zCt}e^5}~-r;HeCO(V)@b22Qz|DhzQfE@Ei1oU#OuXG)sL8U>0zp`HS#%DhKAmJ@k# zS6IL{Xn({vHX$L!Qf-Rtk$UqHj1+YuKBo`R)&36_ILx{O&kxr&cD8+{K%w7kXfhX& zcCmvVk+1su-`mc#a$o=fQ@hO?eUz|r#1=*teP~Hq;KvnX0!hbS*DyHT^Dgk$_L)?7gntR0|vVOl+ zR5sCX{|ZWTld}7dy3r`-%ay4mk_z>0755Vnem7Nk*)<>T7-KOz&kIo;b-y~zva-pT zA6Hu1RFw9D7D++!=5hQjkG7k!%AGrm2b_NKsa@Y9Ixr6UJ@X@o}FkvyG zR~vaTEz!Dqg#04vJM2`tHa144-z*AU1iRs^$E>j=wh?@&D&0{bx@6xrejFkSoz!P~ zhQ0);Ke&wAM`{xTHGcM`!3S{8XVWg3WHxV^G`!N%LsKT9ib6CQZBJ-o0bUu7flq60 z${9Vg77FdJk0&;^wvhA*6fE(qNs9w{s$PJm180Pr%eXndra*dWQo@|e1TP7J1JCZ% z5YzZOwq`<<6&5ABT%v7_(z>g_nTG{31$~(TV(*mKJx?^!9zFyCTC^%c^g<-Kx|bj> z9(vRZ5IX;WjTtPKrGi3(ke88V(Db|S7k$>ywJ}|NKGOH--&4#Lg4*<c=;$)S?Woj%XmDFVLn>9I-?gSaDTz;|tJYg2j9jOI#$hk-Kowmqh)fqGC`XO1lIh+bhM~4xbH{8asH|wxWds9y*VeeNp0r zI$dAA{GjBp9S$lsQXL(YIAsT)+y`{ye)!-vw$5`nJmQ#1E~@e_W+Mil>y@Mj7q7;L}6-;h)nAM*y0S8i_0dLV9e(`%hvlJH_mW!~HQT z7D6C}m8p=4nh|or~(k@1HJlvQEaJWX17V*mGWbn)SmlsR~A z!E)mEFgb+`KBUTiXH)ftFHNyDoo6-N+IqdZA!zt^yX2qkxFg-Lr&RhLq+nI8nLos6 z5>zn<^YO?dg@F5c$taL!F??X-dcw2x@r?bayLzodWc2-3b&R8yotssEf=6e~ z9zi>bq>Bb5JCRgn)qGrvX0Dvh3wCmNgUs@&Nmz(dKugzyjg_$O;&6>arL|Fug(H!* z^g5~mN0~xo0z~0WPcRo*&8P48+Wjsto2kOzlvJr{#WJ%yA zagoy{Mki1LG{lsv|2d$Hzi5Nz$^kb4bDsBy*`l0sFmY3-T5%&zsPba!SJ=V^IeOv5 zfyNbfgq-tS4Sv9+zuvPr5wy)$m5P6p4afx-#WCc4`Zl*l81lZ|QI%@!F=3bZ#FAl? zVd3ygCuHsFEmEFGH{iZoxPDwt2G7qke-5Na8<^l&SE>S3qyF=oqy4{P#v4Qqnk;w( z7|mqoFpzFCUv9KM08%tB$CC8$rqiz9fTn~HV{^>;JkFx|)7kErzb1do3)79!<%;<{ zVDGU?!&JI)_z37QtdjWjWtWquxG0+vqS9Y_z_-0lX}Yo}ay#XK`FY1HK6`#no`{w! z`e*w9pdAU2^dI+8Z`i#bq4!w)hR7}uvtQDrnJ_vN*qwd0mS=y5|1MwMG1!N^BuRTW zuxa$o57zb{x|Ql4YdqJFTpj5_PU5INCSsSExi)M!a#AwP70rq!v$AznRiu&&v%F0F zG>3`UA=(<~z8d&zoctp|+&DHKRJqs!Ryc}jlf z7VfLmU_1@XqEvb60Mtmk96?9sjFKb;EUBZ_VqThADmtJ&Yt6=GGVAVDhI zgMcbB{w}5^VO*GIfmw`y7O<-FWQIUn>Dia0e5(%QI&0JX<)s~S;4NEfYW5?tdt7!% zs+M|QpcEdWxND~Al;vHXN;uToQjw}ACqQds4(A5gIn>p2$&^wsa!Hpd37*w93I z)Lc#8I6J1*P{lNE*!dMR#iwBsxz!)4@M?gis_s#px&#C4iER_6mR+5UxSX7x1xVhk zM9(jtaGi&K$XB4N&)Y)B*T}z{=F20zCL6>Tg`r{TzMzCWjJ{26WXr64Ucc+g|Gw&* zUuiXgk%b125(^swA;DzFh8K%M<&nb|73JuX?z*$Pzt{CEZ|T>`gGFaH;Q@0U;hLPG z%h^4+K_b{}XxXa`g0kl;J3JajQbIy#$>Ops^UeA}j<9B@=&jQ&zyHtD#pU0tn=Q(y zziwB4c`Vd^cYKkKP1*9J>hl^dy!Es^ODJb1k3&zM$;g2HBsL{D#OKi=s?R5h1-Ust zX~S|p+4s|Y*y*y6oytAV4Y6_>ELj=B$&p1a5$+n61(i&m5>L>x;AHBQp`_;td<*Rf z9TAt{ln6@TWK5ijB`ax=NM?tfy5{q`K!ZcQ`vcPgGjQ$hCZd=V$|wMM-Wyv1}cVj6aF3m@~@zi0kBkNJwHb)di*b-SAAa2QMgLF0XIFL|0U4bxuTU z5LAOtL}1#iudK-7=2mNsv-o~Ne1bm@u;j?UJh~?)e>?7+#3on{Cu|V`V&wUMLGZ3? zAhKy=es7mB3<0+e)NgPQb2)u+z4Pw29AMMVDkA&DE!bf>&D(~J6*+LJl$F4L=q}LyA#33gRR@2N$zXGA9`X2r z&tcBz3;&>GtxOm9DJvm?L7~8cgxL-m<19igl!GQ|!l1y{0(Odna{vE;>9S}SbfYGAw-3Sy=4 zNK4{q_9Zx>=JYo};OBCPxG?1vQ>u0&+GmezO5o8m9x7b5qZNaY(crViv|B>yR)`Yc zJ3N|B*c#(b+axr);{*Z5d39WtcFaaumeYJV0r)jCJ`0Ux_C7vXmQ(zFd>{i?8fLR_ zb}os^Ugary|LMO!!(~sxI%Ut2Hz}Q9!#E%KWtmZ zOs<4yH6Q@<=fM~V`x zFwe8b`{PrgLDq0%^bZfitFN??WM)ynU-qMOlM~IVrllm|wOCM;8Vnp%2h`qyk*nF=uWb zbdPosz=q6EUDpvIu7%kMo_u1J&Nx~b**J2*e52?h2(qsSpk7p;bSWp(M^XHJinQ^K z6hlesz>?kQ@Wp7-5NLQxXg$;QF<8;JNpZKt@hF-Vnvl9gNI@_Ju^&v1IoFV&Aya)O zM;7ML40(O*B>V4_ktv&FJGy!EF_hp~J(%!5->P%T0d7t4MQ(a!Qf3D&gu!4mJ*67?@Xw!Y*AS_=)avgA35D$@_Ay zE*~9ii6~xtI~u*>03`7T8)QWI*r^H-ykGiaa8UtOm}yWDdV1FuLt2s-^kE9KO{1ks zQ9yFduO6y_Oly+y0~fwD*$pTY^;7w;QEdyA|87g*D`7{wz;h515|q$gKt8X=AfU+r zTd63kPXSq343{KrY{MR2p@if9#E6c*+heSUF@^gt56|*wdyo%N_gd=FA`=P@4$n6E zkgS=vCHL_BU&~~Pa$f<=;o%k)EdCj|FNg)6YdNh46&W@rJ{|+0e-}}!Rzd_`l`H29 zJ?Nf@QI-zeaivkRXG9(%Jv-$m>g!}Uof1GvTbOh8kB8#E#BZK|n4ax(^?$ZamCA)F zsb;h0>g>0$oUok$i-+UGuxmMGkd--@2q~(5$B|cyc2aUK5rZdA6s8DDrBHeimoF;* zwmq)(drs;DO{6XLCs{wUY1qeb#tzr!{HtNKG%R5AfY#M|#{5ztx&2>~opK!$P2j9` z=!~{JpdhTRvpGLBeYJ}ShPmE%pILKFsc|Hg)* z)gc$7Lk^yd=SgEZ?7>M$zq}Rc>e-b{OjaOffR^ql%rgWA#!QzqV()OI1X?IGJ58a0 zl%j+YJG(x#{?|K^=u#tB82Mfd>PMM_@uBQju@fNKGm?}e=jg>C&xKX zrzk1g!j4yiE>2M*dE(@6Z9}il#79?Jp;0Q8G^Kr|)vaq_P2GflttP(>n^oK?p(&hy zTdRXb6vh6h7=AK2I}W-8!8@u3IKs66rPMSpO-L51N!LDlk?4DE1ZhU3P*w&-Ub#>B z)o2M4ss0~)0-1f$|R&v_@UHHl%mq80-;{>1wrgcZn7{k~hsgI5N zLQ|waC+#!&hGnXbR+dP@L4fh>*1(O_L8xgMQu?v(&8yd zNkm!~WL3EO5&wY;@0WqY$HOx*l!;p3_4yN9KzS35MsZ50WFAuG?Rzc~9vV1&ALqu@Yn=^=FAC9bn4+f5J zrlU?&-+B@ehX=M}6mVDzsyf4{9O^>B?A$lE4h``FL~r1p;fkT@3$)zaGp4M~up04+ z{fAg>5{1OL%DwWtkPAl}fHx?mH@m$%Bk+v};f^-#ArH3%I^O{;i}de21k{Va8`CMG z(wkzD)gal)ZYga)Rc;ot1SPi6X1O*)66>xrR&4xzio8~T`$1cxqHKNhBAxw=9}C=~4Een-K29eg`sDjhdg$ z+LJmpW0Ghy;ndS)ShDySbHENjEIN~(4?S_s;6)~6y=KOXygnU@0uUO0&_yc2N{RkR z0Pi=_!GG4=f+dmNZpUQaR)Ge7TqN+@ENGc3>=#Bx{y4X&3&_$x_T5m0Q&Gv6Tj_gz zOjLIq7~Pv`1o{sP$(u;f+zZl)D)Hg>L(mKa*g8d3mbyNr7upyyPMjk4leD@hC9-q` zhMhuQ^ywwjCp5%GzmOWH=C9ta2N$<_!c02Lp9SfQmVJ^20$f5h3FAowmwwq{K?! zCW7zjZ(Mi$75iTZPE@OYiAgukOhZ6YWu%18fBi%eCRTaD5a8A#F7mDkK}JDgui`pM zS$(w=8&)+ZzKekn68$s1<=F!-Ah<@y$J0gn-R6p4>d%l--eF&C_Y>dm#>%fp&-w>N ze>rd33DEYYd+=28{HEX(rVU4>i!Kkq1V?wtxM8V!DP?Q)=3lG^VOs`5|-) zk5UntyfEWye(V+oEj=g2HU~$0I#s3Q4pgWRCCxa6b-={s-!EV8Mufi9Oh^v&LK@$U zD%>0W@{qKO8ct~3SUA%}A*Ep^uhBBVVak!2R2xxhJ}0*)R9Ku;?2d*FlJhPDW1|L^ z8|lw9$Nn_iaukK9`y!(zZ?dMm%M2pBU{{yqV*jfh=Lo64Bqc95Il`^4L9>+C7BDd; zX*ZP>;8+w0S>x;<(k$-6facb$L&Ug?AoT6}qna;9jYRRktt~Yco#x06GfIdd47?gN zu(1r(c1gctP6!7WIo;KeCpZ73W8PrAM1*~3v3JRML={qvLAx+bB7}M1 z*2pMSho(xY_ratYS@i41h9P8)TG{{-87(DnxaU4TMLGxMAG0gaSDPvnZ*I2s zYDeMIjn2X0Nfx`s5ZdS5Ct!`~qmGE~{dx58H|h1bRozRO`if>n|Dg6A(v$wyYz~Wt zIAwyD1NP7er3PX9(Y5|TtsTQWxo>TgD|7Ea33=zohpumCYXG4W*cXK%w@7AiPfg&H z>-BEw&p|$pOj6xN;&;)a!pBByW0}=bWLm?tYG4wf8N%Z2R8PVbesIP)c4DxAb^D41 zsUXQy1PdI|jfanqfKXXcHz)Z8G|+~jUgIu%RlQ2T*BG-1TZ$zg{(m%`WmHt(+lD2S zmXhx7?(UElknZm8loq7Bk(M9QGDvrKcMc&rbPv3T|61=S*K#?|%$a@m+56eoeLcpw z-!LMl02Rv3Gzx*X93qTtJ{M$eNVJ(jGo@-pw@o|Rp(o<1U>7*-*7N9#i6l;{CdW#{ugCLUAxUMO{ZAlyy@1OixodO zZt>Cj=OD5)g}c){gys{Qr0R(0a3q3USyP}!bx%ymB6Xq!y};QYx0;zsz&=->9j%j2 zkPaHm`;l{um|H2bzU3yCKkzD>Kb&Tw;l0!|$Hl@5T*wvOC=F_s+@I2l6ZD$eI z@^<^a<~5ufbr&OM`XgnQU*Ph_#>`RI6N0#7;#IUVh8Nb~egDM+U&w0^F7be7BEb7~ zk*Hxjq2TWKQX=nvv4)HNAZBLWhEvqmrY!T|p?eNDtof{bcBFBoR-ryCm`18l`q;2{ zrSQPAof~V$oy!A^M>8deylGlXB2lU*As_9yd_#xrOgRe`^ejvJ-+t9)pWl${n?a#? z^ATpIS{JMpYH{>y9+tiU$8E)P7lut7I9yKw$ulc*pdlpp-;%WDc%N$ACRYkQkzA*{ zf@jvr!w0nslH%H&q)R-y3~P_t&NF?EiUOs?d{-pf6)$euvTFT)(C?{zS4nEOuDMq( z>}?c%=LlTh43!Zg3bQ8^5^3Jt!+LjpZD~zw>=kA0^>?MzjF+er?m2=YYWp#f(W9SN4Y^c42nc}i8;l<6_BnQCi> z=KLC98DTtjL=OcX%$bX&q1M|qR}2Q3-EJbZNWEke%u;Ez;ge-AJJ>`{b>&}EMm*;< z>0g6u1i8qS%vO^rddDP$34vnCUk+JJuNeAI$f^Dx?EW*tex#ANwCf|+)lxSgpI{5h z$6vyK8l8iXBLYz+16DkdC<%P*tZm!fhncf@x)>3H?C3v}4C;rb%HspP+Cv&uTE*__ zEDoVV|B(NR7cUUYe1_Z3BsS z@hQDG&+Iwa;ERftBdu9Vqi>BR6PL_5z@!E12yEzeh{aEGMbPd?d?E`D2#fNUguL)W zD1==ep{pLU@v{*U0(TU+Uo1Tir#)8S`rN4K?JsX)y6fKw4ziwGX2b7@ z&?9=Nn^Kcj1UjC4wnJyQm3f}aKI=AA_KmxAjAYN#@Xn%%jpvgGdN~}Chl?YKraMwZ zd;rtoe(Zpl>H;*gx<Vu@$RNrDHOeb`fO3(M|6MTFoh|RHZfJgh^rd9 zX2u%qd+pC(#Iw7mF(ZNVg-z8SKn`Gbl#%@K`6o|0PS$$#CkCY#6_lun5~aD3*k36d zk@n6WV~8`K9gikeQx+nhzH2Z87p0h?Ec)SFVv=p71cK-QBC%W&9J8aOWOm~Fd6(A| za|5E8fpb*}424V0)PC`)#4I4RY|9$N$}xR2DYGnnkWlmMTP<`(#iZ^(Ba8u}c|m+^ z$W5w!VzR~HcfLmB0vBccD-_+V$d0kpX9p zy;asw&;~*0|Lw6K2!gAg>lUTa@RDN(zW09)YK(P6asw%G8;z*{#UZoI(z#50w6a?l z`(asD9otgB8;~OC_3I(>5X#-*5WKA=t&|`VHmIL_>}aSN zRvImTgd|MqC-srO32v6GQQWcpMD_S26TNg9MMV^l<6_c+hey~2M$VVMO(JJ(j(tG} z+x%46VxARr_N3uhr4)5+MqKIVyIo#Et`FEZ5s)YP(gBQVuC#bb_sgufnzzyyjyz17 z+j~>Qy#I!kMsh;^+a(V*)QuHELH>WVL({lS1EKK5W{E(ioN z)5UEza2oSg!PR0qD_Bw#Qx-Q5TM{ay%gIq%drRR+m zP@cRzIF2wJyzN1=QODxy=kDs}9*bHY_QO*Jm^PFs5Y26y(qkIuj)n=7(~XoI2PGy^ z{$9`QeJcd0<0=6E0m#Fd&CSW7p{a=KjrU=xoE%)?E>%ov3S;>qKLFM}0*8r}s(?+6 zv}%W6;LEz8UiGd zyCFoN6kCpf=F@cs9n=XL{!RUDq3KDu_FWIEu@|ooC9OtIvM@xyAr;9h-_qg z;L=(yXdBGIn#l|w*rf$7x2>837s8gWQJx2#l!(Ksie`&zYgzP*PhU{mdoCyERnSFX z0f4r>p*%pt|1S9nJ)(eOQ0CcUrPJK1B>RI#J?TY;H` z@LU;RQVm&+@{fpSQt;>O#7GMAa$1V@R&O@rhY{`j3Ga^HBq}*I1yfzzc{|V8;DLVl z(fWZs56YR}8$jmod72E$(X{Tx1UfbOBN3q@TOPb=g+N48cu|z8g@8igVwhn*82^?j zER>4!Imq+=_Neyd@Yq1N9je~ZlkC&pzHDjdu-7hsQ4Ng2|BlGt3dLsVtFio<^l6lW=K z(Xv&?ri-mG^m?atK>!suEdTnw5zV!;bWqzN$}YB0uZokCvuA1wBTXTK91*L+TQ+}! z6*=N9l?B9P0GQGYFOBxUL*JULefkXx-V}$y!P(7G-cQ!(wx_Cuaj$&YN<8^Q@Dl4w zmw^QerJ=_yodQmG^f23;7_2iG_t36&lV@*c2^1h~1P$kNo+0_~446RhrA{ zEY_7ayW9$*006wkPb-T)*VA%9Gq%qQVCDcaPplbP$GlXmMNi+`Wouw0m|a}01ze58 z56DIHzkfKq`8r#x8i(xyRxE0KOP0kE@m;1AJclnD2j>B)QFeBAwWja9{+U_dt^V@@ z7WoX955iXmlh!~02xyd+2asW>fU2ZqqU?{Wggtdh+~T4h7dLkw0De7OW^|5SO^Qu! zZJD@LMSFQkBreZS!(x?}bEo zL&<-tSGepBVS=32fsjm_q_;O8-~jf#lecH)%oPC2I);XZZ!z~Zk6C44ii)hRu5Lji z=Z19Zlmc|7nL1Ueg^y1rcrbxWSUC2;H(FQj**mf!YN`5-?gkDNC`y%ZXLS5iKbkN7 zt%mvRBQ<&T7KEs3+Auqq$a@QEB_$>85_0)M1w|15s3G0Ny5mIpZYhtfDJGZwdZ+ia zOB@9P@xFmiNAs0$JV#z$-Y{*AYq3jNl5BR|@mmXJ=KwHKE)WM3pfi$cc&RR|W7z?D z7-rxZ`Gf%7k~^(WS9pM^4tu(oQg!FRuM;AsDf#$Vj_aG73n(PG;0@4u3x;)fO91!v z2oVk3IH?`2sqpHg4ka!;Og#9FK|X6fAQgoksy4XojR?|}T;I*gLlkEAR7D@CgRl64 zdmnF(2}nsr!$RhM2@lI3T3|G_TI#|}biMJIVPf}iqE}gy)L7pJ)_qUDZPhrJB`v5E(nBo~eR$q*wGT8+pAX%7i9@y6`@+z4t4Y|1Fg9NYEV3@krpW&-Sb$0t(=8jh=#C3EWV*1BIqjkQgl2>#}ZbZ`a}m z-J5g2C}aUlZqA#qj(4@mnXdyvw0U>DBCvjTXfA<)Zyt*j+6Az2g8{b<1w6p$kyWq_ z$Bjp`=?l$~u4v&sF(=7=~QvqCjc+F0C z;eGH%#S^Agy}g_;?hc2|DhRk=ntkuLqs9TPg|+Y`S6En>@?!t2l*yl4Wegu#`^~>j z{cVp&AAnEvU!-3|0m^2X#uHVkWeMtHnOU6)MkZVE-j4zFkpX&q8Xn9 zXZ0C^H>L9J>FVGjV6g)t=HCx|fq0jRnb34r^?#hoCmK6oj(|-%MA&#Tu?h18kpW-` zHv`Ec`ZNV|Nrck8B(uI&zsakmdP@|xj(bWtIJhMcpui`=emUgM-{J0Xccn_N?t^q3 zw;)n1bq0%VK5g9n1tbaIva4)}kr_$RTfHIs&ab!5zL&#v1Ox;W8KcVl`JA7}m&1T* zJ=ojZ`)Y_PVQPB1`|Tfb*)RMSd^)@L7RDREI!Q{xe7kW9pvwgpz!Ha3SlEEi%luGL z5Z5)5ONuy>9h6a{Rr$tU19Nk&Y43-Z=gHSxAdE0K9(CapLuJ|*_y{B|>9WiITnmv# ziEAW)Q7LB5s>@qK0fFaahPuLA;G?M%>S(aIH>1dA3HTe#iGQgs#*22uzkvpc>h<=E ztg>=)JuY7hnw_m*rmE*kZ^SN;mf=R&&SabkVKKg8?45)L{KBYO+; zhhs$F{Y_1lES$RjP%al=MmFF-!S7_h77ui$hd$k1y**TbH2_>AuM>6Zp?$WzqYi5Z z(5H^>=?>z2BQmS&JCRo@2E zs|V9^Wc^od78^nu4V^AwhdhOW6!0teeM$1Ohj+D*kuo#J>6+~n&YIv`+Qqn&?W zSu=o2#oL4nMB8O$Ws_kDR3ouJYcQrEudlDi#>dkRnjLylNjR!=&7??iVF}(=<2j4v zBLmNp6FBqXAF0VefY0k}4Jk3T^z$A-*gqVq29E%1!<6qxaed_k&BHEUTP>``#l=V! z(LC6|N(r20o&R~rl6hQZG6F-v@bT#hyH)Dv1gUUbO2Q~=ip(0G1P1VmG#~Lug9WD%&(IRJT|L}W)amCR+PT*Cgn$l)H z7r&^i*WVtTz|=^$Ox~4+1nTjoL8UieMXrK#SVhjV)?;Lx!Nh2|5G37kElQPUlxRGH zgQb{g8y~=!8K|YZaIWG3E&#Ex5Br6%QWQ%}10N4-86MS)BSy-o$9H@N8sMfrS!w*S zy}ivbVKPo#cF1i6{8cm~JLyol6)q;kVCFSCQWb8ZN0C<}DQME1r#haPF&2p{m^&Zc zlyV%f z;1T|3;l9K8PLzA1m|%i+M}Un)WgNd3aNoR*YT(twYc{%CGh%x7z(53gF2W7Qlfc>4 z@0v7 zoFo_%SMf9(!~=`#`Q?QY1jlBB{OfVH4}HngK2xO#X2!WGIQEmHQ2B7xxl>tHRh1HTO3!@N zt4NuUloVJSig;c*gCY33V!U#{Q%O2Kvr}fGDOLJzi*op!RUE_yXN7YG?ZTB2qt$_f z9qB-0l*yUX*dC4S1c&se`3Z|l^T&xlY>XPj{3E86c>+%jpYxl1SG=+LZ z0b+z)dKBR#^S9T{(zuRKW?}eu1*iu|diDm3$|b7=Ww>TI=ROn67omPYB5q{Qtt`2~ z>|8jZSS|qwEhJtmI`|U;t}J$L?o>;>+)$t#2Otyw&D-Uv?T<~3?c5Mo2ZNOmKE!>t z35c8E%g;{_<$cNHZTS&qXKEKOd&tsr?{?%KBHOwRfLHtk^`7nubVvHK4?8bF{%<()e1|>DhP$+qB<7Wu z){xhTGv|Oqtmp! zI+qejUtk6ZMKmQ*6%W3QAcWN3ROo^yyI@hC53OZbcNUL;qWu@XAC zQpsl(DuVHuFcq{utV!8nCBG0QDvf1Tk-nVprH^&GzWdVrp40yjg#$}U>Qq0>DYB_r z2H8wyW_^O0w?(p5CUN@3Fksz-ni@CsgY?kgmSBQ!CVBdh>u|!MFMla65Lez!OD&jH0uAk;UeTPo_QcLQif^)yUe4zZ6a3zYD6bvjV&4 zu&k7)bnk1P-pmwwmm$v-wi7=2GAb<31kNs7#?rx$O~GQT5mPS~((NeatyPn@yjd%&sX=_fRDc=Z9J<83)zT+_LC zUw))e^{Be#SOn#ZUd{Zi^vw29l1^pyzzA3cVN+)32h3cEmBTXFg6y3^$3l0Gy4ZKC zAeq8MIR+pQaFeJ`Assiz6UiZ%*1`)4&i-5SdDx=YzmGs~<{%;CE6v9a;jipphEgiR zt-w}A9G;x|HGc@5iu{${bN?75CX32e;Ai2;%SSmFlWNeZjUzhzT~o%o6K4coV>jdt zC<5x-{3M^nk<}X2l(nkyBZILh2xP=3K(%1cMNks0LBeSOsZfR#V*hV}23@a1&XyH@ zNlpcM`4lbAagp^&*MJbNoHmZ8&*kI0s?P+HB`fO z$78iPtjEEps6(PhOi)+M@8~v-KM|9j+@|vR@|Uv$hN6}@s#G!k3kks<)O&LnZPBn_ zEb#QzeAZsy#q(5!qJod&&{5JCUK!okMM)n}!@ZY|d~_hUJK0 zR|S`vyc8dC+yXC=J;#*lR`fgxSR6vhmHe}5ap+RGmq2-mT7$01E`pyODLIo_g|e1q zax*D1?8z$sp9RKVt@4sw+ z2Ido0%K&rt-KHlWy68QJS4U%xkW**cwz>bIXl+!yuKWGP9qEBFDHQK_0O_VD1HX(c zl+nJrIWqXJBI@CmkIZy*fhFKy^+W$um@FRSwtjif)rz*Q38vAs%BuLw^~E-WnE^~Y|u>7Diey}MJsT2})&Hu|%>igcF|k`iy^OH~xTf`qj#D854%X9CN6mG4`%Gl)uQ^fW|G9MtOmI=eF?%5u zSqVbP;VB4^6V*-3!i?!ASC|%)Ck0OY?1ku5uCZ+ln}iT)0uR`-7BnR>?hQIF?Ou8z zucV{ttX7a!AqnyRs>^E))!HCvL+U6iD20w*J6Rl40alemRE(lIqFo!s^YjMUYE zi!oN%8)a*6UtC96&YBLW zSCI5d!2zW#n!`I+J8Wn^1NatTP%75^{a7px@Gf$_IpbEB?Rr<1tj2JNARJl#3mai6 zotWj1V+1?5+&59;bNk{oJ8t(~6z4SjGPwpYV~DU4-glSd8_)ebF!(vcg zyR#D@;0emzPGVeP6tBk7AfQfAoUjo#nWK*{z%MblaY^l)z?t$w(je{P&5p76DG$aU z{Hqi4!%_ek)ziC*GK^HkyD;b>Y%~wKVJ?OarN5B7lg!(R#ir$cln$-pTG~=5f8#!{ z_BNaZs(T{{XMe+}L`3K*YSVh0$raQQ0Ufd*VIO7cx7497iUND^EqX`7D4TJ(;bE}> z4{^=z^7ADd|DOY8Sy(c235nf`7E;-8a33|B&u<>YMkG%427OS^Rp_o4`4Eo&-=~cy zUr1~9miH^v8vj4SKObGDQe#-w9$(New}qVcI|I&Mx6+hXF(oOG*clDFq<{AIPhi1| zA{Gv<5>BGnIG*li1n+52&%<<_M>zS#-%>^(#$7~9<M6c|^h>DU z#uGc(dV$(>72tw-WA-Sye~Js~_(qh)V8ioEMnL?w3fX;NY%mc%pkr_bXor#89F1l1 zMqo^Xq(@xTM{#0)w;vH!H@oqO1#b&@ovfhar(O)glT zMbn6=umsC@5hXGvuwg7TqA`_D9dY*BHM^&P$;lQhD?BRs9yZo$uMx5{KvZoB0kO3G z+5WmFPM+H3)m7C(Pr)AY-lk;cUV@v|J<(n7@AklIvxkIGr_cT-zuRBDMd^uUg{=qL zekl}0<`Q};%YUtyj3qeuwGI)|e2y9|*ybnVB@OE3-N(AI(1@ zMkFDxy^9-|FNXJ#-}-j}19Aw?v3K@GU#!ZDGyHRyyRHBkeR8SnO|8TUudA~}lKx1w z^MI9#^;ghM3HK09T0W)xGJU5FW9Gax_4|%Pwf`n`tLhuTh8|hD0Fc^K}?O|Ay_k z`L_qcV>rm&#lKC73XrpJO>o1E@w+sd4r%A&6I=ef|8jeWdf8a>0@noX58f{HhwN+` zt$nUr>TbUa{PtDbP)_lH*ywp%tl?tsp!umI!DTayY&(xkb=xq0H4LR(WE<Z_E5&(Z)O zWw8u6hc-2s9l~BV95g)4$F<#uk-1p>QCjU${QCqv1crjo16)wAtvahb>MuFblt^W8n|4 z*jIx)5=4iR;GQo2Y=Ju;D}U?Ng?B#x=rs8yOyZzwe*yP}@K2ws-royQ&cjsT@xQ6B z|3SmxBfLOPfq5DE{@Ef3@u8YF#dX98n^)q<)L51bZ!8um>Bm)l1rO=xUR8RUglIB( z!Gp1b{8osS#jk|Cr-b5l&KaMdX#MI;cR~M1c_$8c8nv4e-4)>XIAP=12^DqV@lgq> z;PDB(l4&@+;z1LvqPJU70`<-a2!ORV$tR>+o`~e13l)xSse|dzDpuza7*13p7#_JW zaYh23>RUJCgcZ<0nBM&cV zT+|N>boBaOPNDs61hKSe+@)VChMqGKhAg_$EnwHYz(i5y^6{AHBD^nVw=^Vut>p~v zw;^}NqVa0@kN1>a_+kO;;nFd}A+DG`GW0mr8R}tq*0(!p0ngp5_(vPEuiHk{YCPNb zDe2OJ822B*xHir?y>WcZ1v;zgcrUH?r<+@AU70P&hwUXSsd$r0ZM@^gMc{-F*ygl_zmRzclHI~u9L zL8Laub^lxSu>-aE-pf)Z%m*)AV?P=EqJg_1p=6rT^dxWM6=YxFh)m%p$v&HriYSEL z=TDBJbq2lmNL%wOqF-cAR;0>jEHOmDz+SG&SQG~1w;?b9)cUf-yg%+Duepq}e2R%# z1F_fcbcA~^vE%;8|Qs+Pa=$bkQ$8|28_ z2}&Xn0$oi^7xN1s0CmNxR1QI$div-V@;XN$LD8EJ`}p{^EJSj9h_V5IMh%7SZw_71 zBbCv;jM$ZtKzHzCyXr->YCvj}%8BJ>A$BTp)F_)_^u$}8?JZYlnAh;|Pfkq1S`Oi@ za^DpKjs1w;;IV9W`9Pd@M8Dc}_Rd^whEk1p0I{vh{4kk@-%T`c#L{N-V+#ULFIDm1 zq=R46ksuHjQ#z|8jvfIqOGEH6kvz-_cIwKiZifRwI^XxMgRN-B5U*mLo*0}A*7C}R zu$K<(6EPor+hx=QO@X=f@lN4OL&5Y zkcIo8td0%}ErTGOz*ggZ1hHqN%1uup;06z>Hfl_)d6|@3UJn$ePEYcpPYvpMJK&2` zefjWupYS?#w%$4|vHRDSJHmi;(Vat&s+59`rZ^4R|L(*R($QWROFc#26ES=z{C08z zNb#_X)G8timwH@`f0lHiKWD1`WX74%FxDU;H9d~!BOrb(wU|8^+_qNw1_q8#6aFwe zAkn&91jKQee3pz}dpL_9?)k-JS(L2#3EK8Nmg3;&&IfWd7j{{H7t*JNg?(>RJPpVh z0`l^`{icj?7~WwkX#8lV^!Glsnp|zwo!-Dr3PvdwY3nN13>``Q05;c0oWvIVd@(R`7eu6dclHEa$JC!f_@;3;-*=lcuXYE4K+jX;@59n?~^K)hiB$QHLH`)opQiI>t^>&RHAyV%XWa4p({ZZ3k|Db5W`bzLW9jVC7>Ob zRa6WK*>)?bPdKYo4tprL-@wG$3P`{d9#4u%YDSokY{kz`+$RF)HWfTj$>J@P>PUT)B$eynS&RSoC&R);k z+b-9z+wQVQml~}3f?pPm!Ba`*nzD=s#h+PGOQeZ1i}A{ z!|Sx6WGN9H@goE5OZpH16T5qwCv+&_7CY|jU?fhxab-fEwQC#Ah=@f{t89^iD%Sbzx*Eb`<3+dyyloAgf@d|>nT#e z{osQq;+%KKKRa4R&I2u88)Bedy8ng+xNN)))E?D=-5ziWw3^C3uHNkusv%eI0u1`&mKjD0 z!Nz1l-lse3i<@0<1i*B$T=QEI zEyvC#XFU<{E4A*6qJO3}4FFl&}_rJFzJRW;L0Wz## zF=N)K*7tgKv$d<;&5qqB;B;qbN~?y@2leCaG~gq$dBrpe-1B^lBzL}Bd*h{`GIC+TncV=si360g+#I9&yqmh@C<;Y)5IWP{?hs#|XT zh$|KBztlS~Qf#cX;4Nn8fW~k5j7ED(e@u_;$MM~o%2Y42RMmP+3$yA6qN!x`vKg%o zowY|vh%5S|0D}oQu6Nm$M+de~2QpV>>Oeb7D0UdM{U3Q(9ekyBbxCC<%3$3E)TR2S zymtWnn>r2&dwj3C+B<78e-w!fW10>j{Hp^tlcxnzKR>_wenqi^ft-!; zsdHCe=Z)~aE}9JH9UW&j#dPKm8Wxa_KtLz$KE*+S18X{w&({6W_mGrG7zWXz(3aT& zFUe>b)giAM%RaUFek+`tiIi}GM4gpZHAcK%p^J`&`ZnCpL4vXy?HB94HzodaN}Gfp zypA35RNnUlLxXi1kB|igh5iB_Oy66)nv0v)3$%re03qY&XEHM(UT^3O2{D9dOELI@ zrn=RQrSrKfOc?qjPWZLKy7{!d>D~X@4HO>agpB+{r7eCJB8xzZvOif|S)3O`G(ct8 zV!_dHFabW)4pJ$s{BgH-@8s0#C-9(7bOkIch{+_EUD`Ses^h%?fvt_>xcg`oU&FHq znMtPbkNrjtYbTmd#*ct`>I(bWraL^^9VS`m+OlW#@0|Ds?9lIL+K444T zSxUl8{J@k^UQ>h4#VKj8&%_de6&4t1!d={vaQZYPUt0OwrLO%f+urvq8Xy7?^A-#y zO9Aa^@Jj&Wyuwa2J)+|U`6YGdw{;E%`H))oq5mWpBoynUw+I=XBK|`O@e-JJho@Q) z|CuS~4HFm`_4Y48Ibz&wp!O*(fWM$rBQ;>x%2x^3;&Y@07ngTAjUiR;l&hylIR~SfwIRO$&3|Q?MF8l9rEB4cegqGNg8@7iRsO~bP^?pYCC1(98VQXo7z|q7ear1e6bHBRvY-_483}D*6-?ew< zbUq%lHPp0589(er{XGqAnsxu3FsfC(cfi)s*PtpEoyRmI#@^Lh-5Qw?_;?2tDZD_A zJ|PRlV|w+u{*cZBp&H|UCZbJ~U;p`TNs(>!MT4JTPujgxNd^NCo+|!3>oBFX`XGP_ zFaM6ZOX-UyC5=K^ekhB+RxQ@eNyA2CVE$&lq3!9-g@2HBLfh>MQ;nq<(~{q%E@XvC zUqH7=dZu1pp~NNzvq+vY3Whywn9obwCs@;aQ^@;6*E{MYk52wDe`oEeqv|(v#m-{K z)#O2wY5KcT*rM9-I5a(djC3o5$x%)6THfs^bW!>CTh{8O`ZV94|VXJaltx+z;@%@2!~fI(NiwbniKIx}g+2>=tnG zik^-;r+iqj0la~wx;L*?g(;3s!dF_%n93UWkLDk`ZpmsR`bE9IK9FC^xt zBWZo}nZVD?C4AG@&;~Yy?0j|hA@E0s?A0?>TVACN`s^0UA@zP!ka3-#IKIE@gbE4Y z7eg-oX{cg{!%%u??lS_wga~z=rNuuH120`MiJus-Me5ODIXMZz4}Si-O+g}W^76_2 zc5XuD8bKA$TQQOB$1(Zt!Iv=-WfDXh7s(wD>;u%F4=-Yyy?32YUy=LaO=(OSOkNA2 z&ld&Hczz=yn)b8&+s)BxFTxSOqO7FO#a^GR@tGg+x3k~{RoX1Bds2e)Ne{vk1-tOs z1!a?KAzd&p_r(R<&DiOltDsAuZP4i4e`qnKlmJg*dGp`bwmT@q^2+j<;pUEmpTBEt z4jaIgf(~9EMN%8CZ*RV^W)KjNmT6VgI^U5ZQo9ezVZv%v8;z%}R`=i{JZQfjX)o8> zy$6(|=0GQ){}3z2#$8{bcUN;7le0?9Wk2cD6}kVraleqCK!^Vn`YqoKW}Eq#&&guB z1y=0p3bJ#*#BcmG*ow6Gj&H+7M5I5QE#P6a?N|irU@W3kC@kLnAs1h4WTmmP`Se!% z3I*arr%F;Ze&dGBtTH-zR2e zj#^}oGOTy>@bDDy=(QX8-|$v%)P*(o)!E(Hbv#Xl5esmRY=VSqt-QNVi>aTe&8U~z>8k;$s@Jo$GBF>&D12$|bR7u+MvbLCw z=C#UA*he!LyZVoKgZOlql3aX3GR-Wr0lOQ|2KXIQ6>01m3AgZx$PR$U5f(N!1jmatz@*M*+^$bOn=*T{;s1?H_*&`+ z`)jh5WMjVCzr#U=&$;|1jI{wi?*m2J-@Zr)G|Kn6ZqNr@xjAvUM+J}|X1`50JHnKd zRox+hcV9e_YW(J_3_NeXI{ZE1lpUnIp8+u0HG}uZCe`XUA7iyBfA8UKUMaocIWW);` z@Ozw-7u?@(sNzRa3@_BL`oW_mc? zd=UG)m!5-9_DagPaqjk!cx`a-25y4YlJ<>$@Dl)+vrpHTxNI+N4O+*Bo@=BJ-2D0Tl_@I zz9rflzqI9LfpA15WEojGbS|Nw%x1lmxExmSg1+-!L&1~a8>qS~&t(Ae zM2L$feS_@X4swFhk89QyUb_$n2g;HP`4Vink8^EQE|-JviJeRYI-d$(yXF^9wk{65 z!WyYRj{y{SQ~N%T@bwg2zzgIRVYSI&PwMqds%-~{4ZQU46L8YQ1?-yli-TXjXjQeq z60jEI-~7ZL_gpmYt`CWOu9*yqSA9J-R=3UOw$GRSEK&TW7~_`XuLH(0cOCC9cIs-a zFQ(EM$ZuS8*(fU*LCohnK=T#NS}>g^Z3XGgfLeqxpaFXSNEFc|;rX}KLMTzG2pbv4 zY3XfkdChx%D&c>sm}f$?Jv==u)T`XL;`&^aRR4{G=$i$myqeJAEKHQn^Ppm=cbVRPfz zN~=nD@~th;9ueR9i1wN!)j0LstVWq8D$L+OmA;z7PPmzw9ie_LFxR&Cr3vslx5S1a z+|D*Vy8VfVhBHHtXr@2l8TVLxLXZR&5{wEF-~8Gq*xC<7#<-ag2I(Gtumy!l$yrYa zVycQ=P;H#Y9Q&T0HUT$l@2_8VzM~(!#GbK9AGUkjw)Yk}I9dv#Nd3Y+wKsc+jJ$~y zdK!Q>XqR6{8PX-o_OYnr%M1LFr*pw9&b~|%5Db7N+%6;&Rj4SB8U^OKyKbq}r$=Di zLZTq8(%TScJ8vCa#*N!6vC)g^FQmahgbFV&mdm zU++2wN1fY}p#FF4qM{QMc|ruF1QPW9lkKOD0Gzh@bHN7C%cxtwlQL_UyOarIc1V85 zfc4u6Lne%$V?1)){;%1p6{-K_ppxpO+v>6LsJ_t??peoE4!1#A(jJws+c&)`S&A5) zMmwCQwM$N?mJ3h1kBN{5es0%+u+)Y0z?k-`!I>MT^P&TY@lPTnQ?t=+^> zvDnVYsgTcnrSbT5uiP&!`{pnee0n3VH|Hm(^6xIw%=~;RH4Mz!0Gn`nMpv@{0Qmfd5o%x4p5FZu1neNjuvLX&#Ep#$ zyw5a|OFxZfupR8@IPb6I2{ELN+Empo03EgGE-Lh@F8fkcIr%swd~e*WtgHYJ1R(mw zj>HUXZwF4GlGU6094rYL;AG_z+yhSVMcQc=s+Naha4PRJ1|j8w+NO77PPH8Ed}q>; zFijmhIDPZF`HwS!n#UYcGBOQGE0xH@)6>1e(Cb-EA|yssq|kHWrV;gRlKR}<)y|m` z0&Cr4@niT3_+#GRmM$*gK;PaZ?xX9wRNsDzz49DexlWPtaLi_H|a1!66bA+3Z3Gz1sGxsv0Y;x4jj$sbnf8JfEAD*6C znz($k^Ni>BA{KC46T(&m&W$Y|h7?GjE&{pjBcYRG=%6Tjr@zrJAuvXPtM<{MrY|oj z#xnMRWAJw`GNP0W{-@d%waWR!;{-K{^fhTr`hHNAw#!=GY#FRR+dZe)3%br~l8GZb-t=J16IeS0|V<86zBWPQYPg{l&M#bmz zFHd}Is#5t?%G+ygMCqe{EYftR4l=s7@2%TvT_zAKFyiN#BAd;w1VJq5&1a95_<{EV ztebz5a-3S;my>Kh97Nquh-~fyyM8cFQ)hYwHh7Nc>qk=3QZ;&)S!KRi8*bfBCp6Pf zt~XzW?r)nQR+oMJkl;yworV`TUdL5gpnX>TXjAQ77e#f)wwBRLj5Y_C*QY~fKs0;0 z+T=Qa>$v6tjyv(a{F3b&My?jL)0Qd}%X6{`6()mDk`?OaSdzO@!;j5j9ch>&+S^Ph zxk8#chRxB}!lV-M<#Y-6t;(i72b+K)9ptmgS23wl7)L|+mq_`W8wX&hz(H<>ga)4abA6_s@8u z1qg;UV_!2XOP0fDg7K1iHhKwjL-JopjXaOhn90t-cpEP;AVU$^*Z-JodF=!C?C&^v zxa2;)cUT9-9Ud|uw^J}_SMNR^*Bop|y+nxk-=2rubr!Uqwfq1&VgYM*f+@{P9Kga3 zbcD15LM6ncBHKXM^DvxbW9Z^*WHkTQ5fk491v`Ml$&*d*@L|8MI`H8AmSN`zfESg2sl43HFFslG6=Bk<-U9Fx z8s?je4#2|Ky+PXX(pYo#oFB-Kx@h3eL-xF7sCn!uNu$fLq$r{5C2|A*y%=xjZ_B%h zB)<`%P)Qg=N2~~Bigs@4cW_c7YZsBLS$U4N_KOWb>y$|Jz!>7rPzc9Aa2z& zmBMe&@}|@WC~oi0D?{qf|6{Zj`YE*`OMt0&Ku?Y$(FW{pgZD#5HZrPPAX2-gu&E{k zn~wGuUjS{RwEfWyA#U$&C8+pRTc^>A#}vQTc~g{@uB;mg=>90-Y>X}yc8pJa)cZYC zR^uwoc~j~$@|h3x*w8KDO$(nJTBZo+ z_J2?@;0)-7c45lA&z7W=?mBm2a}K&9nvUKBf*EFeD}YD+ASm6MG&tNG-0E{m0+^#g7iUQ?Vm1Nk6NTQ%%Ucn{28BM9ml3!MD?;_XfH74%Dg zgG40oIYl|*F+$BgO*<^i)ar#Yfecid=}eZV5GT5mrm6Z|0d4&r6&27Iqs|NMc+m;2 z;@8;M`*Of)|FY58b_%oxJopF=4}N)(YDP#NNTkO3@T7$i4l_+=!^ZMikS&!!kfm5IyGgpoCF0Ccv#+h|uB*IWvA`Lss1;%Ya5}{!Zajhl=?T{UjOx$gMTH`bYSSlPUD6D22$IN5JCu0xJci zDcg6*!+m|!DcBQ(pk9o`0WKv}@Zeygt>k;SOoce9G~G`tga0|&Fg9>~*R)Man(Utv zH8D^s(L_vSB#$@G_jxw`7_`e^(HH_!3k*V^6u#gF7Z>Y*eYRTfuxV+4iO^4dyCb+I zBf1Xh&jPShGq&34L)zcp=lAnS^|W7LXI~lx0RH<6F4ZJ%v!iiZNrhY<;fwo(d)3b1 zSb(5I8GYWpi1N8Tq~qr>1k+8P?A!%GUbmN~zj#4{@)KVB2b=w#tQ-o5#Ke5W5c2(! zmzxDs#@7S>kEXMVilghcXmBUE6Wm>bYh#UTaDqDox8NRVT!TA=V8PvkyIXK~cf0ld zW86oc=t;7_Fq7N?HWLAh=(@bR)~b3UTV2+-Li~m`#Xh`@eY+B@_Oh z)3w1i=jRaV*Xnqo=>bJZo5z&C0WLEV0J&3uKL$$|dei;8sE>A1{gc`LXRX?Ay%@v@ ze!$h`J3p7x$HYXL#~yrRxA&v)=;$bF=VM0a z5YR3AnU=QsxylQTNwb_hE&+EW)#bRN(fQ!QPk*a@+cp_lU0uEH>PywuRaTW*-%&CN z>FStA=d*Bw-C7UutUi!3!nUn0pkIlQYZWgUz<*833(Qgb_q`HiK zUYNu_F&ZgWoMllMAHDGIynhDJ>Pc=|Rg$tp|5Z=!$cT!*I@FjBC{-?1M^6PK0QTDZ zj{A0>`%OARQKujvoZ$P<`8xUrjiscDx%sWdme2EsFZz4pAC;YlDO3IWYsR-7<+mSy z9B_dJwH+@*X5QOB(scPm9GA=?S9E@P>foQTu@li>TM#~T&X`<}x?zvx=; z=m{#~z{od0!gHTzZ?7?XL6vS2Utb!LORe`{Uxb)Tz#ST3==nV1bQ(iC%UH`ye6U~j z{>1gzLka2is=k@SM{nHlmX=j)#V-a-oDRdXuXTs_g}a#N6UGW9mOp#z!r_k)jW=@q zEj4CQh7og*)lsSJLg|Y#6*Gi(74js1ByB# zNUszoYc)M=zcn<2V?QNKL<6)f9Q`f=YhrE)4Te$q#H(33G$969g5Cs+&Z#CKg7`){ zftrV!vP+Ka8+eLbj+i3`2L$`I=ngBFD|oD{>x0Lt8$O_;>g*d%X1d=0=?juK$*reF zd|3vx1ylg#oNUh}=UG3S@p_aR*;-7KnX=I--rmf?kKMKt-o@U0Z;SSDYk7Mf^&=v8& zv-Ix=P7}@CWKDH|k&v$J|1|UR1pJ`W%JkqI7g(iyWTI^>NoIy*2zLU!rUVWSM@`^V zib}HV76IXR2jwzSU*F)-vGKi9k9s8)HKPg&MCyKlB#c4wTvZP~Y7kP0ypKl6AMh{O z7F7w{VJn!QA@osJ{YZg-z^Ky5s4+E2ae)Pu-2Exy;W)p@Lnu^V7bVq^iTQvY(S$A> zTwsFLDNKZ|kE72%?6{4_FAQ37f?!4alCKKDYszS!n*y@k173dIqYj5nD{ znZuEPRZ!IAcYk50Vv^CG7Zh`|2wI9j`kq=B>m?Y?35;2Qhj_o=QJ+DhmvGvN~ApNw3de`aWBid7J%&C)2D`Hv6$kzKiKk?n}I(cGNk^Z ziQG=yj>;k^Q2Asr(=vzSnng80TWU2FHWH2qBgMe@=lRiBgUN-!pirB>*6WzFT!q_Y zEWQ^T*ojZr>_F7Z*jT*ee?kb;?r4eal^IC;`BSVlgu0sfxHWUGjAvRshNCj58Z9P9 zk^QrQ<#F-~5)7FVGcxQv0T4InJ+Xtc%_3_E>0;*C0|ZFGMS9f-D4`dYlvsXk&1R|b zAm3)pdAlijTwQ-P=pPuEc*=xGkgF_xu^zMLS$B?<@THESL6W8BRIG^Wr;(2}I4OkK z3wX2Dp71xg#PYUnqWw3o4}Rvegt!#fEJWPhv8z#L=BmZcgpgq!Qd1&>Gy8QQ?m-|9 z%7_eDtSUJzC{E<+h&zrG=uj>^d;KHX-#&;0w$;V9Edd5{n;B}%j%xIe8h#Q zYKBXWh{Hh}$I>3oPL~HIQ~Z;}?p;FO<;KRZ<}j>W8{bCC=jI8o-)A1YPWNpT;ZE;Z zvKIIr&vU}?U_=pdB54weZ|@|Q%X~)3J#$gV?&&nRMTi-E8f#6uA&tojul5GmB=EXb?D zQL>ZEY(!3B^vo0$6MSanQc{>s`V#b=7|!EyR#nv(BZO6v&hrD6Nva{TCLy2wkeuVe z2Kl*Q30`(I6xJ@H?%5NZM3?Xbc^qlFSs>3*)Xk4H?`UF^0P~!KFzv{yW>Rnb{d+o4 zvY)ZzQB|9^;`yanhEos}OKMHpXA0in zYmnlhD@@Tz)+T;tQx%KZmGJxh5@$%_#>y(I&T%5nflNt2Z}U(w|OFrG{!Z{ zvN)0Dp$F`#vN>P_+d@ZJ>xTL}%+&@Y9af>lD17Xa>|}w%O`kwZX|oElUi_2EPZh!Q zZq9R^+JDab?g}T;gtQoCt2HkA+s3_!2&9@+j5Du8=J>wLnL}?{(aL^9!KClfu@mrw zqK>#MWBU-ElgmL)GEQx^4aO2<)IZuQQJX^vu;zB0#{!=-<@bEJgkE~>gG4#Y?e!^* zP^d|q;w>-unS4?mqb}E3dZ`toGqzv%_bbu;v!S=Rk7tPUHOO&(>en1QZLx|9Jw*ga z3PXBOg(83)hrB&YuVI>p0K=$W7QZisJ@Q9B@H0Pc>@O2UT`CcU(*M;~B;jQjfJX(% zAs0c5AJF08!v9hUig3~_3E>ABwHL_PIaO0(s6;_)V0`Z(S(wy){;;lTy47+%trVbw zn0MukPA!>tBa5dd$XNE750XUbhTOszXSVbQ7Dt`}ih}i0L6`>#S_%VPcNe%Dj|Gx) zv*4l2S7RvWXvWE3vfJBX`PNTg3QkzGv`R>jrcy*B{^9cv6(<*4L;2&_-)S&uR2yMQ zu5LvDjvq%Jc76~wGKAX{;-(P7~}J#lA)*s3JAI`zZ*VU!RxO z|C*IyYm}KsPL(bj#goq7)2VKZIFDI4?xspGPE`<>Zcs$bSsNu!>>l6wICzu9_=^4b zvT{_`Md^}#?|wMlg`i(pxOTAy zQS|J1rWF~3qVDYjL%oW5Wxw(ji#sJ zJKhJ`mQNU6sRzu)av}4YZimSOq#DUWR>?t&uV7sUnncqX2`n$fe--uX2I7R?(5Egt@Uz8hh*Y^(Xi`N|cCA>`MvT)%>avJ4e8@SK zK@4{ZvnV+HjNW4_q+s%5!ip>|n?42)`ug&wb31wC=12tIH2hzC+$AW??MFV@~lnvY`$zQQqH)m_e|7M zW);8?Zj_Tx?J%n|hQ@6BI3=kTKH|ky?0Z_vgZEKvQ)2AC3X#(2DfBZ6mR!zk^!UD6 zDuHK+-Luw}Jt&HN5Rt`+I;0k0>}K3s~9~R<}5?Oq-8IRUyFT5sjCff#}C+?&%zItpAyextwtdKtX zisW2OTej+yAi4TLM|6tN)L+}vJeu4@P7qiWsZ6UvtkOduqbG$yZRG|#5kZHtEf#{s>ry&=VznFV4Tuezd)2zNFeMc*bXLK3Jxnx7~53EIBqTY zI>AiWx%=)b)$-oGOQ>Cn_OE+EQI~KqJ_hTntt$J}9q)NS+wW7@_rm%K6s6CiIqk0p zZ2~PZV|1l4ebpNKn_M*%ZqRlaW`wD4B07r8M&+{h-Q?BFIbwpDZdM_N_VWI5yu7tv z-ICl@%CKK-R5t(cZGU-Meq40iz`q~YNw2?1ykpZ)r!w*mQ<5S zx#e$9OAem=Pi%vM*1f+=9!RO!lDns#ob9&^$7ffaiOUwnJlQD9DeYZL4Vp_qBm9Er zo{byNLz7FZHLBB_%R-n#bhWNO(qvRtCR|t@-B}JoCg!JzqBv(l8}`xavTN5TT2f%w z`N>F{X*iPBxci<|I283pSW|LFv}M#Bc3^QSTwL%>yZ_>aXu;}iuXF6TofhMJc^!ty zwny9dGhd>}*^{^>?$+O{5?%d3`RRjkLsQDV8qhy5J~F-=XT>bLHTXlm?9_Lz0-M|I z*#)Z(^?AkJqWZp}wt#t_O5mNdHs$W#_7EZ_LG(+220aCSoW|&-7#_Z&cCnC^H(6}4 ztv#eyzCUY>l)R#TbbO3rM#`@o`zp?&rxi-zc)Lr0B*Oh?vvt?NPghnqZSIC!ZITUC z+UkcQ{~);x@|e$RjAR^L-=9?|aA-LQpePNRc!<{cxlx55-R3u^@3k7Ecjq6QG9R(q zG3J`bZ4d2^;ts<8#V`u(<;#*|Bb`60i(N`-Z@cw6`kaP@Ol{32$lFQi z7}mrAXBE}=tgzABIdyTjg{}y459ltA$1NY@p^a-WBeCuLgE+mo(jYEhWcQK-Qzlza zHTjDe77YX5-t@)v6|ggNo5FD!-u77D6l;d^Gay82r=o^6@Cs}RCI39CoABAL(A z*Nldkv*lPtdsSVtHIu~tw(Ca0GeS#Y3allLH;;c-ijX(|tc9fp(R;fd(F~62YXXnq z9Lwl=`4kq_z8-#O)gL!+%Mr${5ulRhAVI|?6Vh{PVbks%{}z`<|FQ6-7<)gA!qe3z zzPN+|sZko;!W)gklB}kub&)F>0Zud1B>Cy{1UupQMjyQMsRqNc&rOG!2la!FOs6s{ zksTF80+-w~Zk|6I>|(iyHJ5C7D!PYU&l)Pe^E;wsOU-X83K%fcj-C5tL+tg2kz0bJ zkmZk?OYWK}%k=I%jy`3(z;y8kcUunic(%lyTdw5z+GaX8)N79xDm1XbDLvnpXKgdD zdkUZn)ck;bi(GDgl-c>$%JuwZOE%?FkYMElNol``Vjy_A*@-vmJF4{y%%q+@X#B?Kik%fD>T(!u+Z_aXS{Cj*@yY= z+EiX)QpC?Kh5-_#h|-Z$E=}kC>2#v=TIibL#HYrK$7Ox!sAKVEh7mi!F-8nrUe{bp zG>vdE5nE>js|`0kLYgAUGw~x1ITe{>Ww1Vu^y9t4THCm<;elT3Y~#Do4f^3;;{Gh= zQ`BaO=r#gpiF!%WIPO?c*i8IC2ymORjH6j!Fe%G$Wz?_xSf6+=#q=jhu3^FkLNcvW zGUI09{q)vBPiTES%VynqmV{V`y@vl#$ug`pvH$GNvv5XzVvs4AdE~`b&DL4y*5nw^ zkKUZrib#RUwcPvZrz3OkY)(GGBZgtX|R9 z;>qCXE|DzpgSlL$b-6IB-Ylm??K9hN9KoTt{gxBEBR|&jV>2bU%54vP16L>2-baG2 zelrkxhHcSE=-`N=RB_g2VqO3FN|ro+50vH;SQc+O{J4ImvhNs^(}nXsh|it`wuDS; zLLVfDSDgE~&O?bor*9?v9>QeUm6oR-v8*JN=k|V$c&KAICcjW4rjRw^ZjBtw`j!6c zpvz5qSk!m}_@GDpPhu`BZBYxx2y2Ky=I`>=7joieyyLVq!d|sD!`6d*2nrf>7sv=K zThgNwoDiwYb=mNeMyEqdt<8?kW)a)?^ZRojy&fuCpWArND8GUxj+u=!{Vi(1#T0q@ z6e3-FZ}w%p%B*Zw^xk$9O<{gT{?fhsRrAl;U+phyeM7rKB4ldbAzzFQIiFQP184+qc$0!5hW;)6a--*{8z_1BM5enB)NY=C&E)1`j zrOL~tKEKo%&S*rJSfw90kF4S!xts%Vd%X2>`rOLnN~<^Ljdwr&rV=#}rTZ8kXUR;|sARYt?g%L%7kFTWYfhPA0f{VJ53ibTuOq zM24w;6-1mww7&J1UMU9{Yj z9q41;o-_HnZIJ1WNa16nYdWdBA9z=rd$Q!25nZ3^Colp*(4psI*oDl~Y6_6ia762! zB^k|yMVEKjF(rPB>;9a^z}&~vwXC8 z6FQNb0fz58a^&6#-$&s~k_@&^RF>K}V{}ls{Qg9d<8-1NxYpBA_c-(CZ+7tOB=bDd zgkNx%9;zkOES~TZmW^{M1>J7tHnyV(YnfB_FSB6tu&7Lnl@N>rZh6QQJg(%R2_Z4D z{`5}R$qgfABl9=IvmLi#FvIA_!4=KJzF|r4C6i}Edh;!k`PCw0Y!Wmh{OiqYXWKd+ zFC)7gy03B6NV*wyzEZYJjtp$etb9Mbaw^{FRMd9OurCPn)PfiT*fnNt(1@bp0Unuj zL3aQA2@p#aoEi;fST4C5P55Jm;!7c!P5N72jt!M>A23vt&s|$w8_ru;y0Ug5ACsmR z@|tjcP>q+wbqa+FTQG=Vj5U%Ba7s`K(@rFpN;sAgkR(G9!Dq4^2vxZQ9izv=-86#B zv5lDfCb1?+%-^|0CCe}hVEerWY)eQq9|~FJhuRwg;w+d3@4_ZJ5X8kaSV4NfC@c+_ ze(n!(zUm*nwkdkf4;fs&6zU`xGl($;Ie%nCbhftgUT#xIixJ0|6lEVgay!;(wGcMO zahzB+q|;XrnDL5~ZzmncMo$@O+uzf>S|1m$);2S;BG?u~3d9yUD}e3+1^!WiE%kYi zr>rmXu;wXtKde-w=_HNbhgH)4E2T1@ple8e>jJ&+gFGs<8>MJUARm~V@b@WT-#GV= zQlXB!y)Gf=>p*0e720n zO7Mlp&_QUR!UzzT0w;v9qh61iS$av6SleB>9#%oI!0N(k)RPy3o7uqxclj#xr9L)# zCVwgK-nOW7=vLe*lG`U+f+dGP947HvP7^Vh*r`aBQ3}w!=r(E0ZmEOV+-~&5z+AUs z%E|{mo;F91(Ly&!UjqThI7pCd+?TmZ_tP@ODT&cROVy) zTI?W;m{%M(js6&P+B4rTI?FPbFKx9V)#i14$9!M$s`pKxCNPcY=_(m; zEe(`5L4xT%IQUP70OUy3%D(ubUnLf`;shN3zMjD4l+`W%0__~Fo`O3}kQiIqPY}cu zK2>y=gh3}avwYb6 z+lRw^LvNOPcP0xC@tg?r59gp?uG+QS*fRO{1MKIq_)4rA+}W@YIdI?$+@K$Ch9cll zVt}Pk%>yepBWN*tt2Q}-DO7x6zS1AO2$7T53tGL_n{r%Ups;vzOw=dUoP6TKR+X_K zPDfVHbRn=+4P~!a50xgAsAhi-P|PE6WckZ(*KrU^?$b3R!lP$g&6iSeJx zJC(xZE5t!XMTN$o6Zw**pngnfs?%YDtJm;N#3b0X&wDX*a>pxso<1AlN1G=P zk%~m5qreCflZB4oB_BmR`|cX62}#$n@OTq12Go?}BWiD>YmOrmhx+!a6#F%OlkGI~kg_dm$Q# zIotJH$p~@`%rUw87FI@tz#DWgOIzN=LBvCouzS_qKeE9eYP(o_?bl;`-wl}Is}E3C z``NDp0SV7#O=^2o^u#Od-I;K# z$7CO_mVS2ylNPi}g(lE+#s$vsYrNYu(_dr zohTdYZ!7*Ie@-^Dz0Wr9RvcvH(#lQ)YZDU$;xwP$j$eGr)o^Q^(KoR|_NZ0og`^4<6VG*zj$B_Wa$H^3|kg~OR9 zgf>PBk>FPbf9a2~n@osdH5PVKD=AiD$f{2PbW89EskOc%?$S@+8A74@*gx1;FJu1h z(i&|37bPzch?{GkQObZ4+C#|N&v{s*pun1FvkmSQKmwOb%Q{3)*ToDi@gMcqxSzrU z^tNw~>q_7i`}E}@hH-@SdI8!b=&8JAe7%NTzvteH>(R2>f-(W0_zMqz!PvOrhH+YI zSmPaGFZEh{V9zHBjMOg>CZqYs{`rf3^{(^mTdS;HYFsuOaH+UJaqtsV~MR|e1ZL!|BZXy^?BUjg?j<+|w2&Xk;Zp3M$eKiyFAJP;_>G!jdoIA=MFLF;K z%KNDoi9!w!&r=8wCD_XQo%TaO<%b$5$psYL-f( z1t*uT^*ECEQ=7c5HQy?>b-#V}#Z5pwh9*I#^3`UcYJ=CFZ1IO8M^pL*w{vf%tpREw zu)h3l5gqY_sE}MA3Y{tgZO*Nk!p=%LjU3u7Hz~J`5h5T)&Or&0akK8mR$GUSkaL8F zW{Ri%ix~$FN1=|l4{%g~mC9zgn@pmy)A+!EXvWkg^}OG9Y_<~eamCgwY56y+$&YoX zHh)4I1ExNF?CTsS%NR6UQqZuzFtvuw&ZZc0U{}E0ubARb5l;_ky9*tE-Olsb=*ONb zUwT+muhXee5mq-J8%+8@x zx!Xm_*g59ahJ z6>qn7)ve_%n*O|x8U6v2nURP+XlIT$ryRIsht!_N7wYLbkMo?`6-RoQh^GyrQP&2! zV;=iBCI7_F6NzR_SY0xSU8p~j{AB!B(4Rl)V01$ZJ$}`K}c!ZyevdM4ufB%lt`Z+f{mB_t(LF++JE>_!+|5&C^7*AF`JnXvxM9|-OO5P%qZ6xk-H+bs@6$ui+cbPy1{m5; zF7|YmY>4(%y+LIV_aWmF@)CoP+C{-Rr8nJ#adauZG{I!sYt3r=nz8ZYEJ=bEt5?CI z>@+)PW6_I0j}B=L{GSE%a{CN*-Si5Rm;e4&$_%++4dPNFU6uki5vKZ@L3<)zJOgf1 zQuvmTD7y$R-%^^x(X5b_!4&Wq6gbwN&aT4sm^7b19_bmc7)un__dZj(c$SCCpM^_= zx5_O3I`X9xj!$YzK9ZFJm_=DzfDHiF7Vu_VsV_quwyf3EXamhUw2U#FJ=WionVgxj z3!06PF%&L_gM3=gk^p>AgI++xsM=m?;d7&`E2)mnPT!r~oIr20_Le)6_5VI2T!hl$ zfyvz#gcKOt4cb%|;f@@Stusf;X_Te!1sWi5e#dp{a|)4%r;>)S>X=iHef7RgF{Bg0 zNPP^GG=;#|1g3pv&V6bQ{~3n+bKvuR<@ zSEPDsVhwCN6cQ>YVSqOaoQzD8X8ztHV-H9#-98k|GI3=R5br*(x5kpaZTKnF#wezP zEs;VzoY4!rY!u1i;;|N~`wxDq@Q2JGmSK)lR%?@*CjJx?BZpI>qlfAt3gM!M;)!4g z!7~563kqOI3am5Y#tL_Vr+I0XfD2^jwspC|qe_~gFR5;cz(OwrkQfx@-G_fm1eCF< z%@6eeFX!uY|Hv8EH0wCQQf?}mkC)FZ7kQLU`3f-mkPOTo-wLh$c8LK7o}W$8(!tUN zQ~wl4>7KISm5Tbfu|m-2Y@s_zsA8Q0ovh90 z^+#HD?;N_nTM6(js=I%yduN%{agxcqj1u8{h!p;jC*ctp;gF9l0zPO8+RrVUUB9ZO&Ec znO2V!4BrX;z(X)ioi*5X%6s5B@6{pw0U=jA4(aE=! zSneY%@a-CfZ(+W*wk)nn%u}H^swmPdGp;CVY~)RyHiKb_tC|E_0Q0&*xzEGym+B!Y z>UP9xCCE?_^VaPC?C_bw!k51^7y)|Z7GJS8GxW}MUDPkeBKp)3FMovuYC2wnHb*lX z6>?=1mZHo?c2PoLiUgb{+1c4XdE_DFsJ;63Ii&}!(^IwKIMy1z1(@2DaCx=d+X6Bl z$qEGo$HsUK2hR3Ag1_Zw_H#4E%@T^%#I}nrNl_^+ww&51DJVIa*ac;;VWk>&MA*2c z1V7)gPa49bCL-Laq@|f0{UunbY)km1vQgUJnwFJK5d~`a+MGO8Doaa8M|ePH^xYjk zYBxPgOEn{7>(MetLXUvp>v)W9mCTWV_uYxHvi_RBoBidIx zyE7AOdOQ?hOiO5jQo?2oW=FamMn&)t9e8rHCAY>fvC^Sh1Z&Oe@!W6kd%}vipvODq=MFhz|^To%^nx_utC( z+{%uCs?BTl>73Tk?3^(uCkmI-w~w>IZoR)UYeh9BIG(2j{<~GqTK5{uil;<#q0KP^ zp1he0f6eF5X7;>Ssvpr(62K!+zGpA-C9u;BFKX=l8ZW7UNdQcn*i9h8nEczvpD9T( z3fMJ7Bj)+fh+<=7^BLFU0QCM35*&WeRS&!Sc16g}vGK6egZ1xHPzy=Z#pPvA3z1pZ7`diZ`{C{W!p$St* z$2jk^=5U~9b@(E(2KRvi7J%eTO-)5+sIjI3Y}~Bd%o=l~e0Sz#IlI-CWS}brsBYHU zyZ}QJ1c1iIWM_X$Qv2^Cot>R|m^G*O5C~O;u)_~DR7164(IGtZ{kd0^jwQ=$);-Jh=z$B2=-a+^%+{MOoZnAr|3lvv= z+$vX7k3ia}ik@MtwQVmG zZXC#@Ck|*ja`S$6%5Mx$PiJX;cuER7LLvdgl zRZW~=V-VSbW)yl(e?3jJ85SsKiA%tVD8tbJ^3+07F_WGq(vHhOP5f0TDnnK^QPxym zswFQXJ;j=Spc@TZ={76Z^>^$e3Z4q{4g>C0U1ME>9G@Adj)s6dYgWHn}w7fW2wiCvUnVvB)A-iD@tlUIU6!2{T{DHx=esy8iPPTzgfO*^onC&h$neNP4dx!kq!q_U^tI5>uCNWhRH*( zPNGJ={fRUq(E2>!aP-eQKqY_^9y5#_H7@~7rP|NF+?tBeaqCw3{-E{Xk<*d!CcN^H z(T?ExP)*nDxr?kzJgq&AVWNsiPT^yBiusG%?}M>*QhV#Vk&#tM$~=!iN#jOp*iwr< zajJn6*N|Dd6pEz@IG}E_U(8Acu@3ptEr2RBQjDno5T{qgltG*zWU=83Qpf|4{ja4Q z?<$Z&gaw-h##=!JL5F{A>xWtQOX@F9`}fBk>e;=09QYH1>ZoZmg;=(zOASgK39B*` z$yb3~Ww`&R5Xh?Iz4sj3;r zJLt9-dKvUjUF)?OXQ3ljS@Xkhy>tZQ2oJiPx;F&l_>MEyNyn1{?a@^2be`9f;uhoS zvRZm{lwai6n2i51mxRj@o{&+Ca>|iY&sdCEy!C|QTzR3B@cpP`j>14JVpqc=3d|Tc z***H%Y{lS)7M*!;N@YlIB0qGa!!>E#)xe?$E}5xoRP2?t7;32F@VGRwy4>H9y+9D={wc^`UZi~eptZdgG?x8Et+&)FXQv0?ju zp{(yaM0rQH+;_ay5u)qm=yMt z)%F~^1!1Z4t`DoL2LFNhcAP)+rI>h9EAwRd`7>SlN}2^DLXla+5(wI8`6n$j3QcUn z3^Z*wOw^h*=hqJH?TaoA)lS%(P5s{G<_6gd1Xgpw3P{2g&?i$M!l4r8Pyc@wU>cdv z#|mNP>-u<2@!PcrcuR6Z?jjs)XXj?fv3H)8u9k;XGwpWg6RhJjnb*mmpfsy*1p*qE{HL4V~iwe-@WoW9Lo@KfTX;cz)YQJX?PU-dhws zBtDFGy@N8k2qb6%P2 z>+8jEiVPW(fvOAJ7v9ZS!fT^!x;`7%)Ea#rRe(NsGjJ zw&wXi-;oC778T(ZpfzNW>lsc2_J;F29*}dT8@Sso4OXiK71^Gdqz_#OBfQbA{S&+h zkx-v6>YyF5rt7;IXI(C-PZ**vR?dk@z^ku!GqbVvbeo}l+ZBx6XyF;bW8GTH5$-nH zr0#ru^!BoUwtboLe-~J4Ari1~y*?<2bp{NN0FtA&j(a{)sbpM2@l`;qf60Y13iV^H z`L%RZ_2B^+hK4hG40yT?r{g^_8K?}tsqzlp&-Tq!@8*8nkBQyViG}Ool!BA*r=M93c_3L;??L}Pd$E0l_}@^SJ^yRh=Wfl&dD|Hfdbps% zf$82#E^EGb>6DQ`wqsKs;`O;+0aTx_wLp)$)tv>fhAD^IoCg_9LYy^ee_4fxexMfr zrTPu4q%!bHC(Nw!(>i^6u^R?#*ct#dljmr+g*V``{WXu|8wI+*@nMk&`+iK2Dn#4hM!r-4@Hl%2EmyR>pXWFYBYj zWtF>wdA&fd=lF~^b!7AAZp(E0S;Sz~zRrCVSe-RShjN+i-h?DV5y=WO%TuA-)PwF5 zU6&Fy^|v_4G$%WM{g{T)z4vj{p$~D^;8hWrS8{?rkPt^^D|Zl>$m4qPBL%YH4rwG{ z7f=z9vU{A_0b>YM%DPaj0*`!UWtcweKxT7olcx@`B12!|#3$oJH`}IdE;8dVgC0^A zj;mSXe_jKm%zCpR%Crr=^`;zNk53!-?;DU4QJ*M)c(krkxffZcdEM1WX4EUM_xSJJ zFTSG6-fX3TMd)tP^dG?IECe3w)e2|ue}(l&d4<|QbzmT3vam*$#9a2cD7&2e#qf7r z-`8m{W1ar^sQkWr-t<~<|L0}vu?Z<7KW14Ek6V}TK}sT*Iug1BLD}(T5X#4XW^re7 zXM8jKqrC;tBG*?;Z@9CjKEbO)AMz%GV4!?lk&R~yrIy?=1ZWdra8ZI&F-7pXH+?d2 z+bwKkr~AvXD)|WcajNVPp|XujWrThNlLZrl5>wlN%MAt-r?CV(;HVdma&h2?B?V|zTewt9<7eulljDT zyivRX^~^|Xw|Z0(!Qly@XuYdtFpM25BA%zR!S*)sE+*julja&(lKnjrm;@sjj7y_I@8% z7O}=}8g{%2*BxJlPWWW%<~{CLtxpt_K0n^Hcgi?8kp0&VPD$LT6g($S9aF#jBl-j$Z!drlWq~dH@+02yB!V{nAk5T zzVMHBxn<8-2b0$xBgA!%hs%4)S!kk+x`pq{#m{-+SpAus!7Q}sQ@$iQkyOK(s8ha0 z_aJpDDoKSxM$MuDzk=-`~D z8CzG%Z#=%fbe<1Gw?enIIa|2UA~%~KolfUcfNRZ=*Kx;9uQ_v}&?ABLgl-lcx%X{OVr+HtgEZn)KnY#O6=iSZl*q?FXJ1%H5Xk~<8dy2cP{)F z!e%321N!RYMEZPxe+e1WL*&q(T~+8_u=`g}=HQ8uMrO902{}v`Mj`dg{akYOsnz{F zPlI{GO9W8<78IBYi03j%ZsPw|5eTDiGRX|EDIYALy`Uu1ql=J^lWkrcjw>rQUBX?c zDQ25!d^;69u>xOO`accSeJ=hJO@YXw!YYet(lf~4rAWVTD~v+W{mf{+!FD^x`nBz%XRb0@!b?>Y-V|0% zfUgpwK~x9OAvJguSyQP~-J7h2ggRW;$*#2CA9Hl>ca*K=^_aE!a`Z&MQ{B1|ZS&@_ z7h)$!K`e~ms7Uy=WdxE<&tBllzcweWy?Q@R^@FAYMm2@V(#F;utf;Ybgl%Lf zSlT9Kni<%`OfWvc?@|-8z*A?!3VbkMf(@J)UwtM#Ij37uQI^rdk5C{jVt0nr#DSSY zs}n=|iwjLYeKTiQOJKuQWt0_xHK&_2{z2P?FALUv$dfjowyIzVAp$N17@qyP(+ojB zYpM~Oru!11kQOK|*hvp|H=s*zI(%9Lq@seVl)N1Ev6f~h~Tz$F)V?7K}0j%Jb_ zEXl$DN7P$Jwb_L2+BiWAK^ojWxVyW%OOWC%UfeCXI}{7C&;3OmpH zef!;i?zQ;A3QX3_J#)=<9!D0gbaiZmbbi&7KO{Ea&D|V}jy?DgUOjYh&v-rT3(nLG z*-17II#vNr7DpiH7-yVQmrI=@>}Bs-<)@5Biv-Tv7xyKHy-4_6_(xnkpCSV`cm5pH zB(%Vlw{OJ7#k-q5ncj&1!Gl?4&?zRRDAB`B#lYOkrdMPauKV``*Ehfp z&w(W{F@ZmpxC9qN{<|V-WQjB>lvn@>>tM~+ne0jxF>%I~k57H5C0#qExaCqdqRlLh zG_HgO!p0S@Qypu!uEYc-j0>y|z1#(xV`P_pxa>wy+yLM|wns-A=|Ca}vBV>(9Q|B3 zM>R|`WSIY2l}jt5*Yh`=?`EnTQO9-;ut!PT)KFSlasB$9JorC58A{qXH{5VM{20~B zR`30jd?Am0JPy)rEVvj0(xz1mb45$amr;_hCQO;J&6Nz1P)w%WyWH7ZnsHUMy2M1q z3-5o^5H9KNVQfb`FFB}Qc!+!IIj^q>egChYeQ2wow7QWKD6JxECt z_z&`sn3%Y9u|czrwkQ!UZqA~|^|`LtR0#f!2iB(y9BH+|y#KTZV2 zyKe;(4cSFM!!Cki+WT(oB>Xlr&wex|Nxn92?{{Sja6hd~`R?R;i``7O2EM#`30=+x zA3{GpXFS1~vj=bz%3c6Z4e`j!^;lj1Rr;V=mGdO}Rrw5h3M{sDpYvE7=$s#`EFetH7ecvb{iIKJpLpA~z z_4f7_?oUC_b@@4E`NEU9jxF6RccJx0o}>j1v{#{%uzZ{}9N%v_;e#0#->x8iBGqJpszP+tDz!~O)p^{g$Md{H+SS^P{;B*~@Z>H#R466l!$gO9$ zWS0cmc1?gXTrKIK(LNfY{1HJbUO{-LR4>rDY1oW%0z7^4nqxnA&MyNW?;o&#R0>fDF!=(Ymx@`5lK7X67E)1DTNLx&X;!-Z1eB;KT5 z^idBKO_*xH8|?~LZpOHW%rrGuI=IL10LCQH8yUKh%i+OW1C;LYG<}o05xunSppThS64GBd7@SLW2l-U$DkQTnq`{nre zNohMQO7wRpG6Xi4HB0u@(!L^3-d>Rj=hpkX`=KlRz>-8EIeK*Dz#yyq_^)$r8$D5h zEW$2vhC^k-A(Q;(jYw7^4D57z+T=RY-PQWA&m=JlugCRWQCU2yO86WGegCt=rc_Ck z2OMmHSO3!^BA79BNU%jTLaG3PYn@m6{sI0ZV%~9Yi$XAdc;-+8*5GpJfej*;tv0Ak zNk5!whmp(p$xup9Q>drGk>TJv%yAb`yHkU| z(a3ifo0^KI$ecZYc!GL@&bC8xh7|pe-q-Hc)HeRId_7nE9`gFnti>1O<%sLwV>;NZ zE911GFR3x)oa{Lyp?`o}VE6X^Js1XlG&GkxRh|j+HgY~Ax zaf*@nTTc=}z`f_uIK;rRBk$X>YXa_F)9+lSqZ#Lyf7!1&hg3lYAx~Qoo!<3e%cVF; z5kSXGmEmBAbab?J38>N{DU0LQo8PR>jRwLo1!q6ar8ZspYh1-?K!lawd3nRZ`x>UE z=u};&KHYN_LLzXmDGP7{z9{5z5p9Ul)qEbsk~P*B5FFIKrWLWJdnjl~w4&7hO8yagy) ziG{8DB5uT5{xZjRi*SoAb}iw(n@jEWhG`et`_5ZB7g3A-fs5dn!{9S5_$#YriqmGf zhKO7=Fc!VzfAM)FMpEPcj|i}IcyYF&(t+u5;fLya=Zk%Tm~el`>c^(N8Dv{c z3cJ%$OD->u6e`I(z+(P|_1`}}9LDWwhHzCuU!T%q8*b7qmHm3$BiPa%|3A(ilqpz& z<$}QBliZ};Ksf5s^0I!>&v1ctS+#ANNtF%|=Bo0ppC1@?!$ASd&mT^fK3TI(507-q z*%D4C;XS;0cwQZ2KQ&>js7A|;7aXU?LQg^jQR?3{CQJQ-q@Gi^WnGM z{90_P+0*&w}@P_wzzLe5Z}o z#=q3M-(oj?mN$^FLc+J&aXHAw*$Vg0=jD@jowZECSA*m_D(P5P%eD9cK<1^4RIy7; zJhA1pz9H2C%&=&0?PVqs2Ba`IH}jl1NJzrHin#bbo38nqb1D(c$@^{w5^vKAZ>PVW zF!}xTQIN-NAIInShP?VeX3oAQC~Bdw#g9wY58ci2{~d$%r%oLj>-R?UC5I)&?~q@9 zeR$0~I0hSk&e|CtR-=38f^UWkF9z-6Q#d?6S-vCI$lvCX%_ZSV~ zmv!l$N{9;9^Dn9jE)T`SkddE-Adtw<8%{w8GE3ejNI9wP?`geQtVBmcVh{aNb-n8- z>WS508ALON?eE$G&j`1$Vjo5lgOzOn{}Aw|jav#NU$;g4ejnf@6r7bcL%6do+!+#Q z>dDtWC&Q);7S=YTKbm4eBZur(8(?-@PNW+fjt*5!rkmr2aERB{X`V8Z?h+KOq4!SY zi(!L&W!gTEV@oypeej*dig--DFnyG90;pBRJ1*?Rr zIcbtXp#V}i1@u-(S5p5iw|?JbUs+$QfwEzen5?LCT_V7-~7}XUoXeJN%F*FZN5uC~ekZY@It_R7u47 z$6J#nzhxmmJswp`Ong^G>GSoW3%OZ-9ky(LwSVVRA=LRwjX4B;p^R4Lb-R(r{Vh2N zCFsE}Bp)oSHg5ilNf~nDNBM8yO_eu}ays0sS~-p$uKC>udDS9>?)85Ah2l-%eL&zt z1zD;N+*jAQxUw?3Y-lMjQYbMLbSNXe?*}?iz<{DVBgYE4H+bMPPHHhCj(I2>Mb9~e z_bXyb4|;P$q>i4fCdNA*HbE#0pvW|(Qh8OpjDBASNLh0e7-ItuMWWg^ZaxsYQ67JV z(`zUv8drW!n^C;)>|(kTAW?L&_XWdDkkPacVY4ATE{nYai`GeWH;@kJ_7+}DtzQyS z4!6c&%k2j_ymu+KJCBjBqrpRi0QopSK)$u8a&fH5&>0OMfUbLKAUZ+|dnaTP!v})) z%*t4fd?gd<)3DB~=u>W$!DD=|=vZ||L_IQq2&xyp{dZVV8W62`O;3PP&Ud6WR?WLT z_V)=vCSx;&7gZ5~uGEJzeOq1aEx)!G7_0t(un+#z@V>5f0hcO0dHgk&K(3MhT@X?t zpU5wLijWl&_yvLQw*B$7)xnbl*H*X5iVvE!7QWup=Hy0W%eJHK7VlnLov!bP;&y2j zEfshL0%8oBN>W2MNq4JbmQAw@(*qD-z)VcnlCT()nSdEu^oawdk#mTn8W5G#Ybhx6 z5XGibb zq?N)79rp81SF8&REH*BYIO|_ARNr#!&{2Jj>1Vt8)gTVvjuNHU4{>7tRfst%T9)4q zTNJyx`Q)~27f(XUqP5DGIFm2X}J%^UH* zLa)~|uhNsmX2CN!-+h0Oib?)Vn`-=d-)FSjb@=I!Z2JKXuJc~5HEi|0+Qno#j&i=H zSS)g&&*LU2KvQGs?{F!npw-VfW}V9`wWLi~3%|n~RaA{iRR+tbY0OZ}BPrSpT7XR-FL#!@c%h2bpo3GJYqnPSeE1xCbt!7?`Py2NI$mV6s6p(h1`9^0 zkuE7WDTroHgme{%fld%^*Tr2XQ>Vp`nUOd*G~YETPs$|{`|lZyUD+HZH({&Rmn}sG zMTiR)}8@A&2BDX0{q7Rg8=SzuhOIX)73d8C*`v zii*pz{egE-Lrkr-uvYN%+ooyP`N}DazXXOLyc&(2m}S&uO``g1MrM=bOb_X+SKjOG z>`Q@m>fnrR6KvDR!eR&lF)HYmh@SRs1Tv1R5S)a^A2}{;N zVkqmSaI~Zs+zupgZur`va~A8vj4z*O(KN`cr+cQSDR>~zUWj6)MJopiqXMOb>+vX; z>oO#D@-ustw`yzKHew(n(P(GIG71sg=J(%gFX#o%X#qDoSfYy6V}bLuv%@APC`t^M zUUjZ4mBb0@R+dL#3_HDFcX7uSrQmoiRFu)=C{27*1SpuaS$}912$hm9PZU5Ki&R1q z!~eNqEGHL%QN`R2wyGBDN26%(Gl*1Cz~C8tpqw0arw1rk>&ckR+p`{zA`S;HKNxfG z7d@Kwxifo~>ATi=#a$I(l)88%|8N|v39?~2sZl3rhuJmrVV)7`OCSsmW697!0Vh*f z!w-FU&7r12jV)Z@nqXc?KI5du8yg99>+eL9SPQ%iOP-a&;+nke)qiV)qrBUY1o3|W zWVlS2;liHSbftxj0x1xPgrX$GDrKNVmsxdwVL?XLT-?WHkcyJBBE&6}dTB|JUnjp7 zk+HECx;g1|y#|ct(^nTV{!r_*dCh$o@yYo*y!+f)vKtWx|Y=pU~KzJP)Ne?7O<6Ib5YBG=E zN^yXss0@E0#|I)}eC;*`aBuIlm@{((KXQDo>j{fiLo;Vh<4m~Tt!-@b+(wjmIo8}; zSxyHGphzs}Sh2x7jl1;V2ma8sxYCQ%$%^CS3uG9eyoA9pnH2@luhK~vu2Xl#o1;}$ zUc(o!P{tNd0QIJ{qYP8XxjaM9VNPo$-?_K&I#ZFj%K20We5iAYjI~BTUz5}Dqj*cT zhnd32s+n6OlY&@=-!Tm3_swddNtMBb>L5iVrT`xtJm?R&)j-O0%zc!ZGQVZwm( z0xV4w=#KLExhiq2CC$%T?xH1CY7n%H7Ce)($iZRcYC<5JMFWU?tKD+^I)DsD$iG1y z>9+})w`Q2sS zmjjzeCk8psmX!b&-Z3k$6LCWMmw1)fj!Nx@c%$S7o6ef1(dBNXIg~^e&z0BzyYSwW zMLk75&?9jGhpsk)n3xo`YAtA{7@117ni-mql8_bn-76~)5?Nla%_x`WP{i(RBs-9k zpwk;r=N13EVU)=Ata|cb-!SlTTl`xYyKZ&>!ZLDXhSer<84MUy8U3){I=i?kIUP2z z=;f`P#*iF={-)XLSjXUV$Ms2vtJq6AmHR}EK0UjP1P z?3VnVxJ>e^G0V+Y^QFYbt7g}WJ99ASZ;+}Lb4`O@){m$dDP-$8^!v3X{apj<7NJ|)(J`B&kP;;x%U*ZFjBLkey zNzg(S{UD79VY#D%%gBUz*WLGp;6jcydR~?lv(ISSrc)^wyl``2@ZI7kIOsW5g{Oc@ zIwo%s?#~i?LxU~Ogf3)!>ENaF5T;4vtjkAQt0k3*q)|vJvsBJ}pvjxZ$yrS8yG2@TA_oLvk zG3|r>GmxMoP>bveS@5z)A0jsrl29hC-?9gIy3g7TmxFcQ*a zQH1j`t15=Q-Et(9KvM?Yo6?QFZ-}aLP#()P8ScnZ?Lq_c+q^5c6|2A-=2SbPR zzZ&=Y(k!0j`yOQC6o4od{N&%mQ_3r5J`6>%b!m(VhSg}10-1p2o5VMH*nuT`^=gv@ ziP84IgV+*|`DfNiYI+`LsSF zOsd<<@6$5WtjRI04aq%L9aVePiSb%q|u1T7V_1Vc!kUw5wZ4I7Z1P%J(E6E!NiA_kjV)yj)xNLNzW@@xP z&6uOm+Maf>lYj5c%+KPm{x$tx1%~vWD5AJBxwf%4u3}Vyo<_bgQV+Q5?Q1ie5AOD5 zx&QY48>vhrW z7kkT}8S`cVL!@_STQfKLg76f^z%EJaJcR3=KcAgt|2T^6H=EBa_MyJceP5b+3LzZg zm9VdFSKs8Onh|%^YLX_tflMbfw%(^JLzdb9SzH8E+6ldV`ZnUJF4pk(M(qQh?xSdH zNa4RcUGd-IBlIeV%9~b$GPF*p!tSfaTq_;A_4kxR-R6=7ZbE$)uEk95_f^v?XruXh zV_UotB(3=v6sDQTk3#dF0D23ZT^js^G&1^Y)5^e`#CJ3X@C`sCu8WnDeK)$=6m zzt4_=}#rs9`^cfwq@c-DYx0Pe{-o~bWz%KuiSFgmxiAj4WX@CNBjxsL20@bh8cSiyO8 zx@IUr6g+?99*_8p6S&oDEKc-=Y%~pOS_{F&ZWb7%wU+D=QUGX1 zT*sYHL*q>98=1Cz>#>&zGtcEr@W~1FF#wlJc)FQRF=u{#W?HzFL}-4fs@|bt#%et- z%}~Y|NP%*s1C7)|d8Acfu@#v}J8mTr@eMcsdOyeQiRQT};;8n{J;hgAX&xmuT+{I< zU)I|ur->1;Wi$5ny|DOPGK2nzn&qf1^7d2MM0@!jzu3h`5>Awa#bBM|yUZZ_lfzMG zNhS;D>z%*ILgCLF)`8{*vjp~-y!Kx<)pvsA>aKFv$d`i}!E2z&__(XwG{(F6&qI0_ z0dHu&NpO<%=Ufd)m7csdB2RvqR8mTKkf00Wi;JYvY$xQk0YwmMdr&9FsXd|*lERSX zj^_0&Rc*{EnEcUG7tnUB*vJT?$Au;(N=-9}n3QcMt=%*3^zz1`@*WjD`w^ixq;^yU z%=)f~EJO_+Rr^gMwmD6Q8QMwZH5 z%$TAEw7`TD6=~g98$M`nJ{4aKW02-MJJi*}SPX}{8#pXPyU{r%RRVMgFzB>ODqsys z*`Hm1EvL(qlI0yYxY}B6({${|FDzq&KW?$Zb8|EPvQY1Zq4^q`^okvI0e-lWqI%>c#CAa@)BOx81wd!{+yse>2u?qtT zrH3~>xzmzI=-5>JdPDCgON1iwZg>tvV5O>Ll(u^W=;;|FIXfM5C(p~zCm|uR`?;@7 zN=oM7SS9;58gxeW)98aFKaRSWk9VqarLdniw2bgKTWelLx@$Rc)Pfx>lg~DTDdB?Q z@T|$Q01o~G_Mbmlns%MrC<980=g^xS7w z-rTvi%bwHPjI?Biu*j=y@G-QuEiFM}(&p}u>zqsbnllqRa@IE{!;L+C;cvI29|0-0 zcs$NKGA17Uoq!BVvJAdrJGH0sS!)(CCVs%A2cVtCa!CmbxL500;O?|rY@+^!KkA;? z4hKgsKa}Z#DsTM52A*9CkN||Az#aKzW1nDAc(`}crbZ00v|z$!*Ss{yrq|@q=M(j} zYBA+eJne~53CQ+l#y>NOY^kKrc_T>5!c(iJUERz??X8DT55ai$T=|1fiPyAJ&gv64 z&E%q`Py#LRqmT+@QzOHtwazm=t>xl}ob;Gl=kKTj&a*%pU$2afztQ8X+VVC_`Ul?U*u;m{{Be(Zq5E#t^XAu;0f_L{uba<-0~R9xYxu0Y+TO*!+-qtQRI*w)J{= zlv%eMH-@F|@R<6BnZPS;*0&s-Ps#s_=} zLVd_tv9a3(4a4nBJ_{57fP0G-Y7ZCqqpioi;;gi3)Qq2!(-AcsdL1lpH}wRBM!%;L zd{?LuuV?(aZJSp(ao4lCx2;Z6W5l<8;CImi-kpxxF;4zu`+o6NGT;NH-KzffWANRU zeW&hBx(dvA#bHXO$QEp4V}mTg^IUX9Mo4aK*%`{0m*fLfK71QHkH@F(-rl^*X|;in?c zyY+yOkk&BfdHPWf^dj??T7ht_N;v02(AMcR~ z2I?|;9C)Uk02^)9J#{cG5}!Ui{FAh@Jb8>Sw1iJ!z~*01Mj58)s%u4SGlpSBsyz`w znjo&9q@wc19}wGR3rU=|lzVVq@qWq;uWiuV)TM&7MSX{ASwq&4hT%fK=-e*9Z$)Hf zDIeG0W%rb@O84*2;ju+H8RX$Lwj5sM$!n7D=}R)X56;a!!U8B2t`>sZ1NyFeO{JXU z1*~RN1NJ>^PZvhq7$!^}UxwZX@Na&}>j>)mhic|hO2h^~5RDT}JhC5yEOUpqJ$2J~ zg@xrgvP)cpi#mvA;H_Q+xP_HTtGJKVEFy-_lH%e+gL7Q&r6lC!a>{ce>?Wmz!^)&f zkT$duH*@IW7kI2bnlnKgBOKO|zzwHf>BE(X8H|QJ$&;D_PJ2zAM%_nGsj1qujcSbP zJKwuJy}WxN6aFQM(wN@M`Dg5DZ7XHN_@VruTI~gf?K!3U6Uu1CXc8e&B|N#dwvLkT z*!CKqY=hqyxdj)ESfkd8eg8$=mUNX*c6{Ve)>9i%GLO-O#(ct_@%BKL~ZL2sHFvuy^91wGGfyi^uEZ(n~H&lQWOt{PoN4`~|u(4K8y`jvJJv zD<{Z#ygdhPdF3qj-0K;Z5f%XfLEZWBu(vK%fU|Uslersn|p>0r2*%M@!5TEl3v1Pbdiq|@<^ zQ6S)9eB}a>QPpFsTaPg6EML)OxE)pzh-#MC3mxJUQRr=#K))W|>Am*d-clFLzB<6Q{ZnL*hgkb;T zKyb|6hyM%c>~j2_O%fk^^Qsc#KfFmAbhuc!haXg7qKkvBpMOkmKQCL-MfHQyv*x=M z)~e)-qvEA^Y2C=1Iwl3nX>3rNGpE4@M`oKcva0A999>zswz9nTOz-CGV`39%1TYE< z&wX9l3q*o|vo|E4av;GpR>3|AYO=_^+j2(pR`e7_;%uI^1xMT)36m%MPcTJ3=I{Px)pi> z#A;{+%BrV(EvrKr|AITTqMhDYFgK#MIL_gjobL^j8L*W-h?@5SNUj8HpX+jCFXK4)7O z%Vn)^EpQZc+_$6-Sl(}GH^1{7dYtf9VlV57gBG*TeiYZ?DCq_>4j-Hk*ad%h&tHXS zvbb`L+!I7ws7oI!{wrLy-b_YEBrJL)1#2K48-4k>Ezw5w2dCg*I+vGIIG&W%USH0q>8MhE!cw@nh|N^J~r z{Kne@Ch4pp`^($N#9>}$2^|i$tSDq*+{6sv4W*7BO)=ARet9AWB|LuNLM7E@`RZTa zzwi{Z`@STwFx`D|1op)=xO^563njDeus})w`^pSGC5XSHQeO%gHa@) ze}Xs`n5c!TorXED;%DTloFH$|HMJbgX4{gTbE1i1%Im+XMx8Z`z{4L(%GOlzC7B3N zz3|;!;|u+;z^ICP`)Tu+cY>M}J#Fe`%+AL-U?9G+SV>AdGwQHTO00slYmIp7;E)MA zjG#PJ?iW7jxm*s6QZh|lMeU+SAJnGRDKOZ4>}`etkb<&GqnkZ0oU@J9+jXIAE>{-! z`Ot7Y)(u~O1g0!2P1T5*EVq=uVj-$HkXKLGeUIPJQAwNf=X88M$rovG9Vd#AQ<3I4 zw86F&%VaFK==w0TsT5j^q5~kOkz%Tvs!NvvPyA4oHZU~3>~Bv}4Z?5^vTCv-D4*-( zG5-*$)=nu?K3GPC#2{^wm^kF6X0aiG#zNno;e6Y5vpfd7Z(DhzgGB4yn4+WS>1(n3 z)hkmbMWOj?$6pd;8AvAe0IgVd$FeY~sDFwIBoe+-$Qdm39HWV>e4x|dOFI4O#~}mg z=qrg*7o{s#nmHTABwv*kA}K}bmuG%!!_IR^Q(v5BRHro2q&wr7_s+@hc&#hXEecSL zaH_>C#KHbu-@_p)l!)KlkUXkpW}mj+wyA|Lt%`kFHN96pK98eGBo`1>BhQGSx`V+l zh=iyrJH(2DsefCZh*K!1$C- zx6tm4!Ih*6c3MO6lxI1hNnqi`W+eQLP=JUQWf?e&G^hWmtL7<9>1j5Nm5M`AN%w7X z{AT0cSWM3}lMyaCK{<(wQ-RddXik05$J@KeVOmb_NBk+`-Hn_52Z{bPefH*1Ln(K6 z1O@~P+*wnn^U?%~cL#!;Hb|MO-^VO`o|Yq5na&rdetNY1rseQ628&j$1O^2Y`ujE~ z+s!EAme;p`Zu#?8$ws<76QpAiNObQ(;k~4-_}^npKVda9<%N3qszvOA2c0APR*kVF=4iUX&rN+EKv(m;~r zqRd_&{)m@1fgH<{Y%@O`fvi1$63sl^-;O&S6quAg*Bawk{LhE}_i*Rmi^E?~Wt%or z`DtM>)VW~E49jH`r(gV2VeL3e_4sV0aSo}CesyX=Nzl@NZQ)Cfm9Kyc*x3wt+Wz0i zGZ7i;$@)W`&w*zQqDu>P-NP97JYhb>VLeLACcJB}ZYom;o=t4Di{2-0;4F-qsDl%V z_Nw+NGu{6k0YwT)kj1?V@rntskh-QMX#+$)%b=0QC-kXJ!aa?CIgX4~9lc~>1ARlL zoZmo2roLH+#{8`-&ZtSL5Tgc=d{tf;ceG+BTSujhJ7dxgp7x?NIps^4b+4AgNUC%T ziivCfDI}+?Z(y zON3BvR-M_)m%w_L&|^?!Q- z+%nR$W`SwdSIQa%LIZQ-Tq9iNhhJRJdiHQPNUsxSrmxTK`&8|M7@R z4zBe|Q`9)nRr;ov|KFFpbfw~Jjx*!9mL^XoTR;y7U=8jf9V#ev?u?R6*z!2kUzue? zuiXFs{R;;un|-#!f^w4!1?Ds#J94OLTt27D2A+ORzWFnNobXLe8#BU5CrH{F8@d8= zS$@?^1*wrTKGGdlm;e_5ByzgxmSPxT~^nVmwKV)JrW!S zv)&0ot~W3A?IP#d^Sm7AwyvG{m2VXC;~nu(tZq+_((K681IPwn1t?DgdlWWXrTa9y zCxi>-b||~zm8kt~^gOLnV4iLo&~Qiw+hCL|~@8uYOTx{^g4D^oC> zq9>D=M|$PqSAL<5OV=h~YnGhg;ppg44uchXfEFeBa`Il%bL#fAz?r_gP$u7B>xXM! z4n(#B@8QD1I!JG4KiooFYvA4b?wqug%i7B+FP*apGIdwj_OagD!@s}-L}QjLqsu$t zQltXn=I4!BL1Q7*5mI95S1`Obcv0$9TdB)lcdpJhAivt@3W!m{vN>3k@dw!5oQ4DQYHb)*V><<=W>PWIx%rXjU8J@b)yzwQ3OvP{BsyV#cFBQ(ZK-cyGq>Ip{WVZ1o_4;|pX3 zo)?t?JSQY)q;X+utL!L8eKImD)XCKW?h<>bebeyVy~N-0cq%ko?TCv8=n0qh%*o+J z8?i{UTD$sQc~L#e&|L)I2gF*>NWLt-1%bpAU)MdES1U`Zq0A}|3x<@tny=TK58re( z@#Qcc1Cf=j0pYRVIylmlbjSG@wic2SaRingCKXBJlhU27V>hRI7wT%Y39afGlVlP! zivL!vTIljFI^r7G#HN9;hM@{%ss%YtnDwD@5dw~z8>DsopmaP18tA-3da-vxa~5?1 zw@C!|a4I8|Uxb@pM14Jzp47(q(6PUw?`zi zf0=;%CDGcdXYBBpjtkxycBjz~D~#EnwY>+tMQ58VUVV4GA@v^6z_a#x6ily5JO zmb7O@MR~oiI=4A*=c2U~HNrLkMWWDvMKI>wN#tc#xNS2P6tEsT5-Q(1PKEKbRTN~goz3=et*F*p%1SUg1#ylp?8Y47sdn3HkU=CjwL_6=d0*+6PcQ_@k zFmQV>kz6UxZCiysqL3u-Jte35UN2+(W<|Frj&&=Ayna&8B+eA$NLMG+5+01uio~(l zdRT$o@n};!8v+?KEKoAx`erg->4xk>8@nuzOh5^)l%FY%(}v?IBRSr*6am5VQf zBAX&1a^$C8yYw?pH5qcsDWw%B&Ats0T0l0GBszQI7!FD_y zcfK3~%ZP3BA{nJ$qcB18U61quUqLUPg-wC{!Re*4vc^54p5#Q3TtN7=vNia(ylDSQgL)p~fe zh4yBGL1@G6)FZE;l;uZo9BpKi-lQG;2C_r$gnUdoRu3_q9z#Z@l)2QbflE|$>iJnr zn{Y>jgBmc@O2j_sa9Wc#%8teMdga)Rc6@*D9q-k3 z(s~vS4(mi%S68lO!0gw@Y|fBeo#xn4pbBzPJTVtHul(yAbyo%2`=C7wy-^$McX_#w zetg7iIO}E{6kP6Vqqjz@tVzz+eG0LMI+Ll4{+|QDw@!pZ&K-SK)mlWMq4u zuYZK!9lpB~|70fcSq`PHecyv*cTJ1KQ0U`tv7VkvmP{lw*n&c21RX`WI)4#bj1VT5 z2t9Wemw-_^u@cwHu248LHlmxJNz1ZHM2B0jL(2BkkL{hlz(0MhMs-&84EbzUsr1Ax zB$6{5R%-e;q`ZQXW9ga_L(|^}ujSbti5hyPAFuJcyC>MqpCj>9P1Kb5b4PS?5AP+% zs<-xrn;GMD5<63lCA4##6oV}BM`&VjDSjQL5@bXm99Px6Gb4zEsNiLqoxEnq$&?b5 z18v3738I#JBk60byyXbVXz5~sQ-V}4B7H9;;q{aG#E9NAvZMCP|kYq74pO zM0|u?`G!+J=0N}PB3wT4+$Z+*j3}ocfMZpAUtKYgB}417k-V-(tjMB9j$BQqBf>+d zz+B4pb1v-gm`qGDz!3dI*S-38pVJu!=lPYN0l;{rC>)egfZ8n&d1e~Rm^&cc>Nt=! z^HRU(t0A3>{?vsqW*PtMqvSvPm!XTm$bV1wl`F{UP6gte$jnl^{v?B3yPqWPHJ@iJ zUx;8Mw8{l0X@T38w24vCNHWUdT>Z1}+{E9opr`;!nTh03!{wMFAxfZVI0ZKL@e#G- z!{)cI!FTp>C>z0JAZ}Am4U8vgv0V)S7wG&tnlBT(8YXytxpq%{|`-9 z6&6Rg1pfdb1b270;I6^l-QC^Y0>Ry#1a}SY?(R--Uwm=y*r%!ctb=B^_ z#cP9)=jEqetnQJW9pWw!BZ~HQ5`&#Dk*18AR?^gBtTMUO#KJ!Mmj}?%?|>&P0WdgV zc)9x-!`y=Mg!hd!;A1&pFk?%l1>&X)j%Q#9Lz0%w6dj@KyEuidrl=@IGGe^c&%qO= z#5w#BF<2b2Ee&#^h_OC;Es5VuhOTO>d%xtYCzEg7kciso^_Lq^1CwDhoWd(mcT*>q zQE+7f42THYfkp^^NE4IJtP6an5CvGF(LmAkYo3}_Q8|& zA7xmAOgGEzah<(NGo9dC>3{knt}jI@M>+$y7j!nCKYRiECO?0)tn7}FR&#k2v|xW` zwOVuxqRR~oR1z7Rsh@g{wFFF5!gz5@h0@xik|G(daJZ^B5=7T~W6kwZz;)W6KYtuQ z-oSfY@@o0=?0MRFdj`b-aZEVe%)8MY@F3a%Cvh2c#1=Tu}t!*P(d|N!a~e- zl14(B_!>o9%;E*)2KlgBgv4Zno0x}52AIOq;Dc79+zzH$`5bhF_ohxXfP=)}{W) z!zpkf=1Mj$4_St|&WP`MGho8(aZMT;8T(2kNn!y?1M(7u?ESkdHjl0+`}*8z0w0IH z9Ea{WXF!6QTKppq)~!!Wqed1sp)ELs`OWX`?mkCIUFtOTo6bs?2^IHtXDHvUdhUT) zF1L{l5@Th$LZamS_IBJ}+r;D~Ge5uBaJhVRT{a%hfOQPWGo3o0W;-x3QOBV@=CGKO z_5judOWg7soAGXlbCIls22~N$KNII7a=WT3Q@yyKCsse0@>{EtqCqS?e6pmvnd@y_ z%RWD*10LpG?c0LBZ21f3#$4%+8kYg<%g9TXH!%c%8aadHju33MZMkDb3MKWVeFb$W z*yG1vfFnh@XAqI~!P7(fnOr*t~ zb;fn)T0_}jL?$gA8a73iLTWIgLXYW$A2u{3E}g=Xw1);5W8e%srKe|$O9@$6P#GaJ z@d?O!XkZCz6Z+k)`ySPSZdgIySe)l=8M-1t&d84Mebl$N4W|533JOTV;S|3~Vol5~ zEHbjP_GAp6QS+V`N>ZWvoLeWhI(@9Htc(l|1LFc-_k7Pyh#;*~af8Zf$o*k|7X~}d zu|t0nQZ(|mPAndR_HJ`;U}7D83KHm>BeiMQ`1^vGGRQ5e+&cuVp{c7;bZM0^q`}Zf z4r6mwNJ)plnq<=9d4tYt--);VSpm-#IUxnMjF=^L#d>!jQ4`KydvlJoPS~0KP`;Zq zDYKh9}`wzsZ@M_acdmaP9KtZ-p%PpH{^?BcqepO-RVT;C1Gjul_M4F) zAAGOB#6m@VYgL?%mv>IM_#)t@O?bHpRDCWH4+SiO^#|lsnY$dWh!h6AX4?`z)~VHA zp(WcjX(624$EAMXd!I0ztQyDRRK&zzvWAAP#+eCSDyCVPtL|?IkJVvp&=OLWO|lBI zOs<#sM(E6JY@&*CpP|{oR~1f@`iPAUs%cNv=FhS}8Ejmo#l@uUX;b2FMfw4I+?nO= z@vAH9&59*rg5HcS{h?v=8K+qC`af<`OVv6*RUB-0P~o3e2RhNk)r=5Lg+-hlbQK@^|cDTLTwto~hh!lF;6fcTsKnF0Jm2a>r_KcfC#@NcfldC+j$os~o?n_9cz=igaS1E+W^iLp zsT&y8{tF>6Ue_8u^|mA$p_ z@K+U+y^ibDbxSMTeDI+Dmgn|c_9bZVHt&f(W)+`bZ&MeW;5RUuzGSz-#upeq-+%{s zA5A;%O`UN+_6hw1u1|wVZ#*^{9=9u;-Gi=%tsgm{L)&efSR$V9Iy?EgX*wJp05lye z>tcu~Pvq2Y7CLLl*7{nzRn z{G067)$hkS**G}r9kvAk*Z$n2Zz)#~etCeSH{=OV9k6DPNWc@4>>LsD{wHyE&9$(? zo}~}B7IoRh%96gex+JQSE(3R*nIj!_&W(R_AC4QgtN(m}I*5#V-#0l>xh#8V046N7 zm~w1TEYc{W1Fitlf@|9++E)dxLLEG#O^uu!b<8D%7c|C^=%DjcS^l)xOo;Z29r_wJ zgT6vFqAoMSiP>^Y`KT&PP-B_MACQ;pACFpaQ|BKJOqc@fieHVbDPOjpIWU7^QH8`? zO;Z#sbiOEa+q#ig>0N}N`kH7R99h}hk|O?KODj7{x@V=P0KC_UDPmPcg+`{T*8jn3 z=d$q6xY}#S=jY#t#g=L=4}*NRq8CZHv2e3^6~}X(Rhe4Ihi*4E~7KgTvPL3_Ofy)yuRlvS9n z_1g1(5WGjv`{+CJ8fJWjZQ`30-DbYQvnO9}%+1(~n~lGHJP>?ljl8|(dp_pWq8|1= zUKW();s=sK4?gzwKp$q8E1fade_f(u6lyDP5QEcQrL3U_rchaCP7M})sXvVw!o zqRY<=T~|enEWG^v4^=ue-!O4-@l8P&%__7h{~+Sl%caT76oK#M?T4s}NbbjDz&j;m zN$gG0Fyb|<;D?N@U35k+wuP;8CYF45aammge+4TH!Oh0|TgZV}UqTW(&(h77!J8cH zq@5+C76r0${OF@=jXuH>Y0*yGS#?2kv&SmAyPYI@O(2Fqff}pdGitVgOD1(}D{$5_ z40H`2U%kc#Sz=Wy4Vq)u!CO<{t{15J==s$}F$o(y6O+A(>FGN6ejXqcp+MxQ_2N(` zJuB~^JuVKmBW5x1Wkdj7l>b2>GB(9Kk)e|5SAXj`iV02aDT1S{kEQcL9{bcXOhj!IWl$T zF}pR}J9O4m%hcTi9AgQN?VdI_pomSd-sN(Q>N#|U;dyM1Pzm1CT(-S1G}*59Eq7nL z{op#3^VlBTzeC@Co@!q0v_Q&`4c$Vc`bzg{Q%_GeMuCOPF_quPy}|B`19~cVZxY<` zQ!cCd>O4qd)X}-E0#hqu9_?bCy+jX&7CK^c-B1 z+7EaqtJtX~N}${g-z~5Ki$Ar8sq0#s4WU7-B{WlV^YgP46OS+lqbTxSSNL%Ac$&>^ zS*@c|;^N{kV<e%o+CN3s9Qq) zOcIf7s*6NJ4x}ysSPU2TGk%d~yEnVKO{H>3iZZ)pU#-0wFGN&9kCPw39cpkJ&RME% zPa5B|7nHZsM>CJVhZT;SV21({ET{D?UQ1hhBOqqupNHW6*|N*q)EO`iK#SeGdfbb< z?SXW#0Q5NY^z=+zT;Y3M8*WDe0`J#x^K%m%Scn=wq+_AMZMc zM|5oaw|950tX{kDDZlzc-E4r%(A3*IQ`jVkbK_4|msl9M`{Ss^$__G4@CN4MLT{tR z2PsQi_kEb^J=UckYo*Q&&PySv4h9Vn=3b`^&m3#ABahQdaA?%D9zs5$1#6cR8GS7X zT+P6#tlRiwfpio$eRbg=I8^g~!?^2B2<|!{ti1L-9G#EWPyZYAg~;$e)4r`;gPEIM zPC^23=1L`oZ9SR<6Nl^wzV{N<*4Fmud29}Dyz=#v^`HC9=TsVW=LWsAV#9A%v`Zx( zW#ncQ?}g?7yX`?=o3p^LeLkAYx&1i;5~yL1{%8(9>pD36`!|yy0#kGQ*uy3cVuWZZ z)Tjz5do@U1+LWh#D#1~Q*CB^OxWYziuPWBL%v47T8a>Lwytm=$`hX83%90W;{~M^y z3Jsuj7zS$MZ4fx%zv#cWSmG@v+X9yzXL1wr)A0_}iu7q#b~Yx!)1v2Ks{>8(O1btu zB^bG%uk-@WnO=vj04Fl`SSd_Hhx2M%x{Jpr_)a@oK82|6_NVS|vCgqp zcZ6r5sEi6(^M*GX03G2(EaY!DdV|WlEl-(&l55Y?Vd?p(^U@3Wl=JL8BU-#JR;Rgdf!T6QW$1{ zjnh8`dii&29m=-T2z6Mfa1c9Se)v}9VDejae zb1r;I_OY?6JVCJtU0E84!Q_Vi^2KZWWh)FBV%beex=5f>u*$!X^niWL2}M0=fMkf$ zlpsiMF0eKuLyKpPSF_#xTlJozuBM^WIa52JPQv@cyz)V6q=ROMz^$K-zxSLi;o$?< zP{5t(*L$zS$$T#2WE7iq*^%RGg4Q2wfy2%Duj(+bN=|r<^-FoI!$fu^_G)je)L`L%q*SqUPV-rPrtuwGck`T zfWdrm&fMQ^uCm!iL~J_$Sn7|L4l)&OQU73~-+N(z?(GM#Xx@7mdiSwpe`87njVW)3b8f~!Fn~IA&s;e3P9fs4z z3M*@S%1D!X|5V^t`se&XdtSt!bB_|o4;+6MR#d=+PS39`Ni$H@HK0zrt+pR=0Jo^@ z(?$YYw1iDaATiW1;nLC>482pOo*wKmH!-`BbUjQ`lxP5<8qln8a$ zU@ML}WyxcT!4n1`b*_aV^f{N3&*dBBZ)m90Y7Y%~oH&Y?zK-gC{IsT>`4v-|x`;Y8 za)*nJogHPE8OU%NbpBf7{eeIHyS3=&Nrn}DYUq$KE*GVybYA-S0Zf1C8dYj^-XPcy z6AKGq2AY=ClN0|5N{@G)gQYpNh_zIxm|ptqJbed8%s;-nTFypv`)skjg3HOUGZr|rY(=mQI!(n zg?JnC?X5{~6U9Q|(0Jrc><;4pu6AXwL@=xfv7Bt|r z-a*)?Kg*FsyI=`9)Yv}cX>dkP2GECPBLzJ6Z?u8kQ6U*St{@EFZ_``ZWsx!AGj*-`$s0Ht($#C?gn5U5bpH z?19A0Xk9_bY6Wc7D^O=i9S{kE zxp6ZyTb>THoOILXfm>`7fE)O)T$o72IUn9x*>@NL)r2)VHbxn? zugLO*8kTvDiJAFR50F^~%$-yt#el0U_Kby}f3i3D<;31*2QKdkJ_#eDG}P9bj>~-? znS}v0cU_@XS4gV=^_AWTnOT5i4ESgM3LRwSe6*+|VH+E`!8r)~lxIIENha5nOzE5^@wNq@5Yl$bT(d}8sdD?{KWKRT}w;PYQr18KuaDPl{}EM z>JzwtVPj;JAkp;%gU4Z4+zckCluFOY8a#wEWx)Y-!h@S0+j1OPdSk5GWvW0m;Q}7o z>uciZ`zTf3{{Cpvh97wIPg7HUZSD8pio}umdDbkn|7lHXCXnMsP$XR|%_(Q=?d;T% zncjY0a?p)Sqx)45E(zDCX;MU*G>Ys+$TOQRI=`_n0st77eNV;=+uY(*4sBkZ_}n;5 zhOdcCOKhh2&Xbdsn{~lD4x2JIN7k6arGUx##)NTvakxuS)KaE%SqR9~0JMIOs>@BJ zeEr5gz_@B^;{Xw)xs zlVmt`($dK9%Us{&5=}=%(V##5J8Ros=e!*!Q=I>7Oel4BdV(NjWo55sG>D8}nh1b~ zw%}h>7?3q~ecmwLV7*vggr5k!5l~So0IB5dqfl#RM}vph08q{I7ieW?iJhS) z?U}$M-Z6J87IWwII_X9S{n9<0=@t2>38IenJS{63HM_BGwdb$iizg?Eb*ZYIl_B!2 zyHl4TX?U#yFm!5-?*WOo0lq0Xrg^tbz&^XEwJ7NACC}(1Xr0S+P z@09ENAoI`pSP+PpN_WO~xjZKx{3$ks6@_h=o|j|h>l%Gs#|%B4d$3TZLQJlN4OGp4 zBM}3iK-7FyRn=n#yb<=?jAF|VzpJ(HHo<3} zJ6wUkb@lfb%2=}rupu)39@m-JcGhy(|+?Auc;V!Hs~8s_zK!Rs~LzBQTm+OKh9KRJJXkdc{jw12H)dw#k9 zdc`zkEiN$)csbH$X2D5*rj$Aw1e&9wRU+g{{mwSrnLD&x3?gg-f`b!_Tr*?q%z3{z z-GDuN^P@u?0l|rp5o#a;fB=7*Dpo|`dO1Lf8)mi34(|!i-q6}Sbaoc5W5px%Ul^U* z<|gp=H3OjD%+(eBpzWVDp^MdzJmsI=@$J$JsNmzy>irNcpg-s3;kwvoYvSbHU%t~b zbF&@nxNFKNfk-rX?JGS<>cTpoO@wdy3ssRJ4Tq4>99Y?q%i^cr{E7pHA3U88LLq<{(HY4xAGj zM2@sH>Fde?Uqt5~Q4kL7Dn5|fLoGOLOtW*|N)p+CMoeKxkb{n!1@y+L76x2HtACY% zi#uYB9YqGFQe==zH$7cQe!8d-Eo@LZFeAgn)B01*@0`$w|Axou)h=)R;<7<#pTBD0 zIe7UErfWF2SE9<;Fiv*0oF8cx{E%@PY04Z_=y1MeM!S4W+Lu#ENJ#m_!@R56PLjte!rEGr_llzJX`e?{C)uh`q{RzwaSMd z7NE(@3!Zx3?(MM&{%jYC9pl`u^)T^J!^Rjg<#kcYDx1pVdPUYc1hWJeLPpIPmrF_g zf3f&i{vz#sd1)-Tz>*kgs23)53C9W_Was>vrI(ezH zMf_SMpys4}r8VI`7P5a68<+aUxTLlry0)|aYx(j=B7`*cPj8DDKlnhoog+^k+a}YO zZyO#4aVjP9i57ZYk54s$hv(bfajkaiTKc;CSG~b^>OS=P?a~2_!xn-sTIR(T;R08W z1#xxtZDVtdV!8giG*iA$atyj%L+>wy`*`hwDfyx=>;|ttkGT9=Nm=&m!Uzl7o*5c= zA7(O6>RUV!RHm+g=0e`kuBFTbg~duCq84J-*Qur0EeG5v<0Gu63Y z!Lb^~A|QIosfKf%Aa9Y$=yy`#`$X6MeF18b)cEnVVfyBrkuM76cQyaV{#keGM8Qz( z5BbW**OHIB8g}^ONbe${D0afq%Zn5j}mESA)qyHluyO&2o@5=)L*NDT%g994-eM&g; z`+YzdtJHi7YB)Bz_z&<3{T`jc8?9N1tfCv~>rKro%aZmf@}t3f$%j{=uTsow#rE?u zjN+k}vrMEDROJWb$5}u`q#>)s%+P)~G0Bxp_j4Tf-HU7cX2PhRXkzVEZsmIf7&7&J?Lg~#P{yU@D0Z*6KBSoN50_|p+R z6o~9~6{Jw7;_QAQIMH~Z2C%KD%HY**pP;udNCg}g*8V{RK8T7EBzd`1EAqH1^KiE7 z9wBM+xraNyA@RMgj2N8fwAFKJMpzEeqQu&WNttp{K_X=BFy@(GoKu193y5wZqY2XEh}v0^4mB(=1Cu2F{;$i7%e82 z*t^Cjj&iKtw$LmqH}`PWBJThs2nGX!zaPeWQ_Ecs>^FQ=(>LZ=vPlsGNk_5R^V=j) z#){c0{s)3jYTm)HbYo;xv3sL1LZf-U=>d0f-STWWzhh-VE0di57kHj|-`4}KTYvn5 z7U@BL3j5eeV_Gumj~^Deb@62Xg;J5A5b%Jb{sMWEPu`Fit25qLt@nDm+%>g)lPxLF zBz%EkgKjJ<5DtcK{KUui~dn3or?ibMtncQ#TL=n zujsnrX_y^CmG}Gx9p09@rI#S+U<`yTIq0>9ru{CD!V%1`fGRE)PGcgodU1pIaS-s6 z`74y)G1(GNG?8KDUxU{MgA!_9m`K8n!8)`!<0z|qTB=wg8&pad`MF{RsU$z})WvI( z!Hf6YhEJReH;L#eWvy{exChpJ3)Hs=p1B`i?60uy7g(0q_ z`n`RvRF-$(hXn4Zka!MD{j6x6c~z%u1{S-=d4nOX0gepmDmh;TbfVwqvU?_le;`O? za8AXw7DMtSk#$F@*g33B$d+IMcNNnfCQeR?=s?)6*gP1b%NQwS6GaoeQlYGk-b$GZ zG)lIC2&Y8e{@U`MH57;#qkVk&t1hAF(XtBMG&4<;(oP3Q1B^4<8VD{cL1n7v3y*%=&V7A%q;-Onewuooo?`^+>eub`{kjJmS>|2c1XWmy_Wt5`(r@kR;r)o`)QK^W zDt|d>=TmPa~c1Nm#fXZeLG-E0~c4diXha$qhOX}|!XDR2gVvKPM z4}?Q8&@dGfik7bYvM&}}134s|U`C^&1oycRxg7Q^Q?DJZ9A-)OyKV%sNY9$jXMgeK zH+v5G@_|xK8}Sp8GwbiUMd#m!ikFU(f0xEwoSx-qruk=e6@?w+bJ#tTh-`JEXwU6zc0kb>$#!@LIpVA z9)1gvC?Q}=8C#Y51#k0VLa-dwPElAXhy1P0r-y^WhKF{IOw|0M7=|J;6CTf!?-mJx zEUcGchH3J1r&lsWGbxRLmT07s!ZR*?fpczTSu2;d(nhvmQ^q^URBen^g8cIi%(qMl zXN0z8zvk^YIxbJ(2wzBd0H{VR9@w^I9b2Srv`Ae`o{0h^>DmWMoCOry}!W<7oNOR#E<6#XoR zp&b`~tn!FANTOFE>9O$QNf7Rn4JRc<14qV1V*-w7`l)=~$IjoOPt0~JKfs#IcNIOc z{9mq^>-}CJT0NyJblZIsH1z#qHeaBjoX+`O(N(6DNkr+FxZDB1Ustsx-d<6KW%CI; z9pZ7G1#7J`$RP?eKRu)@KJcgD-t=}xnnB9CkbzeF$;upJh2(U$-z*P;F)>YsZ&ZNN zC}er9l6_eLqHN>%$;K56LI{3KlFXB~t2NI~I73HhQQq1_&~tBtgFPZah+pjoQGJO+_8U-t05QnMduV#g zB)_p;Z;C-T&|P9My(R;SYIQ>NwVF27ti7%DkYuA9)=33zXa~P+r zfJ&6qLZ|+Ewe@ws)kJZTO9Uc;GVwqQHQ!I}YIK^05%zQ~>F5CFNI?qsDK1#G4`I0X z(NouDLDz#m0md_rrLFM4Z*pt1@oZWdC@dyURqP`$Q@Hhf!?>9UVyM(rQe~p;UZHjn z3{@znZKRA*rqZ0D8@MbM$NOT^g1CuZD;oWG@F zhI|}n356LkEd@JG#jCWSNTdIZv7^u6wflo;-TmAMocjiU79J<8?ur9l8r-{*O&!aF zOHLQTVd18z@*=rlF<2~Zl%X~PZu zQfIOz_WS|U3!_!4gr?Q>Sqqs*Ev8vKFI4Zcu;f-7(;`#j*v7<;A&|ftevoPiDI*N|cHd6Y5ZyFfWd5)6^4U_kn8I(< zVoQ;z|Lw8Z{ZyWZ(T#Y)u0vl^LI{KZ0%=WWHJl$Iq?MTD^@B(G6#3fNX#l-!J3Xfo znoki==CHSHm<%dGJZoNFw$FN7RneN&OKf@!LRYj?=%dah2f?XQ_fS2^eCUHa7QR0V4N>WCPjmXzNd11NRMP_IgpA%p zoK(%VggFeL*$;7Ufu@K;?7?m8f9vr4womJHXly>e=$w7hx^;67!djo{xgFlni`jKE?f1v-q9z ze7>=f2`%U4dNKvCwu8;MHR94Ws>w1+06E5Ok&-8REtx}e*&!WGanl<`7esX$iwYh?n+zbCDrUJlQ;6$3lk1(Wvled-H2MuYTm&o$#uC8N#mTHY5SOF zjXoM~ED=9hr0`n3WD~7+)+x=VIZT#d)?I^r?DroHv26-CY1?(?pKLRctkl#>Q}*Wz zqF)Pr7xu5FsAYdjL5?F#`pGdy@3Z7klTjY|n81h%UnKpq`i9*r+AIDUbRAd+{Z*is zkbB-zXvo|?YZpO0;cdiIF(Via1N_C3Fp#~Istz5;Aa(`2S+ zift{a>`j6DcUrJ>_|T>pUhvnLnE2&ZX>3$2YbpBxt6<^mV^z~3BRhSVe-w9 zBC@ZMRaa$XF{K;=OU{szk$Bu+WWDpYOV90XrzTM(rM{1DmNB>y99K~ur(;TLh(s1E z6gyh6=~b!!_3nnT`k1d%ziY@}tmG=fhjQi>v+ln*gez(PFSpJ4v z|2*tiIwe>Z#T4_MpvtM9+Er}us^+& z7c0IgCwp&`>()NqAp_RP+7nr0TRJ_3b;$M4Vs*$fGq=Z+h!g19*wF2JBS26IW^<%a zGQC^9YC;1jHXbZF;+}A2yeoOf**QFT0Iq3areSi|ns6TU**n{upnd<%1d&1Ui;QTt zY1%e8;PgV17-2H}$rB!~t+(cDrX>TxTL9z4{=Xq5ZMeJM)3x1Z=_DAEn3g!}iOn1nFPHtY z!_C`{U-Ktd&C?(88v1Wv-QX9PcRo8Jj;-;%sR#fYrUO7tXTvI>wAk z>l)_oL}%-Nl_Utjs!)t~^||v%=3X!T^ziz7ufgqcK&p(M-RT`6_sKJ&1=)yHtMA4olG*X+E<=^kEao|j(J%3aF^3&x$*QoJrZC5 zc(HDnF`Ta4x8x?R{u>tu@k_`K-kCIyMD&k89R;5p6GKJ`*>^1D_J!ykd4@qyRn;stM&M9M#wx-yzk?!$W(h> z+{`lMa|=k6xrS2?Fb1@s`w6S5TiV+C4E({oeAoME_1a?E z_zh{lwnB+E5GpxL<~TIizST`K=;(Aeg21y&Z~ALB4zoFApa1kuxlK{>nJ)2Qh}~Pt z{<^xzr?pPNgQB#ZwNp+cUB-_@@r5E%4kb@(Rf6WW`TWIdRw81~kSTJf9-ibA*x)0c z`Q&)z@V3z>gUZ0b-6mV505u;~IFbX4xagtnh1;QoI{ddh_XVp&v~;OWaT`UHMol6X zj>=|oF?$GRn&$A8Q4(}Uw zo~3J~JfB#i*JCdRy>{u$Glo zrO|}SX~x3JE8@t&H=?;l@9$ih3qHRqk&{vC;#!iNoYTQ6yZ-y^Exfzym6qYvC55@g zQO0In(&-v3*0jM+g96{+TNvV=kH}W*BVoYHvx26cz7ZuO*Y%@`?RwL9_{afom3gct ztrTRfxH<&vT`2sX%t@;~+yu=5(;e(RlQ9_A=eGK@YMlUC%9Vv2x^^!Df!wwl&_$^f zy^^OvbKbYM=206+0lNtpO#c`s4O>WMLFONe(Lt8i0j;53C^NJcT%IEm1jTX4|Fr<|0OR~Ke*|qrvvf3DNEQ1|BjXgE zSo#iw1PXl+cYS|WlL)WoBwf^4@suZ)^m>pQ8HR)$uIf_^vGGX#fKO9u5_b7oux99Dd;=)g#9cGEA)C)Hv!a3ynB!iT1l%t3-H&{o z(rX=1t{EO()<4?$ErPD1SH2Sgqow8ezAFYOHlzZ~QYLuhyYD$7Z&Db2BTndxqE%5s z-NXd4O!6I{C$t!J+sEEs5LxFl_RiNqS2>`Z{hkuUTB@^~`Q@$e#U-n(4LwD-STOn- zdE2oB(C?={+j}W8N9kwsE=|ivV}>JtA;U&(#pfpMVjo1TQXu8Xx5cxv%_ps<9gh4e zRMWHf@EEwgZx1XJw`$JKd%qIh@dN`tPwTlT= zvG-gp(H!ULcWDb^NdB0}R=;!=)kpZmEZeTuM&oUqwbf_oH5Xr+s3xC{U)pYR(%Ph+ zqBOSFsY0b4JpKwvuMZuR9Ah$5DKAVl!?mehGWuqVK2SN5d26=&qJL;ZWU*P3_st}8 zKhI4sn0Bd9p!=;5l?aO_gWXiUG*qOrFLc!r2ny*81>7{?}DfTwbZP&*KiP=kAZMM_m&q zSo(kWvmBhgoKW-#Z-R-sd&G`bnY(+g)<_+)1*aKbJ8PVOrBk`!xNWXS7en>D1cGVw zer?u%sUb4G$Xv0$UczhA5wAt@U#&`(W5Hh{h~lKtF_;I_`FuR<L|Utd)!<8W9@|^hC2{lFj~puf+KO1bKI$JpapktE zf~x~!W=^Yjym4@Xm9;ls;H8@NQAQJHm_=O>%g|e%dh1H+W z>F5{D1P+9w$uzD>_?p^#hxTD;!fSs%eGmKs3JClXyCK0znOETa0s#jMcAH#qb&^}^ z`xn8O8Jk@_ufKCP0(O|pLM~tN8{l|n1n9xu$*X`EiiL5c9v}3({I{ltzzJeeeQKR7 zOToP>otdqo|J$9`ONS1PPCz$a%4VfMXWM1)!kf7n9)E$I3(i}!SRS7=vg=S!El0=o zp;q~rwEx>h)Fh-es>u)A2 zaAbbpUevZ71oqBrBOB|}0o}}qX65<6@H4zVx`pR9PiGso$>KaKCc4>k4QNXV$tAL> znw5y8n&Gj=Qm(aD-L_SpdL-9uR`ETlZ=W@tZP`v#n&&=L=dA&*E{!TUHl*0oQN`zcU>^zg?%M$!SzyxeV^mihnff z*RK-XZa3szxQ=&MB!mL)(JmHSf5!%878c`A`1(bEXL)F~y;3fAMXEUD?55;(1TF{8 zj@)gq%~HP|sO|P7d9=y86_2*7+^K8esEP=~qi-_IQXIP8^#~CPUc=lg$8|qWHFNu4 z!LV+6-P8xxdI`w|w;fKjf*%22z!AfhJ;5j*7K5As5bE~JVO|W5T2gG~pr%@e;Uk#= zi{b7{4z-G9teB`=Lr>3|n1$XdL3Mvl)ysfzMIYn08m9F>*JER}0gpuQwgaA>HM22p zr3D6&$aRlyvfL24XPWnzn?~B*D@)`_HCQ6q$Gln%=Oy~guoV^j`rc3EHC@k`2EG>y zxIuR>0WV}*e&EyNEhXacR&I5tiXUs0_3K5G)!TC8q;VaOW59=sH2lZl4)}iEX{34H z3A&+L~oy5Co zY!C6+tUMp$%aHS_fm$qG!R9VuMr%LcYL1J-Vnh=j2p>%MAxo!GGF>^l z9U4vJ0#E7iy-lR8cKI<{Z24!s`83a-eY-6H1?1(uK2osYc^!`qbHC4^x$>~WFOr?2 zkP6{PQp|rE82Py8?N;b;|M_&m%6D^8!tJ~7FO8?!=AH6!wEgyp2fOxV$Dhz=m&W~k zE6&YpE?nKO@YLnBaoOwXi(p}Q{Xm_9V6TdTpa`4&COY0YEZ*fT$M1U%MirGDU!qc4 zOmlNCpF{e9`zpbmwJ}cYGI z9woR})vSLsU=qiy$Mt^5_>tZHx+l1Q{P)H4IfBYbl)M?<#?0QFP(AE*`{Uh%+xbqQ znqL3lj@M#EkhlN+2}hsDBa-Oj&P>4VjykH}olOw*A7c&1|VIsQpUL|kLD zWD;EOJCLuN27X~gA5R8Oh9Cg}09aIF z%gb%^vq?ZLO612rr*6Qxxml8}t;(2vgMZeQehN{u7e=y5S}1v^Ldc8-a;6L}l>vrS znN5sT))!`7?bF-#?Pt8#HzU`Vc~HkNFaq~axaYp)bUo{%MF$m|232} zs=XU}h7(we9th1^9wfx&^lopsw_6z%{5)!t z(kb57$2Jg6v#R5d2_EcXm2mWW+#(vO8F>bVW-CVi_EbiW8LU(RJ*z4;^&Z=VELw+m za32X|K5@h>Uouz(b7s5UGt_vaE@XdWDcrt+{PFH%MTP}Fr^(+;(FvMv$9_H?yzRK^ zCsK4}LB!|p@hLGly0g(c#CkB?MDNtkJE`q!cj%ltV|-7C1QQu~xkcR8yoI~WhZZRK zCM*hl76O#02d60%!0@q_}P(Ey!1Lt&rLWl_48C+XbK7Gu*xe zZpg{bE5nZ0-RbdIDZ25|Kkw-hJ7;UzO-#z(?ng+ha0vEqGn*z4GaB|em)P*k3B+T9g?TkAvrGVPkr-wMS}P&-G00x27r8VU@C|A>eTDzM8ReI z4P58rj+fsj==p$kGBE+HWCZWR)6VU`>jcdF-CrY`>N^MpY7@xCE>&rgiOxVCJ>Cd;AUo@hDkx03 zoW816cYzV>y(6M5w)P`x{By{BJg!2k9i0wvms3;I^VX!SpsI5$PC7lPE9)(`{V(&L z(5FBCN>%3yPX2WHLQ{-c%k?Z1C5y!k%Js@}HiusSCgEZ^R}EI0r!=!h&31tz8okX9 z{(@K!>iHBsuBER>!B`UB6UEpqtK{DDc-iiI$U0qXVMJA=3G<0A_6s7x->dhxQf96r zLwme1kBeYrWDFLYIv8VC)fE19k6N2`h)>LFi_*(-belbhEA#DW++U=|+ zbo!{c8mfRdU2gGL8`6;fN7PvcRn@%@8z}+l^3dJgA>Az{(%tDHl`|nbzQK-pa$jv5XJmEMJZmaGdf_P-&K%gyg`3yzM@C( z77H4T$pAY=>z0*2SO;!#fYHQR4M53p413BT3Fn(J)>KhecKN+sFC*DO6YtAioLq(i z0?u>hqviTNv2A@ivy=W$WOnB*$3+F^ZhT2ElG!e#8F-{*(TSr;dp{Cx`L zv0xeJ(sxJpt1Ny(r6psAm-{Grs_sd#WDwfE?Z5^th=gH~nSku#!y7~YspoCl<~iFE zaY4Co=`9SMcltd%uP@s?uc;e1`exxeJ@#H1muv?jLd4t-V7*!<>wb(7FR@Nton~3- zbU7#3oI@|~(l>f?9QmvSF|rLiCjQvQNwBDUDQp$}xDyJ2q;IrmovaZ2nP_l6hjq#k z94mnUu@EbU=pX*t?kj92ep2^+lka4Lqi!BaGM0gHj;!{DV?BlUZbbx~{AcW@$NLD2 zApEad?t2SK`aRwuaPQIUoJL@w((jr-e>>tx)KhF#QtA9+K%)`Op`AtZNl}yfasMqp zGZ^0NYH}MN`ujW2kSP%wk})P~;7{xXTDve_egiB~5H?SuUKr>Dy@@JTgm!(K>zySx zO?>vPGThB}x6#_-x3939zJKJFUZa1;gx((N7^%N;x0PIb-h{!J!WWHcvc+8LD%5sL z{|Mx@m9^38#`Hdgusjc{WfmszMpVkdh2aQwpo_9ue8;BlPZjf|V>sE+r0j6a9Rd-c zGle4;LBqN0J~KFPfEtH0U0V}nq|d|>(yH!l?MwOXjyy-ACh{k`mMG8#yDvC=xMIl7maQ8B~0s+GwhJW)0EKo`^9%D0>W?>iDwtQgAZw zrM5=Q1!yl-D~5C^xN=o$f_H$|RxRgmvYr0+R-Lv>jpTNR>>*=pH!rx(L6S0MjS>R8 zQ3q#`4YY;f9bKp=zj+JvfXV0)_TyIPXwXRPj$PabhAwiK)XeZ&#zL8@dh^WJuk-J@ zZ3CsqrQ;*G>&PhQH>o((1;fI(&B$ej6bSh_5DRI!VwzLSIo{D*p)*Mw2&+y|A&Pb3c-IoT*vVwT8>M zc(>z1HGTt|<#t?)4$iR1=h`;T<`?TM`Z;olyyu&?N+hx1at)%=(_Iqm=zG6$)FQX4rR z5_VRbJ5`%)V%zbC;^XhY?Ip{tsT|_v=CFkYQZ9=zO*PfK7yr@?^(0CNXmpUe+9IJy zjQ~AtzNd7;IooC4ZEiTU)WpZYEczE=(uHKui3Q8%3%7V7_A6!#3N7{m=BY{1q?DK&www7O zR9{cG)XYu@ADl`baK3hU)gci%?yYw8vYIn)mstbU)KGOAH!OwMA~4{u9~ zNzsodsxG01`uv$l{Gkv!@Q!2ARgmVVf^dfw6|oh=Gh1jn{IW70EVMXA*>{!4p*x~^ zxiB=bqvWY#iN!IAI-a&m-ty%RW|qa$DU!>f@Hb6tL#6#}PW~MQqr$n}s;jV`%W;yt zO{PqrDLm&i;~&yhMIkllFPI6YhME6zQsP=Bm}mp1Wyw#Sh{EVF%C z;~tDto=@EQ%}sXas#yuXW$U@=v2(+T0BiS;*pMkw6(j9JHWK0h$dL;8U-egy`}&~t zc7rPYPoMoxP%fE`EI??Ew(qKT?)VJNz8|6c{#*LTQQP$g@%@ES|M!}mQY*)+?_>^a z_N#g6=6=uhoVZN(A<3Tt%?yA-T`QtOI0-bQFeXsK0}%lA5*u!oe) zWiE7lwxHy|vBil%N31smG3nC{;K$Nqxos;yqidanQKUpHbIMk;qvG)gjgfr0ohR%g z2&A_~Xbz-Px04&0kZreGE@y$lIB5h{Gpr4I+RviNVQb*cwHZNW=T46jMU!>%oI{%e zvR>;hE~}?W9+jF}8F4+(tJQ2FVYfK)5}A6m$_x_Glf>)v35WPT#PhcDMZ?1-yPFN` zOm%Ht<3Sk03L>q2Orn30zYt?ftJMqL9w(um_2vB=%lmWQ`y}$P@rHTx>HD8o2;0?b zRBat0=eUDc`{NXX@8jRzJ!g!bM@6H($=2y>FW_o(mzzlh6^3v?)}{<^W8XlW$WYYQ z6Ytwamfv9W%uWE#XU;E{U0$a&tl3^!f_Y|_^>kxV=v!}5qKBPt*Ks<_Ug;YTqWyMG zxjRq2FQ1~_CZ?Q5!bZv7e)(;$KmEuuUPUv!pej|qp-3Teh@_p?F;mc>#EiivawxB> zUumd!oO{fxrGN_k7&yyxS$m1Qa3iAT{uZkDYX4vN`M>AbDjk)VEhA@Z%ttnEuT!I3 z4Of!f?5GBg*l(Yq=H63DXXmQNVE<+<-C%iY;Im)s#!aJ=vYSBWWKn7Ua?5)zqV_iv zcB#V-f)6j~a~W&WKWuZ0YV!ZQOG;C6SQ~r2*wF93CDj34Jx0iamKi3L#tOnnkHq{4 zB+YGo={C;2G9D84Fqk@9FHOH&egaJ1@RDR1K!f0nPmtE3OI}o0+zJOly|G@CUp%sA z%(8F}wz1*x@ps(DYjJurY64UKCK^Jm*zW@puDfI;rE_tthk88nVWhjYjoOdR$kwtADtlH2L{5s?%>7b9gwn<&_nshBepPiVlT z&uCm6a%=tSNS9Y>rsFs1mYAvMR$bS5ANN3)Q}z1)Kg?gHMAP!q%y9ONj9;AQ{<01- zs)`044Hen>q*-pN0lo$Wypl=^7c;fO%fwg^TcE9oTrg}(34aGd*h4uL41}Cu2yM!= zoG(M}9o9fU3&=tk-8*W?hy4?x^9h0sm2*GtOTRZ_D!|uY6pyyphO>2`3T?rN#n~du z>1wP%Iz2No>;9eAki`va4eKVQOHbD~I4mV%V(0`WX};#sx%}rga7GyL)dCi=G{(Ls z=f_-3b1l%F{@-)kC{4?R)Le!x(IkOeUSz77o|!qIcV!434&*`JTV(u2#QC+bKxHPG zReIYDtsP4uyd0Em?V>_$eC&FpW|qO3fNA#=DViLLAuc7Kg5Hn>`YXMrB{{~lO&-k{_1Gr6Wf?Vwt?4Df9jkNW;H zbJ^(sKtlH$%HZ6!AG{2|9f?VFP}VG=9E^A}RL;vDTs?J*lTV?% zI=v5CQ}|Ks;kys1hyl^(7lxx0VimD45{EM~a$>`4bU7F1+kE8YoQ@L5ji$w`0N4)Q z{0DxV@&0av^2;!#0icD1?^<6nP(vLNG;Pja>SrdYcVZxgw9!gYv}hcNihZ_986=oh z!7^Uioa*v$vkAQLiG>I@Yx+ou-hKv3gs02TO2u83^v1|iSg`n#Qb=fG&6rst^@K2z zpdI&9`cY*7A&;|dMW~2Y-fS{Ya5BjwZCev(|G7EGz7T(+O}?<;ZBgC8C)MQIbplt?+Om-BY4>&pF63R?5& zfHiCRJC9GU`a+*fzxUYIf7$S8fHt-_h) zw_VfcjeO3osxMvS#n~etcZY9gqy7onE&Z&=rOtb7o$UacWaGSupdHtiZJ`pUxvm=1 z2_GC}GD{-Nz?GVPmS@O(R#Vo%fM(O}Sy^ZCRK@T+i4e|#9jr_tRBKN;GK~>7A}u#P zCAUYO+?Y21Y;M*|NgaCW%a?B#as2OOhzz?Uu!=i=J$OnFfk+iHPxKeyYDGi8J3t+1Z`!xRoY5u3}fY|mCNLJJ14zkGkMPJxzMFEVYcgMI0}j~ z+-oBmLf@Aq(aw4E-U!^Cxkop3$vSesInGs64NVJglYCu}bOz7QmL(rjBaJgdMjN72 z#N)~(5)RBg0w8wJ1Ef=_x9{N^3aKGnKgAIewNAQ{io}2EMk7k(JO(rpcx0GeYvYs$ z?dqfRT3NVdFuZSvg!7Il#F|!Ur5)o6P!xl)xUaD}0;B(E@XehNuB$zTqupo0zu;oc z6Lv|EBxB-)mPQ1k1!|;^f3hY?0M#q^m@ox?`9`~ez=Ue1>?$!4q9F0?fX5MfY-jq# zq{x&?+d1%kB`H&`h=hfhva&S!K0>z%8HMw~Dy2A$#Q;aDIEh$r1ARC}G<;E0KD{mF ztd!<%X{EfZgf7)wb%|EI-b(;AN;ybSI>EmHtPNfUjW)uPp%O$65;o&&?9X!mL*|UQ zSoXpGlqd*@06;uM&={8AYz#9x4nA)Ra;=?gjA~2X7>V~et5^<(h%uVhgwYZ~GC%em zk~XDE^11+LmYKm=9jqBj6+~R)kcA3UGKL4UNR|haJC^5i(YV?;^SXGpsD4;Zs+jUe zBv<5crYC>#s55Pu5lV-m&E;a!Z1_UBhVtdCaTww%g0u|bKMYQN+@TTw$#)f52r^>t zLCBby(pxftjEv}$#CX0jcljIsHdM#yT4D~tX7TNxu_rLPQzGtl45k-knhbKR zu4W}G%M8ZrkfYLb4cUg^&@7T-+LB=%g%1}FtAD`@frN{g4yl=2G@i)8+St4I#zhZe zM;D=ES)pPxRxKvWMBMo|d>bq!Sw+*b=a#ihGHKU@=b4+JqKPbJ`E`7mJd43(E-kVv zz}v`gMHnE;oww{gw`CXXhr2LyRg*eWtn6=!Y^zFadNcT>X9M-mT#h~?Oo$dthmW&1 zIetex7(Oe~{$c(L41;>6yu;9GQz5+aCG#Ss^0R|OY}j()3Wz%pPcmU`kgB|oI+sKu zf3&ll&{U4d=n4sMPhZDQp0)>VFFw;NCi_ca1xJW!VIo?x1RBRYcBKa5|IGqunxrsm zI8zQ%h@i#?lobiMp|P@wPg?uxzy%9h6wiwRLjmrC7NDc60?HFEssW^M`Non{HNp?G z)M>*VGL<5lOs*XWZnx%z{1M^E<(g6i*iDq&KIU1`$%T_bxM9A7-3{{m#R}&du^xNO zye`^l1&iE48{ZskG8&*Id{q^u)R(RVkJKP(yNKa!1bUQEdbs5DPmBTL(esG*twAi# zgM`t|s6QDidaLE5`5_$ADtJOXm<}>4=bTlHhVCa8zLyVvd61|jOtWw8MX~R;%&j^^ zUep?yQoY{uuINe{V4PGl(=dx9!4yUf7sCWT6VhQynDbYSaYjK<lb;DbJ-)LxyA{mEu#BGmAgHN(F8f_E8~PimIr{~Op$ksOF-BqH!tik8?#FQgQF(CwmLb)y_SO461Yj2l0JH(TG4;xUwz=<#2J8!7we_ z&CGk-OQP+|7}9lHH(llB$=uD0sH}~Kh~W5BfQuJ~0oR~Enq9J_XHayAMbN6K5Jp%x zT-VW{pvK#uT+3c)zNn5*6D;=y4eOoV@5gqWPj@XTUnoMuU1C+#w$CDe62|&B%l1!) z5-v_s#b7ZpoPXm1ZTl!6GEc20%glfTEh5O>$-+5odd@nAL5gMB!>g#5b`q-DETd7d zQW3V`mOjD}{tu+6m6lz667l)w9#p7bb5)n*8yAgTXhld8ck^qIf0a#UAqJAgTcv{3 zwK`R13u=6J>p4{Mr9EY-+>M}T)ur>p9sv(LGQpJ7V-3+-LHH7V%gNwrU5X$0R0^oM zo8t;l=V~$DgeK$0zr~t3Z!P-;kr}gj#(*x= zem-pe3)^H2X2ef^t1Ky|cXlip5V4ewpI2_kN)}n*%XqiITO5j-Do{Bd_l)erM!=ULBd{_SJjt_OlBFwS5|B=XG!gn zvYWp^{}DG}@@c(g1ZQ@!jl@iVS*K;b;GS}g3Y;JnPALXU9v%Yo4wn2ouI-ldwD(%~ zkALnFA&Ki;dv)UKE|jD{<5N=Z3<32+?n}<4_twJATb?rS(sZ8a#oJ}1^)*7XoJeyj zZ;h5mt;56CGx1&rio=<-E}L7-WQNf5boY<1KR+U)8n?tU)n*8l))*f-3HVp$4=waB z#tDtIQQRD(DaZ{iWJxfjD0wPSVGY6-TbQ_$24J>@zygc_P*zqM76WWWlBA7y#Y`$% zOAIb;0IW^AHKde4Q383q2?=X3v`@~=r z8*U~;H+;Q^InWTVi*4tI=jPr@ohvGm*br+Gc!s3EMjrbbTvkY9vYn*RUOku5$El=5 zkr>x7Lyub@FK7PeiyS3o9k;ri1Oet5k_BT^L4u%4qT2=|U4$KSp%@PQq=vEle~KW)Yf+mQY!SkRy-u(v+?;rwU@}_)G|?bzl}c3YqYILm3-QVk*r*(kzKY6#;F;U|%?b_n=V9Xi6oBLMB5r z^@%*=4|(U`?W__u!E@T6edr1Gi!=@d6T-%Ak9b)plC- zFaRFn-x~+}(5N(F8y4)@`7Ob$DR@sNMF!f_K;%s;%%h`C_4WKC)xhw&*a*tZlJW8- zGYY%9v@IoS;NTgQ0vZXrC5uS-v=$b)HQc2dqp`(Bv7p3YlW;`hkx+b7JK!rFC}y}b z-ITa?=xkG#10ok+uHUlSSZ5W{_hiu*C>y%n=DHK}4c`dA(tlba6V(9+@fR= z8|^<-^kD>1tJT{xiu)h%6Z79A`oR6I(h-y}T*GAGbVRWb>((9lZlDhlr%Vu6qRo*e zLjGe+h(E3huZ#5|poO`=bdXm$`HVb8S=bg+FCP`oAsq=)*xeYVuNM$yR&;y+FuSx7 zgqx4bZl9$+Ty1_@eeKxMoE*s>qCl%i#ZbY@JkjvdM;h7ls~e*y?K_i%JaTB-??Sx~ zhbcdEvE>QYabZVz*_8sQWo)qlh@ZHfIdg=CDVmp?MCvJ{RaN{Xhf&2gQKZE9;cLbX zvEcVeiD^tbr_FGyvc!m4IrqXl+mMP355v_PMq#)h`_8|-#B1Wi*y7pR?^b!$X_I;! zXvogBhto^NF}XQVZ%)yT7;>olWz-uw0y7Ew3s+F$0c@c4!0%hTN6N0iOkh) z^w|_k=9Gr}opF${Xp-J(U^h1B>vu+)w{z)g#+e5~K^;S?cr39?amF}KEG)W~>LLre z00%Fk5VIFQVQODhq1CW#r~(Ru?1?Xpm52nnrT?1c`n|cxG|6&f1Q)T?##o1zGZr}z z2I^dAU-_k9Y3dHekZ~qh+%zZ4St(eFzaq4)-^|Bu(L?z1by$Y!7v@)NOyt$#m2!ZO zH(4+cHmiFxh$9-Zw=74K^d#dS0fV6X0ab%q6WIYvF`zIYVh|IZ7M2E16?V<}dT(%U znf(_wVgLq$nI2kr`jy}BLOGULbc*CbI5bOz3RS%7OCl0-fK8_6I3Ca@ z?qB!L=)7zXo7yA|r^f$Ej|~1Gt>zx948@3`6eYl*iKr!aZb1Nzb=!dGOK{4Vk<~!h zV@Py4J|pBX5=iz?m}*spLR{*0mOrn1C_xo?W2+h0 zQrcBpepiyLDG05l4A)mz5`Bhn*H!Hc&*^S2e`l(Q!NJuXwl;_T)5N=hvsXmybIwlU zpx9>da$fA>*q|1bB*h!)J(cGZ1i(i)n%tTAoHhbe6xxnkW(&Q_)A>`!N@u{B64ZP6 zBi0mk${!q%l9hNHO>j*zGhGFxabLJIm5JA=@*r4`7Vv@WNb)82N>Hhv^gA3;Kc+0- zj6T)yioadmMm$<+(hRvxKXHh@6pU>B-ChLcU_!4b6u%YS$=k<1$Pu?~W06M`_LQH3iGr{Z!7=FX&UQ)Vl7E zVq@3HE^F*$5|@8B!i#J^csEJ$wfFRgqI%{P70HKP_P+SQe|(mOdqZZ`Qg*)lwZ7vtP_w9Q15Vu-p=&nFtVs8sMx zKP$5qQvq;TBL!~jYWPQjl|C_mk!N*b5{nhX;k)DZKqcHsIBD(QcCah8YRfvyj*RC0 zZ)?ernJ}yC9N-4(*ptPHrL*}x(mxuyBad9{|9gL7Zr%2A1dME^3Z{IZz?3&5gJnq6 z+nnQ2pnmOQI*!^^a9*{|-|3K+Jl2vZo8=s4XNE`VU6GP;Lnjj%-AqGo^xd0W@7(LD zBuZd9Vw;(_!|S=}cDi{^-~#C7d6vfIeZOx}pY%W0oE7S2MX;mly806*XbytCn|0pT zIH2$luJLjNlcT_e``AOMQQ?{>u)as)uk1fV+`S~IV~9g3>X>oXIMv4cn&8t|4dfD~ zal~lL>0n2$<9+=@g4mUcV*}g;b^*qb2Yheo)!;a8j#~vKP4$pWWUgZDv;nHmH+0E6pDM6)Ot|Y#? zq0_@)OeEH9m%nFqv@F>kTrvqSti^!@XOf8wo5?PV<5;G^YneI&N)55l8)T%lolMc# z!(pC)U+=PDve}{bmP~wtHZ$w5ncnt$*nWxoVz)SxFj-(8K4(mb+;Ad@PZ+aRMYpus zP_AqPRyh~J-}I@RhjQ9HSU6y-t{^MnV3p-zxpMMof+EJ5Mh5Exs_|uMRC0s zf&3=)w4LcOo#Kme{r31tv;u5~J*PD`%#O{gQ%wEg0GsY}-tKWkl4cfKG3GieUW#Q< zW7-JFh+e&duRQc!i;45UIRr~f%U>{dYNAetLX!Z12oSW&GRT81b9;J7S3jKVlM2T< zWUV{s7B>hO3Ofh4KOs!CybH8N_WK^~rpMS-))<$o8CqvZiz4~Q!GXId-gBEuk0zcz zwjPykML6Y4e={OE7=pcY+E6p`s(A5ePP1KlN_0DrBO#N6DKZYpkkaSL zq|4uuEp1sj2IsdJw_GAdzc`a}I)M4}$OJ~6s%I}R(D5ZrwD+rJOtPIR0U_S|N3dAS zjC3~v2M^Cs%}1l+&dQ)ky_T6Zs50^Jqlp+u8p*_1m$%=VrmTLjg#}>uLIA$h7fk%# zr%%1InDEOrFT8R3*exd8f;O3V*y_^d%OyocQ3(kL`fcAbG|FhN)k#Ykkb-Cl-$U5J z_887T?r+_ls_myn$oZFRO8ohlZFs`bJdB4UW*rkj%aV?#7XfhbJ7!4>(v zp+`{r6Qx4y1fx`7=7*FSHlY#Ag~%*^kKe>DTpFk>wr1aq<8_6pkzn=Ls8NzEi)El? zx|POjtSx&@@u#gSGq6GQC^)%4BgaaGf2L5r+;>Y<@euJk6;)SW3T`f}t zkJLSIhzi&w_3Zf6&Ml}=qTkOBU*Sr))&T5+rZay{DK#7uYau$FD?qbFupAnoNum2x zEJU={RL&!@OFpbp5#S8LJJ|UBS;MUkQhL<_}BCk9Xpj#-QOZJ#}V!=DM|52oxCS3K>T!Ybh6}*5<%oHaR1xR|?kxw4`yX{knMkdI$4cigc{6fAR+g5C zy#$SQ>`~{Xa$e}A1sPd6=DwbR+QaT4hJVftG%LTv_V_0ET&M`Htyya_X_v}Z=np?g zay|)l`}}ohc<nxDteNdWJh~)^u1b8l;#e_)yJsMwrfnse&4LKbvZ? z(aLg$YD8QD`OFwW1qn=U8z-l-nMIjywa>ityM$XB`MTb6(s~qemwXWe;Z0|1m0HM| zkxH~tTUAL4W#4je*)DxD0OWVQ#|=KO!>V@)8;f{Seh4oEv&MECsd&+NyNlKGQx34i zxIVi~`+Qn%y5rR?i&wh&dTPzrrbq~KW;9XqBzfqz@S=3JdE}q6r5D`{OxuWgiz%CY^&; zP7o|hKbC7T@~6uG=F3PYq)UEBcVu-Xlr|Lgk*Z|(@p|v~>K*0TQf*OX*?YEyVl^jq zW;_n1q=0~TtE+;5)l8zGue}k_+Z|(O@i|$(1xU&<=v}V6aWnjtG;)$_;!g<;kii+@ zXx5Dh2|=)JCWHlnh~fJldfelibb!2G2k|V)I0)#pj7whWd37>@!79RLL{!`&(nHgIPfYZ6D?jIhwc)uqs#gUd2bq9T6`dW~T z%vq{+Q%_8^21ceLE4cj>nfK;|zw}_-LMk`@6cKIGFs8+VlBi%lS#xUu(=;E-Jr*k6 z%xLk|Vn_EjE{}Te4^ditB0oMLyvtHZf*i4vWLbi)p6kt+4eA4jqVOr?9dl_E({_=P zEdEAWw`u^PJEsxr&LEK$#E}&B#zxEv!JM&L+Im z!CwVIwd$EUMb)iYalRK&ea{=_x4%qAC06F?o4?*oUHHXZT#$-9+2!rsMkKus<@ts5 z954~+3QlAUyo|cJ-c-Kr@Fh&5ycn&I)l=2(;0p=}^N!H@?HsMNnIeZ;*q?`2*1KwX)SvqHGSgCLc^2TN<+>Cwp3H?h5U5F_RJ@j-YMO;^C zJ)Epv5P^A66UwOp@S)4;Bn~$rETo~`=1%MbPXxcqp>pO(B)?X`WR_z|Yi&$MJHjwq zOar^HOue@0-*b#Q*C&*zT*0xkvMF`#rpP*eaqV2w4VE9XT6zR6EqFy-SFTP zTepCiGbgLr8Omf^PGPR$iX^LxvrHDlEcRJM7FIB&i$=Ak!1Xgio3OrMpCDzCcLo+f4d+rjNteZ;sv_9CMQ=TT@;Cg4l6 zz^dQopNtLp{x~Wt8aWd=b`1e8j6(H0TqE>ZN5VvIxtNU_g1gzyO>cK?SOMU+chv*{ zvre8|b2OdKwR(Ea6CGjmy?0TXA~tolPxQL7mMvhDDv7K^WdwVDDZP#siZk!7C^OQ62r%)VFWbq=p_I zYy@ndJ$fXn)e#EHwV1L6!P$);r#M8w86Q5f{fRJog%=hUCKh&1&&aUJ^?kMhM4eG- z3LGK=V*rEq<>B%uP4uC%>!JPuYe+tEX=7tjoXgKh;h?QQjheBo}bYKxb#gaUZ=O+N~-y8M6gkLc>Tsl1VUx zMh6GsN8-qi09dM$ipt#P=2V&JUmM`>*_YOHOS4$57k1VGtg8eSfVMsDn|fn4b+u6I zn^FQvO;jiWgx`-QqqT3(eo}UmQnIuAVv}zd|06x@*v_#0~{~8Mz825hy(OyBZx2Mn*c!_ferfae zNS5giRp)RBfz5k-q;q$BfOLKTgGQJ_n6>C&{FZ3(7`k1S_sFn+|MEDV);qDk%&*7i zbTBhKFu_aZ`&{OixqYGc2xarhXe|4@hcZ@QB-{SCWlfvAA+y)x*#n4I`4l}-kewJ% z>K&4Fn^mlMhh~dpGqSVyp?S~T8{IyyD`{`oE2q&*y0g%=$D@LWd41a!eZ54JqAuFb$ zT@4e}a)8@M*}QMfa3N6d%g!xvV=M&xFm%$=?lU#OkQb{-$aG-5f({hKia3G+JSg1j z_LEPQPIqwrir8_nJj;PVSCk+O|qh87I(HH6+mszE9Z5OCfiFg zvh#S&_n(yF^WXJp4o+vBJscd@rq-eq+DOyQmr*JpK<#MfsgyU5jW}s zye|&7D*ysmE{b!$Ul%|p5t6IW{?7vu&1|Hy{qj0zB{J|h2ygVZx)TxSEFtkP~z zTUpWhw{i4FQdCs*Is|N#62*_;Zd^K*Y~z7Y#Z7NWp$W53c7 za&t7z#m?XN-^&U(h*fKsJgy4D+T5=x-(!%JE|%j2W7SaAO%z|Vqe#NjN>HDbS?E-c zQ$<+Tz=S&;KW-d9UenxZk@+hy%b*sJ$BN4bGklAIXHOA_lVl(sk+hMnGF8u&1tCrf z-$MUy767OmV9HSDI_YUD&;Uvj@T(KcSHHd8;cs$S)+|UtFl#P#_E}LyY0F;QB~5dIpEyOApM+uYxVZQfo%}>eI)Y>x`xBreGd4juM_cCB-{Pm9 z9H$ILMh>2ARE$Ivo%C{}tfsN0GIxfe62wQ>=eff$h>JP7#`=dopx$H5tZc>>WWi4& zCZ);BccN1%rY3@gP~i(M&9d+rZIuI;Di8Ii^?T;-UsTXp%D)g>hgt*LH z051{onxqUi4Nt56TIgBFyhY-CDb%KvEvKl7efoOI$jaW6w3>UvKsY@$Knn%JS+SJK zY#=1%;TWl2q0|HPrqhO6SmsW+OLWnooa`(?^s(;e%>&Uf%BoJhI27N|QY{i77RW(T zh{$*@yD?_bpH=8ejL_~pai(2n1oLO@6IHBWkOnZ<8WK2XC%ox`7c&>VY% zJu)PXjjGX|2SeBu!_qCWkqZx%LYucMJ;6c|{K2Q|?eFEt4eBr(Yksl0seQEMd!vKR z&dULYCYQroU_%H>85xN(uqih#RGH}D$J(gYC^h`JBn2qwBRHRhM%Q2IOEUb(4?Nmp zC9SMJg6-!f%z?B^w^@QW$@1>>OO;+{>dR$sTtb$ksl9!6eLcs|1;P-CTp55?sYYis ziW5Q+8asBxsg(K=ds4dEhWm71u;Ukdxh8-V&Cp~lU|Zit1Bzt8>Q7QB(dO(5w&xvL zZ9XesI-{@9X*b0S`U{tBm+f>SOjxaAmE~eJLa!y8kpXn0jRMpoM9TYiH@!&vxTp3! z(Y3tZ|13!(7{Pj2_rh4wCtR~}XzP#9XeVHXSYB@W$W@FUuCfO!7m>zK?Z?+E5l(1| zHR~6tRcf%N>9p7roVYU14!GGfL;4z&`)7{k4iuBeEe;P4kzQeFzA!OhxyLGYuSh8j z%@5+nSORaqScgv_iR~AWQXAUvcoXAH+GgFmpR8rGbG^8*#p)nkI?qZz_9jdu6Uvlg z%^KB;1(0r6x+^WD;eZN>fKDrzgm$mzIz*)X0u>VKEe#ykvGZIk#08|a>>I*8= zsFoI3b=y~VDWoV(!5Fe+PQ;%r)a2LJFkYMBnLqBGN=H& zg+gsi1$bl6u!pcraIu)iW|!gsbA)oWAzid7DpcvvkpRXxgO)xX9Be_;v6P!6txc;= z?SoqCD;tsaS{WL8mW@~|#V`xV`f{8-E3@wNNP~Y0~TPuuB0l!WB8_S;KG zvA?}Y99%KW2fg%TcG@aFod#M$!LuM z+uY{tRKo#;VUk6atXr&Jx1?w$mRC7bO^Pv%CY%a&QE7xWkz++aR43!=-)S>p z?%B3B@7ZFF+1)Tpc3!n=X5Mf;NwP}(XNVj9m!E_6lv|53Pud|s)jZjRQ$#?%il^B# zN0_a5uzwx*(?w^J!uk8~2u=x*90Nm|A~%uSp_LUNW;fj4efr>iJU}KBwFe~OI~|6V zD^q>k4*ix~;um`OPP%km^*yIA^3SJRY z`F3U~;$Yv{v3iccapq7h{@5rPV-#iHq|&0!tmGqLf*`%0Jl52lcrFz(%ggScrjRgZ z&QXosvsJ8BIajX5z``6a-#QGwv)$Fk4t^K9hsh*Q9EvnTdFwOG8s|K+=rvlZksL`2 z#@!KMO;OLNuZK)bF0!L46Vnlvn*P!dHetaYzM!Ysr8bmZ-irZN)ZC;X*o1##Vk&;p;<^jh z1QUA%n=M6V2&H$2OITns&+mloah@(uO23c?bY^wXt&yH)^w1f;pr6w~qC(eN zK5@dc0vD}UzL>h7yN-lt1k9lvhDPL6T2_`8^>He}=}as=f~49)`&c`1strDdmSLLe zphLgQJ>jl$iA#iIYWUPpm-ls0QIDgZ2J8zB*}#q5?CA@9Fz06xSxJp znE!o_xpjT`Gk1}O{7Q~x{1KT?)LyGzhz`rL)uE7Hji;WODS<+rBiC$4J5XDO@7unV zdO`w6tl5qy>63Rr59=;` z)1q%eK=jh*mQy_Tl}Tt?y26gI8b$&nRZpEXi9M1?pNf>w=B1OW+@or|F&tyR+LW>@ z5%JV6fC`ndLD~aVaL1k%zJq}2)0l9hXi$rO4enF>s*Yg5qLYYBtgqt&w^jKR>{#`? zU?hxnX`4M`LbvvJk7@4DHy}h#+1o*6&*Uv<>>NBv_Lvic&JAieW2G!}3~9P0GPv;8 zG!qCm*zgoY-q0z#Y8jB-3%{W-hP3Yj&P^vWSH;nA{??A^}DhJD{4M^L4W_cy8fWq2vZXy9%?%HqaA8&o*$QMPq=iAG!V`MC%KQ}5lAkjjkw^M z(-O-Yh*znmzMGC;>Gfr?S_>svax=L@LU@7iuH#d!AwQ;@4RRFk)yAQ}u?D(n=fN27Ot8qimk1GCgv=tx*CpX{yn}uQj!=5 z%b9?m*L4gu2-XYz$(q-Hbi&(<(raSL}QMie;0JkGMa!yvRO_+|92E z+ruok$U8Z)CE?%zX+IacJC3Z87aHUS=oVQvCU9dnd;g01@B#PZ;nU_r4`loR()KsE zQ{cxTH-I(=nzmF|Sd<)PGrD`)w518&m%6lSxU?HxKwk`nI+fwr8UmC?UCJ$^xP`c;7~G-mG81JkZPt82e+T zZLb>9S?$7{`EF}Q7)T{mn zBV$X;(19=`Gf&S@AGU6#{rAi|UFi}9IifFfK(JyO-~J>xv@4DuhwHvK`0kL7_UWwF zC+5?|`BBJauadUQ$)(-V@1Z0hfcf_rWwifM z<^zh@#s}kg%!XazjYlf=eoK(~LR85pd}zIMI_B}&x!LvZ(CZ#w@7UB)uGPYL^L&4IT{E<+BmVWXEb0!n%dsR1SU3a?rQyVfcoC6WnXLWUv5BP zQ{06M2wry9+dtgi-?f^DZns-*ktZ~f?<9@NhOic`@%c3MR#;<$()eXNCE zut^4fX;S|~R#WSbZ$}0{t|y&*lZ3tQ>+DxJ|FfP11icsVedV7P?M(uTT`tCNm6}n~ zE%uwy4tl>=o1*};2N2Q5$mGDiH>Am%z8OwfYID7Y1!P=SN5HLE0oQP#c>vv78Y%Fp z{q|>`f!A?$@WP7Ayl9Gz^Ys?O_1F*N$9D8q6x|C2vt+$b88{ppLW0-8pdluzZY%iKnaSG$- zUb)kTSvkAh!@YTxw-v`fG-?}cB;#AAXJ;3ewdU#9#F*9(-tL2j$RWJb39#wHOhi89jV_kDf%GZ&WSE%%HKhw zMiZzNq?gKzphtl*^kX1qTeZk?6mE>4|pRd{f7pEP|eAXHc2oFtAz}7;`01XB+`% zvne*(O5KUuN?u&q&J7ABLX@u8j2vM08WxFrCj<*xz+=lMJ8Mn z2cdtDdtJb_N>%ke*~tG#)jLMV)qwBbZ5rFQZA@(2jcwaWW7~Gp*h%BYYTUT7ZR_mk zob!Lzd%n!4S$oZ%ja%3CyKNtGMKPDOn|z;HFS;M~KkgJiQ(lPPxd^?^{Qh}eN&u>Y zk;H*RZ2S`u?62keyrcVYyVVA4{XzzU0UxEG$(OE&z%b3o^$k_f(~0YO2j*kj;WG`x zW9Tk|b<^*_3Na_k(D7K_)GYFn?~$Ia^)HR9>GJ&!qyCyp%EyL1p}!?>HkaK_Tfk`> z^CZ|K{}nUu#x09JuXlJQ0(Il&Os#(u<{kXF$4qGE+H5=l4ru@-_OAG9S20&1u)2 z3AOoZ^iM8McVm|<{|&s|7jwj&W^e78srM6#{!e-X1J<<5@#(3l;m>@IQ_jLO&Q)IC zE4;5((`0sTS3N*aDv{u_uYs=_)%U5Q-114les#Ys;IOS?>9nL9KTP2-*eWlNR;z2s z=10xuu$!Lu%Zt``YGYo;o=dbalDxx22Z!Rey4?15)^^*pwaZ_*z_!?{|HeU~*12kh z(NnehzJg*jk%t+}{lp!8@>c%Hh8a<=JhC;jdjpCBLl3+cq*s0_$0b3)phw>K$RdA` z86Mb``qc8dzqz}@*=`%QKaqY5>_ncoWCs?qm#o+tuSIg)0E^aX9=4YVZa+qt8I7gR2*TE6zj}pyv>X6_U0!P zt-8GCC-EdParR_`?=y7%(_Xn0FYL6u>H9%6WqT{)oL9Qfg>0?3&1ACn?8e5|-^KC# zQwKF`qldTjI;}B))+tfCJek$MB%)c;LKBQunnv1(5Qrap^Eemnrvkc6(dpLZHC1rM zLokXKtP#{An@TCK5+nDG@?#bp4N&UflRrclCk+jdjA{nU5NwWZ>6GZxesYRBpP#45 zii6i5A7me&;+fhyN0kvZ=bWNXq#>x*ErDJSq;Krb4SU#1U_Lo^!V;Zaqg}1YH@w7z zV{F#YVZGkWlbNBJrLz*~$%LynCQl|b5?DsI6tkDvp^Br- zIA_-D!W$XVijyQ;{OpXMN{Ozbuo@{{{YjE7(B01YHpk~bFw#I@vIs7ppK_|qnBG7i z%?vMHu41|8_HUNF!oO|V<2cPH7L&4S(LqE9(ap>-6Eb)Gy&2ez6O7HIYIw^q@r%7( zh;kog1SK?1fqrQy0nEy>x)on*jm(;T>=)+bOu2_)0`r}6TBOZN$m9>X^4K(3CLLnE zBM3I}Rn7<-O1)>W^Rnp1CQE`MvUCy3$>AQO6m&}*K*JU?i7PrVku;1%am?U4$7ZQi zyC`jT-nTQ(guD_mRijfL&^Mg9x4c=3;2rmMj4iz1S_ zlv4qIoW21?zQ|@5YLo_(k@fF@S{1T{Z-`3pw#xTxHy=XfR|S0R0oa;-cX03P>+5V< zEGtB-8Ci~)tjl`Xr0=f7XB?>3L?;Q2$p{cA1XtWh#&wc6QHkz!NAhSTMmrG~ua#aPCCWNA~b zUuU>RS>XzG>oQqly0$24;q!GKIi(WqU$Zj-oQpcER<;x*c3w$wRk(^*Ua734(2pnz zZMc7~S&37GMa2D$4Db^|w0%VsvK3q$&q1>7YGI&Z)GXkQ!M7wj#6yD)6U;eJu7MI} zmw*H|XCGF8W6Y~Chflp#re2lY^L44Te2GLO%2q&F@nsUp$KkYOaa3W;d)e7s*@mSggsBowuB+~6*BQcS| zxTDY$&GmNSW`5n&xt8`iX^}=*>;pf%i~GhoY|x4!aOPKLC46+!2Evh=>|X7}nk$6_ zzdD(KN*I_tOLZ2L5}-@I8L{;bc2&xj%{(=TEhDz>8yX>xWR6(M*%FKOx7Cn4KL@AS_vCs%hUckeI|EdyHGVR+O4T zFvpitK|a!Cwv!~pY?m(7sGS;B*{%k729Bh5u`#i&%qIjYTq%uyFH=%Rf>+s6d~Icg zeup;tp21=Y&$SK0!4!cjQqtdNgMkl8-jCWgA&Ws#2*ZvY{zdCS@{iuI;EkCZ5W$!* z+lk~#H5x64s062Y+QZI-Bo5!eK3#JtdyF_G9ctNE{Vo>{Os3hY8uS~luQp|OyYUFA zPyRcP{9VF0(&D?rxke|?%ggY_+nBfQk9|tj_(N18w0@KT)SPQA1`Mf6BSlPMx6&dM^FzT7ZpwGIVmZU~r@2h47iy4C& zY6_Srdd64!!LYP%;$US#1({RM%zlMM62YJp2pc_=lM*BMe-kDDbjS zyFBW^QAhW7*wFbfiHn(30ZJWibdsSguPadP-_vE0ZY<48&{ryv1A@xAaPbUaYIqX% zC%oOFH1b~Ql*q7Xg|w2YgtP#SmSgDdj@?NO20ix&V@@FLLc+S_5KoDLdz|&>mqo86 zv02;ZpOi4jB%XXCO$55FS2z#Ew2*Yvs-;#CJ0LzmX(_$!XFRGseWBA~Xpw^g!xyNEdIK`( z?=5o^$YHz~Jz0q*>4e3lx9N5Uyczn^G&Ds8qdhD`qF6}2W#p_2@aZUdri{b5|5FbE z4`*C7mt+95lHXkiKfXiJ_qjLI-@Jj8HpoS)>kaAo5D>#JCJXmGe#WxmDdYtG@gnNL zr^@>&WrT;LWECvsb@LdFHX*%rCM|V%O{R3~d#eBAz-F(_;c+S$olTTge9laY0SrC+ z@0cUjt-#a!XzCHEIJw@Zn`V`G(;w8o)dtoQ+1AGbk{G=cRH;YsO~l<<1g+w2uZHG? zQT>>b1k*cpz87b&ZX0FH2L5(W$nBmX90{azoWI3qoX1L|%ACUYmgMSgzo#ELc{|LLPx+(L=56|L=sPkc!EezP ze{r(5a;j}{eyQtog6Qu(e4@QkE)~vln6^KqA4NH(o}zU*-c40KroyaS(=5KnP$Uv{ zP%≠@J#Q3RY}eLy@0HStY-%*007k1U3~M3BRF3yMUYM5-7wUUS!$rK^pKlBZ|a- z_uog?^eh7+&6qpVpt4BL-v;9dOorWI!C$f4LpI!whJsEt3T(2o%KeQZ}|?bQ;6q4PBi`W(IZb+&Hj0a&3CF zLAkd50&*j?#O0FO8{F#u{^Yxv0V`5$#-FY2(pI*iH=d;tRc;UQ_$IFp>-c=^^%dGjlM-^v2 zM*yzI`@fGVWF8sUcoo{cYDu<*@na(0@vEqom~xQ;;d#31dwLvvbH_2~w3^N@+&mHo zzrBrSi^Q9?Clid2CvQ@#KmqGK0AR4H>Ac{1sz@^7;s5)ib2!<@Px~X+zA=hDDD{jU zVH?r9*}p8;{PVR5m9W0<2m&UTi{R1eHG8{N(^M^aGAMyYzyy#QQK5Vyt6GVj-%NnL( zFHDmplgc{UL!1GUfRp3M$^aez|IgezBX%yS`Km_K?4L*`%7C^QNhMm!6b*vP_dMF6 zHzDkJ(;JWX1eT6|QyR5x+_yBh`MiRV!|<(FL4 zDGI?d9FT`8p!@!xzw#0XyyYE!CyBH?HAO2IA6+{CP;*{ZN*Y*iM#MC>${nbho>@!0vxHqR+&{Y^_c>On#87uktcaWqZ0sx!DjW`18F+0T;227( zUza1tWs0MBQ*&hq*k#yd&=Y?$kBX64cBzO@X(RLmQ3t2f4&$IANhmnjp~D2Y#N`k3 z`+zt+OJ|C%ei=fM8-;-Ll0t_aHI00Z-Tgi5TJGN9_xm%RSvzh*`=ZUK8CGv)Np=Kf_Li^eRKJ_s z1G4bCQb}hzs9-?1ukBR<+C@Q3sS=*M7a4q^?S%E$-ya$U<32Kl+UcZ|<(5iehHxD- zJm|%oPw@GpZO^1-%8|Y#?`<8| zqXH2t6AP?ab}(A}Jt7?;71+)-Cs`CN1X{z)p_hyT`B__*bqTVCFrU_9iK15yD2F-+ ztx_7|@C>G;Y{WuM*C)raS(9yEl+Ws)%=SfThqk)yRRr3+^lwEMesH%Vk>Q( z&rXSl+`GHGC05#wsb8(qfL4?@rG9ld+HdZq`}MXpU86+T4!uP!+5W~o2r<5nEn6xo z%7l`pFQ#6=*5TqI-&s%iq9~9Xzw{(dkYQ(p)FD0;5+QjMdaT5^%R_^5@EKZLx^R#8!Q%R$WRZXGPUhB}4WJuIhWOlnpG9sv1_j*z!t#TM1FXm^+r6h~K z&%tcRXe~t+6|d(iim@1IJ>z=>HL_Kaz!YIX^%x#RN#dH!NU(KzqG;-RnH{m!d?jc; zkTLl)CY_BXmcRpHm4ot}!>-VfNOdFM>>kk?3a!08WZ2U8O=}M&$ooY%WesLaE$+*P z6)DWODRII&{vvzvC1Q>X6oq@<$4!66bBAU_vo77&;!BQP>y zfKjRIXg}K+_UurCp2U!k7`SAg^t@O(j6j<_+WrQ(x}RDfBLE9hfM9Sm=IoMYzA`5t zpIoae%v@T6b&6(r!Iv{5f9T-gZ)|aQNbvQp$0}E8&D^oGxJ<}a7+u+^eeL+MFdLJ! zQjJK!M*4$ved8_%{HPGFDPX<8DtHl#@VW8{XzC$4FPWOa7ZHId=ws>{OW!xqTJ?LQ z=MS=Qq}?3RD*N}DerXk&7ky~HP^OnTI^<5fk9!} zv5nmns;fiBKXIzIapcn98%<$|US`5)w2PZ*lZBZ!`aTjHHQ~F(+UF%URce*G zK9d|mBqWo#eC}5@yZWbHqGHNb3*Yq&_(TynK%n0(Hg&?$Oyz<_YT1$(c2O2!B5r5O z^(J4`XknK0JQ#+5_xXv=WPvVHWrDH9(T8+BXT__veMn^UJza;n4-GuO%GUlOtxnP= z!A?OkGMMVdxLW^VF_u@u76*tg!}g-+e(O|9hg`=ZqLu$P^O79bauqQ!AhOY@+a9l~ zHNHB697O~ZenC5MNk|Z(IXju`X8VdkkGR6#4V9Ja-(~%-PM-wZ619ClIjvlyK{Md$ zeaZ5IezsOnlg&}dylbhmPqQ;>I7s4!W`?mUMh&sJFE&mr1DlLsWq@YeuihC`bQfZ_ z-;hiTca-9la#Y)>HJ$0S{*T9%{pW3Z_qmT7zocv&V~G7KP1lm=sj@&hs!dAJKWkU? z-5dy27?>{#jdhq339!^Gec0bgW1=H;<>oVz4tb=ggQBo9 z^0FvrwKC#iyIipKBKl@LkrtuklOy4yu^31*<%sF*OVwEN-QtP;pbDb+oBRuqI#Q%3 z(itqg{>C>kbYW@NVD{7z$s3|7s0Z!#i}DUy7N)X8qj0P4hL7cvJp$fCus+?VpgU$X zZTtq*YD;HQeAx8zpNrI@?}(C?Ch`4Vv8)|We$LC-yO|v$#&&5;o2b)6#Y6^THv>c=F~1 zw6!}aq&6HCl5wS2bp__=EF_gu_!J_6D7orI*^J%Xo*{< z*@a3--OUz()e4WboXT0)kTW6}=!kcs1J zv9WxfR!XGEKE==a+-pyQ9-W51)5MFgQcoqzcE-CV681&wPRff~yOnP3`dtQC5M~7n` z!c}=@QcG3BYx1%fMn`ATR0xz3iGn1K3R#JKQ#EqZMELzaYR#*BSk;J?A)g$N0^%Yx zziRodG2I>e9@Y$T?4Dq=KebD~X5jZa+z~@i5H{qvWP}VnKflN);Mk1KZm0++cc%DD zA2%_Orr%><{-46u+Y<^of{NyiJ4z5GDx!cIqr@Yxz75J5l%TE5Ea(47`>7v-{;9U4 z2<7=Uh6!k`aN{X&VHBV1<$H!jW0a#Mwdw13h6I@;YrvQelTf=lt}M zD8^kEk&ikvXFN-<#ItGG%hnGrzX-1?MYXx6nxKs=ce_CaZxs0s|FSWvLQ$SmzB~ z!FS|}(;U(|oWx?d+}lv-5P)6O3dIZK7dhzldL@DTIVv*Z_gK_1(>R}JdI{C?_qco4 z_o5NjDjp)UG>i9s5ws${L%vzgcMcyKL7yA|D{gCO$y+atBiRJv0x8i56{5?$ zq4{8R)s#etR|=U&ICs+WT?%1frY+serA#iFI%sO3iV{);36r4yYCwjqtXCa#q1E4Z ziH|kL9Knzah;5m`%smiM`k2(@G>9FT@A4FbRdg&xCZhkbmRB~UjiI6|Lu{-j)n-oq zwzA_vZ?risQc{;NBs@v6WwFS}$0i1I6=**jD0HK59x8J4WE??;WylWZ>SbCZ=MN`I4?-?h`q_Fhn^xNH6(b&*Pyvfel7?SJ>Wcy|Ndm$^L5*~CA>FRJ^nUm=$R)1R%7ywB zW9Ld{=~eVuQ~xa5z*^&7vCM9qCl9=oYJ|JzOUf*CX*HTyLQ346?s|QUZ$Umpd0_FaCZdNW4h|Ce#GhQOOz3#sx{eh-zp&%O^Dx6sg+3 zWgMbBne-q`f?GY3@AyUZ zL2%K0kY>gS&P|v~h>CF$RHQV}1+|A5(b-J-0>K5en8w%VA9PrZD3TFqyj2$?nYtZU ztbd_N3F|t7^+J4CDZb95@a6uK%jFO2C@r0{KWz8g*Z@oE$57>`Rp~ALJG)0NFk~ZN zMu#mu3xfTedob|vuhLr6z}c*QnjeZlGS%dso7kGms{i*h$P>n|d@%S%eBw9=#j^Kz zHD{K1jBL2jF+OAZKqf!WvpWgt=4HXbjT%P;Fos9_OSreN``w%ZaWxthXGP# z8Z)p}(M&T@D}O!Kt;ojw(o!#-7GsX$fO}Z%hbWCWdMK#H|Ld8>VPeygqXF`+>%EJ` zRz+rd*sou!37y1_5$M>?$l)4Uqhg*A6>yO?2!s@H9`&ilH|dpYNk*qrQkaYIM#EqD z<66uANNQ3~c8bA`IDEDR8&f8#PL+rB*!dciuVg*)_17`FIv9s*#=D ziz(>2m7y`W-4Lc_UwaT*{ZusOsX$!X>~@_hD_5{{%BJu`J5u;rusYG5b$I3&C^Yh~ zh{1U-*QVple_UNM>eA(uKG&Y!pi*Z>6BUhOwxFZ-RIRe=VWjY9-0cV3W=)rEk59ho zW-h7P67L@a0aZ%ulHyV=F>a!$Jk^4fVXf#nNIOzndr?jC^=aDKg(ucmM+-PfHA$Xz zd-`}z$U_3y=tx>i45JiLJoz;36eu%x$kP|(y?1WI%+j9>$1^> zT~~;}BPIt^OxD#B2!o-Rw;#c&mPD&XxJX&buHanVCY5<}qQ=5>%`GU()$|6U(3?{} zq$iz=Lt@xbw1cL-(nGUx4{L3oJ5WHPgYMfW6UC?6wsZY~cvuP` zcE6Fs`dT@JrRy*3%6&+!-n}7Oqb-g?Qgp?*2d_%G2b*7$C5R$D*G>MMMC~V7z}uNl zyKmc6sz?ywno1M(H?s1Go?~~?EX}&UCg~EF>U<>SPM(WJhNRAR&C)G*InCn_@C}-~ zKaI~w9_ml;O@+l*rNP;G=>N`T z4##&H1*5Wp$}W91WvJ2&t8m_IZ1q3Qv2+M~n+n<-r|%n@c*ccUnr0!!U-?o&MH)2; zBO%`_Dd+03}C|&Z=l-dLG%^3P|cy^M8j+760@dC9uvQ# z!q7%(w}gqz-w3-&6$iS68gc3JO9@@xQ}v^ zn=g-=rGT$}QnBz{5smbgky-+Zl-rI&dOqdj!+(dIQdY0enckESEB++SW88PK*zEIl z3Li}=iEKxS+|(+pl@|FYBYDNFgh`BKHCfwMLj-4_x^6vMqATXq!)fksKBKrL8zlZe z;_<}qKZJg0RE0{DCXq9eBj;Jy$e?Pj_SW2&SiuUR4}}`}LYpnvL9NMWM4TW~tq)pD zasL{zOD(>cx#fj$9F3@_>F)el^G(M35Fq;7XB zjHeQ}w5=K2Ip>F4T=Wm6q^PT-GQ8&~mj-f!OhlzC!GoG>_H!3JN{dxTZT>Y7oFE=i zqQ@yhpj68&_<8(_YL~8tGn(-QKj54Djf2%=Fw;Pw9_nXD!yuOw5*Z1zBa_#*eW)?dPd-fXZVDk z(wYvS_ysut7Og|)!Pke3%)T&pH=paKYVE%7kmq6OxCzv(l0ffIRaF(J;JbS_(lQv~*C`dKf-Zb3e-F~ZNW5v|HQHub zn=xmYdO@^Gr*ZyNvnfC=)5b~d!EK0i^6DvAQIjz(U5jiO?BY71)Zg5Yt_nw@^aekM zf+RFSmk4eV)*}>0v063V?CIX~n!4Gaz`@lGi6EPHNkOfiV37${v0Ia?19LKlEsRig zne0&Wh@mFNK50v?Nh)KAQI2T(TdAJ&cqZr>VK$Lg=;r7SJBKH43-6W2#>pA@E2FTF z4J=DVWrB{e6eAGt>dDot zyx}yV=(yYak$+)(YPTr*?zV2*n6aEm0FL zBH)$__MwOCux%X?F5&m>Jq|{!D2?OXzi5s`5U4Q z(>{5n@Kb}#84iF|6la#*EkG$(j?ZlE{Kh^+JOnQ#VZ98Z_;}l}`H^s#MkXn7wb5ig ziMzAB)lC^kHurbZWpYi>`rs{#TQS4PTveY8bc)04o&mx!9a>F|QSfwL>wktGW8E1| zJY=AxlB^)718_V*qkls6k2K0}HtR_1>~C(1E1CIbp%yk0-YRp12a^B$;Y2Ax(#O~5 zTabY$H8kC0?hQEeh>44H8p-ugs(L6yP9jIdivh=a z>P13?UA1JjsnDoeu2zRu1mEY^rmIW^kENRX&zL!-*SY+(e2IgNeV{1t=tY|fTa!i+ zhq1wX!)M}boI~_}+pSxF0d~=GYM;hrAcKlSJRA)WzTq?XY-U)FoOj1@842{SsxT1+2X$tIR z#v%9X0|B{=aT=o@CO)QI#l?9Bc|@BfMk22w>JT>gAzy8RkkzG7pk|N;VGU`0AEW~8 zEB|FMRV@n-XjHoXoo&_eXof^$gbGKuE2NMjS~+SfQ4dt@X@P@>cX&0*lE$DX{rUTg z^pN2Y6byhy#zGX(-i8nhQq{xRkUfo{pNNcsiDP8+M1W#Ci~;OsRjC;IQ^F@ysJ6wi zkp)Vhl^%h43!X7$j+9`B49d2SQvgf}3h~SYFlB)vXK6u5kuGAmH~&yGu@4D`#r8Ny z#H6ut=1_QE`yW^%O~^fjZ;l{JC!hmyl|`z!BUwnQbZdGQjN!EhbR5q2W)e{}YILAv z!kN_sAYjO6X0C`$MkKtppAVl#W4Y>$_gO1bVRu}b!4Bz_(RU#zDXB8@@{CvJFpjAE zF^o2-u|;VzvU;pT>1~|umQh+A0&*GZy2lF#BuCk%sqEX6kqrC@f`dhcurC|F+HJ(z z(Sc}iOoINZ!g80X#KaMr3>4!n2N(((JdbOB?{sGvww%+bVi0y?^xRBGRNTPgY>?T8 zrKzOpUxzqg#U_$wiHK!cCgmd%Z$>ZWXst(RVYE1mv$OSm`ijXUkT3YM%Vd0l8A=&f z`Nh)d>|b}X!6&e{g`p!u@MEsmc(#$Gx+(O*V7r>`Np``133*3$v zW37H;H79WZ5QGp=cyLdo)fzrms)x)N6?Px+9N*7~{(hDFJ2P+#*`5Xjgn_GDz?B9*8gY$nmw@jcvJ!{oiMNV7)5;~tH0uF z!;$c34~wB}gnEXSMR?&lL%~fBv-|m}Cy^Up?--@b#l*&A#32%jkJ98EGMxCSr!i=W zpjt^F62Mki*@d;y;Pz>)>7O;xn>^OGfqajMIb~U701NiU3LpKIGBISycVE0%NI>Gb zn!Lvimp4jDN6WS;8cW`v8mEpZCYj>2FAUzkyq} zUpu;mQ_L{}jO5ndHi9(p_e^-KNAU8WaT!sR+b}^HbIsSQlic zZC=D!hfOpXMl0!}>nT)8*sDSDHL}70KSnh=6e+?v8rZ=G^ZQB+cq9hWN#`Bw(0@Ed zAjS-saOI%o9GlvnsKP$~>Pcqp#8QSN@(`VQ+(vrwF0;cpuBT^y!GULd3$~abK1G<6 z9ETB-soNM3i=12x8>fE^UG1-!&Wny@vx#)4O}|H{v*lSsB7I6{r33VZt#ZT~wNa;w z;BK2$+mL(YKI-p{mKhim>5UH4_SUK3=@w$zEz>Y2U5+2^}BTeMTencUEuczXT-&EXSri>z8JOT)uPH*s%3 z%3iC}rETesFE==)PP&YEMrOsF&{iuGlL~D5k z0=xd^3lAPA-}t3}TOhCrThjOQ^WA57WW=eKydH}-@_aiuBroLdTL|Ce&jr-18VO={ zxn;*Rc%*rQsvSFpJWd>3?ZKxfP%3$!7>bP5@JQS&7S-SaZB3WBxVYt|MukRleczj*)%uxkk=Jq}#u= zB6&G^G<9ou1jJcej*20YW_A1#UH_H+|Ij1dP!G3l0k3Vo#-|!UpxHp=sc9)&uAwlutXvMl)$9WyLKH9t(RUp$cDwJfsJh!Xy)EOcuVr@F?L;37oip=~!?j z86vfsoFSqip+>Xj#bgS7i7RjZsYKe8Oy*d(jPLygF?C(h+bq@Yblon_$_#i$C5M1m z*~`mkc^J0({*f4Xp{ZKGJ4=JERC~5Bd!32zV8`l_ zKw$8(Ij%hK-(Z!F{`S!*Nv&>gUbess%ggJjoTB_qv`@ek@T_ek33#(<8n|J+s}C$E z4)8slHQD<4(N!(g?y}{-!`H9_Qegohd;TSZ0DeWjd-iBdrUTXd4vg4?!p%1T8|Eb7 zb$b4G@rZ|wU+c1F=h5VTt}WK)`BeD2@^F%U_o)7~cb+dqC)%PSdJ6iPjV8L9RaTc( z?{kRA$$yU?E;+o??ZQ=K9_E2qV`%G~^LqJ-@aleP{(MvV&*@N)9T&m>e&W^hqoQ28 zDP@AOGw8IgH*k`vxBr1_gLs<3;NvF0!Ta7CTrtbMTDv8va9iNyUV!zK+w};ViLaMJ zD!dq)iqW%L6p&a}KNS4>O>aumA_GxVup$E|$&5{iPtKY(e24z+o@W)i2qgAR8t#@_ z3i^`v(}vLZ#S}9K;V2u!ruyb z^Z3jIJWbK3wV%)n+Npfg(Uy!B-EcmhL0NI+X)o!@!Y zp4QZVk>bPewf*EJ{;FN@8TI~ap^CI+OV(d&4#u7*Je!S9y)4OYnm;fRJsK)s@giX%!1OwC7_cd+v_Os}(K znJIE2CL+gLKFjD<|C*fAtAAGad)mq^7pp- zf^{AHAil3z%C0tRSZGQW6Gw62ZeNcCj9e0~jqax#NSK}DA`%g91Cd@%UcSNYlyk9$ zKi|4$d>8@mdy6ejtKb1qz?EO^FK2!%Jx@ZW-j2}p#cI>{@H%0-?cVoYBy0lS@ea4c z+n3fFdaaI-_;pvZfr0n8TcnS`Vb@?;#@+~d0M<0Kr2_Ch$Gacjf7Ix-IUU;Nn@sCC z+&oBw|_8r&7)%ra_;e`K$IAF{nkpy3m zt2Am%udlxJe%v$R;N$MC+SHkyuX5n`9EsTf`tXJf5A!-IgsRZ6(RF&>f7=TG96edE zdG5#R5#orGVk40zZPY~*4~rbLYPI!B%@*`$1EAN#*m{Fz_uuKT{oL)OZuzL@RFDf9 z5DEE4fwv~xe?%*as9`K8)5LC`w-eyNwA@0+_hyKn|?q?-CIdFD-H0AK8BpDAE$ zZyCF7(~BzqZI8<9dI-zwZdUSnk4kXNWtx9vdmz01V1NjKbG^dX+50B~v(5}W!5frT zyY;DtYbVC8BjcVM3xm?Sx+xvrjlDddfWFaDqcBLQ=eExaho3`;m(JA?HSF46w2>rs zEuLrFv9{hPMu@Rpe+m;(>_3jU92aM;IXqt~sJv_kF0r{CBTntR0tMga@^Aho$KU>T z2tfE9jI=Sm)cb*;)K7*a*q_b2xtC>AyL)T!2HWyMk~E4=@b`ZaF6T>%+@|zq* z8GUwXNiqvULK}jqy=gU^ze{k2OiGYgNodj9X<9KrWHn=lH{gD=A>h(K<*{TE66*1M ze{>tA=laNVf^LYsC*Ip5v7jQR@%~5WCECuw*D)LVNoW#AL3C4r4)7t$<0GBv@ z`AqY9u=#&K5IaDz-F;L5LA*P8?t@Qw#WE}y4chX6c=yw?CPCLi}pAUIq#<-djK z2wXc&@qU8&zpp{9)Nd;byk|}WhD%YoUhV$nBjuM94EM9;DFCuGl?yIsR{q-@NT|d=iX&Etgtz1M++x5=icg4gwf37u|>Dw(G6A`*a#t=>gYv zfLq;)ozl~HH<+(y+bAwJ?nZO-)!_MxW9fFZ`*Uz0o_}(6qORD<6)Bmlv;93@U^>0$ ztqEORlv_I*|pyzq3HIzV|i;g>{14%gg>dAmh6u?7E)D%#W8Z z_p4uIB+u45(_5;hM5`j`+e|ZuD221SZfAsB9ei>Hfx7Y6T@oEo$`AomV-i-Ng@EaD znCrpH>KsuqW3l*D0z7GURGbRL$! zjeI`!*1Ie*`hPy5#o#YPtzIP)y|XQCI+88v1@M2~Oc($!5TdQy{C14uzJg$R%Wb~4 z=hAe~r@rv^^R&}n&uL88`JefpL6Zb6GO1X30ZF3a54QkLB6u>}VB6qhU%>v?ws&pk z2X3pqPwed!Z~TAtP-G;H|6Oswj^f82Tvy92DWShBnWljc8P~r%C)-71YwxW8G90Sm zNHym5CjgK-R@1gQ1q4Carj^0yGL7i#2U{CzZ_nQUo!1nEBqoZUEw|=g`XBQ8K2_f5 z^qLb)q}Oe&Sa3OQLttHHc77&IFm>lp<@+X8T*KI=xg4IiHTi7XyI(9%4bB$R8?=&} z+V`>X%}iSex_={TKZbPYdnQe?Snd)>#nY(yK7~Nk8MkjU0n-$=7X56KeV7qSBXfdW*%YQ06-d#cWu3bTU zY`Q@Kr$WhT|3t8(0;HwgJ|4FfitBxCJhnJT zL$T-c{WHEi&o^kzzBif4f7_+&?FCOxLGCKu;FD)s@Z*b*`}yEnj^aOGG)4aI$n{Q- z+ogbaF5Q50Z+*`XEBBs;*a5QeU!PpP+p-34V1Q#~iwlWw&?KIJc#^0W0}Tf^)(W`B zmdD8RCX)ZVA@FeVZ)nr^(BXTlC&cIT=LgerHN?jC@+DWJ^9t(6{N_7B@2|_R`kve3 z_P?$rdhTl+b}05A6xaKyfH(ly<$+k>K#>1&SMGIieE7V;6flw3?W5J>3lSM-W!8sY z3{;K(i>9lNisF0wNJ%QvC5?1sI^jc%#fW7`jd z(Gbz-y8_DV=?$ZgSt?Y#NFM-jw&`{u#(T{3xvVs9drrU=<8FZvh(G@ntV?IJ&HU_A zVu09eQ6B_j<#%G}KRBSTZhzo}cAjH9o-PcZuKH@XxVSrkD*AxdEH+*A;Q%)qYwrt9q$2KnvV z#YTG)MXl<+qxCyM1VC41p*Dp6-E?=BBP2tSts|v0Hy{(??YkPA+21`JD8K=Bx3Vuf zTAXem2}HVqI1+1K;-LZwY0(&H|v` zJzz!LtcrW=Tpz9f}blszf<$-WP|N}fiaW}(CN+-$K|azvsM6^U(eb|JPV12 zj|bQKnfhcN4x<90Kw@shN}12=8O&lAXbV_Jo?2dRsOpAdutdsw4{mLC_eAy7SXm`3 zSY@gw1C{iYVRf=4QKbdWzOa1K*UCA5mpgVqqu%SHKV7@si(}u=kH|nc?(nb?_L|fm zvrz9zr!!~bHDy#|K3iipY*Iq^jr60)$eKvoLY+C6+ywB3hwYW?XA3&3qt&7TSyx;- z;n$T<|1>2sttamKaIG`L=;0MMJLtefOj=cDK%>68{RvGz=^XGljQD3ywQA+ukEezE zjza>vYy*zY+qQf^w@13rnXZ6cYcZ=3j*NUaFyARtzqr#KLAKXwTea7?>;R;u0~_Kw z-9dsv>%v{T>G~rRC)Jnbj{)7b-wcfJBdSUlvrSBPuwo+K3cUW!(hi)(Yrh#$KPF$5 zEuR%{x7@wNTXDLW1!gM!?bki^G^uDeL2nGa&AHlO$6Mg}rkeXyt$&M+K;KV*s@t|x zw{m)3%hbgVH@(=3R?mBP7Z9)@tSGG3l#VK`*4#`c@66aYSn6Xt?TFY11;$CoXwIy! zL;LzT;6BlnT7h--0`AR$&}_Tnd&Wjcl0zepZ3AW;w@ChFvZQPQNY9cAx&hG;<}xKs zQ0uVjZNF6<>q>$WRDY(yAs`@MthO6H%DNv$kZbw+@?4?c28hynr}5a%*E+riu(sL# zR7grFVbDqA;N%Q8GkrRb5ZefR6npXf0mwc=0`F;o0URK@IccTre7^A}JUskowu2E> zeM>uF=4 z&zS(}U6(E!IU&AZ%h7I677`zy)8_8DI0`xn4M&s|HXRLr?KVxL`8VK`1gIIF&R8x; z{ntTmbGBOgjb+hBh(%E_u(D9pG9K*tpU6#hDahC&ngYX$c0$A0$0D3QdZFE$%d!1g zX~lOx;v9Eug4Eo{SQu#s&A zv59oCJ#DcS6zy#X!kXkLFGS)2VuKwkyBHs|9{O=d5h%mQ`PPBjuRTV^Z!6hNkR?S; zgOSpCMbdWE6LQ7Q*5MYK<>-rJoq4$t@;dB3e`4xog_tbV>CHLhx>!x#FfnNzn{qy_ z7!g(Q9S~yA{DiUd&cK>jy;3Hd-x&kCtPCcuU9d@}L5&xC;g|hEN-2-6oXx+vHoip# z2%C8O8j9O0kq%;T69bh$Je2xexTLg1E}4)P(UiLIZe+W^H$uSgPC9sK@y>Cr0g&|P zYdP1`QOFdqRLe2fWsmy65HjF@xVd`th{wy%>tuPU4x< zBgq-XD29wsX;lE}w5X<3Zi0a%At|XD?3Bs-oMgQZPUmlffAY+X+tyEqrqSabVYc== z_*I872#MoHCz(&AZsCZ1Q%53B#EQKNyK=%x-Pj{2swAhXS8UO1%#I zsmA=avISy}bdo~^_vxe!i_23VVy_f+?Ab#9ZBARuhZ6xz?spA?6U*4)T7J(hrf1RcmLn(kI? z7*N9(@H=1!1nOwO4{%!g?y2a-A=0Q4*n>y8tMYOUADA0k>Dl@SyYth3B=s}Q+T_qE z$!~=kaSwg`kvC&~wJJ+y9B_+kDiz|Tikb82Px%MuN(rnmdNth~{5#57g;eHQR-)ib zxfy;KnwCZZ+KGc?HgS7iFoDJ**!OK*x9UJseA{-Y#82Er^H7jVQr{QliKIVVMFf+7 z8+2lY?5=6)KGAs{2)*_nKVjSi3C78Mw8yTih)G}_OHGOfvN68Sdlta3YoXbhy0V{@ zt6sgxI-UJ8a)xkMUYKoTXITAsy)%~rrRB8M7En_|ltcll(x8+iW+=~T&fA+WSege# zs9L8jX$a7cu5_|HMpF{r8rywkWl(mJE{TzgP39o%th8mp%)%pln@*+9687#^&yza$ zby|za3WJlsHPNFYBU68)tQ2JK_rwVb*b|7Y{h~BM6*gGAjU(Ln3fETEp6MudNe}Lh z96rP!`dM~pEqdPlI?)+$Yj{5x_(Df~L)_-!(0wJjmj$STl9#S#7w^s1qIl>-BK-N* zCISPFR1JjPqPv5PWq2L-4u(m&}y@mAbjhlKI=V_-r`stBtQ!Bvcf1ZOeSmEO+)3l8Q^fb}!5=d=;H!lpj=>)v zOIMw5OCDij5=|uk%CaPL20;7`IQ`fK1cm_%22)d0xG^Zy`RUGCIXfH9^yg1~BeVLF za?C-xPXYlpNrx>u1D?klKo7}uA1}S$c7AuFmVHzXyZ5+7;W5a;VFwq7) z5oG!9e8DvS0s`xZ$0XsqoDB4j@Mt^PF-}UL;Q$5G-Jb2&4wCQJ0cH#!(4OM!1v$pM z*qXEOcc4rCA>O(GdLSxD|1T;KEq8rezx9B;Y|MLKKgQSEAMv+&oD^gg#oDh7?Tm3t zQBz}JU~ah!YNPtX^r5a$@|~{ww?xE1Faebhn~Y1g^$s;w(v-;zhHInzrKWaU;^5-C z!gv>-V2+xP{Uw{fdvXIyQ;yeuaU!m%JrNj81TCJueDBVubb##Q6EvbKil7}f=>8nT z^1{14hNSh*f86dTh_7uvGyy991uNE0oA)^CGo)Ud?6U*xS|@8t)Ak>v-^`zO z{GcNXjJ2TKTk_|tU6A*_4eRA5MmUCCD#Xg`%cT~@orSq=g=&^c(JAx0Toaa-lw@RP zZhbs!p4-KRn!fc>OUj8@n2_|bBU$f1AF_blblALhMZkdH@8>VkuCie!{<~?^ccQOU z$;s+&ODrHEx6m))q+%YS+k^3!$KCq^m(v`)c55T2xi|&C zWEMR=4OIRiM!=X8hF2*7Q$>e2Z=b-NcR?g_TPY_(jrC`9O<&722uVn`5y&5i@H5dd z-oJOAVR594rjn7BO_V&}%)LiaR#N5wc%@2B-Febbi-2%Hz{S2**JJD)uPK$E%1!H!mEoZYa^$E@PZ~Ntz&5|syhpso7G5!Flkz}3=&rVv%bXq-#bo`+QYE5b!7J3_HSDIXo~ zfF|>@a)*H|iBgBA<>(zh-}8e_ZI5hb3gW}EkM190#QwO1}`l|&zj_Daa_KRC2+0`mssUz+6@@v%lkM%aVU$cyI3{gU;S-kd}`Y;Gd*4vP(SsOrk`fH_TR6*p4kViAc z`p9<9K$!XOdD|7gtMTK-`Uo5F-yVUEO=8_j&BL7n@Fxtvq7*_?psBy&Hlw8Hdjc-D z^iQGz27kb6$x(ircm2uG5e0X-@ni$!`Aqn)){WwgbtJJoy7N#5WzwKf1L^mno9SuW z*~59&0?YH47t&9y*nJ!ltx~m7y%0Bj6UF=+F>~D((ez%t z0xkqcQ3YtK8k?7^TG)desWx$Zko$2x&*vN3&1$~C#~m*|!7F{HGbKvere5oTkEjh3 zzh?i^A10TC1HKAtS8K4E=H|#!VVfIb!I=qk1No}f2b*bbY7}@4kOnmhl|$Q!M^%Rh zn=#?mBiVfWreL~*AllTD$wk?`ZB-y8aIJq>L16!W+#u!X&Fksv!UF9BI4#hA+ufi) z+oPza1aO#B)$qR|*Q5%U9r&d|?Y2ky9*{dswZVhJur$>wb?83(5fu5FRw|dM+sq;} zlH-P90lNN0U){FfscIM-In~g-buS)jC|N$?1Q_*|nxiv`XuoG|1oGaPWsD|q^YW%G zQx~%;#v++AhlDu5{SlNx=}%)ZCdzdJtW{W;oYF`EWl#g zPe(*ZH*}`u41Bq`xG+DnUx)awIQ0UjU^vGQX1jGr4xneFHPQ7JJ!8ttplcPjqLg;% z0$%`@VH}=3rx&VjCROo~qrH+)n6v>ewt15Ct-5hR$n(G!>ktwwNi1o~@sgQf^n9zP zr8|kf^Ky}fX?BtKTk5fyD7Pgf! zy=6R=n&{9glwdehJ>ek=l$yEL$!xn#^YS;%+{0+ zh~e5>QdK*!?j7X4c-!g#p*p|@Msa70_K{2KGbb52qQsC&qG8BwiVXgmu*mHCX5DvG z=US(}D)f&4pcLYoL392b2`G@ZUJrQV(?YL^NJ-sFkmdlh9L;neftf!?2(huTNhQS4 zWDQ2JaA@i$45oYEDUI@3VW!l2`}e`$eL8+%1?T5e0-Zx=Qd6LxSinnP={I`YqiW;Jqgv z;z-I_Ga`8qC6FlL8+3kO(a2l%=#0DMAf);u`Gr_bzY#Cik&o`D`$4@k^kEO&P_(nFW9*W)xaU_pJZM z9=|14jx5oUA=H>$0#-noX3j{390_3K$&l;Nq*yqWH*1qfg9_GVq0?68$ImRK(NPf5 z!I&7Ge%cM$_o04YsZ98vs;)XJQz-anzh?SakwyXI0NN7;l{}9D7G;Hzmsu?LFkB4p zQimx9j~F~dWShRAMHEh%qg!&;e0J!xQ zVHLQ+L*zyYzWj(cNDx{_Q3|Jun;I(5@E^88UUq{V!zizM1v{V}t^3WO@K^2@b+H?V z$kpv1MGfDm2cI61CI)bubyB|YS5COvYtS@zH;gK@p(sj5E+{ELbQt_uHC3}5Rj!A9 z$aQs)u&_+yH;sHcx3jKwP|p>vwia|%dF@9pW5&c}hD_cSY7;z-f=@#mDj`ZCBX-!O zc}5bSG7khhbXHI&JKry!;`-3TvJ{ADH7UbqY)2Q&sOIjm1AzU3TC!ILyC zCcyiq8NS4$o7X~$=AJdnP$#6Pl}|>bJ@J-bUmiRn2bSe91(dde1{@?&!Tue-Oae{K z^n;pFF;zW$77+$E6OFvZW!^w^o*LyiMvmrNvGZXJ3OvTh1ck{Hx8c}NzckK;rKb<~ z6a`ay6d3-q5o_>ZKtr#L!BWmjDMq%}d%67D(!Qg7r0y)a>SLxOs_h$16ZJ;brgw|q zfH%_DTVa4|?pHnSpU)VS^BG+Lqqn1mA}t5ri~gZ@#6J00)at|MkEEL9dVfh~5fC zOBUGVSd3a*7sw!#=QIwPN4X>?+suMb&P&E5@Bf_}l`WvA4 z5FJcG4_*%YG@O`ex5~3Jfk;!Fr2>aGUP3+8$_z-xFkVFxBo|8J=wppCyVB%QtUHt9 zgd1C1s97nutvW!S{&LSCO|c9Wa+Dm0NDDcFbw{@v@k1NZNj=(D>)7ycT1=3-brnlz z7#^ec@rp)MpeQN2lLeS~I}Jb2Z)}2N9+=jG(AydV61?eY3&XM~7;?K{?8r$)F<7TM zGkwhs!%GR~$WV0@hO2G0qVrmrJg|g($o``S)0>#ePr6bYT5@t6GD24vY=&>npIuz2 zE>r5fsMxZY=?Dx6r{mgC%FYWJD=pAzK1)RMvQp#sP^*!hG%L-Pe@`((4(0V4p>Uzf zC`N`Ri`XM@R(_C6xg6reoKAhaIdLT{cII1RH*>mzVcM11&XS4I>&>2Zxa}SfB;TKn zoZ)G~;Wiqy$~a%rT7P=rV=1E-NXC0K#eGQorAs%eCXV&_zlvIV=wN}WWPxxl^EkUE zHXVZ`S_2+oVIta>q=Jt*R7$JUEwilqetb#^5ZNU2J{?_F20=+eK^2c8bS-m=@w%j+ zNU6VP1{B__Fl=dTBT*)@jY_mr6e86&%%z1ma||KeU$`uC+OVn8|6pq*Ff;BzjpGfc z87H**Gh7!tXA;4VHifVJrc~P%APZ0YHGSd{wQSw;L>x}J>X6>QM`eIjP$Wqo zKZP06uw*a3;q5RCUR9C<%M8c%E2D=MX;vm#m72b1|r_ zF_p;i#4gDguUx9ccgk8mZ(`jfqwR^RT%>w@)cO??uV7 zP3!r!b!k`1V4bw-9nBuAt!Jm2h!-2Coc;CcH;qnsZ5m)EXDvF!6o!aJ91{ay^#o^) zIncVx3uFZ2^`oOFZ%>={AH7BjS3MN#ZU*4W8jEzI=|nP5-dQJoKorecP{I&imwg~B z;8NbzvgRFc2(8BKxq8Vk3ab>`ma z&=EOd=c>cDyaLsHo0%cjgiBrWvI)NK^p-c83GxIY96hR@1Uouavzo1Lg4Vj{9urbG z(~yPp$(rYXDfw2fNY1RH9gV*`%;~wa`-}3@fA&l($g?Ge(^{68U{5`+bYw0B|EVUZ z04pQQA7%%{e(P{P`!v)`R_q0e=bh-2+aZ>wy>h+M=**u0w^22vD{&PlAepvmBS^{@ zx&6>n^ZslsS3X-X6NefC2W47IheMG@s7>gMUdj z9sM0h#x|8;Z0f7JLXAjZ?ShP_Vo+Q)>iqnylP%}A9Z_G)GA18=n|~pkUNvvMgOe`t z`^5LT5R zh~VqFY^k)`?&G;|Cuv2@v*Ot(D>YWf^87b-(+VV8(oGCicp8MGE5i6>bg8f!z! zf2ldI4fo6{P9dX>3!w1*)Tx=HsF-Ur}G;+c1DpghgolzcV9p|DHbR_rsuV=-6YmrJ8`1>0y~4K99Q_-k9-h^5_F)Vbz# zGMZw37&kZhZLZ)M&ur@GFuAy-%+mMlW&~BQYWEn-b0U4lqov&7Gg@Ew1?liiq-nCJ zs$El+Ttdb7#Q)6Fm6>Tx$+_A9vogiy`6D2Xlj1pUURsNvY>vW!TKFp^QCg!}5~QF< zUanDYChd=B&yhPe>T=ofXK(ehX#XhPjPxsBkN$e1s^{C{BI;uA52^cV6m46-pS+^j z5cW50vWMYXD*c@UDG?0}EP2^v&$!s^*&6nxADITy3�fnP5NXhEqgQPqxh`>59^6 zSP|I<(eq=E;?NIs^yJJ>3ghcHftef7%wN6=Qrormg%FVRjkrD>n7Uu19?~Mdx&QMZ zOi&c>IuNE|zOOfTm0*<@FUl%YVYq%oTf}tMdI?jwT#_X(FI16Z`>+!ea$2wK(p@F6 z1(?pTz3~>^;}O?`3!biewy(moh~w6-;5fL^o%kyoe`qRVbQO3M;dao~_f5~rkBtVhmP>&zs?)BlmgEFt524pd!TMSpMmhOYnG?cVAFSUT>mCjxiOU)5 zqaJ1+ImGqdH>5(e0@~a$yJrWBk>*+TaW`&kEo^D*juv2cRSVi`Zr3LLN&aWB7aKWp z%Wm3Yqr05-`;RZ1w6Ah28R606_U$8_;AXwe_sZxUw8K}4e)O_snE4&Q`c&Qjr#b_ zeFt%ZY}avY|N3?`i9|F8%ndRrG+aLT>oGQ)aTi6r`?!^y`$Pkng}wjhKFyVTj{%_Y z+V1=4M7sfygn-vM1sp&+2pp|`8mV@=nbpeO$IktT@A7_hCagO{sMc(FuN1~sZuhMP zTH*4tc#CQVu~br%POugBJ*8$|0CkEyehwHClr?2E4nssIjvHS!x(cgEDq57>rWZ%~ zHsE#KKYh_(8#Z5cu(fTy?GINZU;}73F~=6d9>1k{)3?^Dl0(qk3CLy z^)PQ!FW;bRYA3)a@9P-WlAsf=a8}or*u8&#a|`Y|jM?v~wTR=;Zjr<%)G|C>@Eg$^ zQt`EjD>}$A_?E~gLV!WWcV?Hg6XS#=`(CHTp10RV7b7O zMPNrPu#qK(+cLae?RPO(O9a|Yg4Ag!zqLIoMOiiVuz{Lt{OslQ?D8T$FdOQ($F<_Q z?(esOK)!J>RY+)h*Y#Gki~M$EGWvcF$ep>3G7p@14%kPleJXb|)}jxVC!zbCiZvuz zfi`096r{Lssab!|IPl%1hB0^#~FO{U;Cfng&r>*GVDnf1hc zf^(|}DsMX8HyAT#`S1JCwq$gDcqmX=v~}WDv7v#VNQ1_z=@@!oD5FdE*^m5~Oyk@m z*M(}>h?E8niOgMLpEy6Ir&h%gNfDJ;fdxI?e~nD)NqVJJ%5-tw|M`YX$=`PDBhYed zvn0pH;3wei|B$f@arLhup6;mXjXK}zuQb!39LkD4sJ?8x zfB6phJFx?1Fr}h545#f^%4A*}Z(g3DucXDefiTa&L7-y-Xm#$lHM7Mq&zLJ8%x)Rq z4xs6Mv?PHTmivn_>rZA>wXL<%wH@0g>WLerC63Kr2lrnr9nAcw`96nit50DQ(uMNP zX7xd^Q7b;x!((nwC;GDM$kNtWSLnY|tn3Tztoh1*lcIhq!;|isEe(I^-DKMSQjzH(@5-VU}gTv?O zyE>*uT?ENIE~(6cBArI=k1WTgkKJF`Y=C8RogQ$Q&JXM?^7|p#g&Jc7zBMoE+{cyu zf5SF%VA%Es=+d?|0|R;Q^X|8c&Cc82tQU(Pc3R?Mo{l?O3)a3b`&Zx~-U~s&##_fF zi^Xduc=!5dEr~7RlX*3gdogzYGFMAoppvH#Ch}6Qw`<$C50H3XMS(V7RkPW;9xzhO zXWfM7zrJxsU)L`G!=z0`zhh&bwMmWMhd&&2jwbM-paq>z>ZDmpVQUmbQk-jbNG;}u z4QU-h8-M>9Y!Sz05@8b5O~jC3kk=>!1}Sg^ePW6xJ$cjng#-eusFK9e9{`ERkAPz2 z31{7HV^c?**vqyUYhd7YA-Vr*vZ|9cLe}`F6OXL!?r!tvR=KwMLBXD+&MRU5vC%Mt z4|zrOTxZN}8lY4eH7hy$+yuy;wnK=vjhrhfEP>!kbsY$l8pAANO zrS-aB?d@P!I7-WkgdaA9Y8@!-&tl{?vuSzX>C@>7o7Yx;0?kx6%ljN9oSng&abws17tP@Tw&# zDAA}{ImnL{vC|PLS5LbzCP7ac{!Lur3>Mlv8IvNTRP%nBX zV%}1vWE9*_^V7I<8UF2pk$A*vO{x@Ef&$BEQkm8jrG(_<`;AO%T_yHHi&qy|kk`1& zpN4n$uM<6MN41g#kHpjD@EE3sFT#E&hNCQJ0noOVn^mzlg1h(op!~nKoTeO0Sd7_m zP0otX)9B~4gyr53Wu^Q)e1n^#?|Of=0pb$>+_)t2zRF~8C;5}Jy_c0EUw6gzVcvP! zdws(Eoxu)qr-ljx9>avdn61VtxxlPi$(x*jnw3cMVT=pP&d)ytI9%tuECZW-%Dl75 ze%V7b+GFCYLapsSYrxLlw_me1zW_0!g#90DEv|H(_gS6ZAVseW(`&`t&_i`NU@Dh> zrk7y6h5vdz+-YzljIM23GmuomaJWU~r5K`L0`&2firfWN<9hbiO8g}smc)&wL_9*~ zh;?IPw7E|_+Qxbz#D0c}yS$MA>CC4xV2NYeb#xFpLx|#*r>L4`rOtuPC;d28&8uLFA_9lpfgK|neIK1*P9%xOm>NA(b0c1bt?(uUPboFQA)q4XE-TuH;SeTmArDeE^AM)a#Izt;s=;+&BpiJB_1&Efm#YBG35 z%NliLEkNrQfLA}>L5wbUR0sZAPCD$fi#II;G|X5YxmiO6zmBdgyLW}+YEju1t?c<1 z{^T)S>CU%3iWXeu857NrcDL34Z3HcFe$$*_JyGG*00owpLIHaz`O2Vllwx?oKj(Kw zA&=v{DJ!SfXBYtC^^dNttu-fB`!4p>D`o}-iR=TWEEp3Pk`;fy8t0$=aU-j_o{%Pz zK}pL__vw(XXYPdu?W>j}jbhyN(wo?tG9e+I;7pSvGY1@}R!?6E12aGrsrPPQthVbx zETPnVBUf-!)k*V2h!curXx{W6*3>Y*Fi4YeNU((w3!YH5WPGU=oZ>1w-kvpKaJU|+ zRFG$9ojbJQ$b4*Wb{@u>wyo~K|Nbwh+1@69<^KoFZ8?KH!j(E-3&#UP_J1=ozd(2B zsOWvG2qa^|{QRgN`HVXxr3 zw{y>8K<lCubkZ%j|YYEq7Qe* z8wGSlTwGjFkDaeV=;-KAbB@pWy}iA=5RW#@t{)$T?vep3JO{|VMZg1a3x0UuctyAg z<&m96J2WUP&3iFD=wb@@jaqb#ivP)hZP@N;(42M>cmLI85w<_cu_$0<7w{Y zzTZp!a{k*Rwe$6{(=Z^uAo6|SUGI^0oha*n{48bErPi6O>u>2(g-iiEn!1RWq-R^C z^hU6jG@3MH1?1WNe~;t78@LoSE&XK`$SwubcKo*WqQ-v9vl;f^??-~qtLERNI|&>> z>vE~E+WHCWf2-?m-WoSH1C= zac+Y&Wji|v)%Y>L^&m!L{0*5&fMw?S{XURAS2<1LOvezU%_3c8go2Ilzt6?Y3O*_b z3HDBR%?NEo{r7U4wzq;LpJ?mHqtO1KPY=~5iTA&O*VQH{`3%TIE?mZyQ(@+h^Axsx zECb(icYpJ`-9trp{U)o5>?$_jbZ-N)vzO|+yxnhTXHq=<@qsqKPGs=;oKmwTKE}2T z`kPWeU@apVkGZSmCkC{D;hmgae2DnGCZ_6ApoDJRXn2 z&fz??1YX@KR`w`8W%oKg4 ziBXX21UQt9i%}cx=>C#ycc&Vv$YujnYDg%23yYVo4==N!IvjbpJy!R#XV z@AZ{TYo4kLNn8%`tFfra+qH0tEs6Ki6sVMQwL1%ZAs(R`o73-Zr{BPsm4D$At0kap zy4b*a_8#pipDMefB@u3Y=6?tlY{DDD8kyV&Ow*exZzzjB`oCLMq8D3K1njod*&F0~ zfNNCnkEcm$B#pu(b_5;awv`R$w8Hd@e^j~^jWc4QCcwYZes6|M$j;*la`KW`I*;;0UO=9-N%z?I_#?I9GL(g@Yjw`-|7?ZK8m)NId!nRwLyOSUTfK$-8=W5-?JXKw@rURGv#Ib zUGvf6mF6Cp+ASu%8B5x06kn>ZA2zqg{xkftrD=2e*sSrdbSKq3Ad)`g)z$jTpA**HDz7J()fIF#gT2gvs#0RF<3!9a5jOvv% zT?p9{gO8cCgh%L5Cv2&jbp{xnUL;xAmoXE3?SMf7jqWeqAu2;pIoHbg2K|`xMSA*_ z>ne|H>Zj%-k?6lzADXSEfLlR9>j)2;*;PNAj!9s;#ao6xgL*P~SR)8@^IgLvZZi(O z!?uYy4X0VAOK%spSU#r4=a@vf=@-!-79tr#8^?68nrNvkm1m;&7V}58HK0m6*3WK> z1?9&aA8MHJt47BIs)kYpV8{B=o@V7WFUMfVgz`+*3X|NHFPM)H)mJ9tg++g)^&?Y1 zS51De*OO}b4wef z3YZ)6gBh8v}(;`_-fh8X3!s8 zCj^A;*;*_aYPjz_N;6<7?oF3IH?{-=w%^9C+1zAWgCu9SZO8=+t5^OM{pX=_8;+cQH(M%Kw# z`?NPhQw98gv6P@k8_3exx(<>VYi1lmNaZ^wDKs44c4ARHU9KOy81cfT%!3GLK=oj5O!Kii%!WWy2FOH38rsoq3nb?1u0bW zdgP;ZxC}@^XHzF0HJ_x65~mZjZGFe!SmCs{cXH0|ivWm)w-Jlr=%ipTplm`+OKY8E zTq%JTg$2)mq?4KFE`xPPPb-(iA77Q&8JLrwGL~$P%iE|785Xv$nW&?E$Ql*SDMn$2 z?B~0OV_{RK#FS-O7dbtz!$jz)kq8T?G6vKQ)~b=zM(Wm9+%GRE#2^WaYG}eLi6v1? zzMz0*;LvXeat_yju+km+$WU-N_m2x zawpV4fiDz;@gHg9Op9u?ld2pl5L#fSK5cvx zlLSwT1WKZ3044)l`=2S4a8i=I6imiPnxm@?admROC|{?lSyjp>Ay)D@AEU&jV6Vdz zw=&HaM-Bb(uGPYV5vyoI6d3&02d}bAs%8!oiis5841e}!k&RVS{-XCxzia&ci>+Fr zYw$L*K&AVA1=E>tccL0PB*{%T28BDnG+_?gbBR>IB{bguIPmKI>$&yxpTrzy*Bx3E z_=<59Vbo8wCmvtrBvp*vgX^LvOw#j%P|DS(9lp?F3?;D=O1T=pG1ePXH)QxyGG#59 zCp_&ypn@W~POXR?aDL!ILvl;2c?~?HDjo{3Fn}xxLX!+&|wUi;L zHar}2R2^*B%LP?{cSj+pbe3WRyK+%J)zokLkv%5 z^YZ4RC1`JGv$v|6n6FGr;VUY93eI%#O1gM4Hf3e;vbB(TP?FKLb@B|5(1U?E7=t0n zZ2dEBT(7b}S(%Xc_XiLzP0l+N(F>p!cvRtZ-r^UGJ8W2zW43PU{ZponVoO9u*ach3 z+hdTRy}n58%1lw%Fs(xj>sQa4Aq=9767qt`rWGNARF;&!N^YUb6VvtO5N26VJB;((3({iX=2!pB%Gkmoe+|6fdNvd5Me9yu;`$<2(f?Q~A-m1}GMfdIml0=;GU?cq9cmMD;%3xh-g($EG z5hY7Q$^L^e(uZT(Vx$j0wtp&@hN%5!HYJpH5NLvdbxRjD??d}^rLt+vOBl=igrTx1 zS^IN2r@y2S>SMkccY013^R!-gm! z7D*LsFA9#k>E3iBrC2ygsHMvmP3j~y+R7kK_z;ZfBQZ@JP5}k*CAnUzS~-=SMSJK` z7D~D5L9(uX+-~<4yZibNbDT_Q3Vfxy8~!%axVXqxW_fjifSBx@lAMq}yo#~?z|#r_ zSm87Apb>KqF=*+PAKkTH4nw{v-yz%(1NY!}5d(95C4h8Y zmoW%4eC^pw_E9AC`pLX^9s|AN3w-8)oVNrbn4XKobH~ZIeMD6LKoR>1&CezkE4g?~ zSq1w+Gz5VMxLJh_9OMAemXu<Ve8Bnh*;UUK+lH?wopQFBl~V#e z#%S>dx4hz(E2TJ!1Qz0GT5WMkk@W~ba2U6!r-{i?j$j^Dus_sIKaN2iA2|c>&^0(m-H86z?` z?v=@)bR(;+EW> z2~1yr{Xm$LH1ILWfy9tuGV^{>Ae=aadw(wj^polm;mdE-j_;d65|U6lMYSTZ7yOsB zuTg%)U`ExApz#{PUajD;dm=aDdf*?<^^huP^TuMh_D_sP3b9NxJ13*&1or7GQ~uQwrNx;f%=~4ehj?)B}Y)cQmqs_ z><{Ay2=3VUmreP2pF#li6yuNMv2mynl}0&sDThuPyRfi$X2};&W}aqwqFEX{Mn-n#Mt5~!DgZrfwEJjm z*GrFsLx<7}fGq#v!QWvT#TwVHN&qr~RdwlM9GRNs-&hlEPtt_q$;BoBod)}cxfP%t z2auHE9Rx&1Ij6a$y=@Qnn1&=d4&Z<@vT0eGK{~U9nVH#Xqw5Xib|XX&;>&l|zE5UG z)K=$o&F**B_Wr5`8VJgAY|HuP5J)XWZ7O#t;7MeO8zd&nWhf5dQ-AQ08SFDW= zYh6>O5nfvtXP3`s{t@hin`>=>04f^!{(3zSWO=J{ehPy`yzRVD`J9S&=Cv$hw_Y3d z7V;#0D|Ra^cHf=5%_e&Jy75Tn_&6oB(B#M#XA>9y(m&|6mw|A=ybZ8wHzAK}Vb#Ly zX$r+7*KT9tN>u*wQ8*Fz59ys_fBKl&M16x7Gv0Z2KC^~$2)k~`LtgKiybqSwOAJV-ZM9J*DQmlq5AiyC(8~YX1_cukk9PkX32cl*Mw>0YT&;be%p@Cj5JqEw`6MX>I z*Gi2@A^X@VZh}4WuD%P?P}N9HGC^0~eAg3Rz_q;(6(Iz{Eg2tPsZh5VAQAcn;2R^w zTwVS7%|jdqFfTBR5!Louwn8Z}{BCxgp)ERcZ-XwSLba>reV$>1q6XFfOEe}P z!GkJ%wWam zu^$ExfgN}PIz4ADTYad)&}~4&VBVUS;OB<)suY>X~_Xq^-Z4tOF#!@WA`@ zKnp-~vqo(1 z0{=#9TwF7LH|2)ruP=0mZcBczosjXzz&$AdsK)kDpif;zr2l=uIU$`2$PAY1xFJRU zLiA7P-~w;};Q*TaK?rZXpuTG%Si!Pn-l5d8KWfZJ@z<_EFn}iK(W8Lm|Au}O5k66c z6>WJ^w{igZJ-GkTVUyHMRTBj3=eoPSwJTcf&K?8qQF{~EF^I^>K1G=VWNFfLFl$~b zJ>*+2zygDu8OIqL8NpG~ei|L}mpR7*0H~!in|)C@e~xZ0?=@|#eNivN;A~mqg`YmY zJOdlXaXn7&DqQ3Xbeu~}Olrm9YDZng>FA`X4%TYB_+@B8k5YktN?9T=yjKt!fXB4?H$pXtYQ7Y~PLhN0>Yld(ihVydd*9CEPa+yyXCB zKo@&_ki@}&a|B>-@jq6z{iqH+VIuXqWB_;-4i+VJ-g{-wcFT2ub-B#OXzp-8kc{bzk}?;->pD5}dixKNE^8<_0uX}l z=b9k>PbD&3VG_y#Sn_6$)Ri$X2|S3W2PKRV^JS|d$No%ASKoZV>S z-v7~bmSItLZ5P%D!~vD=?(XhxX_0QEyIZ8CyE_$up}TYFZlq&`p}YBR-sAZG@NbHH z$F=vh*11Bt8Xz%gj*Cu5r=C3;!G08&7ZNc(b}!S(dpZ)I=VfQbRWWf?$=?PFU?(j4 ztp6#q;rnd9M&hO9cJ*JJWuPMC6*<1XK2$whFr9{D{qg)^jYaMwOQ-KoUHi2#XsbHC znSu8isj|ouyaeDUyUs&oeeNXam zTUq6N#jm%}0-`ImS?%BiC}O{|gtEyIqm^Bs5^WkQRqKVNN^>*5P# zkZYmKHq9>`K6rS|UM2m8d=#D~92>}zc;nqfgh1WXK1E5N|7xY+tFs9#?0}77l z15V?L;a?(Ga`x@J8V28Yv6OO!dn+0{QURV}&Wb~4_RC{2OSSc`yiyKt_bSOfDoF>F z7--t0XZ%s2P5DVq5Z-w@(f=QT=$;p{ob3vO?QD1f0#PwJ5Y<Y5lWLy@uD?zX zc6$C##CkF+=^1@Dlq9V$!h~dii?vF1RW2AR@9on{=Z4(`Jdb8`sM377K{O1co;BHM z!Y5RwabEp!yuFucZ_<13_M6fiU`7KukS_PLbV}L0-HU^ur>CdOTwy!7ZG5sXUlL3G zO`=POT;GXOqy$YevDfjR1EtUUJstA2V(r~i+eHD?Thd51nHBEo&ggG;NHmKLD; zA<=EHHGg?#4h=<6r8geSm`fT-d|m9jyTz!f0r4UU#A$HX`Ea#072pZ+z}dVBB+V-< z49WyRb`_ZmwYE|$tNMJT-@eu5nmQ1cO#LiXP-180?c3-gl}keP^un(P1xRdo2OG;4 z3l9AoWaSevI&oV-+i@<}sm=;_#?zFauQZhLf59X6xrDTNUw%5s@8Ko>&a9lTl2@z# z&C7vDzn`$xU9W#4*E`S@q70Z6OT*Y^u0RtPlhjH~9_gJ$$+J%S3(|oELGrE~{|1U$ zqCPK_Xef65{%KlCvbAK9YX;N?yCbPCGm0nOl%EQ8LVgjyAZ~9bx_Ws0uVu?C4^kZM zhUV-pZl?a8xBlyUL$lay!}H*O4rk!?M41h9M^(JUP`q?GVmdKBi9Xrfm{E4zXinYN zZ%_9Y9A6xK^RRYdY~OJPfN$O^} zyH8^H+9PWm*B9Os&n%Zk8kOH#3ulZ;A2G;>T%4tB<{aqn^Ka$SHTfs`?>Pe8(w_---Qq%+GguALSBC$ZGxeuhFnZ^imta@wY@x@m@d`qUS7Kw zCP{;O=gS&SA1~hD-JJMlPEDcJ$%*0;YECcB3|%c4PNY<1@;Yt77puM1l+~lto@$K} zSZj?PBj9;;;-0S=6i5#O(Zj$hKyA&*`#4+{6%(C684*p;h*}oM`e*yz?>FUun_wtH z=>Fk9^NDer{o`ZfqX=PqNZ$8z6VZ9gd$??Q(gZklZ)k7t%Hv&G`uJ0bGDa>;(3!RtUsv$)493nkf}(X4nRMx zPXh=S;Sr!1S?u(GY1Kb$3|P{o=IHRuOQQa0>f9{&WmkTNy|lhWg;u3 zm)rBW8IF**Di$>$&d zj!~?dU8KsCcme-QnTVoXu@-i4^mzMTWCN-!EGI(-VPGNr=It71!(H+1_Ll7X{i5;^ z4pKRzSKIwxj>p4Ni+@K4-*$G;a&Ctxe$y5S#1Z=Kzx)1tIYH-stB~^E^WZF(jf=a# zbUW;B&EwfnaLQ<9kLhu1|A~;_H%@%0n>21(;*A`-TBY*YAO#9gUdL9ONb&IetqL;{ z2K*bPyL4*@VFd}+g+0QN1MtRY-Swk z((d?myaa{e6JZ0nk$yDe!U!0n4CjWJ!2Ja6SM< zj@l>Tm#Qab(=KIG&G}|h)3Y&&J5x_@fuMvj@M(ZrhHuV4!&@CXkm*o>9b&ucjJDparz|4@W6d~uxSdMfxQg)9_b$p|0=&M;)T+L^4(64 zlxsDIe=Tby4IT_DeeDvP$PxZVX$~{XYc?qssGlHcs?fjP;zbTeL*>^)kNOnq? z`ZOWf`|^0t#d6y}qkJ)l;y?KEd~?Fe#&3S{hB9Txy1s7Zk$O(>+Ao$> z!S7cgWikzif>IKj_dw?oZZx#H&q=aaZ4Z!My@kYfcKfWkzyWUeKJQH0guVkW>k3-T za}NAGa2aR*j&TgJS8|0ePxbd+{=lqA5>L;Z zAlEK8Dlm=LC5_0Q?z;ESqm{;Ln;Rv;iFbuVyT0tD?cw20B_+dAv9WBNoImFyaB@Tj zXVufYZchDBOx0H)b5B|WdtBYLa)?r$)g_JOVj6`W+ z-&fsAlNXnXsijp#%#fWxLSx)%5nkDs4OE-?itWYlL;x)^DZ)BfI%B~*Bhqz_RmQmF zsHc=I+}myIGtl=>#s&d#jtY=4^Ix#K1uxIbAP0CAQTu1 zjn>twbtft`-L_r&!{>EC*{p|F%=H8~zMUR%dwVI$4O{;n*z#97&*A6XFHPJHyxdd* z825}B3j|inm=33`fNtX$B9WnkIoMAODNG03(|8LvmcO#I1vHQWE`s(&W+o;lkxGWm4(j>&tGCKOdEIk?hwP{y>rFu^hxrN>jTOG;T{vD- zl<`0TO#08=WXL3b*+7UkP?kv0e%vj!`cscjqnx`rn$Dru?m`n5OGuVF!KR(l1H#24 zFkLvd!NVhfzJ3y=T$A0p@OeMF1p-1mcx1Cz#&dlZlW)R!Zn*w%#e?PrmbtzW7ArUm z05H5xI#zyb*nr5ETvo3HpDtMzTih6Q8|=+&U4u6_(cF*QG5~}6`DpD!^X^_|^HYof z0O^uJRjYB@rj~{b@cQn6{1_G{L8eF{=sMa*OD5H_%(=hfSb)nfdO6U4vEpRPnA)YZ z`%Fi5R7G9!#Ijlq1+ing4dx0ca7`m&80vw+jXVP*?(C2Y8>0L@XbK|GjxaSFgA*YI2{ryQgN8prj z{chYtyVIU2ahI-yVFqxPv$Lu0DZISVA4y%RHZB0x`AVnlXr8?2jisjvG-)=V3$Zge zwXo>2Y9K8Q!6V82=IA(heWy-wx3d1stz)CNVCL$Yq-)5`0t@gRGcVDZC zjE_f~uUP5o>!Vc70(O1?_d#42px;_qj3)g$cNH^v&em?$LSbG>BVWq3TT_6noOWWh zQl(n^Rqv0JAPH~pR16xV3iw_5XkGgy85s+n5OEqn4csnxKB#=V^hLSWeAWB<*bgPd z#l&x;miAq!!Cy?Bj*|gRm<>mq|JIbNY1SU!s#rULc{^OFmW zf!16-Zi3VUG{3*n;1Us8jC>+kYBI*aDBPa4K?8X8YiqlYTT8z@56@)I{tFA}Mr-k& zXJ_Y^Z`T1r7_dMKrY-XulRz+p$EjDS^Z>8-BYcQSIQW>EVa1FTvEpxBa()dWobNh~ z+@Vhnlubw|T3!tnHCL>oW@(D5cHZ?%c}PMhPwGPgIKBYU8U0ef29_tlqXxQe)Je@7>wK?7X%? zVdrKW&zQ5(Znoyi&erFR34-yJ>(z&PYZa!kY~C{)7j|FyIBe|c+V_rOIT5CM+eHk! zCYN~_^!h(l`b(o~4OO43hs2B%3yMtaRcKzE8M@OcC+{=w?jO*rmCa4*oE3{aQXI_j z*Gnh+s%&(`KB3P6Tjdo$u!;jK0y`(W!Uj}T{uNx33*6igL7Z+KUXD6}q{x5A$0cf| zq{T%VWfaAAHCpXLpBJ6~D~hBh|HJbSraJ_%Y#DrSHc!~Ug5ySZ=`bU3;W8U-#ca|T zQ|Yh-fLDvz^vZ~MlRTgtLIL7+vBMlazd$Qm43J3)x+c1g|XJ{=orx z>IkqVd4oIdt>??NXB2iey>hOccyRn#bqPMlj^xA{SPlBhau{DS@-I0No`;~n+{M0p z@DhP|dJ#@sY1g|G@vQnrUS&#NJiP3`kSdT9?xVsBuXr4jWZ7 ze-7n*i1;>gZTHuG|8MIUXn zE7AAe8I%ovWPs)y?4%%USS9SQ=KKN?8CUlLguQX%&MOZml17F6B!8O_f2djT%;Dl2 z2g7&|+xGAQo;1SneVF}X6J9jgVCwHMws1$swl@p$|B42HJ`B?0q1eI^;yz4w9H-;- zU6CtOb2wIrI5NaZ)p}p^P8<}`kFJ{Lc=-=@dChF$=m>DFRT18Y;*#VVS^o)y#Z1o4 z^#jL5Q`5w@%L6ig`Ru>m5T+>Qx!+vmJw*WXi}%-knAU=32^v+CSb(=_LgEu#l0p>0 z4yX`eZl69e5o>_P#?{@e>ggaG2*(OTS$84Hq`Nj-D|)n5I&0kpm--yxD6srod}{p)FU|pA;?Id`KFpw4=zgf%Ud-Q7mpM7 z$WFETQpIdf{$4;#j3d<~rNw4jR;f_Jfai-S{$btz79<@iqt#Fz)^&qMDH~4_fzSDe zOQT$?AAqpU%>DH3z_2sw4RxEf;Tle+4BsfvV#}vkjrhggNyy)B3VC?uU5hkEzJ=Rz(a$IG-iuMz6CM zs!YbLZ#11{F7MDrBReRw=kNoP!C!Jhsh6LbPCU4ZRecnJgWdhVdC zEnf4b8gxIumvAr`Tq2Mi``6fne0izH=JO-dtmR_)pDtY*uJXiX#f6Y5F% zn1zIdqGFVQwfWR9mp9_)HtvF3{PZ5Wp|c1r*`o8DyM5~ua*n{QpyA6v=lNj(T)9?t zf_(k3dU4OcMO=XL2f-b4VIl0h($lEaAK4E8?h0xRC#Pz&q;Z`#x+2vN(82?(-7*%| zJ%gS%*-HMn-M=*>d{L;#L2yBYyqtHwp&8Uy#W` z-t~uP3Q|fC%tMP7bFt-!J|>rUXz&)k^+r#oS#7r!#h;`YQ>eWiXy`A#Q_Zly1g^3y zfRYceTfJh9)6$GQJ=2_<7255K9rYIK1>Sq_`z^Nkc;gY}_Q{6DfQd_N$iS%-QJ8Z8 z4+&R~C2Si31fdwjqD$g;dJ+t053cUHg8NGvJN+M-{_vNtNX5*7ZF3unn3j|=Bq}zN zq(s)nk`xi?f96@IyRTd6v zkYY8PjeEXFU$n#qE2gMZmv>RFr_NsVR|w(UuI}#JUcz9DiYy)3vZ8#k7Gb2JZ_RdnF6~q*934d=YT?#QeaX!IYVX6jN%ey% zWRtMQ7o^FEVkPkiS*oTgb!O&P6^r%yNyYdsAdkWV}kL|T8nON`Q$2d9`QO^HxwdzA+0fDyR>4;=G&=Dc1 zq1B2c^Oolb*~$h+y66Y2>dT|vCWTX znq?D;!Ch|H``-RWd%itNO{NDTa`wiw&`e#eXm%+G7Fw>`8nAx<2vr?0mRe_zLsq3Q zhBeqd?m2vq;f-=E3Zw9ag~9mC*Xv?z92SG(GDsK1aPj#gsLt>HyIJ!WiMCEA#mTGR zOYv(=vrvDv zPMH_C{vnOI2|bs*Lfz+Y%3+Fh74lu6kuNthw2~sEy7o+3%nr7WHpvg(2H{78COm*8 zvk1nf4UU`GC5s71k9O5h3INvm;Y-fDtWPOUL@4RhpMgxn5iBv#%CF$QD}D6>xt=uO zG~13HXaP4T*eP26iC-18Sy0z~MHoDZiNv=h8C3O+M->6$B$q@Ez2gPPN^kiP$G|Z9 z5&MuJH&gOtAzg2#-Oyry1J3z((RyLKRcs_L{CFZ|^ul!TT-;|`9J84XBy_X5A4$m3 ztkj0|D(P9&hNBevBteu>7|uZbgKms2Rq%;EigkHI9wNOe0RA)(i9xvVi+BJxNun@MB)U{Ri3{1(iZFnng2>ivp?S^4th@}%FpeM4F_($ z6mt-lMRgbd_wPV18Iw|nPUEtohKUjWdtBi!4?G0)&OT(l^U z3BY5NSHvF7M6KLN;2@rMLsW>$JrQm3iYhO3BX-cnkt>qDddmQeug-u_>QQ+ z$-j*;HOoz^wnmjDFIHJL3hpLlRWk{e1nh5^pY<&(!h7KNTP)#vs(RYpW0IPA-u{@0lx@F8YM>chw64>yw&@ zBM4<)jYxic;VN5`N%zBMZ{QQk3kZsh%Wuc&P=5Mb_(;@rQm__!P=9EMIo zh5McgUQH|4mX0VmSkeaFv^HJNN+i=#q8z;liZOs#J>8TO#vu76Qxn+Pii$+qiT@)c zI6`JdQW-$qK>|LVooMTw7kV;knflA(#FCT`Ca|OQIE5#R$^L4#oCrSCeRp1K>r^4f zRHP^0-Nwz#Rfo85_EV$Gl7aE<)r^?RVx7m2I3<2rUdqxUd7BnFP1yq3%@%_TAvoR` zA)3z^>EQ*R_ltx}xvhyvm2B5M?LLB`Z}HPhvRu?uj~G!$>^C#_B;TO+EYNNy2o!f;l>whzLTU+O#b7yeD9)D^ETXE_^L#;j&7iX za}Z2D#Lo40uqcxl0Ne>sv3UfLgj}I=YVBh+`I*jigeL>p{VXi z0q|t8NPV{?-y+LqPGgo|>4Jh1hu3g9$+0LgW8kEVQhXpf+Z;E@WQSY5xJ8Z`R~bym z9}yrIvPlgo6bsTb1m=M^!D&-CSmNVfhN|GZIvVU+F2xkpmOD~}CRlsJb=PskH+Y>> zVhZJRJIj^LZ@_f}7ePrserg+9M-AKr?b*vAK+=VFBC%}>=Lbp>Ig!-RB{J|n?vw70 znv4qB(0M>-bOdB{TMo3Z-!p(QveWq85S>DzyF`hUM=3+5XPZ&%VktIdG786nfU83@SYv( zhd5(wW7uh~w;6NH*ky9+l4v=a|9~W_X8fFl6`VJ8e5l?6;!5|&N&AI=Wi)Vdr>aJ zyI7WFXt+gFxD**~6jeKGr17{mN7Pglbe{%{+g`MvJwcn^E1lToyIh@)Gl0 zmSpXDwvA=GY(tu)`J6AqRe?pCRH9^&?)@U>cl;?zoH#TIpGxX_&v91ScpdR0p3&AA zrS%c5V$^-u;X{UktGT>w>G5bt!4+R->$@z!`O%in$n5bt@n6K*pFP_9ua*u?3qm?Z z)27+gGLHF184r2=*Sn}U+u`Gm2=wR&y;rgf7S4UlQ6$sKPYlVUrv}U-xyjn6tG*?A zO0(85>5sEN=q-vl=I49lmyIpo3ZLkodf1p`=-%^)tfpx^R9cZqG3Pm{SlT*9TT;a_ zsrP;lviI^IkfbxuF4LuVz233tOYZv1uY{EgJ-SoX#Kl4jRhj0UH> zJVn_`($TeBJ@Q4WTW#hgdGEF7zPh-p3NwfF5-asl%n|ZJ+sN|Ny`ylA<>Z98^bwW; zT@zvKKV{8kIAcS#$@~pD4kPSPpPGnFDl01Uc24uX``YBnJ@po=RccJ8Uuk$ETE>iW z7!@~j)*f&$%LKoMet8=meWa8e+R?i6o&|1~1C6wFnr~KBo{_0mcb(y0Hu*~yOnV&) zwG=rwGB~mCDm{+Rp!#?`69gva7Q~izBy7-=d9-f#q2efChou(njm5tfCnn%CZe~GX z*rQ7ppfh}9AqvjwtjQL@8{arW7qOws6cR9l8x@BT*5suvEoAG4e#p$tpCg&FSDpyw z86)28%WA~_Ll72n;>B${8AlbU1Db5WDzfB9%?qiTZM-{cWdA!}wdB(H_wRjuiq({L zzI5IYCe}A=ma&F^x{ZTOV!5y|0S+fK>>7;~n|nUfN^8Rps7tFB_HVSvkrZF_<1^$G zbxPh$!B(60>A7 z9UKyu`y^Q+ucIfX*+yMRXftJB%4Suu8j#; z)~G-WSEqs~rlfLvd+@@VzuHj~U11(S`8sjag7*a^JQ z7u*Rgt(#~xYa1~*4&YNL+VJ7j?2I#w^=KrAkd5C#O^jIk!pXYjbrE?KQQ1z~%p+G` zz7!aZin}$Ga2Z|d+pySdY%v+?$xcZ4Qd(KcUCv7mb>RKmF8L1*P% zaMFesagGnR;untAlXjxHz+$O}yu`6}hbx!QAue~HKF~Q9$uN^_+zAi-V2|JpKmDus z#iS~F1jA0;8&TXwh@sPk0iJ`u$ga&LjVl?cY{iQ2*IQ`zDTLqfVOf{V`h(W>+H`fl z@ArJ=PW|bo%f!TO5IUTij-p}(mYkqKaxp~_78ee={%={EpbpusZRYo*`XCTlxk2eR zX>l^u#ka@`Ln}v0HCY0K5;7zS0Hhtwngt;C>ov?cPVNKkKiV-OrJK(DeP$sFWBtfR zUtmzVlvKzE80CB?e%TSVKTZK9HK`8bzFyj__~d{<50_G2N1Xm6ubr?nXM0BOe!(^ zAZNcLnIX`3fwOSDCZE2xcwhJ>a$Decs_$<1xUTm&IjNk^a?Z&%FEW_ouwa86 zh1O=f2Utf~#NY#znNu@U;}Obt^X$m<{~KMJ8?WIhsGEx_?{Yf=Jl#3ViCkecQ%2zv5HQOXJMdBB)%{js@ee10bg z^w=Wr+te~>BYqbA)MMs>r74mu5c8&DQrD)HFy9{CciQIHccaCPEIqD?|Kz+n`lxU( zSob_rV)w1pk@aFa%zWEm{zh;@>_2%t!S`{cERAo9nYz{Gmjn;TeG3w=pydp?Os?SQ ze$kcXtS`j_xWP$)3Y|0BRpSK=>tKrA=4Sr%zps->qkLY>;uj9+r#)4R)Ir^|vzP#d zrw6x}X&_E99B5t<0%2@D*iF%1O)YDAaUJ%-#vh`_hW=?aP;csrtlb{MT^5i=< zgeiLIZSh^Lye<_Nt5-BURSXh)pa|;BiWE)_2@K1uO(J; z--%o3ULOs#s-P-<*w5nUY1xNnQqB_%O{1xQ0e2(2S(xl5+t-|}QVT=z)fCPO4v2ErhQBY=pEUZb@*FSj z)F0~Q9Ncwg_|U1FDDkOhAt0pi zj0Y-wZHye*DR$Lzos;oYiyBVdd~?^oS`P*~_z>{`XRac3dLYPWb!cJiZBq4AHvy0R z&W*zh`82I8Vkve7BL7O_)=Eg%=>^YoR`@BW5sp*t14^!h?AU2KhPw2_#GP08T-E6A z1twC6*R%~7rj>1Eo2S@d#n)Fhk1GVxfEeF0O1Kh;JAY0;f;&V=8wi{R}> z(Bl?P=f-OQIFOeC^o=8Zk8BJx-Rzt7O3KP$ik%!0z8effq+IO@PFgq@5Cob zzL@7l^iMO*1iIVe+Ps#@&vbqqP@ShsGF(vf0CM0Pe3#{sI_i=-b=SQY?ltC*E)PFf z8|LHz%b__FF3zLlHG8t*7ng7IHFicd>!p6b0AOW4>0Y#xcJ>E4wHp3f-%J~QjsfXS zhGJQ@;^5}ccMM(3nel5-bQg#1$GBpobOA-gU^h2a#Beps#1^i0hGN_8)h;YC*|);? zQ?Y6l8g~G_v1`?1eGJImQUteO>%7{1+~&Rf&uRR7UTr!+iW~~F)!l0v;_FK~sMM^l zmdYzvmJs&1*Q`b>JsysmVe4_$gc<64lsT1n3`GhT<%@EvANW|BEeIUmU(oPPT%b;q z4etJ=xA+yK%?&n}bfoWFi`e5}4U22=*$wIWuYO4nv!qB`iy_O(X?>g=8d9}nV7J2e zfm@+=)%-eYrAahx2+D2oF_~P^7Er$6EL2Zjqt7JVyM=#P8A#ZQAS;U5J}v9KF9YNc zFC5K!fR*J5_WFdj^TUWuj+X0Rjd6n4i>897U2wkViMhU-!?%4H%BNSA{@JfTQW)x` z;kg1ngerw1jN5HmZTA?ZunPa?^p?tFb5MIxlMm*UC3Dh$zdUxu+&c_1>&AdO_o9(2 z(x#(h6++*aSXHRXn+A)8b0$71Fi&x>abLD|De6Lzrmts~*2EbC*ti`LtTJ?OwiulP z<;z^Jrmo4_CkNTN#;^u7bxgl4vzP89$~FIH(AGX zcaKmJWf__GfU|?sX1;tASaD2zeY5_@Had4UQ_TTzP5$>K-!Lr`$kKHzvF|$~(JWS+ zg*8*IBe6}cKhqsDw3>;yI35=*`ljzwAMj-EjApF^yDDQE=<83fm7gvmrZkYc57zBn z*CM1xDV5mh@k#~aKP)2+^+-W`-uGWfzOH%$aC?-I#^EbsM~ zJm1(+#anV=jmZ+=QBr5ZkKR3e&NzI)c8bIyHxR>(X4OVU4?@FdAmrdkLrO%)*bl5q zA@mwAS1Q>J#d90Q}>;p9H2zm$b<0OJH;0mGEKC@`A{ z0W`g5AuPVes%Ch2c$>gz{g2my9jUHJT{kT+Yi`)IS8AfNYU%yNgXutm!W-j^w?sYv zsFyfFs5Mq(T>F&qsRXdFeeVX87(p=(OGS&Xo= z$e`o;=UqK{h-l{B{zoV|S1?6X_8^6-55Z1fNy$xpxHTW_}Fjg_-~TT+s7vp0st1dUgNfz8vph*c3d$5 z(9D3w$M#qFqT$nlCeGIqAQ-bjPIe+S%D_AAa|>mO8LA+(G!!xbb{b{9Dfgtsb zdAX>ao_bTcKz!AQqKjroRBi{wE}#EsHWqV=bA2^u(_yk~FzVyl$rCXUgNOxm8f#;o zwnd&P41u+Lsl!hIMda}`!GhP@WAL|j--HP(#z!Mm%W`7VYl19o{|Q+tCVP;zPShCr z_hm~{xhi$PlOsKcYLQd{=41YJF6$f_w3VE6J3WP_Lqx0Bz#G7Fk>THYe^3UfL0{wZ z{&NI=(3z(HmF8!S9Fe<35p8ewj9nJNliYrNFdwDGvmPj_YG)>H->t!ZX{53A#zM{8 z=R0tVQBA4U)6sa_(J`3I@D|6f9kk>1jG>AA&T<>Q3+sXt`O_yhR@OIN)uxc!Va<*n z&5rZry|ecuzHzUWm&nV7i1I~mr^_O+bi5)+Z(1zEEH zhVoj;{L`&g|O`@hOD_Eu9 zB9t{&ssgGmTZ4b)WAoA+#EN z$4not8a|dz2>+H}5iWhz6gL!Sm1B~=D+e*a;-uc%xM4oBwaewZ@WSu`sa%43<5XT! zMyfrVO(tWu-Mo3s_UM7l7-nqg-}K~;gbQ@R(GXZm6Vrs0#=v3vg&zssZlDz@3&Jdn z3+awf4XJ<@zI?m@b%Qs7GW=%&0=KfyvO`pbMTOg!Dv`1YO1ViLo(CBX7VTDD#4<0z6&unC;y3-qOYFa%}xPx9Pl8ik%Wc(6k)=(>K|KG|KQdb{JH$x~bPq zb|OB1g~PO4o53q>{&`E9J*>9#+M(s+HPy@y0uMt2<>ko5N$#<7HtGo*@`z(jS|&;2 zG>AR8b!vU8!4y<6Nu{tSh4deLE;taUTEqGj1{iDr7s$^E5q~Z?^0Cw7Z)!6C>w)WY zbL=+*kf~wCP%q00AV_7ORHF+w8rCw_JylX0h1d(CqsoDz!P~o_4}pHHi0>58W^mE% zIX9;VaLcLaeEEzhpRdv-_ujl11HYbsW@hF#C#(;Z+xoXFx(lJj{EkN19Bs0^XU+m+ zB&-EQX32>U3@pW&(m#}B)^s+^AmCiX8l@snVJ7{D!aA9Lb#)a8_yF=20PpttP3fF9 z4i?=Q^}a3n@XsvN0___Ynu|t^->LDJw&G*dd50NGJBjh(^Da6#Osbe;55CtP?$JCH zWPtr5w^omN!8fJ$1@xWR4_FJO9D5lHyx5Oz-rD8APK4I=_*dRUrV3wbP!Gu|aBcxb4(=QpFE5zV zcF{#>y>=H#aEn%~ER8lIKBn(RC`k>-!ZJ^<=}3+aSaPfJA}fOf{?8gVW2V5nK%6pe zfJgC;t(tG&KgaAhL4(wOBc%Z2e~zp9`dw4={jPI}bYV9TlMaLv ze_ofh=++yNEDJ$22iZug*P3oAmdAb&Gh&heo;gjb#)u6=^C0!u{7vn7y^azQ#7bDE zBAB0|&cXczc;|@=poo{9(t}xZpXD+|F13c2meM&l6Ly^NROsO?4T7|#TR1)&15f&U z2au~9|0G=)aPlzbJ#lYw-K-Jm)&LjBL|p4$voqU&<2NucK#Ls-{3=RJJUK>8q*?3w zy(^sx>ty-<1mcN=oN_;xX1zppiw}v1!rQzh>h#5ta-Z!#7o+Rz18IlUEE)ZIsOS?{ zKTSUm)<}86o*J03$yQV?H+YZBEd+eBS9PyFxb4l?7nX&WZY(||NBuURkhsoTC@H(m zkzh^@bM0oL^5pBhQwaVO3gv48hheG=zN6fak(sxsxh|Wt?sNJmDx3?sc``R-Ngbi% zn;?S+(z*e$txPeyqK5~KT!CzYyV4H#I0}wTtb?gsp87N;rWz7{H0p%Q)UrK^cTT3g z-!i5>o+@e&_@^$D9;<07116HWlWMq$D^`R8+M+_OzAHgj^e>f~ zPQ|1jVYe}G;*+We-&%Bj=`kmc?3$zLS8(;4R2SP8nEg-!{U^fIN)C*13j-=Z4}uzs z1~~Gg+Wjjk;#^C$NFy)+)eSIJ)Ji4uRgA2y?+cdrIVULz@wzSRBg_-kr15Lz6s*Qf zEVW@C=0`d29_sBeK9HHm$ITD%)Y4)__V3M`a>ttov-^N+YFL5~@0YH08Ut$C&5C#! zG|g9at?3$Tft8w{pI=2Dn8)VH?QWUN7j5PQVaBqA3`p-> zao~=UCjNvMi!(xyjle8bNh$wYH9s-$U2o(^ox z+Bc}tE$}m|r%gu~v5*nUVL$((N5&Vw7H}bqzr>2Xm@-*Dexw z5Qw-!r*A&2R96eS&@7ZA#`d+AU^MHw6USey%-ET>wxy$sC&7Bxqi(Ah%NXgdAaZ74 zjp2*9PUF(GwELU>ZBl!k6p{kJQ@GPpm&{ zUDO*r?+r8@ou|b}7t%(Em#P<3vxS>c0ok|I#IYP)T+x48zHy2Eun`lLJ;9d^Rsn^5 z{n(q=*%>?YOL=B(ZTx(9Y_iAuF2x1vJUHSaJ(P1*5(v-bqS^{;orU2|2jp^pJL^F`OnE5dT!g|z@Vt8XvP)a zDRA?(>v;>hf{h*duFCE*u9a4+;cI*jUqa5>2cTH2HR(q}4~I91a8l?k@OO>t&PTId zF$c~Iv-9&QLlZ{@+^)3)>cd~`l>e1k;Vfg{-{_+-TYTALiRjp=)xpl^Mhbo8c|5$zL%7Bj-YpUDZJYXqZ~>o$Vh zx?0^cztS(tN=39(Df!hqxal?r_phSfbH_Fuc@n%$wB>&FD_YvwnQae5|7!^?5T)I* zmxe$fuZf={DQ;EXSJtsAOPG;Vl}DJ)&5Y>^CFL58c46ZAD%7MURw-PJ!e?%TVZaS5 z;H}?3JS+l(kyjeRrA-wS#}X!>`!JX(Abta&@h2&DQ^}-ppo!yo&QA^)fFO9QI5T8E6D-dE=TD&(k{bVxGoGuE0%uBBoh>0G z`@(PiP3Omql6)BdzH7z>bOIRFM@L6}CTu;M0L32+?*}j<{2s33<%_jCzdr%Zgf}Eu z@WGehfJ@5H{8N^gBQ>5ks~+i@nS~V<6^u)lIKqZfu+Qqg$>laUT)Ao3z*UtJ&GGS? zG#WM%a*3)qKl%)gebw=f9NG z6eNb?bl$$(bW8)T_>$J?;3ZAj6w1^MP`MOMO-uqm;4q)o=01J=Ar*<8jMED&XTSjM zyq_bWOyH`kt4sPC*_dhi4w!UuDX9PTvI088(<01hGr22qx4WynmZK-(&6P?;Wo3%s zy!!h3a`8&{<-u?4qobp7vXs9oDwtOK?~eYlw9Q%Hly$R4)r1cn9x`%qahU}ktQ=^k z^aKC;CEFB9axp)@Cp)uVY($yiZEEaDRa(q{M@MFW-Rt<+9vBi{F7K1<%s%y|H@>|L zm*XX5PVDj(Hk`+7k|dX8PNhhef0M)$`HZ{V=`RA@#=j0wg$=*jWI%Ha=>8S?vjKwy zxW=x~q3rh``u6tr%d4wu<6Z={(j?87Bq+$gaO?kw`pST)qONNMm7zmGx;q5v?ifm1 zKuWri?oI*eZW&5Ix?4)5OS)S?y8Amm@B2RA-{H<&=FB~3@4fa~YcGUuJMz8D;_n3y z?VqEg9f0FnX~SDBaD!y=-z;2bem&BRdLJ*alNU+^$`KM)!hBdHxif%;%tOzHgO#=Q zYny333V$U@A6tJ`ic225wMy%X!wg}K1%$g2pB(28$-O|*=5_fux3Dm@H}Z7~4{ds( zVH%$5e5QzBHi+=^3$G`~#{&wBv!{R6k!6F)+p|^1oSd8!Q*Fo^D5D&A$27I=S%1J= z`P>ePTilM!#$i(4duln1^2*(7Y+wrR>iO;@bwWS;vnwQ9f4HO9&nVic94^?Xv6W!7 zSspX!=;xCnV@lN6xpj4E$=kFxgR4DNZYt_YmzS>d3j(PbSzAL*XC~|fR#sL3$u$Ew zQGb6wyMu;CRCKf}95C6Iri>GvbOxKX^nDp6DUvY}-!1DUJ3F_uj~Y|)yyu>^^=IjB z$vmtfRjj^hdz{WDj-s@z?60wDG=$@NNzJxzg}7u5{6vy1t38LUe#*$qwcT;yP*f@e zB{6AYqlfT$J)))!5tEP%YBjqfHJ7WD8t8hP6Uny`<|{=qMR1(-JPHS~ugJsx;H z$(dgvy9(YzyjP6WiXRN|c`^Bk)0))vj7jG~>- zipk5hyY{zlFEs)q?Aa88VhJTQTqc}2h&^`5(-e}kl!PVZt%*w3;qWHjgFmC}j5r>z zicNpl>&}Z2+_RHYK#`il^4DgJ&(5IDVTxCvfzqgbixB0HUQi1m%a~4j7vdac1ccf= zS6~SC(ebshlH=&D7nZmfG|cGDaBrkftIHqq-oVaguOphI5{k_@(GK(-)3fGhw(L(U zA>R%~u=}d;Gw^rroBmY-dOkw7EW<-13Jz=ceEH7bii-?V}2DMPi*5A1^d}%C2+&}4oC8AZa8^8P2@+X~`^{a!ElkuY4 z@6f@cOOcRmda=g^Xnm7zRXIScXLLe6*rJK8L|w^}VGlL5GfVG3F$^~Ty8gA8akrMq zkc41wC(7U<-iEu6LrFwJet|N+A1Fsj>ue+#ORdhgGd^C&CB~r_7zMPq3%^7R`&Lmw zhmAfyJu!6tn_4EORf3by)MLgGJDj@7CiLvJXKGefK}}6UeLZ(*n9RUs%8hsQ{5=2r za$PZgq3$0)$U!(AWEfvoCcM47yV+Iplar7@P!iOK)t6^0(2j1N zqYe+3fd$ChB}~?Ux1s$R#;`ewUjQF%nv0wSh4$6UWeT`uYZ~0}=^VA>^pSc6x(lwQ zKfB&gxVChDaBUT;efP{x1RVb8!7aKihMIWjwld=M#GTBWvC-j_EI5`9mx~_0*OMtK z5-LA`%FNZfaHOx>Z}+qeDWE#6bpb+uxYD>*&ibEms!V~E!PPN{IOMTt^of7&FQ>@$ z)lse`;l;&;|7KMmSy6j=Hp1P?*M^3aI_sI(ev{NJ0^`1*g~Ig>>khh1K`mBO|g`39mAD`Q#`2--C`1>(?+18`KXU<}Iu&B;t)LJHo!< zQNgTuUBfy0Vw_Hw@|gAJJKNj5K1)*C_}L3YMMdEkP=-rlcRQIhCSk668ZW#&sf@P7 z!BQ<~5|*_U9GX?eYe|)&3ZW$-UJ##ge$Mz}K~w{lnyi=v@(#j1f6av)$KkFDIb6y!4#m?9;-Yq*ge z-Wq}Vnw|Ng@8eUu zknZ2zHO-30%!7q`SV?(Sr3T}e)AsX~heNkH$0yhNgT-*X=v)i_Xyq!sD`wrTVzqZh zcbyJf=8)%*7Zglu8FC@aB2WDo_(Vi9^nqH;KPPD9{~QU)OTPZ1^aTq!>c<|}NlnXK%?;!E%0zR@7od$PDIPl#b$VNI>2x>*SDa4& z&}ObZw-lf;aC*4bO)TJ>32c?4iKjgtZ(GX^wdWUnWqX2)1}Z)6*>h;M4e{iP;8>E4zAt8W;HB1Ssg;}(hPj9=i| z&qkl1>;&fhFxnw;yeSXtNoV()*A>{|G<<&Sf%Q(W$sxOp(hOmixSxBwa8UTbl8!Km z_@zlwc8Wg1DGn=wCo;(AHQ&pc50wAM1vsD9`4SbyE+izuj9nNz%+AjFS$k;G>+*SX z3478THa2z%SYf!N9*5$v3w?SJCEELPo4lHuxT-Z@N9|Y4l~I&&ko!M(E4hhT#;#U@ zWDj>3TDAFEELWg4pMzu*jHVyd&k|%!8 ze%XRN9^9?arKIKgSQ3Rx2HW%YY{ZBRbp|2!o0@CaRYz(m6crao>$Q*qx$9)2oQGo* zXGQxdN^=V9#$?V7am&@;jpKz+dBK#-A6kRc(-VoBdl((IfoB)R^^mzp_il~(?A@hG zddA*3XB1bd=JC*^fX8k@3UpLaO*6w}YTylQoE}4{F=~4HeHTR%iw;k<)koY8Z(EFn z1T|*cPtq6y-&ASv%EUgZ=wv)c{2njW&Ne*idrn1}%T@(V)GdZ8jlQs1SO>;llyOi1 zaM=;nRZvnlGxEA_0%NEHF5n5M-Q@VfdZv8K-ZNR#_vBS!Vc{&m>KE#5C7>Y)cUPx- z)?Q=h^k7f(ftrc6?Hs$#g#lEV9%sXC-uD}$HI7@zzV{nsaicpHR#qVQ+7N7fQ2A#i zc-e8rv^;w!ANs}um}FDUNhww4hbO(!h(9Y-qU!Q{c&gNEc9fD*5uSfmpLu$XoHUL4MngFj00ZG`M~;@{ zPN%KTzuf3gOCSAK4RwMncUebRbLh)<^CzP2pod@y#yT#L(yj~MAG^ADZ~lr40xP8C zbR<;D=Wq|X`mPgVm>d4w%z_FU#I#?F>dgS z{oxRn=V+GU-E`kvy${05ZJ6MRJtQyH+(Cy!hub$Gq3GT5JgZw?>DXLVFbRg;Mw5AV zVN-EhfB4(!vcIcoMLFv&BAy|UK@!X#szPbX7}z%w@^Lbt&|F#=7Dg$AT1w|*I$oXx z!WVR16BQkz{&fCjk1M^x8jtpCA_H1HrR04j^#Se|2>)mGiFZNR~jD%7Chlj*?6tB}kZOy^rLg$@qTFDr0zEwe@ZfU!8%GP-mx1Eqv$G z&knUao>9=GGb(Ga9bhM@ij{;K7RQbq8DL z51(H)DA??ul3BiMjrZnZER7!jfD6BsLRG@O-evOoLqte16$=w4=>26bOYP#gOKHX+ zqb2{fm_MCTnQiv$)|!)x6;@Rq-MNOO@3V!=$d#)7DiZM+tz*iQA<(8!1? zV>10_Wb6HD>HS_*n}z4+A~zw~Vv}lTS;TRz)a2y%U2BkDm>4r&QEqOW(KvNdi3Fq< zg+TSAy?ZK0(Yw<#gZ6jJmD+XN`uv);>;fr3!RF9h&HXB(h|$gI7Bx2TCMrx#OEY$NPyG4QjFYA3aH+!SsEr7pfM8=aw_&dS zKp36WH_T~A=@@VVFr$Bn_}uCIn@oh5T+g~bG`CS(KQ%t9J_w{l4L1`h?LP)Ivi>ey z@niRgEax%X=?v_dTHgS=6WHcQIiTpxDcJHccZ80ec8RPHt(|eh7mA?d$M^jjzQ<# zf7ItuzP7gBC?(<}5zwWFhF4*YzSNLVQI{(mj&qA~yjQd}R{UC72e-JTlD< zuBpeh;AI8|?MLOdD=|pQV{vjB=}V-m>!YWq%`^)#SgUP3cvvFwUdhwW`mJJ4);RTG z%f8FxA7-j(l~ek}D&Qt8MUPY1-X5n>I<2gxHh8+Vl#RCc?}_lbV^7b}0XPR0mJ*od z5XrK(BXUPjq!jgPoF6(RHJ{DbMr6J|%yvQ&7GtX()&ZGH<^!1^4 zJJ6p-l5j=JJ#o=QIXK~zi+_ltH!6*$+4u9oFFvrT00*d0SCLttV~YD_D@oQBtF8#SVY zJXnrDtDBAau*qC#%|19!Mv1&YoHC9Q6na=n6JuivoP>SVB->^a-a9!RgYqK2Y2n3u z*&dgC$h|Ng^e!j^n>-Cb7egpH8{SY7$^&c74%kLet*`z$RER$p~oGP}4i&N;tapdV9D5$&8Z;+@bl&QDZO zP#BwC>;dPN$9g#3FI?vKtBMsMYxmc%o>87rmM>QCsUi_?j<%dH7u~974@b6dAt%pw zBlkuMpz5J1uGhUNmz?4J8y`?>Ya@ywLysf>t)!>Q@Qr{(Kc}pDjYTfzt^%GAvEiGH zEkEz4yWi7XrwbhqxcYv^7}%eK^YSOlyFVMF5ED_Z;fHvKtM-e}boFe=a&m2Ye3AZ4 zXYH}M*4OCPEiG41p1@lDR3=f&9IdLRrbLe|HANMiha~-ybz(t8p|dhhH4$xVG@Ea5 zN94&Pnp9}pQz-)vc}ZBF0PhP_3{z`eL#RF)>+{W4-bEd zicTcSC0?M&hAOk8BF`~%h12uCEZhxaQM1qQai9hOn`(c)?YPn7zTX43%)89(qKbBD z^D9Pfn|WQ_pec>{6~a)eF&vV?coU8nnP#24YCEa&<_tJ;{(+`^l6gp7x%7yaWa~p| zlinvN2HR0>pAt93lI3VX>>MN=g+oI_Lq$VNA{jQS!Y@z_PfsT_o9O=QzUd(R5WYf< zbwG{tR;!ltC*UOYrx1(hV!r4G=Fic(wEvu#OO_QB6@@|#9Ui?|Kee`}Al3_gUfe#u ztym@}jyA&AhQ;BJLo+w}K-9>&hgjm=Y&>m$uGjW+50*9+sAtmRFby%xj)wzj<}qKTJ(?!XdXL2$e}D5oQ@Qva%}q`-kW4+W5dg5oilG4j6g6RZ!YD3M7%V@&4nH)+R+d>F zwr?oDMqkJf7cH)+Cln*t9C>%>7b`w4KJE-mkeYPk#Ft}KN@13U#4@q6E$AVDdAsSz zN8GnoH={2B>HPFC{i){Diay9%!3^;DmUWe>O~~R*TA?%;Wsc!=BP_$j>c~o6ljX>f&Nb$3XEM`$bwzvON0JAAq`GMwTY}i zo6v(vjdtiu8SoP5@>D)9qk*3tY1!R}=OtmZaz8HWPuilfJcsHK_?lfl>?+8?;5^^$ zA(pqo$tmZ{Q$b$s&QEw;pwGIVr|m`~?_d5Z|1mx}!d9roSbgI;GF zv%*5)iPOo}tfCPGoH*WP2@a=C?hud?Y}L)U)wm2wH)}c{ALqrKu&&&Z0V5-kPG=j? zIRGvvC;(nKTlZc@ue1qM;Fjkk?5<^|9LJ9+fmsli6vinO&=b785q~Cx11oAsnQ=WT z^s9`SJ4eN^@$;8tmurs|n|u+ac)?4zm>8E%YfqeDp-va~gO~}-T0dfGiHEMeZW#j1H&6DB1KYR-wA$O-IU$clx(=+M!721Oz4OmqlG#0b?AJ4?lpJvPph9)LoPEHsiq=GCs0}Ew}i_3O;`oVtp z0M4Ch+1dYWc$MjgLQq~qWMBY3c!ewjic7=wljnUgIr&xG&&0QeZqD*iCQv%32CGeN zzm>e>j5liRNLi{lFtfJ^_SQfBnaxxA9gTV4#&AY$wDM@U;rc|LHLf2gF4_bz%0Zur z$0!{3mA?9~0;6P7x0*kkMx!-k7nsw4C;!M}3EUds`OQc)&A#qf609Oz^5Ms)#zdh# zwZxo?JGo(GQsKYZc)2^*d*vdz+F((rROjSR>lO5XDEZON%w?`gHxW+8kd7I27nUcR`V za>)WtK%FmsGzHmwTYGZ@h^62C6yw~TSMx0y?r(@kQ>;eLVLi^K(1X9a<&TvB5TTSLix%6D( z&4H%rv+t2GH|6nc<>x_t+V!3a=akP`(YSvC-SyBjbkcm3BccEFm@4M@*G9`Cn^el| z12Xa2tI3R6UkGy_1y1yF&xjtefae!)3K?T#j=^MBI-H2Hv048EUYnIi%r&jl-pG_{ z<31|gKTS~32|6IjN<@uRR}^Y-6_SuJMu~t`UOXOv+&1?cKgi}1n&&?R!)gwfqk4=S zlHJOvv5QU3-u!EGfR@DYuUY&n+qRru`44a9@J<@#D6>K0?RsjrB(Pb{S8uoQ5}PnX z$HLNDpr{XM{3u?4V>JCS4(a`OUFoZ4FX+@%UNK{@cy=Y- zl4kJ8EgDf}7Uqcw{9qjKH^GN0bJ^d&IoJiotaVs0Y*xfHuaIHml?}xy^j%5Oh!A_O zMXuoUPDHXzrN>RBa?fFq8U3S&^MQ#jwi1$WVwh5fSzY@p?ej&)xgtV9RfVQ>xY(=9 zt;9*(6^9O5s=U#_NnnX-=4%OKnnLv9p>%W0`=-6Otmp;h`^>gS)Oe8}7viU^r=Pu1 z@jToZ4i+yzgMtOijZKN_<#yjQ9yQcLhoB*L0teDo-BaXxQ*xXn_mVieoLl^46;Tab zki8N{#toZ!ti8&iN8G(y$ZyXL*iN2yM4ceP5CMZxk%K9*Tw0I2 z&d8aGWdf-%yCUU`B(4T( z@uOZ}#~VuHjaOhZ#rNallMB<73`An>g?G zo^$8)@hVx$I9|0$ClK}37zreeRch@~fEWADuiR(cwyhZ9AB~LC=bBJCoH)RWh>mxG z=Iz-J1dM-EbN2RLSv0?^GWlx32r%sRo?b+q{vHnPlg0Y2o$RMg_gPAyf9h zUQQz7D7j%>pobn0rCqvTmJV;gAlu$NF$QHg;K1hk+%@{$p*O$(ZnC2`dVIOoz~`|o zxa%Emi(yk_ed9>X`fj&CwJu|&FdffmYJkg`#Xu!`cYb*}yrikhR3aDiYN-KjuznmT zX=H23j#<7>QZ7u3S+1{o#1VB3F#Q};>!c!+D?#+GSV0EpLooRl%Pp-ISAo!Kb@=iwe!eyBfKC*GlWQa&RxcH4X=&?}fSD*4+(p5k;+E7=u~HeX z`$k?c`D<=d(y$I$zB>D7$u85nr(3iPP&d;MyYiehmmA~Lj&>X~;7EP_Smk-am`|lr zhsnYs??82C?Jq7E2P2Z|c;VJi=$v+0P_W78NgQv^pG=T}B3 zSCQ~!CT7GhbB(#ZRtSfMR+23CN{lbMA-~8CsUjBrR?d=B`l9@I#TEKm8o_nG24i6S z+PwT6`qxI+h%R|ct9f+ssUxacZWB|64@ ze!BI30mZ3%;8Wa;b%<|Jw zPo;wR8m73z*?5E7cTu?v^^(x~-UF>dS!O&_?H%N7_fu^vRiya^8tZ903OvO?BW338 zDmg4G>;3U=yiwsR_`==T&s^l30g@8qxY@p!#)9X+y4?vrj&o%}IlEr_ZVcjw1{7MA z3prAY^Ac}!3cS~>FpH_n=ifV2h)Ky2 zvETq8_k|4o@)2&i)uYulW`?WbFYh&%4>GE*)g@mhU-Xs`8XrE`t)yt|+}{yb*lo8J z-IMdwMkki5qdjSFwXa_J^|lmda({)HVVw;Y(=Rvb#%jyMKFT99sJl&L!5BA_{FZ&P z<$d+45$sG<^7p?}hwLqpuW)$Hlm&cC-&n+$pqh1mYV@LKohai$eBV&KfXnEjl|4Gp zp}GE*++MBY79LI{ztt~cWg-HTxBh!A!PJAOJG#_a48!t=KSG`RbkPfVC6epzK)GT% zvpu;WNr8#XyUZ1Vv)m%I7O47;imhV)-p{+=%O5VKTTcS|@XX_Ik+1#nqT=jk)UVz9 z5NJ6t_&iQG%NXamx|eu6a*%Y$L)Kp)y3t`!FeRk7xVNYxQ#|a-Fenjpy?&!Nv(Cck zT5j|>Uc$PCk*(S{_-0EK?Q z%z!&uj@j6idVE*)^h2kLm_Kl^53QYXk-wcY`RA01N0h2%X|;LHQ`>-!UP&Ss&CIi1 zEbNXRWXJ5Ra;o2_*X4;rPHar0N*Y9~FGS29D>`oCuual_7<7A8w0zzoJcs(wSZmWX z`+skq7NF~G<(N6;M?|DxBBGITSj=H`h>`Cl$~nAH^~XUMM>c6vOgcS#a}_D+fn8dU zf{yu7_>fS1Ph!SpZ-0NM_~_|=^eI!Fu@`hSSeWOyMD;yXTs(q#=2BwRT~~y4n^Ku% zPhY#GlG*r?K5IG;=Ss4n9TT2!%sP1 zt^G*uEMdhLrDeQq{q4-v^5A{>)kD2iVEggoz|~Dg?fz^Jg77of;2bN@HKN3U<=T=M z-g4p;c?pMM)}wn>2KtF41Vl(BrW+c?1xfqVQkKbD;^SxE<6?>8ZKXwfxrHM$wTEo*x8QyGNsPf@iy+eF zee+d#R3H_jNijP{6U$#n%HPCMWX#h67V3%wm;q}^_#78jyGM$?vCkWC1&yB-H&5>^ zTU(JnL|A7~4P0h+t!T}zmi{eJl4crB?CQkAmT8Rll40D^Zii_Um(&TETcX($t(H^d z3-8u4M=H>E-<<6X?${N%CmbQ3xm9Rpdk?UOR>xLbiG82<)?8S)am0Ok#He*1)$wD^ z`o>rYcX&iUYEFiqgtS2OEZao6nF5-xkN~_rDt@})Q=sQ=-WF` z5&SU@Lv_FifWEWXd5|WRz21{*sHPYzEtdx{_$Nq8u+?S2)|8`9`8!Bq| zM_1Q+@4pk@$s2fjT9sxhi9$Wp=C+Pp&V29Wrx4SG@sjNx&7XG93K~;@mH1mFY;_t2 zT=)2KMz5x7j^Bv>-aScp~q|6i3`X zIF^Od1>oxQmU~Efk&PA!is-j5I(GglNiTq3e9^cMv6PobdD`l@e+|q4)P(EJN3(Ub zVAc{Igw5-jx^djMIK>|fTkIPR-cN50d*QZJU@*2h%X6#*zH_H(sow3Z>uT%PWI*WZ za`~eohJT2w+V>!&Uj_}iiZ5*=OyO0#>=5Y%bEPoTu>(^RPpbZp6W6g4OE zz;zK(X?|2I5KniKIK|=rq@u33;gd4+C>*e_wJlK2+rGmM7qPRc z9@ph{!rb~a=uy4Ebk!TuvF};=6+^Q$u-sk7bQybw!l#vVXyFhEj23j8{5yIxgM8%! zPmxp|l(3Sm>aWN0^Efl}KAy4itGDI~oNTVH>ra+Xdm+q&=S<9n$btw<V|q@*i8aoujuHIcRM^x%rECY1f%)A+i5R?A*_Fa5h; z1LGk+nq|Ul74Jld#cPziS9RA6&&rvu`UeLxggMotYUQJKJ-^@HT||Y+=|C`3EKBA2 zeF}ts%m3^SlY&0bsV5vVVcHuctS>p$SdNKz2Dy_RI4+rVnG3X&FYRA9?nh&^V@Xs43 z9cC~m)EO_b)6xOXDO)tjQ!EKyhy2e4t1r{lmJVkDOW8}m#-tzn@lVX-AKFCP|9LaG z$Ug?;fWGRgK`;OJ9q``2?ZGGh`|SUDrGf5{kZ2+X8%L_sff%)0bmqci=Xug+_-DeB zzi!AL_+Rq^KlzQ>BvBfTaK!vXP&p=|1AK-pEg$nMJ$%96t# z=?f(ZVz?-;Z*ud;#U)<%V&m89#Z)BBgW{c8L>f~UC2l*KL>lyG+Y@kPLjNIkVgeX( zcsx%gPWAMw^T4yWg@r}`Ko%C3l_meF5cs!8PE}gWGfh9lQ$q$qjD*8+{0mFyyJ!kf z=(HGUk}W+PRB?F-ijF&8M6O2#=vLy(A@{<=6Lqu2YEq?QccqIn<58sy$IBL3>R@*L ztg>MqltxBeaNr?9*2v{W@D}BrMVbHQ3SRE2QUHi08WP$R%ER{0GaNev2rk1CR@%Fw z-Q6b9P0@(7KdA0rUJLbYC*NWGl;rt5#C8i&QqsAMU}QiQZq7Q{q{0XjV z%&?Dnl!Mr+Pe{*%ATlB?K6YcU-$XBE{1<|*Q%^2iyWoX$R}eSeu&1AON&MJXo5R_R*r#QmgjR8 zU0VxG&Zk~P_kUdJt=<-6*f~hrGHws%#15~t7^j?Gs)<(jLv}nYC@JyWm`jQc%n+jg z5f$)*D`-|^9ziY1!*Ot%<##v)nHzC`e_TB#8=8{*QujRXAJZp*P4U%WtuoFFskDxo z4mEZ~pZv-n+2`0B-$GKnJT75X^atTDgTHOYlouBpI^E&n*c?NOH%tSN)h~IFjuU(lx3Hq9&Ci!jS=VTtj*^2wDJmakpvT+Yh1TTPIP%ga52Ib&m& zp}d^Byl;=7PEIJWQWTq43-r0gwBr6HO}pMzwm6Co{okBvmg;S(g2m}^+MP*zN6{`j zCy^0TV@jvYISG5KXaZ-ke;ygsy9Cl0{?vxWeqeb4Iurpxh7e~>$=c|-{m9K zGi7287FFTOuT{oPQuiT&Y01(NqK8=6S(Q{%XdnPydh~C@f)&ic*9aCMYQ- za8(~UH0DRjNp{X<%XcU$^pLyF?PSireG;KqzN&(@IuCRHJ^|k_jDu*6Af3-BJU^f z>ru@%F=Ec;sDRCgp5<2tEu@#tE!wdYkzCkN=+VpnoK&zz(!6@pub)G(36Y+|QZtZ| z#QEt}$z!25%6jZZvf;G4at!(QuO*&+ZG6|UuBu^J*IX%XUNZW!F)lXSCzq-~puQZE z@)M$4T*CM~9g{wVInj;?2?-g#k4F&q-IzBIyyg~7yZStd`2-QW_@v-M?*Q#+oSi#& zDp@*Ot76EER<+<^;LjE;`v$9&FiiNhMj|&U&$GfS1OFIdcyUje^}X&hxt+k>bBRE> zUNr^=_v~5s)8T4veRuBQvxUR9qB;LB%kJJkJaNeL*XuS5mgnABx(K%LtbFOd$VcLg z=6Q)yIRc_@3}TQ}piuh2Jf_CX?Mk{*lxGv%0^-Fks7!fI-( z&vE`Yyg}@(9W*gjfiMe1KUR6+(HxP{BH@c-9p#e$AEE41FjW;Nfg);^$>3&yW(TOf zPTcSD5*hy+<=_@+f^k;ee0SWSv_rqHd$vlb*!4MumR_!;5?|9trFgsfQM|sW!#DtUIYD%E((?2wX`fsvy#_;Kt z-_zB<78i+t>*5{^@&AJABJTAsc_2_|b1YZlemCcl;h!(oJ{U{Z``TbL(%_yF zI9&L-ltvQ$cg;1|s6I*TQ32JZkdPuTv6+=sgc9f!g9hjP{QMuF0aT_xj{4*s1O_=< zH#C3yZ>r#idx#8fz4EZMa&kVYgkbk~95_$ae_9#&XHEq7c*^<|zw-33LWhIAG+^}K zjAPN|-{QzfOJD!wY47}ZDNswprDkU4gTX-lVWgg)MXrNHK7t=f7eO=wjKO-QZpTdz^o6n4lXLX<@20@Y4SEL8r}mJ7*0kd@Zr1xNxjygD zFZ{@eA2Z$zTm4O$Jbl!FBVubE?Ygtk5b7_v)k)2mf42M8-A{Z(qymbfkxs7#`FqOO zH(37nX_$4POtc`2m^#{CIsZxzYND~gxBgIjgeb6+l6$&rHM^Vx$B;TRkA0N7p;v>6 zvcJ^P(Ckw>Xp{$S*>k_R8C-i$msoLllXBOBb)2*D^giQew4BsnYURNgJ|HS^ElX3G zKKCP~N-H-{+s+7C{~?dc6uhR@You9-rI+#P!|(24+m^lfkt0RBj+WZL)q7V4<=;_u z#!DZv<%A&A$jLlm0kPakH=``MKQb`#?{xjjod)yBRR)~C8eG}k@z2sjpF_hbZE-5} zNGe{>im#HZvF#F2HMZiR9ez17uPBdGPc>so}lpF{GYp0qK6qG~qkMgEl$(9+Kvsao|& zyun;A^wJ?UqDN`3?z{c&I(S{q^}xRoy16NEcVp0Tzc1Laui`3HAJpe2_-m)*T8g&F z+#Ux_<{Ok^AhNXDe{A_ny#$m~ks==%)*Nb?r0g7EHMePI&Vc`d6PI&ATIGeOB*N}$ z>dR!)j{>w1M5z}-`9=bGW>XHq)Hu^(yql*4wXw*A5UD_0ibxux5;^Al4K3P2V>WKS z2*VUn-f!aTi4h+cosuHPasIM1 zCh}Zl8&mA-@t-R+w&*f8^Gr3P29h0 zfcdO1g%Q=518WkP%Unn0?Q9Cu%b6Mr!w z8=T^9uu6Ztj0KV9fK+lKj)Yt&nx>cxcT z1dVSr#Cp1g^^)h3-LJ8s`a-24? zcc#SR^aEY7<^%z;&#}AczgE&fU%oVs*)9d)&YEeM}JPmcS5^GkiWRXH)=b?G#Y@M*JqnjO~x1seF?Ds-3F9ne^pSLD#BKK+jdV}~V|kSBaSrkNM_a>b`GVc{_Wq~M zjht&fOeF2KWAWAChl+kn-5v~l-&M6sxV*ePn}zx)FpRn8pE7p+-&$i-p2?BORTJICT*KOJmvSUBLJq(QwU z*i{xS5|R2Nq+vPk@Ka4mXppEPYv-`#li^J@1$Ke5Duue_`{ZBb(hyng_sYqFH$4p= zx5ae44yUMq@WmA{&AYE9$UVUN5c8C-n4y7VPm7m|GP41#<&00}8OTNeJarjcqca=zQvw1C7urj(%veprsM*rlf$e`M&aQDA4 z%UKPJq3VQdB*UC*i@%>^cwbnzo(>Fp|B(^?2~KO3YS=GCEvC;w+>qh^lNx#!OD;UB zq&`!h`7#R6B$`oqlW)6dx4{Fipr7m3|Moix-rYwkjJh;k2^|?vRnwq0leC}rimWc) zAZ?qq3|%&(z9b;KuOizSX;~Tm^#@;7E>M&zxQ9Q?Phj-bnX()O4fL7V*FRTYS~?DW zBn^(In+}-SO(UGD&uc%}PVn}=$9>R$UB)%7&Urm5%<(4Gw^iAS52aEAXZD} zGaaWxCPc-EQcV*UC-iL7{*FXoiE*~Y4YXP!McR>^zG658b<wAZf`W`y{ZQQf! zV#{a8W2KhTCr_l7TW@e#jDYpHLy6E7;$BHT>(X#GH~&SA+Mouem3yL-iO6P~=a+FO z)x{EEzsPDLU^K=jvYy-@GHfkcvSa^qMUN7hn9U1e(Tgu(^q64jUtMKD8xD=ZR&T*TyHpR=VksgA6yClXRPWnB?SRu?wh|=8#~b zV+_nxEWP^`?LQg}1bgZl{9>)&tVqJBO{ZwSP@3HmbSn4!AZ(sQke&$kHVfRzasQ0i z{>VkUWo7pm7gKFv8Ts8SeUP;!n1#qU?P8zjErr+BrKfKBesh(PI@e%pqnpNm7xh!`a6o5gBF!^2fhI~Rby zcRC@@YFH-4&_uYZ{ zTG!h*O|AV^R5G(Q`)~o}jk|?RbFHo{qux8(@1m4m6|j^yn;{OSypeG4>-kL$Y#dDP zE}880Ro;i{cZ@W2?#7Dwg87Zf8mHKF@MS?o|<7}r>{SrbV@KUiyBFV zcybW&OH2+;v{B)X89v~Sb{?~JdA!ROeD@6@HZZqJh1*VR^hAx$O8WbdWqs(FL(k2L z!)b}h*>;q|yG&z~d__W;As5=Tw5%Sl{s`0b)-mr5B7>sujEC*}IhDR!jGWO_GSTE4 z!Q{5srK!B=otqGhii4#=YcGQhV2Ri>80*%tfDlLyX<94H(5`W1Ik*JF!H>3!j|95` zG0K9Q@HH|n(~iT4;rE-nPZxd&lDUN(0*b^k;O;xUuXBo4j$pN`@$zrPka#`+usKcE zK#S)*4qPNvdNyy6mKUF10>U;JWgUN@X|wYq03nmlD-_scIGA~70+S~+p2Z*6*Sv@r zq>>C`aW3}n9VgL_V4Ql(f{l@rMYOZECysBLOqiw#21>-OqtGQzVbl<+Q^B1o5QvPd zehl?c5EggOM;tCP11Val+D>73XhXHj8RJhS5|g9DC7d*>THI1F9dh+#Qo-f+yH-so zQF%wQZ$*$MJk1NhH!|ysw&ry_=Y8-^As@r(^*0^Vth53%Yhi%b9svr)zS&AcA?uln z?q+^q+uEZQG)?%#okN?S7%Zo{&8HzODwFEOF_qQGSzNYGy_`BQ| z>GW#yxonXBr*y^r=^BqR@!LR&F#WBu3_8nvlsVU}m(#W%B2^2{N)!)ZdDV77eSO52fKqe3V2$Fc(=#cIi zLPF^-1w^#Vx%b&;pM71g zf`7q8s#VW;9Enm=D1JPoH8gG`1b{V8mtI;GQ4UBG5Zknl00H^OmE_aTGx$ldm4gd` zD*;K@wN$+57Ba_UYi}BhUfwfz{OKwZ{qF)i90Qy#bmz)_hw~R7xk{-1? z2~UqWJ{F;eHYTQ_JvfO(;YuyZNrMnP5=Nj6FV`C&g1W}V3D_MMbFf>FWQ)0)bT|Fe3u{|LL0K%qg0qW))l%EpDz$F~o6 zrJnsu#VSB#{159TBq};cktjcTb$trd2D4Heb(?(0sq4D}r0wNV%SQo`9-p;VoElLP z=qN;{(06X0*GPRT9A9}r@L90&tEq(O#JQY{t54eR=hOf0^d{TL%>4aEk3;cK9zT(T z?cVf~o^eG;r5EB>rD@HsM`(Ir&Xn;z_a4xZXtFz|DM|%7I*Dh$@ExMs3g4JpK2>M; zwb*R60&W%j;-u(N=LAN1-Ois56CFOH**c|^scC&Ck*UoN)9VXlwV~MxTDW&lfyl}O z#IU}872907z=(770z^ba$H@4X>~KPXmED&KvFDZpKnUW{A&-%?zltM4o*#kXq6$O3>oD%m>ZWiMuq_Ts};e7if<-T|E&z(MJ{5>)$PU=2%sU&ybCNt`HmLjxd+9mYS^Ncwvz&^x6DouV8^ad9S1dd?RU$)j>; z+?`kI93~cAhW1mqgwpIC{9*=%6PkU-{gA3^_+5P(!{>{K?BiPZ2Q?oPvKRv(#KU?_5=FP61kRyj3V!--Vq3z$3C1ES ze4}UIh`QH;6w_NAAI6CU%=*$|GZx8-vH6}i*!$)4u~!>N((s5gR+rS%?CJI_T958)YPs8# zOV8oM&muCSgC}LzR7Jji%;WzKeT&W@bn(#+&k5h!4?gyGY(GP2eU-HEy|!=WFX1Klx)@CS8bAvGPaeviulWKz`g)bL<*1hIFP_4Quj0+xmY+B^RTCAFqZ*_8y2M|WZlSKCi7R+l}`Nf6K>TaC>}M>2H| zgsxgAZvXM4Y0SSw@qK#bI6VKn$>H2(lY1}~r=0hgag23%g#g2Dx$wSoEqRa(s%Jq- znTEkK8jDb4{1B)0+1(a!FNf{|`+6RZ1-h=w^V~PDn1(njIn>q+2d#t1^KI1<=dy}c zU!g*oZkdld&`+tKz8KjX5&Hb&4c5CKZwWmsc~0aGi*OH(vFdR0Ci(CF@IR{yo3F`e zvA&}Nwh~hH?K_&BoJf4E(FmU!({>x$May>#Kq1*KiI|&j;Fw}~`EHDFkJ;+e>;?cO z*Pfar-+RP^trX;wo>HNQc>H0_XYnxLS3y?>@sovLFICv$Y3Kk7F9b#@1d-IOnYThO zXf1Wwvq{(YAb?`Ekmwwzhp74tr@hg9UvG;~QwpVF+E58t$}VY_8^_FblN(8w*p}bj zaQMt+;R*@|#75Sx2>` z3u$L&PG15yHX$aIJLLAt(0baAK&gvGwp6n$* z-}CxkV|)$FIoTTl@6w?p&f-tDmV*}8mWBaz$MV~KV>;*l6MHSsNzc2s#gnT-y@jKV zI_od8gAr}6OYJDSx7{5%fOvHp{RU88$t5sIg@{r8w+1@7g-v956iurqE0|J=Zbn(W zBjNegk+&!;;-4;YdBi4&TWcmZ)`x{5*nP#SmXK>TbP^wz&}!NgAQ>81KsBDxY_kln zz9(Au-Qc)jlGHUy*Vfau(ovzQB*gI!CIADaWEM)~jTzyAEYjrS;6r?IrAf6!sZoTO!s z>25gK8A&bykOK0t&kEaAHN^@(HH6Z*>IfY9<`kvY4mXbMHfRBpFAg{Y8mlf|M;G~g zMX1C=~BO zAypZs{dslBL~F*aup~)Ei~2jA=}^ct&KoIjY*+{aNM>u>T2}{%h}%X^F@lYM(W4xv zyk0+GoK%UZ7df@95S<|U3csdO9i|ViA~Gxk!zC^ct@}b?0RPX7j9byv3~+0PQybpN zb^qAJ-czvF9<^fD7q)Y8L4-yoG`gId6+<1~ix!J;K|b|&A{0WpOs3zEt>ZnWonc}v zb&fGah&bwsh{+B;0o0M+Q?ij@z^&Sh&#&8TRZLo99PkuSDoOSlK72{9uegd`>VY!hXX zvwE@IkwaNkP{iyUNRe{?|%nqpjm^KEmI96qc#iA z9)ip;xf;A1q=!!*b`hYyHm2VaDv?MdcVl8GF1#sP5-yg|2T8 zZm&;8b96SL{eEf|so#A3x~@*fUo`vhmDt*Hmo+U|Yfr=>J;PEFGUIC(?R$9x(u9-6 zX*PC%#SL(G?2W(@8005Ur{ojQ6C7$Bs5tVu=j=k`O4NV~k1&wn{fwr}t{OGPy$fm2 zVzl?D)J$A}OyWmm4;Yq}tkNcNLX3=HbOXghv4Gp0z1uOozT-DteUAg46sVDru1*}5 z%bbKQ#TsLNS9Ez452Dh)|voUr@|H2lmd~aj(@cdU^`7 zvLt~}HyM*Qo|T!|r=?d(=?N~;ABhDP$^fPpcIqFatnyG}htECtZU%1qrylr#HJ{F- z``j3Sx@cS+t?Sj8wumLlUeLfY8?E}3{xeJJx!(nZzo!l)408WX2zQHs3*Q*U0+rZ| z<8LB@o(ESDhQ%-+NnS zX?u!v-8fROm^ zrWNB%fg7hX_j@I8q-FE{c6>d27yYl6_3kg@S|b2$i=#k-X5+DE#xh}{<{a!J^GMx5kjW@nFQ?j6XQ-X!4LyrYB^5#57k=s zCNEm74g-^yo9gw}2n6{0jhR^EN~-z2fo(d2loHI4sF|Kc42hxCWVcT+Ss*u%Ertea z{Ol>aTqZql#U}Cn?&7LjMNz32Bi!8{1<&wEMMT~uP;lu^XQ3gIFQ3y|0fXVOY!i^B>7wckxjU-j=k z1icD4MBi?yJRD#;#ThToeTzgimn_Jd#W zk6%_ep_&F35a=U&uZ4itjsnlu4~iE|GX21L)|i@{7ZZT4vPfWD9cC6>ZujQ0C46ih z_iUthL#ui$2n@(P{(b9?Pdb%yj{MKSc6&U-`|f=4bbl%!qNs>v?cx6Nw4YG$xIb2~ z#qC;?gh}oj8>x(XCC9)sf%}suANwBnzLy7Hpj+nj;PiI>S>nmfAK9g9yEk@Zr1#qc zxzhgW?&gAyQ-6NS+?{!gMj-bt%6$)tB2A<|MO^mmdQc0z>=%3(YXFKTWdUa>rp>L< zl>hKWrOqjJfbZIA%(zLX2ch}X<;mXrAxnqT6Urjdd94Po@xx1D$@z`vf#>V50sko> zk&G7qshoo!J<09I_&tC93s60Y0bxE*B>ry8-#ladaA1yYJ(4f$zx>6SFh|_Ie#Sw-+`l)V<&Y2b(1cWdK0y_Z}M4Fwcy zEKMc`)-?oz%ySrUjjl^zk6W@_I^u=vJNeolv@7Fl0ahiBX?DQx7aEj|^+|^&aK{uc z_)I*3y4Jbul<_JoYG=K*YR24W0X^$Vf6qZ%kY76QLE)?;HsZ`dTwPpfX{Rorfk;|j zW+bErb_tm(kq8_8=c}p^AeYKoG@5lbdu903gNdrFvQp7vz8*99(Khi~>Z!wI$QXWC z41NhnfcK;}v5m0`D=ewdWv7vUoUm_v-Q=Zo{rjW%QoOZC%;ukypECy9ui>uPjy?V8 z_rP?VwSH?9*3x!VV+g|fruECAC8j~{FDO2FD4_Uio%;jM*Yks?U!J@(gM4x5f!{>DyfVZIg%Cp$(J-u6~ zp8P${RCibGML!3&bF7%_qStEO=jMQE%oxQ)1GPlYhr3Jft6#9<#=gDgv>&feiGRFD z`LwP+1K#ogcUk-0#VT2GV0~HjY-by}$+yIkT~y@9(9mm*N9lO6KzCMe>?u`60zSHm>l3K`<0dgo`!9uE?ulx}yvW^G>K1H9hRZ8A{C78u0a%;%IMz_Zi+m{_zmjWJUQnT zWovLbd%UQ9`Yf9GFT7*`H_aP(Lzne|eOJab}8{k{0aDLmucq!;a?~Im{+oQyqy<}zb@VZw=eyjyTw5_ zi2|=JW6zm9bCH8O$|e2u>a)kb^_T zQ$AQda5R zca`cS)fyG~@u(C|q_Jouc^o9wNY}z}kC`>P*esG0d%`&O+gy=#A&0#wIg&*snF3Fd zAxY}H)F7{pF{QdCnVJRzbk$Gf&DS44=rs_JK0aSPx!`-*Wwn+my_F*W&--?kmraub z(X;Vc?sWCr4dQ#hfb^>{XsJ2T7n^Z$pi@ECsjO*oa~CTp$D{pRK$3rP{WZngHLiCfjZ{i%)9 zcAsYJYP?^nthfPg65@f*hf@8O!AUG-rzVd0nBk}SIj`E|MeBV09M+09>P|1r??I>U zPTiS$`NyNNRA}bYZ5e|}u)vtE{I;>wDa69O<_J+ULwjIJhw4`G#uBiSoBIEjI#Pck z&@7|&I|@qBv}QmX`nWhhg|ZM!6Ae=gGv-M@uY9>$FqcTs%*yf);QY$tIIO zMd(ZQUp=xW)?7p<8DePi#CbxGnoiN9=1E6(ewbiQ3MU=d7SvH=#-TeRoeJsOUmDy- z?aBa4o%1{AXVcFXbq_ZD=5x~;sYYu@B?UqcATCX~gmjr-)(sd+m9~;pVNoXtl!`1q zqe_74Gy-)m5CczGt7uN!ZDlo4u%Y1sIg&UV7F+uz zMksSk=HW%t8rxO?R~B>E_fPtJ;Ih!0d#D0$%nWmCKU?(X&AlX^R2+>RPP}n!Yx4Ie zcAzpcAk-)D3y#(hFd&(!V7Xw4>{KLcYJGziH_%$875z-#keWdi#F1oHD?35gZV}Y#@bQ)9a^}dQsX@2pgsitf6EM;Vc5S4m#5&=V4TUp8sHZ07CaTkr1 z`LAB+EKeDXZKt9r{?J8O#-kZ~N$~v)*FLY@7-PN*9Xf--9Zu2Q)1cnZ%@PNX86yjW zDB->NC+X{~uNam0D#+YV@dtfh4G6`-8}-+Tp1epD`Q_$POVR!}^E)A$?=&t3v}*PO zX*jfldqPUT{a(~&JpNNdVo<9ObwQmfT7WC!udf?`Pp*UuWl5H*EMO?2+2ZiE2ldm~ zx*B|hSaxj%K{d!U??P#%C72G(cax=*@gUSH7Lsv~E17X=t#TFA@GUeoZKDu047fxm zas7rPLJHv+X>ICtit1tTN@fKd7K`^?V9L`4pZ74Py)>nS;&9#-XVZcsE zVj;x%JqM4QsYL8KNfo=2rh^0C87?i*?RLV*5MGFRQmjCrhZr<*rM07Vu{h%U+xFI& zU=xb;PXqy^pASC?Qo+ieA&BheW~iV-R7Z66`PJXp-)~D=>%k7bQtC z$GLuh!Avz#Pq9HrLQT|PrRgcHu$fBcuYREv3AOycdA)IbvtTO(RGPR$k78Lg*_yo+ z?0Gd&-xZa?95jT;dF@b&>Utt#Rs!2mO)NNzoq~m-Au>fgvQal_o2smhC?-b8W1)Z$ z6O6H-mDI6jB>>$8$}`Q?+~ed`RB-3)XF6TG{pHV%s2F$n-pfwn$DR7{8dXWXra7C2 z2Tq;dO2am{x-$jGX13Be_;}099Zf&k(Ed~;fiDJ!5^%?}X+GIHJ%~5NfJcIi68&j7 zQjybB1aWl|rl`VZ#wsQL-~IkRR!_jn`0z+(DpOeU^9T?5XE-eJ4mrg_rx?0-+O&9{ zB^nlzyr^S%a@u?Vb4inh(CT6EOz8wQJbbH+%~>2jCAEDr2)b18QZyRtMQ-T`vvM`K=vf>d)nIB`9Vu858&1xF zZwiB(fOnuUbUNn31|b)r;_y{C-N10N4z^g6Q9RkI!o;hLT|l^E+}D z&4wOv*N{^=mCkS*t@G{DFHEjxJL{|@9FL`>(FzB3jd8mNlTdk@S*CbW7vXfv3=^o8 zB-@OIRP*ZxbMm=dKL=w&&9&OrPO{IH;HG*W{Go~wZB*8kul4R-%c?8T1|(l~}&svmO1Q>UF%A}y?}G@rxTW03k-Xf0mL zkdr+VmR8$(iO>XgXFiSwFMY7Yrmsbl13K;$I8!l6ycCjN#b5!f^*BImV`G!Ani*;L zeA7h-H6*7H5kx0aJ|@Og3tC}wM9py?y?WsAH=RGtloQo>6=_`jx}W-5tQI*jFsC8? zcib!c&1Nguk&m%sN;NyJE~ib=?2xfy2MNFj5K_Vqbz`dcdDp8CdZ zYcM=A&BX>FoQ@OlU~zIfW}?q%Ooc*{=){;R{n+2;8_{p!CMs7awf_kkn_F4YZAgUV zLp_qpb&8=w&`k6N_im`YAUiB~GiY?5HWiqzAX^+I9B2`@W^B?%*N*{_kytYbAC*YU zhqyY^3L*HOkSd<_%lGqDodz0ZLTm8l814k%*t59S>64ks?%tcuSDn5$>v-~0P0uGG zi)e_Lh?+BlRNQY!OTw6+rfpSiNkIltOo&j`?0H!eHtYjaZe&+wV|vHqj=57>ta#6a z<7ggw@?C73{2^hIE`4QZEVT98dM&Uj(08~A?K9Jo8v%oIAA`yi7rZe|U4fiZ6Xq92 zbgZ-yUJOb7PES{yK^4TRlXL!pxcJ&F&cVfjngy%2#-7j@7GlWFU{g2XrK9xgTqYZJ73{N z1tTw3!k>X~`;CD6O_Hf(yIQfW5BWE8*`~a!tE=77*g&A3p{e!uX-Yd)=W)dgVJ(?G zoEF3l(@@WiD3sBq@iTp#ig#G`LUD$uGM7bABu)TgA8d?pXwjfl5z|7;T36zy7V{F` zbX$DTPr`t~MK<~ZbQBvFZG}cWC#NLxucXro*W27Ih%^K@|7{dUoJC^4;?M>Hc~#KD zcd!aIy=VAMzLU30;X*vRF!M&GpJ5Yrf5H zL6qby*uMD`;rI)amun z!c9Y)s5JR;Mgzf&`E{<2yKIK2Sx(6}B2w);eCBXBRYkQW z?H5{`J(!vj`74)AgEhuNwN}it7Qc0HB}P$i1EPKeDgg^HaBFPyJAw zfN+#lG5YTDxoIJ3S2Dg;B7 zbJArYT^#hlS+#Z~hX0|v=fgvR^}ROqsKQxB(^bJ{$6n!;Zwa+gaHhPdsbz6lp~N1A zYMb`JmL!t$vFIeMQZQiZwS|kFTXd~2KcCV$4msakluQ;jU1Cn}RY@yyB6W8Bg zpS$9Q0{P9G8_5M|2((hSf-xF+}v(KX_^p!6#VlRw}&4AJ{FEAZ%_Y{AZh^hxDW)278B zDfd&{(gzSs5AM5h{`vUM%zPn5X2xgUDa}zGTZ1O3?ziSS_oKqGmTQW7HNxKt2@0F9M~Whg(&t+7Gk0l z?>~R`b9>(?8FkA~F3OTo%49<}Zx?>==NoX%Reh*-S*)+_M*ob-9qsK4gY={vn5YbM zV<@q|DsQyAQx4WHpTOZHNr})=ufg^W3Ut&@+QBZmGp5l-fx2_f;TD$ zuY2R4wbnJT)#&v(KVd23Fg@gHQY4O5SQ+GXk3ObOHcw^IiPG(H49GlXy0c zLZOa7r+uo-6k7GstOWI;bqo5M9W(Q)N+d*GQ5+qNk3Mps z;CteDEavG_x$K*a=mio7p#n4xq|Mte+;p6zCPLBKF)FyqJX)f2x+)p6~t-V9b z&MmvS9q6pi>Z$IBZ~yX=6Pa4;q+fCQRzqY(NJSEx9e4Nee81C5ri!pV@?5D$`B}_4 z8`wHl-2L*B^KlbD+WmoQZJj-0nbggJP!w#7z)i?IN3{p3`xm%pRFr0(6sAkzJJc{D4QiLynU)`^?okr8|&K`dsN6D z9mtH$&J@;b&NWDaX1|l^{m0w!hmhxmtRvJit5>mGn(d>brRTzvsjWL1tQ(QZrXV3l zj$3F?co!o4}lO7wh?p)H{;pD-(BgJtzJc*~$vl_%%hj>O8G zFsqYxdfIjQsjrQ4Nze(>G-l%L_ZvxF7V1k`AT@{sQpbT@nT-gRAF5JV$1xMa92M18 z&)2w_`;R^6JNfp4*L~l|G16F-xz%QG4(=p)u@Cv0BoSNdF|1imL7nfro=la}4d>vg zjLg)4nZNG)@xlHJKQW2A>Bn&`FKB_ULxCMKxBkdgV1?#Q?eUZ&OB$x>=cE|FT|Tsh zw81?p7aa``0&5KNu6;?TagDasp&yQBJMl}c5&0v3D*KIBiq%M6P{=W3XJ4}njLEU3 z&5swB3a!r}I*L=|4(G$kii_NB-~9$>zpRwEchFBZ+j$Dcgp~X!5Gj8grufJh)$z3F zhz)HFuM>kqt7roIHK=AJSj=1j_BPO>55SB?RC5$*gr%fzq@I_zT`LvoJpnn@(K66t zD1dDTPSBRzh`*I09||FkI#de}k|No&Xj4jfAmwCM{!lTBhJ{#DBP`&q>|7JSd2C?H z4$yKdK<`AK^E&2=NJ2)h_CUt!t?I>98f-H-{~i;?O33;klY!m&^fatCAu~6-xP>RQ z4NMz~s5n?lDETg)tXyYo>*A6feT-l1Hz=XrlL+(^Dir-L`f`91PjhaJd3|n;?Lm()pu4_k5;{0q#DhtUT^J@mFkrLCMMuh zCQlH}6YsLZwub(DN2x+D{g!AOq>79CdQBk^`3Q5YjQro_ks9MZ$Hz@901>1QoeyZSltyn+F+F?rNLCC&!Ho)=bm#rO!$X{=kcm+Lg)jZh{%d~uG>*0(tyX@VlBiVX5Z-* zz%T^a62s>P5?0ug06^mzSB@de2a3&qaxY)LtnECAvD>=hvJqFZay5S<@$=2>lNWi$ zdxVPjDdEe#-t9l!vIuRo^>>aV@9%sXd|u!^2{+`W!d2B;+A%Pm(al1g7qlOQDIu&9{p(^dCyXU{T#5XK+o>%%#0FeieyQSH+^J;&GGHx#Jx{Z z&Bc?tu794TFVzEEWz>Dl;(U1=$6pje)~ZCG$zHtsuw889VA@+)R1|#StCf6AG3r5E zSW*%SG*Xr@PRTaKnQd4>1yt`oWP3Ay8_i|SF{=@83pLWa2OQ}OC&z)tY$&1ClxtDic`Or`)={cOgpSNu0HP+tx`jf?{B)Yg98DT zpIaZ~KI_>moKvtX-NV+e>zGrRWG2i8mg^VEiOgKXnxODab)$v~%sx_-4(IlSW{2jL zK(s9S@;c$J(s}(z@-Z9fV|4fLZ@h6L`Ooz7?1!9n&aOSqKS)~UPiFKQa>~D7No0=_ z0bj(|iDRBh@yPF=+yq|xm$WjSOUh&K)`a!nCSB^-pOjQ&b zCs(DEjria2(f|T#>i-Qb&FZA`(*KPYaCo>V$N$DQ0$AAoZIVO12LFwxJpcb+>P#T2Z5K)QN&GrXL;fzeWvW1~54*Ly*68){M?~o~LP1~6a4MC{l|i(&(Ty~X=ev_#s|Ws*TjsgPxwEHl zny~B&?!SnP|9fMa7kKdF)KYIvWLUe~F6Ci#D>h>^BazI6kn@^?pPR4AYZC^OQCo}6xP-OQP&Vm1u|R0pAv3D#qQDRDXsi&kD7BC=`ynQs zEBa^3cN4@7&sLSACDEkQ#DS?#zZtZS{!tjX!Mp(>8r@_SzG>Jk34lQ9JRJya?eCU5 z^6??&4lS4Jbl8ttzth-%b@^I26c@n0pdM!Agh3Yy#tqikvR6QXOQMpTiV&Y$aP8SB z$(BI18a)Dh5G9WDZ)RcfWXhl?m@J@pq)nOnRt$E{)7l_-V6i&Y%x5rWFqph9WztMD z96U4hcOZ~DGf?7x52JjZhg#+N(-l~;K!y}Suln0 z()zh4FC<{Uaop&1?j_@_HL|nX)#tddBR2Mo)e@}W&#fIoTCM)px*?wY}2Y-*Nx1j z%9)@=x+t-P91dzZvyMT|es9(nE?;JBYWt<+lr&nSzzHnko_FSR%AUlolqS(7{QYKc zN=F?()Z({iVzw$V(`PK1l^UA3!r-j6`9@zMbY+wYD014^G=frP0`LNO7?Pi%$gKiK ze(52FTbC(=!XdaUUw_jKdw%Df{u$P6!Uk!=HNc`^(Vki3Nh9iM^FbU91y#_ycoJ_D zYSR~%4ykML_i1K)!L2_7yr1_TITJH7*RjO0y%xc~GK^zSe~KhXRi~VZn*l$E!9!ca z=u$HjhcTZFU(Ni2KZEzJJTmmso4N#*(C|?96ATV95|?*5zkce23xCR}q(F&785=+6 zLKRXNar94HN7w6WgiK0mB}?KJ20Un2(y+#;k$TZPy8qE{O&$et6vYrEO*0FLWTl`; z;VuK#cWlMFwWgp?N#k4G&-tKF3k5vsVX?diKR;(IAjA1Bo3Pccl#}~t6e(4lYG@hh zY+k>P;?T+fXpdnDVhPy8u(|#yx2MnOBf^q7Ge*IS)n5`wO~%rA^9zPdbQUi0`7ktt zUo)siM$+bGmbZT(sYk=Av{S~voL$gw>>UTTQe7?6^F6O)%^9^mEYnw-LR!Ts@W+)QW;bBgh(MVv$P|) z6RPH`0bWbor|8WxN;9>qo>0mV&Gxum(V(U;^|3-RLY0pYwMQXTsjgyOaeY3Nnv#1$ z%4Wfa(al_C>~XBAUP*BBVNc=L9U~{LW^5W`qdx4O^wz&Mzy1342xV*gEpJt)sVJ(1 zKCE#MiiFuLoLG+7b3exlF%zTRV@cwreWC0bM#&1>8_48N7!{+W<<;AOK9yWll-6H> zESU9k+wE<6mZRuiYCYbNMl>4ZDA>P5mRA6mV$k!YnfWRYWo)Jb%J1oH8EDa`%4kef zTwM5NJ!|UV9*8uSjlW1d8q*y|i6?G)j+f&ki$8SW8IgA1CY2T$b%cW7}SLKLyMG@+;D?yBDFrhU0c!{7Sr=&~n54@`{QK zw|a%$TuJrCfy)>Dg}Ch7zuHOK%&7R-1Cd-HOrTfIo4&b6t=*6#<@ER`(YA{~Q=wUC zTLd@dmN#Ql{jUy!5)Nw`IDWb0TenmjTSCH}cfr$E>Bn%E1R1WdK4QtwpEDW9)SwbLNizb`Y) z+O#JxN9{$z+IY$T(nkg?a1ppF7qOr?7WbipKG+5nD4EkUii00b@h)X?3D0VyUo%AS z{-g9V)n$|(5z+gQ5nKeTPNU1mq`@^g^aAmQxxhSiFIB2);j0xJLBO!ZWvrv zjit8Fh@3$M(6g47nhBuPqZ@Jcf|V$YHMy-{mktfGSnF?$Y=p{O9*6+eUD&R~aDp&V z6AF|R!pk`Zu*Th#Bl~pjd|Tjy|KuQP=p{OdyrukmhV^sau4CX6aI= zPj6TQhE~YIC7~Yj_cP?iV={n;%W3$>YyQjiOEGczOZpPF0cAz~=e2pu`-YzQs*e-M z)t&LHITTPGn2Tva(^9~C#nWw5%Ls1C9u6evm(IJ14~=?F&+Cty&k;lCJGd}OA!cf-s{faSH!pN~4} zFV_jU5GmMct7{;S#I+U^C-8MX<+Sh%6lv(`N?W7gx;m5pnBCoZIah}Shgtu0;nyGA zwn^X)19K)L1e3*Rq{&4;|L`n%C zOA2W~E3<8oMYkJ0%w&Bu`EpN)6$Mp)l5|XDT^5s|G*;#b^aCq!2+t|Svxy2pJ zrue4L2Ih1 zRt@Qc?>cX4Z)lZFGd9aX&+{D?RKuFA@VC_bD zO6C}fOE|dqC87~x5&`wiV6Wg!8uszq1p^` zU9=pET>FSu^PC@b|F0*%wn3_bU$9tBRx8 z>dIuqRGy-^4E$MPZuA^g=~{c-gWgnWURCwqOllK&bacNjtSGm=&`g(5X5p-bfAh`c zRU+!?v z9avBP7+N<$tS+i2e~vBKdxg0@BbvXHUVx3y#0JTU;d7R<>c&H0~n~w|0eGEE&g++tnyAgNjKVOc<6OCT?Yu9mBXiN|sGX zOJ5T`fbWuqFPuNMwS+AoK>X&d7zQ=R2mVn6C|YrtEKpp}+<>hC)>Ao#ci#xQ;U)^&4+#4{rf^pT7gGL?_`rONAm5N5D>#`-QGa2FKVs# z?3n!D{wZv!%L5etd8A!Oy4v(D?r7r>P4~CHp=kR?_06lzIu@!&$W2f%8%t%nGdH!6 z83ndjGi`y5oZfRaY1LuvIF9uWHXO~MBPlE5c^7=exDp~wnm6=Tn?c&hJ|E?og%0w? zv@k^+HHA7emFPk4N9h4_89%1jwJdjhrdZIOhJ3TpO<&2>U88CsVc%y`2fT^;P3T$3 zoLckCO_JUxgkoPDt@fexIv?Fv-&Yy2saI!3pREV{=^XI_R3;9m##_zQr6S zJt#d|A}ghw3$eqWh^F8Iig~JMU7JfzjPN!xq-_vB> z;Y5qYzpFP)+Hac5TM?E7bK>ewHF{|>eF^n~Q(kN~*X((}ZQiRpSot^MZr zXIM>mz@L_f{tE`_Oz8^1daL^hgX^E(hrpGU)jfI1um36ND?Z+^&%0zzecXtJjEf<$0;Bq&QV4_q#N_FxMt%5msNSa<93K z4M>h@aS3|x_edO-2((|I%^E*oQm8pJ5D&ZH(MZ(YY9h~{#G93DjWzeQ3I|7jZ~G$J zNrI%Bkyn`=HhG0mhGXJQK}zba#U;uojTOwp!#BCOEY5dm6vo9z8*R+p8gsf6I%pa| zNx9Xiof|g``H}HUw>aP%INH+I+SuLV+aA9?5Uf^yS%phYgZ7)y;U>^9Za^4oHUx=* zH)UR0jHB&>_7U?Wue9`sB2x~8naUwPK#+*SoG>e2ndbLtejGd!W?rrzw7PU zjJs#ZfefB_^UCmGwWy7{$pH8ABFcVw3}~*?uK4nX;^iy^yBj#Or@Zfn46;f~f5!M6 zX<6FYnVPsKioITn0nP8>Zfj3=cFpJX8B13nuiKNIrbE6n`_~uz!H#;u|I-5S*);fj zoiwHq8u*3*Z9l!sqhD|AmXvGF?(Q<5$s(H479J)OytlFo=G$Ir-Ch@8WjB5vGHvT^ zf+^8>dM#qP61KLU77U)yeWbQ{+_|($paEF%14XE5ZRe&ZerJY@$$C9Ry>rJq$mcdB*Yl;`x;|s^y-QT(Ij57__Wib~onXev^McJI%ORaUf zium4ZiOQPKfyjX_f-omDG_Sh0UW%7nF++Vf!qV}ukr1g4z(5>j`6*3&+V%%FYPisefdxSY_)jr&$^vY=VG4kcdg}A zdx=uKaI}qf?pXJ4I}_nn1AE3UFWBU*`&T)R`~#-s(a&!jf7tLv95z{$o_l8+_eD=l zaD~h!6ZH1>G46s$NH0IK6hTs*eE$`>0su^;KyWSsrmzFWF$&Afxiit`_^=M|&d znh*c&nx9yV=mlr}nlI^`esxA4xmP5RrcH{jqi?+)4=lM~as3xDx2|qI&A#5JHQ#k= zVvsG%Nm21zA6L^({aC8E-Lp1$Bze7ydHqHv+AZdD@J2C-L@F@wid<-T?M2LQpgzMl zOr+&`+39$v`LyoV!M$*}<@M2iB9+kl{4#S#Uua^>G%3Z^!0wM z+UN1>Z0YB|)0dOeO5?t-qPLBH+11s7fE}ZtkWl08suyF@p!d^O+ZaH>aYRV`)q7VP z^UO@jZ)Y;Z^7;O1PjqO5My}x~oaL@PI%k6mMBxW_L?h`-*R;w}}dn5WZ zMX{4haZjX4IPgGh2hdL%HiC;ijwTr98=pB_53xdcvj(3|R5wv>P8NIm_rW+)ADrPA zl#y~>tKbd#O{)9pzE{QM#7583KRi6RufIHMS9{`%J#PGQ|65c5psT;Uwu+SKHpXN6 zoIL|Jvq35P-WkBS295dMynizAyD>*YL%SG$uZBC#y!^0wdv=jbcyM~U1(?dWZKq+1 zO52~lwVSW-@1yWS(~^C<6?+kRX;bsbkb1;aC%;^1w0%d)uRkQx=0x^-HlQ{!lbl^@ z!Gw2dQZ1l6N5>j-u`u@Zo<);=FT>zZ5?LB~SE8(ga7;nwlC&IES4!K3$IBf+N&$>h z?V3-HZI)Ux4_AFy>X#q%>qK8c68W7JFC7#WK4WigeiF$NDRHI9El~^T=2#^`OC|H6 zk_ur_G`lV}=NSM=>BZhV#p|>+O&9`0O!QAU$#<@R*RS~%; zWY&Vv&nN-R9Kx@{F``elt8RO?HFb3WfT(kO8*izub&%s_lB3$}7}|O{Zwy*&OP#zT zYGt`UDiG^gdpcgb=!{6a8+qO0|FN{t0eI!^Mladt=9Y$yq_y^OtaxDpi)I~g4Wri5 z^}uHv(ILOTsc$?FUIM#(Arz{!-P&q<{S%3ivhc^8aOF}EV4Oq@6mc(FK*K%w{Ooao zZIP$V{g$Jup}M=xcZVghprB&WVe?Mo;tzuw+34l(78jh-J0k+-vyf)CdA5h=+O!C!cO{G!S)X52M z&h^|U#)fZ*t$w)^pq>ouIPvh{4VYDHTWhzySOKle%!)gXHDM?LBq5k&lxXlbCo5h3 z{hV>c9p8!8MrhN7bp83b`l2becGK*8UGaUXhBg73W;5F5?ih{Nh^PMi6(}U;3di%< zB6q-(936dtWDct0JQpI`J}MG2-|~u8Yn2pM=}7R^?L8;ww_=1K?+kDD5Z<~Ivj41R zP`$pM8o4`!sy(f&O^#2Fu040XZaZf_g8Z)J{NSougFnoYPAFC6eH6f18{!fc9-dMY zQ!zHCF?hL1S*SEdZaoEVV;KLvT&cY#s(EkX9s#vZ#CHUoTwJ{zPn{fR9RL!BA=5iP zEX=X2N7+*Wy9n)%)vw+&~*dkOd+F)9&oY);6L z?_LbeUVMH%Zo4@8rE;{;6397Agqxk%eksz+Ko9U^@JYhapSHwaXn=3q0zjn_+WQ9w zh9}F7PnQLvJwl!C?uPa8zZVvk zcK$#Uy_e$}bZ~&9NH=v_sajG6k#64GO}ii6Qab~-3W5U@?Is&Kphu5BVIXUZ$Qo_X zHGbslfNxfWJokzq7~DQRjnJqY4CFZ@2syTmDIW2A`}%Ymodo6#{K$aC@~i$9!Fkuk zD00`h?S{o>r75W^1oK0w=71?T8ahU$MTey5T{h-_Sh8<4h;V}69L^bx#LKMI)bj*# z!3^cum&EPYxPH?QnecX9b>jh?*6k#zS|}9?btfnF@8pAHkq%q?rS`#3#f-Pd1$*nX zwb1q`{uOBtxuD0F=e4&|B7c&FGlw9hGlhvmKo@leO~&Tkxv`DkF)zLAWD8(FKRL0D zlMJ7Thv(ebZH!DZ=SV~j+6p@r?Fio)x;uWo@d6zzbQ!$Nybg`<%Ph}&vn&M2mFOk9 zV3%b>*{0mF5%(WOqpPkkuZ*M2Je}f|XSY(X4}q9Z(t4zN%flchAsPM)`IZmnQaf(itf9$r`>r{Y|_|z*G5+?~M z4GPtcA0h1j&HU902ISi;J#nmgD={oBEY^!oePdRE)3xvQj>05d#rxr%!6wJcCdb{M zwpRo`J{W!PWqS9YL74>o!L%@7+jz&dH7ds>)2J)KB!kyeZI@QV=b9oO@6-sfx5(U? zpCHe3Dg4M>eUcG>d3^+kOXDD;b|e$fEigMU!2|4Tx*33yp;xGHVCSMln=8h4scv!> zf`H&y;;4s7g)o(GnfKAcHnf&Lng)Ogj48#4O3u0wlcv#H^>00jRz|;(sMVzVp1K{R zGBz&6saQk;*d=kgzUD93Br_IL2Px0uDE_cXo(L}4ssQ2yn3JPOjCX7MV(sBw3WqO~ zBgZyMVytVuPQlZ&o^na0v>-5*>+6*K%MS4O-WjBJ4gQMxoj^39U1@}fj*ecU_b1t@ zQCT#zptd#&NYywW&2s?;C}#XO!)g36Cnp~N{sbapjyCy(Z+#z{Ej3=a*tyC8hsVcT zmG%N)ozRkh+=-m>S6XzHD3pVBPYkG>G(e{A-|nVexokSv-_I&22st^igW=(!BEqnQ zFZOdmqAsD0?9LI|2d@{o&n_G{BM_Q8*DIpLE3h)kneD7(R*k6theT zucsk;L&@L)N6&fp9Dx46#Q+KR)|30fQuIB;Zbk)MMwzmTKY_+n_<|22INBJ)&%H6_ z|LSbo4XGE;pafv`ImSWgk_S1vp+o)sjBB1}pSv}jeDfi6C{j+1pvq{j-uMx-GhxiR z%TQyLTBu3}jY*EY07flkyQ?surw#jwF_Bh_Vw@ z0)@KoMwR0Ex~j|hKe|tC^IKu`k<^j3;IhC&4?qU;dxnI=exVZ}1K0%P>u3OE=fh^9d3r`+pIh(`h?u?e`@#BSRn1fFB$Rg<-`XK*HkUH1eGGPbt0tMJND10GvAD1u^+X zU1JlI#1oHqjGyMX{9YtM403$tj9S01Zf@R-a!Dvz6O^L=B-1+*YzVSla>Keg-J3rr zCrSC4M-8WnfpPia)CZGprZ0L`;X&;tVSu00{fhI?*W(-kmibm=LZ#&L?ArHguj4Gr z%BmV=AJ62!zML-9rUiyzaPx2vvy`_E0uAA+UL92?3r_mW7tDYkFV3-^^McFZO%#AgH8DkVN_EwH5CvdM@B|(-2d=27Y(jV<_vex!`uNkl=a=+A&l8BMoy#} zRZ^W_GU29hN_=Om4^twr4!SRV*9>>rKZ2?s4J7!7LbHa=8TMs?s91yTpvfdBxKLkMYpiA>%I22l90y= z-fucpWs>1Gwdbhwp(oBVZDC!|%}}QA+vw`U>MUZh@#yWP2m3aM{Q5;e&!ChJo(PdS zU#uhZzM`Qpb#aND)Ax$<@1Xi!O9BrcsH~O*7*v>8SimMGxHh$&pQJG_oBn)f{zODX z@~g5S#5AJZ=sZ42c?OhR{wK1v16xq&4-vR7AtOWd0U1fVwE=y@RJ*}}>mLmi53%(#Y>~b8 zg**TjRnxft&bGQ(9|nb)yGi2wq48dsNXhp(>DGC1`b^`c=$|m?h8cA)J$=LZPyP*a zZ!D@8lC468Pu;?bm zIQxOM(enI^M@rJLIas`(`aZ=dJ22QRMKND?Z6E>VfKx>8S7pl&V2Ts+eS~kHoLNsw zoYu#&mA`V`2dh4)W|+)$Y69e@ZhrY#shzNSX?2Z^vVG>ZCbDe&RwV6M|fH@F@K+?=HzjpbWns&Jacop(- zAT}1iYD*J(e`%I2Il#-sfXuC$x&b&94vR#stlS)kBsKL%Dl=EXpS0QJytq;Pa2FH> zELot^UE}6rSlYFtrQ5TAN7?7~@LkNFDJoh`PK!UoLWa~|CL5IEnxZ!_ZW1LG62slb z)t5TNUhsWra%EQ4as@vfEFf+DS%~F*sk?9Rj&*sS+afnF@5o@#P~*u%6k3#W+z5W- z=I?9i#jMiy-`&_R1OC1+$Z)1uCZuurY@e|>xnv`}cy08f%6mbs9`~Z&&K{+Oiu0e0 z2eEgwIH6P2v${4gEct_VbEjd0iqMwFo6DVYZ^S-F%TtRzV5F5(23@|6n7;Z;HI#K- z;Ij~uk>=`_jjzs16hTb)%2tMd2!$LkxdACj0jDFd*Ud4Y;@tmxuv2@ybYOA1J%6r` z0TKTHnQ`M!M!hDq>tdN}@2gP!1E=b9a!%qDS^|+qVI)56e;i(^YtI9O`;7=J! zl=(fc;FcD6`^6b0>|hQI?jA!6#543Epy#@&ag<~mno?`P3YO0y>2 zovNWS;A%#{)>ccDi>;lmwEngCnj7XA)!VDN>bf=Z5Ah2Uo9O%fsrbL|Q!U?gTm31y zd3XTv0spv&+nZDOITg_9ac(S&L(eCBDdrFx_OXDVh_{_6V{Qkj@9W70katH6LJv)U zu=lxeXe-ufXN}Ky{;jn)e#|hoS*i?lO)&_V=S&{Rxh1p^`HGP@>loUzSYWIpoyU8zp@HGz2poeyBHyK(#_cj~Sm{ z?)=M(PDB~bMm%R)^)biKA$F#C4hPHzlnzs(e+~Uu6Nw>RyCnZ=C)Qb+L5_+ZaA-f@ z|4B

`>4m?yg@31w>aNYhZHlwnV*KP+Ae7Qx`Yx%zpj>A}t^Y2KbucbvGElm_Gq> z2}$Nfp}kmp3!`IGt*X~{-v{Ji?dlt+a37z@NY(MlSq1fC?B3MgUj%|(-y!+oTc-Q_ zsS!@XPd3rBbziaKO@~q{PpXCvM7TmN$0qsA*&$4VfT=P&R61?3={!+nz0#vO6fu8YIMU#>xopnGS{abS}JEmsFl9FXW; z64Jksb&>vHjExIr{(#*gWgKgnS6ducc@F4}dUaYG(xUj60i_8VTFf{OyVo6s7);{D|^j> z03AYQw*2i=kWGUx%~rw`UX?&Bjy2klRv8=>P+rG;xeBplR0{=x4j znq(FA%ZSBJ*5OcX#h()1q~DB&fK?wB6%HhFjf!xrm7JAG-Buli9BoPFrrU>dQA=Sv z3dzH#-LgpK^WE;e^aZR@`V6PG2eR(O7Z`xrHT|W7D=)1_UV$o;Vb2SeWcd`?H#1kV zmx|8+C0~xWPCGXY?e3oX)brLWEE4e`b^sqMI;4<=!<;Xh&<`=O7OR(pif+zsUffHL zVJ1uQvl8h~=cd9LNzfeKXGVwX2WtnPl%9wb>O>`bHICzBvf-a?--6x|PV&03+yC(t zVVNt*ZK+K6e7BO9orc!E;Boy?78y|)|JBUbJS_Dcq>a()kv*n z;EXr&nGfg?V3>F#ObA#K+JoSZ?b~@j_jv1SFgGa zWBj=fKogbiy|lElGFp8K0xN3t6W*)P%gMn+fl81D!< zw)P0wja{mgKaA2GDk#nxw+0XYZqzQq>fy7>XG)wdfqD@~Xc|aZpxL5(?DFw$Q1=t0 z5r2;!sI8&KhZ%;I2>_S-n#;1=ZQ>%vC*8PT=~SUgth!Z+_wVNXfv5<{(!z@F&^1ft zKjybp-)gmK*dM-i!a``fhX#qVa7b-t{)`Sv-=jIVg1 z^hUFsZGhm!Wciz=QG0i*amU?azX6gi|GQUv>W;ljdS^bwN&;Z~D9 z`z_TQG+I7BUE?VdqqP6H>r8cg%2!TjMg-)XDSCC4K7an)Nu*O%dauP++Oqq7`f3LN*)3+WTIBP$0k_h>3os6*7iHw*f z3WetSYYA%_{kgDNHPV8by*9b-QBsCFj6}Y5fP2tJ)W%*ad2PnoI@X(efG+6 zwl%sFgMt-$BBX)(sGm{~zo@8FKm&Vn2q}QJ=uLD3LH1^%K1Y{;Ts)uSXr-k|q%ep4 zr)~f+*MAWSej5kekOaGojRQFoBvCGek-r=-x-v2ym=a%S(_ed%S+k9RsTENvf9aPS z`bZQU6I-Eed^dM-!P$`OzYJiU=vI(6L>Ls>t>)W0Bp!Y}*-o`~Gm6~!okOYeAra!ePeUPL9pxNttEDTUkJs%u z4A`}i^89se(n*Q>kTwCGva2N~BirF^yHY~on9x9Iud@}x;@;2Npt}Yv!c<&)WqV_p z_i^VY6Z2KmcvN)W3n&!KCM}UdC*CZQf>xFZ`T20>IC+!% z+Bxxt`p`6t|9oWUr7|vsWz! zW%aY=8e3yYjvs%GV`kS=C$8!QYSUr2UqH&rc8s~!#8$i=57(p?wNO@ec5c4PVEtsO zC<#Rc27vQsD58N^Ic>!y2>ka?Ab;}20CsXo{#mq{F`Nx$H`T}DEDZ{VD4Hfn9Ev}) zaQ}B%HW`L%EF9c1c}Slpr=A=hgG;3GNb1|awXl3m*z)N5Gme(wWxVRXVT|bh@4_?S%CRRHYdzuZ173beNmg2+QCOL^s|un69l@)HqfniQ>2h4UT;%bn9pxhqvR^!MK(T)tB( zS*bwG$7`{}jFCg_n7^ZK;A(!~9YIJ{lh!$J_Ml_Z&W!)zJ~bSg*;sXbziLY^yZ+9XKk zHwqcuRTW$|o+C6@fG6N%>W_Pm#OMHN6&V!#4Xk~}YzM<{w}t+3)4fq?oZLO`3TzW5 zI;wUe8qjxfP-XHf+*0cI(ZYw7b}L9$BUI4i$dYf2iU&8`BvMq(hV`V9?5K2cf(@yF z#hT3I2zvE9C3n1$IIcvDzvvm9OdfmtY5|gES$Qv!<<6UgKO{??hetTZ4@_OE1MHG< z3tT5X;mPO#$hWZ))9+|pt803QoU~*3B$s7r$M)iNWOQjZCk7cJw+4}%p@^U&=Pb=9 zX+sf+HMgV(QGeS+ro8RVKBK!g^}!ocHnhJXRvy<240e^jp_b)M026K#_;fwaG%;ROncW+ z(GcWes38d4Ya@5Z8G{^aghT{aKx75`w5HiJzeIV4o1)Sz+&mfaCoC{>a}kP+LEPHV z!_ejmN?yg8agCo1nl!2;+JyNV1y28`1u$$eGI2@dQNh;7Jw&3f$MZ;OPSM!TXg*U` z8>2qw36ZPN52`2_#hH;k6QrNOUa<@LP#v+)2#cN(-0U8(G~3%#AiWlkPNyrib}}x+ zkyvTp5Gs}P& zYP`rUI@dw+_*}w*lIgRd2?(Xe&4d6hKQT22B?1aFvax~NL#Tx&sQ&4iG-BzlB4qBa zzJ<#-7RHImtB6+Rmtx>em6Do1M0ffei;t+0Xr$;@0w;kN5~Pwrx=WC}Zz`ZlwAjKY z&BXlM_zjud_G~<{gpWnKW__2@pONlu*;zGJBQG*D^8yVG={ZzXY}}btZR-kp8l2>u zrC)PH`*>N0UESC8iSJ5U^BN{BDD(4HEw};INIWgjdz0(hJ-=_ElewqWSjcz9VW6vt zGx_{@dwHPdmkLy@j*k{=BgTAAoR@uWSG)o9HzNRm517Uve*<1ezjZgiTQ}qfJr2<; zOPrEbAFb2LS#3U>dGQR=Xfh$-1;N~Xvte|Xg7lFQ^az%S$!2SI_XWUx} zkW5E=-ioYsP$H_1-E+hw$uvQ-@Yp!>FU{gy)QH>Q=6)<`#{7z2EE%fpEG~j(rqZuu z$6wP*9H!$@=y+yfVP1~epPn zG4-QdjdS2F!CTg2k>lI*tCuaHy!T%e@UE9+= zvaY`-_P`lq?{*=#su!pSI0mv4O}xE9r#`U_raG3DEP!Vnt%4(aB9l14FCTLb26Bm& zD@l<2Zf;a75VH*PC(n=S!)&Z^)1>l6-_w4|DF($Gz7vT4kQdvZO061vaNX2kmomX? z4dxY5DaEGEDNy}M9gX{ucupwV$Rv+*RDEsI7nN-nBPD zowWil$xtdxeQAlBGu{7a5d02Z^9G`*EV{2V25;2k)@C=lhpdcHR29ghst);b0gCA( zQLCS$SFzrfktm<}H31^2silps^gxQsn>rY0oJp->Etoq%D0m%R7j~y}WS3@|(ui~- zSL;|_hKnnivf-=z`gTuPFdn58d(!Y-pt@*emtuBO7NY0M{>@lP`|9f);8`=m@N7}l~7k78qSG#?eCh55RU-+nU z9H$#e(kwD|sLl1msvML-wDG7^BA1t!($Jhdecl&6%I(&x=VdWj4;xc5O?QFKDyqC$ z=*xc0OXxpqUhfm<%zrK=n=Pk493hw#y#jq+YmfRbPh+p?|4egtyC_~brKF@%1c$`n zGqQ#n;#coJMI$oO?Yl00%hFKm@>oUca-@vLlTH;DV`CzqPS;d2ZVz%k`%cXe_Bhg) zt!NCdM)dIwEr|o3%pY3ks$u8o_vEG2o-2HDNYV)IFcig8h`d#0z+@*BOY*!(+ZYws zr3&HdJ%=e}uSBZOx}L={G=$KB9V{!C*dZQ8muz^b#)z2DLVP-uJ(difX5d#%}_wWx)Fj90Tb{ z`cU|K7X54aXE=Xu_b2g3?wjZ73o%-vUJ6!rnZfq9AQ&n?W*I&$j59K!P!RTDwhtxGZ-GoNlSH?8#G!!(vNjJpxdR^Bf4s3W)aN z6gA4{&PEXi@^QdvG>Pp3N~yitxOq>C-zMR7$qQ?jek^NAaMi6T(YBO`A0i;S<92d;QK@6!QL}dEhxfNgb-RM#Qf}pw+IPtC zvS`98J4Q02ahqDu-sC~PjSOM0_iR)$ND~PQS6Pq9E~+R`~@iIX6Tvs!{!Z_qe33*{>XP}ZTFV$T+Z1?CC=}oNcxKGY*J=2I z*>N{cwCK3)QpsBAFGQY3Q&n(iU`z2ep-tSfwT5|9z_9j(YhT|qM>m-WYQl6$Xs*|I zR4=Tyc=28`RcuSgZo$=4X0h?4{=&m5spg%y{Fqnf)ZR~W%#6>u0&W~)6zD>0A`gB; zrfrX~`y=x(=VUv|ujb^K*uTO-W;Ve0AYdTBR?odm2BO5Gg~GB6?E{ zLrNV8*hwWHgxW5JfCDt7?RlvU5Q4;~*|+{E_ugR{9v(j9c)j5GuNeT&@7UUVkz$Hm zVOh_WwR8)Vsb@z?$SyX?%G&1Q^+SU(#^aQ~d5z?g1b1h>p`3zo#t@ zPi~Ugih^2_v2LqA=8uKy*`1di7b0oE$D17*Y)~vI0KuD3+pSj{|DDgpwu0#6!Wf3{ z*vN=pxXp7q7K>R?Z{y*{=TEZAVs=B(JIZ1u%tQc)qg-vZ{LeWEv9Wo<7HN^v8ZZ>b($ z*&a`}AVJW!VeHNgL>hQ8P9xO9CvgKa?Tw%gF9Q<7`$3+qfb}D%D=|6wwHX212W6Z!NCF=(*sCQKWkyGZ5hcc0EYYbV zw9vt0y^1<7A|m2x#^4zrs6_ocV_1y!kp0Z%V#s&OUmwcv|7x`j%85NpD5XzjzM*m) z-72Ap-h3b5?1d4ZhRVVCd(+QjtLEb|C<3!hIUf2_TzAAlJF1U@R(CW;Lv^gQqI&?F z5e$J?VfowbyhmDl$=?;blR=XR?X88B=L23mD4AP7S>QbpvLhhBq5B3%4Xh{!fS=6m ziW|kh2YWev6*UGDB{ixA@PKXx4_McJ1ON0<_Rq8SdcR9V8RY4(A?n(J`q+fp{aAvP zoifq}II@&XRf{=33)IplR5rKaNfCaBjNr5%YH+tLOcYaUpw5P#1fTUC^K8hGdanBHGz zdY=IKc|l;?6weMk#a+A1@WQ23#vT!_WM#gkr)=u&OUZEoDj~UV52k_Qq6o$*hp)vT zYRZ3mls}%2w_awQ45FEtH9h?u>P$SDSd!)SxB|l)i47$^GiD(r9YNI~@ zhC)CF6aV=?V>Bftr4$~&6!>NCftpJ@^TP=Oy5Il@e3v$gzjyhPADWrfq z=l+J&u=3cX6^CQ}W#E2KUkurnlEIUtrN)MupVW9zJo!c^zi(qVefsU?ueS&*Ab2C4Y@t7K^5^oRdspC<%W0NK~kDnQ56pdUA z=L%78wu9s*Od5>UnK?m+%=dmM=BJMGn8>k9MC-OChs)}l;V@j?KPAIzKZOTYTfDGW zxkW@qnkpB6%9uXLT7K83!3 zJ$vVSBFuEXxMBw2Vs|hmSBuOIb=14dSKTNam#Pd`z>l|Nw1?NRQQ28ye_6Oa1+u8~ zIJi*6l?I|&>Mj@O))et9r(duA#F;9Vs!ZR%J_ojqG~VDoO3gYI{k^Dhwq+4*t9fxA zO{shM{L*Ym9*eRp<5^xg_Dq&8jMUzL#`*eO?D3gNu z`4PB8=f3xHOjA=bARr*{c)Hsvc*}%pKw^~6<)6s^H=(2&`OtS!r`*-E*8qJ_{$0q} zZ8|WEo!dU9sb?8>xk`TcDLVo&A`e6mK{HiyQWHQ6C?5+?2zUuB@3k&Z@ z1>Mg$<;KC;71Z+c(yt38v#AfZ$3ZHeJ&wFBQ>gvMc+rK=D~-*82EZqTG2u(J&d&sU zX4*nc@O#3F|4FV#O30v|1?oN1sx%zzrZqetpRRv?%-E4!*tV7{3{4fop_#@TTC9qS)649ro#Q$G*Pgb9?+onerOa!GDSXZ_@Q zi?BNOWC~^XdiBG96BIRCog7M!9%WuHmM;Q%rNNnErLQ25jGCDh_YGu_y*AMTBUb@0pzM{8TBL&VP|E zxXkIff3Da&U{Cq3F(Jj2Gc~rZjR2K^;v?%6~cf<=V$=AlT;S`fNlQ3o~amjH>C(4+*99I{kChuh96~WKvDZ zbUJ~;vxqPG-oK_b$lR61_+9ZXYK98*>y?tPM>ot$KVoAQWU4DDaA0-c)1@j}8y&<_ z%hw=AGe(bj_yR$bKBy4IG6i2I#_o`TQHyVwS8m@r1J?Q2w|RUQiDcKygH* z8ZXAuW-?)tNus1B*CBD%y>n|6&Q|QZE}+U|lu|)DyqDgUf2)X41$70YHvOmneSX|l zG@U|Th4>1HjV1{qhqH(CqV#W6h?8MO70AcZhaN$`Xq1I2iaJOlF?tGq!SQRpnli;x zES&01)LS1Jc@C_Am75=?CqFr!V;|mkDw7zWuf|CSFshCkDt`c?Jwo{Zop~5m{)q*F z5if)J!YMar=)vjb14Nc2QsDR7Yr?(-)56-$`%Qtkm)6#U_P67M5z=BUJijFVp1f;80U2m^DoQ z1-3w<&~`zq@GM>;)B&=QAA*J2auKBSFX-Kqq@&UcRxRktd>Y7%-Mh~pRSZHkm-v|Z z?xwM!c@-U@D&?WY03-9?mk2xRD9BR)c1aoD7Ycx5Xth;SZE{f&)4zN%5PG@AIp216 zW}f>9(mQ`oR}%X2#>k=fAlvVrw!)j7(0ut|*rk%&aAvur`O=D^oP5Od`ZD9x#dUSK z)uN*Lr27KLfIRmjtJv*T_6+<0`=2j5u)~?mCdGxT7WJ?x4{c(_7qp9dYWuN*8m-p3 z{Pu6UqJ)q?!vZg3!q=cNfyeafL)8+eAcLK9huOyWF1tUUs{(T(_k3@hGpt2~=Q5s* zx_h8)!YSMW2KwFY1zn9Nf2`17m))6W^ny|_fPm7oj|^zPBXiUJYop7p-M%&6xh3q5 zo$JVG&Pm<*F6@TjkPRs+5hq>5mh4E;d<~j|Esq(5z(C2p^RcMYF#tJvk|LK5ffhmu z%2*GV86c8?wQqPwW1(6juIjjyRMxe7MSP^b!@)x><cmoLerh)sVaLZhpdrQYsS_cs6Os3X!Bj^U#(nJQNE3~E4gK)YZu76@;j(rPneLS zswu1hGn`A(*;dt zQ6F(mz2sSEt<5x{K0}(KTj~w z+~3GIb5ert3ca)5aA4^t2{^b@4XRiBE+E4&eKqo9wMo6p72os{bi@=)yYEdvs0Yr= z#Id$Sv{?!KDPFinpD!NXuNM}YSWZPMtkiJ}X_k)h>XKZA`PZ%KtB!_G`VUY}MN-X=ny3Ha9|l~s zW;yM>fE1L{IFyolcf#I~L3}-c*=RNN!X1Dd8^9C4PS)t?Zau#GC8|$Ag;uyS(H%Qz zKmn!1)i7Q%JFyeR|C$QVXhTHyTe4vVb7YUU94#+VSUff~L}7?H>=q}l&(INOEGb_y zpaH=?B(g@7{43rElj;}G>#Fbe^oMXM$`S4T7t-}5NTLUItF!&+XBPp%1|rm|X55`{ zna$%3qkj)v9W8d*)17JN&QeeSC)snriWw*WtM>(#f#<{5&W)CC5(j!rgb8_NJBQU^ zZhA=zbO^S*vNjk@tBO*BcD)O0SE#6Jt6Vnll^0Kvp518a&F-r0G;Hq4{V%9HCs7U@ zf`u*HtxXN0-dFXExgtM61b{E9Sj-XwL`=M874FtpFo&3&^pY+Uh9PLIX;fiVFkI!P zhYx!@>)*%IUPVz740kbkLX^DNbzKV)>N~D$QPxG+G)nflBy}$1v~6P+OTn{gw|uZC zp6Ik*<2*Pp3+v$rY5JjL8aBJ`p7i57_xo4P9iH|ECg4#Ci$LSY{TBs^6+%;8zK22Ssm@1q-FDehaC^=*fX9K z{Y4+a!Vt@n%WdFN?EjG@`{RBL_i~p9Q2w@G3aX^USCskI-dIH;F99SP|108^9PG$p zzp@W<^UPddgV93^+w5p#^)SPl& zCQLu3J+8$}h|i7y1o*^Mhu44;XtR{kTgj{>)DJMc?n?So*Ynx+l6*$g8l1dZT6r!N zi99;T5_n4oBr>KF7EX`g_$*fg-}P}t2_$hz5$ zm7P_+Jpa2e@}4?e`Uv)_p^C)pNvtdvJ^%NTtPFbaXV`6aq%oOw6>Aq%DYe^z?tFDa zR}6LR8xtBW=naQ{AQcq?lqHhstTScO5FVT(k1Z!rwbOzQA>88%LWkH<&>FiF=UH|J z%;me})9w|<-!wpS>YXgWKEqxilc;2JCN08ur-=m&@_xb7NG6t%J1zMf5UyF6Sc{w- z>K-cuiK0}Isb+TP5z!!iC68xwhiBNEsF3a_8XH^GcQaK zt_W{du!I+70}dT8z7tQr=uAI$kN)oQqv2eKfLN^4=R-gm{XOT)!W3~$sPA)&^nTb` zRubhb>M2`Y|M}?p&yEE+Iw}ax9%@azcG{M*e|56_LB*FEj1SxMooL>Z%uI3A@|_XF zQsEU>>Q$hWAlk`r>LI1h(^v?lDWk$3XtZfu^}kcrRpP`%#-jd9G?eE-Jfu@rMfc_b z4N0SjSUIN7T6ZmdOa+|mB=N8_JH>Cj04F*T#lz2XT0bZShrO8XafpnDM#`Pl!|lx; zuc8&;e0jEN{(T6qeBJ~1Z8YO#9yO{Vo=VKHAT?DewMxeA{ta3s;dBDY3N^faEQH39 zQF!!ocyq`k`X(c_25&fAxG?7Dz&N@w?%N&j$qYZPMP1qxbTBcXiYDnVA5t(z< zwI{>&^5L`;eT_@Uq1Xc?qo)4dg(TOW=u*ggKI#z_NOYZW5?2FZC>WhdN^jnA%Qc}i z%LWrkqm;jKO%`QrZSy!lPAG7W<|(BLDmY||!%;`5MWYIM|5`C3Ki_ggm+h3?NeZi< z#*M0`Ix=3%QkPMn%v%k4+d>O5<s=O=(uI9P&8ml* zR6gYA@kWwDEpr(2Tig>Fz8)L7JdxDdw7_wo>xYVqCQ);6r@Kl(RkcmFbubf1<2?hC z1=F{r8;Occp!n>d-?J_Y?Ni5f{Y`ATaUX!R5tQ5K0>R+*0p9yz>b1Wk@X=95b>cYI zb&*jxOmiL0k+!H08!Cxo{ns**gBu|lN`lK2HsC2QTuUp9+F!-~Q#Hb_KC0F*>GWp@ z0dbV4;;eOoIT=*x()-x@_VNc%<;;~+n>=(0O{7$zhSkms=eE?eXTv|l2rHr30sPWs=#>HKD3EYQ$@gK>ZuHzjY6 zJrA+<$0v|3aK%O>w@3F#ej|Zsbh_Fi{50Nmw0ND6mEhUiN7cNu?*F{}cxqramQgSf zm#42Zfm6cfFuJa%FrP;|8&4bkUq~%tBIMSAL*K~|Tsxb;n%^-GGIv@ml>th!o%|Fp zNWje-{-Qat`3GDxLv#*ABD=hjXqo{5r zl-P%LpO4o5gdm^1GEYrS<(mlhb0j57w6qKOK5XN9KU*7^k7bxw2K6ik=$8j3!!ap| zC{oF9qHM6mC8JEt1+pKOmFM2!{1!VEuItwT8?jAvCb%xKj*g65vQ6qhw>!$k+FzgB zL`R3O6lTjmN1P=u{73*#!J9kK7tC2s*m7)yr}NC_#UYXQTUI9zcIV0L@HS*}{6Zz&y$Gf_y_4TYHKCGYN8aImRwi=+=MR6kn2986_yUS>X;V^GY; zuyI!;^Mu8MtL)Nz#zecsd>#^n?`n}bWn#3$D0yoUS9j5Pt*57m%(-a^Y$Wm!x<&*m zlTpl(oW+R*4J7e(He_NHB|U$LuZQJPN8|n4SHBX}hSb?C_8%JDLVcU}B6zIc8gF&s z1?B$KX=XVa9aqMMg{WG`4HHY#$iBs|^GXy4htv~%#?v;`&`>U+wJeqBbEzD~?n{-Q z;hg<2PhQv0Nl(NT6&2%j%_}rte@oQz|M)t~xTw1C?F)*uq=0mngmkyW&?Vg{-Q9?U zAl(hpAl(hpNJ|Xe!VuEk&-VU({%@a`4mbmxbN1frTI>2=Z4$%`2}!*1rnZXMZ_^_A zZ-)-rE|WCZ!@57~fAqkj#?y|a*nAl-C-)wk)c@R3DkQ{XW|XJ4uI_U}npC?YuC&(C zu9^0`nJ`lu*3CYlst|~fj1KXu=uy=72}bf=9S`G9_cC7G0Q-Hpy@CQ|22xE|@`wZLz@+WQG517F~irbNe(nSLJ#* z)MK2^Z8LS{n!Qzn5O^;3Rh&f)3p2EaA<ZQAj81N#nCf&&70{)RPdo>b#Ao* zW8R~L2~11Tf1EqjKzYLubnF@O+smW#-P?0CkQU>gCmLpe!f5 zp-Mvemz)n)JiAY@`RkOsp1ON3qc0d?lCwaiG#*(g$yFwvAl@7#O{18D}O zJ>8SowY9Y}n<+~*SdyS;#km|T85gEv7R?;vf&wkqm(DlE+upWdt+R|!V4uyR8#W_& zLuj7A8_QVq&UPENJ%}nsSZO@k>rh4S8p0WQva*2^h;QuOGNZHhC#;>9PFp9XXoaAQ zC{P35lnL?ju*e~)Sh&A;0X>7)FXG7WYLS!3HQ~#_VgqHt_RlU~CKhHkLH42RUTS{D z9k-TVRs@C;x)?v>P|Cqt zur(p5v<&Nn@PJ3OG-WkS`|sx}`R5bKZX4(;D3lChsFQVLV32;ap?o}nznNPG5{#~! z`2xG$_fDh1Zdp9dYEnHGW^2MwHAa=+Eubv!wDAYo?|A2GzRi;Zbeqs+FA4%gEsaIK zb9dwyu{xRQ;PMR#)Ike63W^NmQV7UQ?;04)VA}+wRxyPP%?y}hvF7?F+CTK-lBxBc zbMN4`7)?;V$C4>crtz#7TUP(PvoHHjd9`5HGA~G68cXLbnEj~&S<*I3RZ$>;I1an~ zLzT)Y%Z|8I+-%!6m(N}7fCYE@bX5mNg8l)S*A7q78damc_>44u{v~nN>oyc;U z$fDe`QTMNiBfKdZ=u!epRf0j~a5dFe?M^?TuTjMP-b%IeAD0(g>vZM*3b+N;??auA ze+ox16!Yu>Qz%}%xyL@Ar&UOBFil!do_xg{M3@CL%Y+q#UyeCngPtbr!+USPtYzse zgho+jh)f(szB{hAl(93AoWW3LL`1|pcER52JZX;|A`Esmwt(6YV1!kvEch3V-adY4 zY~mCb`#WrkaTv%=&-Czu>gZ7b=Hf95K*lFIg^rs034~8$qpRGHR+8~4n2|>@$nM|( zXW(i5W3La!%4z>BdzzKk@~hSR?Vju4Jf?aby}LagCz$S`(c!=J)=jd1q2N&mB7;y( zy} z;mT7M#-xpu;BDZO(X5i6d}-pQeqihB&0A_q@vJLM_%>&H5^6J!sVSd_{VV64HRCpX z!N(r`w(X?Z9IC$9p0D%u`yzZE7OaTCDK^@|;CCi;1Orayxq55-&Ac9$Mdrh%O}BqJ z$R)d$mq!Ak&L0!p+wXYh8xBy)aCptbC?!>1ALSnVeQTy&IK^kJ?&QBe_8N4pfj)c@^ z+rRy)-{sbm2FythW_yNnyW`Nqx^%NSmJEz&rlz?uG{;$IQzH{T;rD7WMo#i+(f$ z6>TWb$~oK1UYNX#dgi&RN!^HCr}c3Kx;1>04`ol zJx3bLH03{UfCbXa;=dp)Momzc&A_x?{qah`1G< zwi4Bl1R)vEF#FgTRSBNA8}v^p9U2=~_lUcF*;S((^wyV;4cK=)o_`<~bV#X#8V!8V zj4fna_5X7x=&;(3>j@Sq!_mabxvr(ZAflYCOJ_VvQ*ZRvl}KWd#g(dyqM(-mjN*ON z<}Q{l=km--w!&~S`s-Fr?)&|>4gos{Be8VW=RF73J+R?q2)f2m zD}r%>m4U7Y#3oo4Yt5%&yg09s615_k$rKFV9f|iU-Bi){pUEC}=$e3f+Oql?%lNo7OMgDFKc|?{>WV2{u$s zRu0_4HVHIkVQ;Z@jk&-A!TF8yaSh{fP1SrePW+i%c(~yC8qZvdF>~YUjhh=8|F2#d z^r}+#DBiwg47*G>g>Er2q(g%a{iwz1`lHVQ> zFHhE=4&1fod{PiQ9=Yta^^DH?(Wk8#!oyM9_I-~wuEWfmVTPUEzw-t{>o*aj1-q^7 zJh{LvLv^)s#oTeS7WlW#5|qAW%)mPyTaPt)I<2Nu<9%fZGN#LIGF!fsT}4}v#D01+ zrVYa1n;%20uYW7~b!#4ahk`~U(7gv{H1+#lFBUc(H1Ncl3n>!Mww<6if(wGX>iy@A ziHS)W_ay~_PB28V#7Jx@`$eFl9=!+yjSfTG(OqQQwN^^@W(!zSCunU3f=%c64=GpU+mg6VcPd5^F9pyc(D-Wbmqzj{+ ze(S3cs9w)&A|hgsQ!KZoW7?Ig01U^!$6_7FtXIlJ`or6Ac}_u$?s|)L)JfOVrPwyi z+~az^()oHqrH+_3DvK6k2;dHjJPl~t$fBI|dnnbY&T)g#P z9WD<<`(2ZHSbLlnjXPY-AYLcBw*`WmIi5~w!UoFgddjW6@5PkH4=>axfd+0%(!+f75`goPBbfL~1JtYOcx`*L5F z@7>L$&{O~MF}-Bc$@ElQPL3f3qmYRQMfF(xr?&-muaZyJSEnm1^$n@t4w21LQ*2|~7ITK6 zXB?-(u3PJSSuD#wZ@;r;pU1OobFeQg9S;!=){yEJ6*lem6Wy$1_z(W8hrO0rz)Lby zK_If}?6R>l5=<~S0@e#V56|#)(rCWrP>#gc>jMlx@Yy!M*+@QIAB?5)K#Uf7X}i2@43ay@j04hs+^|7n?~9|`5OLhc>Vtgr!gD2$ z-U%8J?L39fa||${XKR5Nr^EIgk^2?xA(^uV!!54+;K5h~k{f`Im@Zuw^3=Fmp|0K> zy7T#M@TzJ46$PMW?}uO?6N&wzcx zN7$~2DG>Ud?odtdxvrdV^VAyW_8$)-1G_B0sSIAPgs)_` zEYi{S1iBo(mzp*|`MyHgbfoK&(IAw7O3AB&>$vq=lbxNtzfd9FqS2dk58bLhC|kHW z{I2uzh*-!a#jfI~H(~wDNU2EPu+)rz_SUy=OzP3Dt*b-(TX+bX5f z=f>cl`T)Q+q~<~zFP;;?m~~J(P9hPt^|aRf@1vhc=y3nhw_-oFR{?m_S_qMy(Q+^0 zaawb;WG?+ilCHrhhW|A|FKShx0+>m5U1ZYU3VSaH3C1A)x!l zsrq*1Hfb?6Jsl=zc!QE@m)4$Rp*!o6IY?Qyzx zw#PpoFlu-^Wny7VK4))luAlCyHTByAXWI_VNIlk8!EW=(%`WN4=SW~=Z0uCG^8!vW zlfTdR$}hMm%PXy1mnROt?{hJc>8@+54@_Y7)95w-$_>#G#n~CLun+r-3gx&G0LNQj z$gE5DVq$Sk$xa8gNb`D#W{v+-Eto!ZcN*o=bOwVjQqt0?8B3oTfIx^d@artYtNm3| z0B*TG?#zK($?X0g&nVSzibWE&^Z7GYaANH{CgLao2`Hu{XQ<)C!cGZ|otq>!%MF|! zxRgK{%=eU`5mL`Hojbv43YPJ(xpc+2??h;NX44=m?zw#&|d`P*J zjf-#e@!^iwb&qpg_zHd?I`iY`0++nJJimz{&+nKoI=H{5rX+Go!qADht3E=qKy=HG zL}GY|^d04jpi8K|@0|cKzeh|jVXjUDcal#|SYM{T3yb!bxNqXsgBX6-R8gc}IGMcZ z7U_1Rd#0s2<=8L8B+{7o6&-=Z7lw*T&(iJpt_KnR4Mls9a=6u>GX&W!_F$9PoLxp! zoSthjQ8hVK`rvc@%gkb(Jk^rZze=P7sDd5G!K_vOv-^T4OH&r#C)91;3o&UjCcJ%p zPyX{+J+G9tobG^0OkBw?%kFnyp)cdLTKHR=HX9bT8caw!R{MAUynCRciy5N&ofh_s zL1%H1fQ*QCFj)P^hq(7t2_|3y{+;GWpcUx1`i))xLAqLfg8TyzMU(lzQo1F`1S^e0 zl-9V=9a?4kC87J$4Hmb7Crzv2s+@B*0z-cMga;`=hyh;O`W+l37jS*ndc$x4^~LO0 z91U1>IV;Q=>zgNnrU^n`B8GuH&6XCeHV?LN0Rc!aZ{Ie&z8t@HyVvV*ew6nriQ9#= zKW5l<=ma0mK^yoE{%bVx_K!^c7tPNS$A7C2)|xEyx3utES~IY}OH{7Vkdc?q(K4EE zadlzR2|Bua(J?-;_6%&2o1=k<*OmScntyuw5{9@M^cu6Q>c6RGovri4*fYLkTN+4R znbK?Dm0eiSNlmFx9>o6zJ9DXXb#QXY&~G)^>RqQI=5(A3}DNV8J7ilceafht#+ zurXai+Htk)zc$Jf4NUc7anvR1=!HeYNbB;>&%Tgb^s>92=(dNv(36Ff;~5^mb_B(> zQ*)4N9Jr5KT9YScW*`~V;MaW1V{dj-^GRM&apP`mTUkrOS}xZ9>A@d1aiSUagL$dN zIoR3ZO{od`lJ`+LTGUg94@*8_^A4h_#loU)^WI)0OIAKBL>9T9@D&-~NX4w%Nqwbn zq!m}LG7_dZHeK2~7`3)Iic|CF^+!uuTDm63#quEIQ0lK-X-OtH{87q3MSQMWGyd{P zC@G1|t~Q}l;NIwwu3lMK+fqbXPg`MCcHE-a6Z7^0B+H!J<|x=d2||#JQ)Mze@)LR; zm&iFUMkVxHw&g8=u@k@UfYWX&t+$>tpU`d-<$XONRbC!}HS(7j6K9TQAJSEf;y$)5 zr&MV&-vm9Df#(=LA-;E)j@QS=&jeSqJu4GJd0vNK8_Q%+17~LS?}XtGfG^WQw&5wf zC7W1LVRzVam-j*}DzURZ4MdG?Z<{5+u(kygj;Qh}ey9V}mNkaF z^vL@>@L|ajmidp12Fvo#B1c2s`xI*WVocyum5_ zkp|iPopzN%uv1`f6f^7AsW=QB=5xEJmWWR)<+07Jtjtb}ip?4)^1cKR)V{eL-XfEf zEEdPV*T`-wm&PF>(!BG|-!|!#Hr{4iG5>2BEcx7(qrHlJ$Im}DIDxbr-m10KkG_OXV4bYcyuNGaR+SFU2W56;OTxmeC%hHB^$j`G2eWKQL;1(8>RZ8BkC5Qg_03zwc#pSFypwxgKt;(DT2%!EZTSKn}kHek< zkNltRh|@XcHHV7R3MbU_Rl_IMzkcggpO96v7&2yKF$sXRir#5VEiH}2jVU(Rt&G5g z?}%)gHoT%pMI>|jCKsTxCY+8Nf?Ij?Rx+968GI6}slpNG02i3kT%H*a0Qa~Jkg3d? z_8Y^7kL=?@SL}3(8HLTwsV66)9UW78etkNOGuS{QTAf_!2z@%kc>D}A^oXU)@<2hp zoQ=S8=IQqp{gYbU^x3JX!Y*u>D#Ko)3c}J_Uu?xpAFue=8{Np z;kE1E!WB(c3@QcUxxN71NvP@ z)#Qo>wIUYw!toLV@Py9QT=3r_ejS9JWeCm;$C?hzyRV@)9Lv(QowYiPqmH+=-Wol zSUU!#j~)nG4OS)eN>%9f`hKlUp`oesy8Y$d=VmFIo9zFTY}iHQeRXn76@i&>Wq2j*Tmpn!>={ zbo(-dfP_d6he-yQ1wD3hzGm!xIpPo&9-|Yvfjmz6-zov5`TeWx$MYgU9cp&)3CJ$| zFdAdb!Y=NG49L9k=?zClv*BsJh?i6Kc2tX%tKD5XVZ)V6qA}w+<;Gh>iA+~I4BU-Q zQNWd(oLm^%BI0&f1Qq4+ zS~?m=^l^#d1Lr{0<-`KCs~lLRgc@SO!tFd@>wf%~L!@gV=q)xLUc{-o&du`3+HNl-!usCz#suBP+G$F~Df=MI0*d5aXYMWZjA zu8&nTes>cgVz9Fdj&un9Lysc8)nuYV^L^Zv7BQNAYmaH&#oVYr&=qL!v@=1WgYU}5 z$@$*fIg3VrdC6(G{2p|Ed-9@%WpfH5d87C|@2O4maF`4mzDRt1#l|@yy_yP8T+&UB zcVgW7?E!t^_-7#GQT2zsam4oA@4WkE3IE}9_28^{Awb~78emh=>p|%OD8w6kz&t(q z`5eOm_;!q>YBcC^0a-uNXRYJN&?vDT1m-l@cgFHW6K~{vB{g}t9gbD4aa-mGnn^e` zEhi_(WnJXGyE{)`A$&Mq{mJcqW%ZG0_oMHCR!gr_i#wlm)B)9xL{Rl&GM*Cv7#P1$ zmvyV*mdg{ek72d>xV265wpA3FNdM2ZHyV}NeUUtNn*#n%z8zQTxiwBfC&lfL7`zlS zaymQ77DayM@T}&SmWKC*3wT_|ezml=rU}C_@Hs*FQJ;cCrwF#QzTK%J@G@0J3zH$B z!+*LuTwe0pFZbCbTK$K+7DMX#`SV$3W~Pg)D;M_{fTF>#IZ>sPf|P6Im6u1}frrcw zNIq!j81dsjjc|B@DfmEx@*(EvFjU(rPh5AnSb6 z^thY{v~+8pXPq}U;~Z>IY4+Zc zB9GeQ$)2vIiTS(|4tSP(;|}d|2j}%y0k2%}Vp@%phv%%1_3;&`rFembhY83Wg@u%T zg_KiMYM=&KSX=~o3Z;N>Lx}{hm@PcIm25cn&v?~fGe0?@5oC-cm8U>UG3vk#)|0TG zl*(BHi9|e34@nA`+iyz6)X23u@&if8MsfPSd?<&rWhSwxL@-45;nXzTr(II^urO3k zOllCv;n8o5ticWyb)3)LT5?_;sLGKho@qL{CBgh7Q?=xFci{8)@JDa}H;^uR!cq85W*LTURdk6PY4! z4N==3EHAmQ(oHOvGBniv+i+?vT)weUi19Aw-RXSCkd)hp&dz zNJ$RDwVO?Zo^Dsm-g_qbbOaOGFNvuGnr{c%F45yb@*}fBN>OwD;FhLAS79l4Reoza z*n!}!am~ljROoR55E%%oN%m zw@kZ-8x^fb8-ISAx-c8`Z(G|@D{|U0m%FeY0L;J0ubmwvYiL=>!I#Yer42*`jmowN z-Ui(C@E69RVfsjA;I!V7lANsHZ~t^@Uu!kPn4tRaY~pdU5t3P=`VEk4bq8emIx)Mq zzK2_}EzsJmIH4!&cjREjK4&@zZ)w`3a);wJ@!a|_ZN-(ZKGt!!u&+Esg#-^aRZ#g6 zn1X`|VV&EFjQ!2=!P4!z0R11Q&s&8g0u!`mDg%@)Np8+CefPj%Ejm5_hYOokM~*2q z8mDG>M`n{>lb^t!*zdJOY*on{sv?M0nqJ4xfx{>2LhfK(wIH!q<%_>%uqhvBpAP<= zo??f$kb6D@urBd{UWYNxKI`gQzqT4q=Sg~JA83j6nP3$N#=SRN=~m_s$pr#pqd^Pic_VrcBde(sQHetn>L%A zjhqHza#A3zWzl^F9}yK=FU3&RU8KrEEft{RVH|5Ux)$siq%1Gr!WkI`otEXwSEgQw zW5q3&!gAcG$xvrx@%aYgsP0u;eNiWN8K|-qL8eFONwTOsK|4)cVZO zMvUayM!tTVRI^zqQ2e2EdV@iue0gwahDgOAK*xq4n>f!@g(v&|4>(~CY2wH{c*W^_lubFkN1DtVqTZd z*7{s{0l|P*Z~5v(iQ?z{E%IE=mX|q(HM4+-3lV(sp2iPB73$;XT^j|e^N8Y`^ zcm-NCFh5|UD8R{SRCEtcY&lLMU#+-{IF^6I{NluCb~lzeactpEF`lNA-n6kds>Q0L z9*H$+6d`SWhkbZ+{UDQ5OdVf#CXUG$G{JPZXEdBd^pi0nwik;1f>ai{qWMrtX3Cgx z)pTa>tuiAyk`oJ|mQ8U#mMp}oK9tKETIIAQi(TFf%L4HdvVWZTu*+jzi{6Z5wG_Jr z*vdrKCfUmt{GG9iIQ7Xb-tK;D840_Q*-~No0P6o{JsfeXAa(W9u|flx3=TDCRMpUF zIQm`;BP*+x^+?h_WLcCTSYFx38g(gpcmE*rbBVg@X<0=f(gCbyA5mu6;~x0X&rNs~ z&jVmLTKj*$wClk!P;Xhi?^rXfqYYcSdtv-4=%bIx7x9izbpxvf$`c>S5_Osp1l)98 zI61B#%{Ne5B(_A9%8=H1hKjDXbxPRb~poIs^uxk837Wlw!Jp>cR`~GFFZe z=hPQG5{xF+Vq0PRwArq|3hQ^94|NJA_ebRG4#^$jf5>Js*bshR)-z(?`=LR3PaNj@ z36l{W-CmtANy;QrG_D}nwX7YmWJvLu>f6`msZT6F#@@3|y#RWU)@U z)A%+VZTEY<2@)lmn)|yu-QV%(z7$Gg9V=d#+RFYhB|IX=zzLJXSd8##7UwoLgfZ3I zk3?hS$qWi>RPP$;aM-?auGHRnxxpOO9>2fRV05&R5sv(uJkwlal<(-TJ0$SKc&Sr* z1?R=b42@##0odx<-~UPm}33q&8`DXUlktEFO|Nt0sr5 z6_NOHj~&Zueel_P{$Wz9sp)^6H5OTTqgJ<5$%-#qQ-XbY#Psr~f|w-}g0r zM6wjlhM^i>!(#|vlLN2!q#UaX3y2_bXU)D_f^BCA0CGUAZ0dR-k~MQ)Pau9P!T)~z z9z?ukbt7QFZ%emNd+N;hdUvB%A5zymo=Y#nI&*u90)BU*TaTg-1DulzQ z%IM~*^F*cNaUyzWZ?9u6_}9Nb1lk*6ho+Cz`D?1>4efs0oqb$pX3mAQ|UHBEHq(>FdvfvNpfoV02!D$*ZRQ?{{xQ)KdkdgH-b@78~Vfo)e`PAn0|UZWqpd%V{wm_OIv>)$l16NmS=z3+Ia)8{2^u} zy2qv=7`%TM>$bZYL^$+ZnC5J>b@h4MTp5jrm#Py-QJ>NMYuID#PmN1FFCtpa=Jg6)y*of`+J7{ZfLG;Yk2DQ_YnY3! z6^?22cj**G6bZ8-i%zf5{=>N1!|>`id_u}{7h?oy8_Dk%)?Frg&N5>g92WuvOB+_z zNR5+)2fPBMz7J>jt4Eh}_t<)WO^;ySnL;RK^>Z#v5C$xnI>%AdU`efXZcc*D%b3X4 z#b&;>eT=Hz@sTq;MrSDP(P7HZNHjjR=Gt+^bV?GITBIMXUkAA{I;WfRk#@6$ytQgR zB0CcE4ATEh!=`3iHL$j)9WU1uoE8r9#6wM9oGkwX6wOl_DaK_rjG76WH}- zi&IkhD>WFAD5l)1&WQy^LC8i28;XCm_n4msJZoiy+fq={A|0@rq!&#_`)9 z0Lvd8TesC-tEV;d%fPyq6f6uaPLPc_3u9~M|DL-%kz1-)q=GWi($brA|7zv?)8Y9J zUjdMZ`VIp`a0+z5{_5ZK{S=RGfM(IS4j(_7UKTzxviTS)0CJZ8iCj#&{F^%;19bEx zhyv@AbZ|%8G4g$fVwD!JuP&`N(2j83NIR>j!}`xahDuc06?7^W^Bp($P-?QFR7XQ} zt9$3zo;FBl+khyN3I<8$7W7hLy;N^VpuHl+%a!PA6v$9AxbkLEA18i+jYS_+)Bjmospio>-CU^9LuCW3r!(qgC zrJc8LAD27t-1Qv$Uf#u}m!z=Zzg>lpDdU7kt)DGFt)4kyz^VxF9bJeX+qFhG^Ql6Dj=+ zcK;7(vIiJr8X3%zqsInoBbsIJ+O*%8y1TSFeq3xIvY=C{UYqj%tI)0Y%9?qBP!Rde zn}@9d8ZnuDf;VrBZEVUYD10{~d4Sjg;M4X9YhwaOe@YD>82wM_{GG7mQrDB=#F4&` zuYpvxg$(p4gb1jGsfDfOR!`%~ko(NOMf$TUs|%~g(a0yfFtd=Dp@bN-kLUM4Yf7)4 zOmeqv{B?B~uVeJ!dd$#W8sBju$*uwH9WzNHbh$kU z^PlGOMx3!KHRxQ>I3$Mqf~SiK;ddO3oL1R4Bg#7HdlmF})-^fgop6l}H2hb|xD+G= z1m7zwqrqhX;@KD&p>yqcyr|@f61iRr{72OT!ETQf{`Uj^5m($lTG8I%eZhohcnwDT zu>K9GzSI4|;DAlQz^N+hbR#%z=JqJdkd}rbBS1yLCEgY+ARXe48jx8F!4!{S{R4Mk zwk0f1ymsO(KN3AB9|T>9>Bn=p~!H_pT*TjZuezZd@w+G-)DH=#|PQ{ zGDiP~#Z!jiL@?Xi|H9el&tYq(+z}Hmk;-%N?+N_jcUsoJ7mOTd-waac!${7`9W(XQ zV~!@i&bGKkS#ibj3Wxu+Du-Z4zBZE*xB7*&>lrAS-i*y*%L$1ikDx`9fH#iqHsMrU zew!JuMi4>(5;v*oqHywg(}`(7=(pA;@sychJI8%)v2OqPm8(phlw2SL`$r;5qEj%` zhXd(Y@FMEYpI<<@>@Np*U#?_0o?uaXdnU*Xd9-amxcWOEsQpvm>>&j1 zl2oWiDce8Oy0R5c}RH1RDFZ$`!e$3I8yCjRX?B=3%eTU*%Ql$=}(7-b~ zw!5jPQ}+yhN6z}5#uAD5d$!D~tTyLg9;8JX6`aR#$4qte#jdiez zSYH%m@P))#E{+(|6*&CZP-nM_McNm~_$0S?6M%d6lqADY{W6zc+>6jUhqO=5OHtpD zOjxyrTT_;0Cqw6IAz6lQe3v#6;H#b&Tm?$b0dvKegD|-{WN@Exk$mLD z-+xngsmfNMoi4MwL*XgiGDrQyE|bu)Lw*dRY(B8!yjPx@_ht;$?87IaptKTc9*=bT z*LZXYnPIJ$EMzI`4-!8-fA-VUDA)eb&mZ_?1)sM{*{c~69>}R)yGWhiicBF&pV~*> z{vu|6-h9x3bPbWh@WKC4q``M*EL=a~e+R$y=U?R%#nUKyJimUfe3-eKyUdAx_N$LY z;eQ9i;{XXM8P+$`AJk}T`}oE&LlYv*2CFb9tCKyg{68DltX;!UQ46d_V*=zq`6E-L z%X55e;vMWa`1iltNZ65g5z#IR%CqnvGFe?=mlIi=9%ptu6&JcJ9{OGrvKc{LpFcPc znZWXc({CQ4(C5rM<9G+IVB(wi&PyL3g;r{0#?aMAhGlQU1->qLcCzB(S?xG~cw}|+ z7J!A{&YA=`ue7|+*vv4*z3^^#4w#qx7FDH8Gx}uLCG1y$I<7LMG4i0%Cb>A;`q7VM z0fEqJOcU0(=yj6=_KoMF|HqTg_3xwO6Z5OQ z=A4;car9P9Ggb!}i%N*0DyUYUBT;QXjszo&MCjx@3ZlPaW`edja3bNW_Gksl^rVl3 z6yLeCa+=PBbzEaF*UeZW~UwU|sKCY~h?bZ#0| z=%Ov*Oj9Wp+X<4{0o`^8VMoFeA(eIBd4a;FXieca}yu+^23pI|MI7?5Xujx3tl?v zXDdnQZ!tACu;Bd|u%G{S8I9X3kBAjYC=<_$loQka!7OfCd8odz9==SJF#wZA z_;CJ89f^8UrV)~4#{|$1sHl_l`O5Tq3yP6ax{(O^A8NU~;lnLGI#72*%Q8p`ayy!R z$BXIKGdr=e5RHj0)I_YizUxEB9=Y5*x<Ea6ZH#6cOsranNw;WA^pb%SW^L!mgl{MwK6jrgDma?u<3wW8!PiyW zsfZg*Ax}S~r+#0KGqaRmL*LyRc~gtOe52-V!YT87K|(h$;We&;7S8t)ihRj6ioGKW zbaAa9JiBgJ<8`$a8)8SiNi0D*or=_&)ZV5MQgQB;+DEbdy1y4!bxl9#HK+>uLQ^IC zK2*4bQ`FLShZudL5Z@b2=?=!Ind8I#&LWh#`0?nYTc(`U>Zp(4*RhWMu(lOTvnkr= zCT@l)pQ3HlC_SJir;6E$ag#1s9O8jhGS*m9&6jEQznt<{_4fwLN|*RmGBHfey@qad zrp!VQyDQaK<+b%fbNVR_G4N;Rs7G%P+j3U4ry|WIOt$@qb1+%XB2Ok5An!CN)x_;1 zT=Nmb)oFcGwYhlZ_GpiPwiwt4^~p|=W63fE;qCN(FBg-0o+T<1Ho>?h$~|*CLjAq+ zYLS0eHt)1heY<^nmXAB(jQgE)WlESkO+-e;GoVm5gE;SU~2Z!@dJ77#cL!?bn4viPf03cU@7YVYjreki5ID5khhCMo9j6GX5@M(Db-TSro` zy|m_{Btf{i!ifxSRD|2d5KiX&#PS>KEQZ6tQ=D$h9q#jO{U(d{me9)cElm6$jPXE?A~u(uuyT z1o5lVue^!R;Mu@$O|1f5xZ}ygfP5hbH_I=1t(?=n5 z?sw>ZzEN%|N}?Q$UX~Q#0*E3x#N|1U({M?xa#YeM#e9Dt}LAw)#5*-@)fd# zq+K*SzC@MDGow{qy{eKj%7@^;nHl_+D~O>AZ^c%UretaxF|mdxyO`4TUI+)Zfnpcy z?0qi~pcFPZZRh&$dHn-YV%6bPbK~jD)79&B#v|%JPhXiR#vG+Kv}xkKHL5Ug%3y}4 zeEor)iXoF`-pgHy^0n)j4^O!M7%`Ydaj&5;cgdYP>;Nf6;X-|P$Z+)I_7P|TQ*1== zBM7LMEAJOMFllOZBV_m}(fYfoTPFfSNLqQblxwN1+@}tanz0{Vz&G_atyIU60!j) zI07#H4qZl1TYr@B(8E{U5$_DdE%R+HD3(c-8@Wnx2(GFtUbu5xX$4CbJ{&CzDZu5M zVRXmIj+kE=qgv>(OViain#bZSIxspjXu^a)(ZXhe4KUR+g?1dJ+ z;ZX%_j_{=y0o}AOGv5=SYCzg1ByQmfv8f8=9!l~>i_D%&5#`4@uK>5!yi*SqPDSmzt z#*;izr0O`!h4%`vIAJkpk2(`ENK{KM!{S(->MP(5=o(U}hLzim{4i;7p2=8!!#>hS zBPsLs>sReIkCVkL_wyYUXr-Y)ob34udAX!^c-mWaoo5$)3(P-d8AO{edUYb8B|`?h zbh-S<0U_$H+rlHNzcM78=Blc)xuQ`5PG5^NU{h6TYkCF?u8) z-=?h9{Iz+5^FnZUgmYFLJB^zqf92co^dT%Xlq>P{$Y!aeDT-5wh^XgPoG=!2iFBU8YESHMq zXYMOpgZc51JGH1LvLyZ*(0$+asHz?JuN-GT+g@#{o95n@G_|pkU_AEa!Lvyl)nEu_ zi$X$Sm^K_-2M$ z`YJz9^NsOwoVbN+gvb$q;&mB}TpK>@X|A4T0H!Lb*A9h&*KUD7-(@!Zd{BG1x zE0ub$66{p+1q|pm3yKls3a-w43ocewq|v|*`WnNSIo~%zm>|4oXcp}uB9`En^MA7d z%5)hQ4*D08eGosun$6;^C_@51d7|F&@~9*^hY9qao6M0|tt8)B4s*@Z zK$c+20?wo(|IyY6=8wtYU%0PAOqU?{x-3{cN0i{DmRe(H-TM!kv)x*!H^c@;goOy; z6m?tZB!$YRR-en3PJ}}hT>Dh{p){eeFmw}X{0upLQKeZ>L#8b9cVUR4iIq;?7vgI; z4jtSog7?c2e2PB;4n0iJvj2x+o z;mu6g_H>Eb{e1zxcB>c7tbsH7DD&v_24S-vTp&4=aP^Eq(^|&b!fuF-n+=jv655bt z#RZ1TFacrGnjTmD#};+~OuYF;mUIa*#X}Hp7@yZU;9Zh!pI*$?SoYw3>%$z6r=B4Q z6P^9hc7E@Cjxp18ljN<{>c++IcxjF#SFRxmfiQmy{lTT9vv@2dQh%2)mM1rq!Zm7pTr4l?CZNphSbZ0hJDacq4Pqhn6^=*xyroIH)nVYEojq_nXXwy7xu z<^Wur1jWO1b-^591Kp?spiiKP<-~y3)5y_&JAP69!V3_`GHbBZlr-Ap@c`E!D^}_o zBP9kK@28d~A=0z#W#<+s)E(;JIq3)x(-Gjew6g0%*(Lsj=fvWfO*CnVxV<3zg(A$< zXLUgB%SkoEKlL8SA7p@)oR*drqZ$X=_j*yhQCLGgSI!a9N|+(Wrg>YQr1d)J1-OZ_ z!SB#A&%!XT1C$E%#83i`Byy<|PL(GIbR>>;)dcU4slYU0R`lxCGuh7#$XO`w2*=JZ zk887qhCcu^(A`)$J!==iOj9R55}1~%Fa8!c8pJ2TLMLOzHiS_^bYf+CA{eG%6%ieM z+I=?e@S`aCJ!-Djv32&HLQ67JmxNkY*2Z9L9`Kf??Kjw(pTrehcPLFN<8*c&T(~)m zeIP8Lh7y)lQ}c^K`qm}v|5+serHg~{t>6)SW!YwhCa&Uy7%7!V@SLfB+ugP7CVxRu zJd+!emtG{uIP;ANM~W(_`$`D7C>e0m-f4ieWHp?4L14N1rxSzWUviyq9zz4vN#yuI zh3<;>J6FO*9d3HKT(rP=o={YrVC^xPNC8a?J3&rhnp|0drci-No?rOiqShFdRr#D> zn0js{Ci9(cixtuigvAGyFWP@vjM5$40)6hG|Hso?09Dz&-`^@oBM3-$cXvuR2rAv( zc<4ru?(UG5hpt0OBi-E~jdVBsH{W@GuQNKs;5lc`zVCa-b*=STYpI_Jea=y}78d4f zw>;jkM8D5kEL!Vqm=D4{`je%|@gUz#l~`QN92k8pTQllSN#J@&Ok?~J3!!10umZP44$04a3T39@vM>LA=%Ehk-w}`Cp89W+ zc5fiKxvBUbl|yO}3DN=;mbeZ11Qd-zyYl!7JW)Ow7&B7_l5g z5tIz3DaPSizTm0D&USw`Sh+QZ(C$xV32q0y&qJeGUjBbOd?KP^H3aF}DZ5qP7JNhq zuS1l@crR(1hIIR7xTv@{-o}pEKmkRq`3Yd2dOp!^B8o|_!AqzNot%(@oK_T($31|` zh%iFkJQJRlOLZs?h{E*nR64nS-XMF|Qbl5j%3n^#Cc~)Mh#paR?8G9C)+VdNgn5TV z$0&whs}%Cz`{6%k`Cr^7jIFHVq=}!h1)pw2&NqCY-h)t-=fqxOZ$fKQ6z`s%Aotq> zoSSW)=cFI@grwz?Ul=~DYaK4BdExjc%xI7Jb78N3me^vi`z2Qu1E05dEb;?`bAdS< zEwuC-wOHvL_=2XD z{2kr+)|`XMEUyVT_}LZ8RP%J`$pWcQux4=i7qrLu%_@D-^<{IdLIG|O3Fr2WF|W@9 zy2wpOmx6K><{f*TsB=zG9B+@-Uzy5pRdo08cOlka?b;5px%FE@g*^3kZbFGag0*ho zNvPR<{Z!ihZZBJfS&;&QpD4AcYl2!)B-q)Wr<&%nkV*RSRiIZ?`{#&A6wI#!wVXJg zwJi>Z{+n>&(!zuT;~n@*>(A$rjK19f9o&g8-xhMM>cntiVOw{&vsLhP!)dqAXic!w1_hnNlwgCNV_85aG8`-xgl1K61X?CWMC*16eG?L zYLsiPFP9|}k<@xqcnix4Qb`fUwBo0X;wU@thc|CX+ZBoezxa8`^lq zNmv74Rt%66D?gk7$@W3tdz*<6wCRvBgUJ(P5(7=;pliJ3gn(M+OF^$2R^JnN-}WD9 z!gIV=_keg0JU(ki9}acNzkUv{f!Po!so`9Ti+aBRVjB~RdTwv6?|D}ir7exZtf6{; z!afY*5fg3(i@2re#2ELEWHM?tMR?z@u9=St%7ggWS-X~?Li8-(f3jzP%mOZor!dMJ zpWxEMh6OKc%n`(*$J8U4*%yw})t$<~} zM-g}j@YjbadNrCYIe1oTGc%4cd%3{cFy}KF3A>`0Fz^+$xAy-1%QaRJkP$6YqZkU* zf!uyLNX;U@@TTl!B3!_*R%BNH_Cb4AO&?3cChpTD7q)XP8!vCbE3mRvdTcoW4wana z=Xc6tWm@DXf?lgIn0c&je$tIPg^e2ds^tym3JR7UX*$A*|0yYB^dj2YmVu^yaKBTo0-XIWnWP5`u*eW7x}Nhbppjk#DmH#Y&B+D0ul$CL+Po4;O{l- z?U+FO;S0U#I!KIuZSLXeww-Ezl3+0W-&Z$`PMwgMxIT@6EqYbi|5Q>tI>^$H+>dVi zV7f!MkBRS?LF2Z^Y7khw4i+EZ2nn?a-risWX(dqy^!slT)o`vJi*4;^y>A4n$ctW;i zvxU`qoi0d0wIh=?dZ8Hvi#!;<=uMAwD;)n#(VYPpIt2xA!&1*wG)A!6;}P%u?WfT* zQ`z^hn}ddmA=lP%{k7a#c`vu+19t~!$--QO{q-baJE!elTaK#1 zYJ)nd!pi*Gn&tc^THjz-Arx)7DY1mR;_pdL-tU`r<{3R`sCE6}N4VF^nTHbG+y4~P zHR?U^8d*)OJkYeEHZD=tK^J)bg<^hU%+Ye0eu6n;=EW8J4KYfV*wz^9l({W+fgt=y zXD6wpg9$#+XmNJZ*sq{v{Qy z!0uW<(fBL#W8)Znog5yxOQh4JeeW=PdXydShVYO&RP!s{S>++`X@bvwW}ku$^Tb{G?Y;NEy`2e%99qOB3HpBL#lX@$*4X zE8(`yZ}w#4kJ6lI0a4D^WPy|?RI86iu5?hS!^Y+8IwFmv0(ln@&v(A)Vopw2waZ(w zJ}{^my)SKhU6RwkxF7$E#HiLBSzuVF#K;yM|aR(=-?mYTe~~_g)m&0qo7jfSenA zKKk(N5|e=WwxDn1pscc9eaS_C3K7 z=rjyApW67gNFmTfw83`x%@eaug`7^6k}M3%HKtq4{}s|NZ_j;Qjveup`+r|^URAzA ze-(NiP5V38wf?s|yYkcdX1}AJ*OMl(`;CfHboMq-h?)VG*Ta6>1BHm&0sN4H;f@)4wj_%yg~jl$+4XR9?I|;$jJ~4P1FHbT<#5687+$6f4F2DI?}~u)|@XyM$IG$8F;V@#)DAe)sT@3gHb9O#_hYgmI`(`r$Hj4E2$N$eFb9LMnSzIg&2Y1)7 zS6HT?l(hx;4biMC=E?}cJmfuMOWjr&1W?@i#SFCm$c&MY`nf9l(D z+b`qcJzFq53nW~Ug~fz- z*f@j~344K({Pf!Q`BhgJ!Aqpk?f7J{#ne7H&YZtUxgL6-Z%ATQ&m!%;et=R+*dKEH z)?4bly!0x@a9|7i>rQ-cx6*ZLToHFoC=6MBeE8#g?+A?j!+m`SB3@^7f{SLBhFN3w zv5tgcZ=)&0ZpIx)PbR`yDlHvJF8^WZ9mAdJ0fE6eX9c0pd*If;F^-PyM%0ETi(1-P zs?cMlr11_`ZP>GNw6$-}a|m89IijH08SKxneKC69OE!sV?ta(b>jpM;m4}2P&x0iS zI?U+7m5}GMA)DR5WjxUv?#$&I?v4Divh$F*L-U0gHCck=c#U!eN1g zhPais`)Wvkh_|g3&2X$a@tx_nFzOHH`{(=VeC{Yj{!ESvD`VU>B$*tSX9_+aMBnU1 zKVbDnqd?AvjbSgT^gNF6K80Pk9Y6l|IdIPMeR>OB;T(AAB-ASpfIGW=Q>HcqFk!oN z*f**7A_G%Pvcz7Sn%E`bHu%Krz%l?#5bk%u$~n$MD=h-^&E`1ajzE{N;)&pu9m)~U z>7Ro68F^~onG-$WHT?x04zkT6`@rM1cLum`{J(;!0w)al%@@&(0&#J2lV2$TU=AYlA{0P3Uokcy+WS zS*N#E#9fghq4`9;+6KKNC9xxXdT|286~BXP?1?HYHf(qA*$ zG7vA~76vRy5&QEX()X;~z`-G-?aud!pm&v5serv_Ww{v_{~wLLI&P^4ZntcA(a|%O^7C$RL^hvdF7Udo4jc&yG@eHZ$i@ZC z>I)2PZo-DkPd=QCVLl8b`~2uT-rDLC+1%`}k4c)h-k5s_nK1CUV-y`*kI#OO1i7Vl~bhh;}8w*oWX{)BSHb9ad=?C_Y8H? z3(Wl5y$LAv9j=pUs!G}H$LIIbE&a!*j9l?NimQy8+L&G_Voz6NBYRF`n z?^bfvz4e3;$ojS%Ugkca(EPhW^2`e!LNu@m0!|xk`<6f3!|Ast!6Gk=EWr4XhG}*^ zHXNLZF)Ho@>#2fpwz0v_>=w`KZ~JBS6O)r&AcV`fR_z7$Xg#aMC=V7vkq)%%yVuxk z_QbxK$38pSUZ=@Esj-m+?(3m6d>lSu9e%F~<<~&nUKTAL)124qhU)6DIaPVZm*qvz z$LH82RWomJou#{p{LU|%)yLr-%T6U^L&~nvl%)QsIXrsFlV#WphK%z5w_qZUzLA3q z@hk-3VKyD!QO5oKEBcPGAu^J{!~Nnu`bBqF<9vLG@`W%z>_i*YYWnTnJr8MMH}^h= z8AghonJT|5Ouh5?pT>q91WPIY4PKD>33<3Vy{clw-f4z0OU}i(BlOK+4(Va)@PXaRE z!wS3j510$AGuTkXJtNIZh(*lP3Q}N3I0dI@iC-86^{CQ`^7FaxM3|RUy{(j-Y=Mqc z2`}n+!cQkqrcab($xD|?$>38`Zj^|V$lwzgp@h;HIwdDh@4H!cM5?!JfJYPaNKPdw*~_p6?%hTpF#e{AB8KXQ-6H+o4UP%*xF_^zGS2&-?ZRHqNo67RIbI zM73?gD0}c?h!U_qA7*@SnB*k;H&Z7!3B!5cHQbjk^7&lw`jkY;i6QYNI~2DU#u^?q zZII@rOS>QTl|*FY70v%rIa)S(kY@6O>cmn0Ec&vk?t8h)#>V$YvMGH_Z(F5ZWS5(0{>SvDmF$L z$@*?#HAQI}(8!(nS}Rd}T75&!I85oN^P4#K%xSqviJYV`RWI@ z%7qRa^FVg@x_+NLod13vX_m>Qk1B%@!H+su2~dB}jKXee;kb{>J=Mbo<%nv<6u~kK zZhL&uk^rG*SIF5Wod?4QXhh_jG;l`O={56l3Cfd>`gSuto05|8Q>!HBi~k1y#YF;b zV%WCMXu)`Co|BlbFG<#p>K@(SM(!x4{^oaLG=ko{vV@B{pJ-JFc7Cbj#L}K+$&b|a z^Koa{ex^&N!wygIl;foDym4U}I{nd0V(#J+yVuX}-yA8AmgZ3=m1pObnC*TiospHY zc`${NUT-H}OgVf4dwz~=LqO2648atrw==V|^E1~2ueHlsnSk@>B~3mD)C5sr5koid zM3h@N>_gT{;hmyR+WU%agma9v^a%+5af85Ax4v$4U(fjMuKBg5OMachymi^|yHlrL zTU=l8i2nV=F)Bh!9I`R#YrAmh1OZO zr}iK=EYcV>wOYap)v|FZxAT1dV?go;3fyRKkOIkDTD%YDKW`deKNI?Fa&U-5CUDD# zbDcF3Gs@@2;g-GC6CRzfFLd9ZvZO9FOHIp=*bkW1^Ns8et$D$iZS<3PW%GuHeif_I zFtUUI=qB2EnY~Xui0eXkZMBbiKF)57{5WP+_pN{uK@4n0u>vy&uhQ*|%sjCDeyWxm z$S&HjqWc&8!%)HcT*hO;nT|z>Q%k+$-Yq*3Wkh*VhnhnZ$Vy2*9G-RUKq)IBoSdi1 z98YNmW62#m2UR4?mbS+H!6l24OG~-acyV#TD#V5S z#%7T^3d5?7pS#9umqz6KMpL(n0OyL{+$tpnY-JCRddB0`eP;xe!#}wPR-61m+QE=;Dq4c z(V>VZs7~#3b+T@b zC}k1s^?GkkYevs8kDH^tJ#}8(>F9xow-ZR3;(3Pb?rW>rVuXtZ~>>G&3$ zd!s-*u;*M56tkonb+!R>06;Q9sxV;FYN)D~r~y6}0G7P?`m2s-9uF33!h=bCQbW_&R2ow1I1Y6aldd0Tl%e^|S-cCr04iN`ETH#>M3| zhY;86H))a7hUnz^lwjo=$=W(dt$9K3d3;^JXCl6TGHxjE1x56on;9Mw)Aa+*vF1vq zV1R$Tx#6uK_6elujXISFdhwG^hG1auryMp5Z+#L*4@v+cWS+S??}!YFRDF&7FZ3$( zo9JTb67M4mM^)>Tm}lkDgXRpsS2E=r7sQ8i!Id&M?Y5)JzI5?#yF?xU;qi9+${yI! zySW(0?@0Mo%?G|dJ@$nBl&Pf-;o@~SVw&^4hQGbKCf@M%I%JuL+A?$zzyYodW6iA~ z3_;ZCOe!8W4$gebj+s)H@BqcCXFx&VTWZ2^9;M8!I-b!=LpKWhthBX@R62iNqw_gL zJz=jDt(N}3>d~xhLZhJ^H5pl2CZm4M?z_#=r^x_)1PHNGN5Aixld#hPF&eHdr_u2l z1Nya41An_vw;tevTyKtjucO`EK`oSTBuiMa_*1^7{n=PONvAzX*GefamITY>C%o$(_9x1H<1OE?b4b58Bo;nVmPZ9Wl=fs(>k{r92SPh^o=KmOcO71Egh`bscW z;_R>1xBh^UL&7e^CtkCX+oVBp0h1O9_X9>e!e*)GY0=Km#Da%rMKF+xC=FH8xmXsL zCo~R@JqG2I8UT8q~^ zF4JphWEI+9OlQP6qBP9PAt1lnPMYuD5IAEIt2I*_3h}UH$J)7VO9W^+U^jGn$tRHlv&?qb7@DQ&4pB7-uhTDCkTQ-VF zWW?`BeWm&6J&3V?pw^bUu6~9t4-IMkzPjVh(l+#XLNV43o@1^3QDtj>n_S_WnG-2A zrOie&`uh)bnEeycH#2Z{}t~Gy1UG`z2j@ z;tU3K`-+)|Rhd7?VkB$u2|jHi3tqH{TTp7-FZ9C;f5S;jDe&l{h!z}}RDKQ#?Z<0< zTH|qBJ$OU%bRrEAnvY7iT({685X%evh>*VWg!-^4bbU6JBmVng!1`dR5tAhucq)|1 zZKHK^f=_EcliGldkZjIa7l(*Plvs`o24a@y6;*x$m@SeH7q>rYLGGqt%|{eeDsD6Q z`TX{=cp(n{pEo!dr^&CD9B4$IZ&}X9u3LK@Sz3GiVBl%5-ktOm*ARMdVD&0x7@F+A zliNZ)5cx&}phxw<``la2sFamq;9{8dH&*2(epj_bL^MU>3&GcI9DJLF-duNupaeWTSynu8w2WW&DrT%hm$xB^A-QD34uP9&z+ThQ3 zCmjkjxIZ6)+cj=<>(=I(+RSWcmo5=^u{w}844lMGN)uYBFh0ERVQ#)A+DyKa*3i<* z)nU$APf=Bl1(cDIbUQKYz#aEj;O)m&MTXkfs4>S@t6vUO=WiKlluNcIKQpS9%~UZa zXFqj&M?~0BBoD@Rv!!!K8!d9HpjUeD(`Mh?^i~SHXKNZ&+rq)Y)2Y)R>P(d|<<5r1 zSfQp%_ck1^5qa$c2Be8e01P}DYugvoDy^62CN(?V*v!W-v=|S1IM*M}Lb4qzP0|G+ zB>j6)%mM2Yz(k~!DLCA@gfU&fPqX3{o?6UTi}CxmM;jm~!HVNCAUTlO0xB1Lahtur zkB_bm7m3YBhuFFJ2B$9YdY}>Ly>F5D(tp&Gtli>dgOff{Z6!KX-ap^>TL_8pBO^ea zIM|C|#&aw=>@!8!E{<$o5dKjOwP@|3SoIAfjrjG&1Mvah0@KB2a+?icocV}v?%@%; zVq#+zm#+JjSsQYq)o@R`Cr3{Q7=p)>dedo?Pg&4>GQp82&t|a+wE*CNOHp1q&+F=x z-W~j|Bg;D++ZL-d>|%Xhtng0dS@rs%!#vvlQDkzG<6$aTM66NAY_+Vu>bd>!;_6Bj zxIpV%NyHEa5|IoERr+w|TD@^V@*-q|l^{s!*Q}Mza#Orl&d?$Jv5|#aidkNVE&P!| zrEf}W$7|vHM&I7eO|0^bagniLbpO@6!&OrckD#1k7z0fd`=ySZ=V4s?7H1Gn;B-#< z`7;-HbQCMpR$$tSXchuQ0Udrm^oi`*k4wO742<<`owRF5*S-mqN+%9{T4mUI=^mlv zn2Qek&}FZ`t4|fbx=pnANpKB79c5}?@l2>?>C(@$@pA3{Bf^(l+9WyNazuHk1CjwX zrnKHXn_oKW)#e&oBk5p+s?CqWT2212F3hg=HwRaw#@PIdUFxMO{RU_-`D-tR71Mn^yb)*nPkK57PPHtJ! zLiMrOSb1f@FK>U#6C#6((4Y2p*6h2BorQi0I35&I2?@d=Gs*6&%79>MADoCPT^(dF zThywRyik;MPBKzcQ(dRe9<}-$=&Tj-e=g)`RMUO%oNKl9Tr@T8jmqqXC}2t2%&|(u z0jeMu*zK5MeiUIVUV9kZSvzz^?|naP7EdGq=o%pSgPoQ2W0eLa!kd9DB+&UeJfNaT z=dN;IbOD#`(jyZv3l$e#(Iwx%l9SacdqoD@MZi<-?vy|oT8Yk?#uY~i400%RrUI<4 zguTE542;XlxIv)s2x2Cr>a+^J9MPbNi}OyJ&p`)AGMg9Lb{zQ9hNkA5~0O6!qtpso+rK={| zZvnMkIsNA@G*UH8|29#d&Br-O5*MF5dlcuz1!>~nwur5QrBX8e>kB>M@5gr_x&_=N z9xYJ`aj~(H7gv{<9jgHIiEJ4lmUOgr3D;xN~UvFi&NH4 zJGWNQd;>-w9?Zd(Ilm34ebAT#K4xGVZObWAGrMGu?4+R^^Ua!q%OyhxA>2UQZDOv| zifnBa=C;AjRV(?+3tAt?)X9V6GBB&=upJPE$B4+N)JR)LM-*G!PJ&C2kb#9P`7+Lg z;&ob*)^n|o)CsBpbeRyRm@Z9snQ-brY>1n7(Ws7OdsrUe^I#As7l!*&4tLg9f0k0ybQl_?d zxNkgJsM>s_J6kYq1vwwSkFZ7@%chPR(|QS`NKl1U=^Go90$pS9`Ndp3$IWlcxKyw} zYvGSkD5|(P0vR|oX(V+!3jt0T;w*>!sV2#UR*m&6bAAH26+q{8k*%?}rzZv~k40rO z-!v^Kf`E(9zTtO#ZyB}~;FZ(2(!zt;3rRC&q?Wa^D5JxcM|o%0?yT!iN}4JBV0=?Mm^rw$5YQW2t&0=25i__oQN6owUZdT#FA`-O#1r+Y zWO~ek+ZMlI=GR|d;z+Y_v0{laBwhhN(Z(-1ON-%h3fzUXQM>yDr234xoNl**dd$j$ zXfa9oz6LRctK=xgNCg-W!ukzzIMKfLkAdJ1RB}NT zC?+kKxA7+0KhrZREq;<(s;S!yTElk zIAGjzcstA0oFz0$Asgp1AUArh@XE1lQsJXw9FUQH`M$+JNF61L4o0_%5qXhY{3Dj+ z;WG;}vug1dP{g)nH`SyL_5fTp9p=1*+-a+V6548S@OZxnP=i1PUuPE3=)jRiHV*fB zOUzG)d6qgmRS8|J7SW+fRHSRSN z@-=@kVP7YirVb0s)ma~e<8*@;Sd#C7@Rf<9 ztge4zi^md*4=y%-B=xP%h(^{|F~VMuaInT3)&Gu)QWPVun_e-~<}OV2Kc+#2Rr97w z$DzKvl$}P-bSAAbwR>-ZNH}n@29qge|4S}oCOTaI4GPqI@yf#P&4@&5G3P68xGRj|Ky$hNq?#q;~Ej+ z?T4zpH$=yT>ru7RW{$kW08^tz`E1r-^ZX@e-LqRS?MCyO`vW5R0@bum7E0N;50^=r zT;*KVEq^CmPHmzKv|wtx8Qf|gLTDpNvly^sF#cOAHH+W z_hV9l=C4UELLR#I0)qUSo53QnMgO|kw8r_Fq?!3PL^rv0CAXO6?H@5ekk}*06TRaO z76*UwP|ScWbOwZt6rwAHmythl?^II8tlm-!(Sn5} zmx~uFoj0CaVGsPrla5LIJ)4U43Pm#+%A=;bDyy15e_^gTOSY>??NI!U|Z*t8JyP4h5pRT~REhObfihX1j~ zi*nz>FJS+rje4JCQ}0`lq?=TY)ixiHJ8n^Xse>WuR-P(xQ-(f!`fFBkDprTtJeL81 zp!e!T+o#zJk~?N8@@C>5`aZJ;JUSTTL(B=--{8UTg;?C0ng5ERUUk6er4BO3T6ZT_OVgf* zGIi1_B;z3;zLvIL)>C4^Lb83E7Tcs_mwI6~Kvy$^jT8vI#J0dRr=tp0n~RE^paxbU zEG>pyUh?G8@iXtcyZbS%4R~SvND??RHrlV%sYaa5$;0drZdNnw(1?a#7eegS@tS7U zuP+wFf7VhX83~S3=`+Ssnpuu^b`Ii%bcV2wQ;Q?{(}sLRWSr$_b+uF&p^b6H_ z0-KRWQmT%Op~=rLTJeR)+J~<<=qLwJ1452%oqs&9NCqIpi-}kJHi3EEl1S z>69wAXB+N%&BNv1`zQ?n5E31M6~Nr**TZve|&>Ql{X?ToE&O=;=8x4?&rt-0=Ev3R_WS4N5G`2*wU zf~Aa{pYO`S?TfMk$$(-E!*!SH*sgwQEG6P7K+;hUkdg^aA0(&`9*gmr9rO!gjryh& z%^Eg@(KuuFvD&7SRsumbK}%Fk9r9Ug_&NjL#c`duVH~s5G z(tJuaL~<(GP^D1Ars{v&4l;v%D5zpul-(LhkzxjXX6Om3g|dkF4O!t^yxoQ&3f=*J zA1G@b$>STfoS@=Ag-)w&n_EN=J;bnj=k~UJ=oA~f+LhJmIVYeWQ$>l$EZ+8LCEgM( zK$m@1OCx(BOGnc46HT^@bX8ck;c7D@HT(y)ab`(lVjcN?hm=VMeYwZ?d$7}1v$p2T zUDeLh;JfSfdHD&@prvM1Q|(XRkuiLhawtc`Eh&kEaq#k{>vPvhZH9yS}AU)bR5D zI@#uOYS(dDP}kf*u2I&#Tlf^m1A}&1aoS7|W%}6%JpPp(yqaJE&EVe44iQiczj5P@2wN1>}BAMP^mAXJ{BbnG0HR^;_@K)ebkDhmHmVe z@CsnSh&a)yq`0+G3=TpkG|I!p^5ug{ah=q)b=U_#?Q|ENPfo?^v8gl(moCChusdg# z;c6rqKUmdSE>brao4y%g*l@I#c|8ZMqO`K@D|Kg?JQ{9iS->8rR6#H#+mf4z@gDt0 zO;I#&Z>>qe5jW9@Vm*+f9uq$@9eL2;E?wenSHz%D6v%b2qX;c85~hVMUcs`}-&KgF zm!y|Q@4TQGbWvbj>Q-=Z#)pu}(x|gf*5EY`Iz@9Dmd9OW3}L)0O&M~X`AXP(*fhIG z`KdBvmrCi2hkZJ&lEVBDi`iEN%Y4(iOnwe)H}1XN1WWTaEuqG}gyer?U73ey?bSn4 zUHe7mE)by{d6`w?T@)_Icl-$Y(1!%R%yQgs{7>0*gOpTQJ9jRr=j`jnlONZlL@VB7 zm`CoIw$+Eyr_4RdL?b+Js#d(kvaqyF=%4E2D${fnX8y>=rlCEFdto{euB}gl*Aok{$D`~u zjLDEjpBfM4IMX+IwV^m+G8N{0652F|{R?_Kr1P!P@MHr~y2|X+ohF~+jojZ*N=V&H zHnW%=HZyfao%1jHXzN+JRVSLP5DMrEl~JGL&F@K=d%MQPZ26RrHo6ws?LM@eXU&_t zj83yRWtk-9l+j4iw+$(`oj+C+BG9oFh~vDro>AF39XZZyDmm9MUv}~tJ({0i-TW^A zT~okvUqxfQd_ikqpa6UTW!Vb>Ym+ z0TBkyi%vMYzvIF02vCx9RaqExx2f<2nTs=$uYS3{?dH<(X`Q0clhfSd>QnJys$5BH z#P+TTcZ6_xu5N{tmGCsX@#M+N*rV@`j9yxhW-?*vhb?G5pDAFk%Tze-ji4+YA8!3D zNzIdjxl@I9T6s@9?&%zlrCb%q?*EfYmXuoE@cwI+)3s-^%ujbHx!<~}%4w@@PtGjb z=DH|{GYj7oP#ccCp^NcHqfLIm-QA64(USQ(byi?z^56!AOsjkjI<0NzS%%|*5zIV4T$3q3Bs7Pg+4+-h5s8u7h&5Lb!)uG0 zn*#KoC{$IjmIzdl7@gf~m_MDXM~I5d#&l$zIJb|&66v+`+jI}+v;w9Gt@W!$kQA?N zT~QdV6Adq`tO=;J5klfA%a)OY9|z#1EmK+5ol^#>iXfYh20~L!Fj&4R1TI z8JX3{-dJi<4qS+^I{%7;wG^N=y(?B*2vF57AuxN7wh%p`{a zxsr?2bjB4H33FH9LNfP*s#a-K%fuf~WL>d=OC0iTBXkEoP9I9{P_^`9gq`Z1 z@o-}%>&d`{jcNN5>sIHqGKIZ!<=_0as}REXg`$08!Lm8f;x1Zi%KSO10Zx$d>P= z-v2@`m~`vhej_pKx)s!pDlW6ZyG`=+m*l1sr}bOZ8-AY$-nMgrwl0y!NfF(=i88dz zj&S*ci7;b)HIq+!>qMPlxPF7q%pocer`8hHt)|kDRYlC4Ypm{p=Q-#PYVOcC%tmoj zG1OQx=Z+Pzt}OyydISh`lL>8QP?R`IQQANz8yQS-3)EH;blBIS{5*6YvHk?{7CYfJ z%7>JbM#y?NA1s0c-1VjmIp#TZ>%Q9^9{DYQ53~t;;+o$MSIlaW8-xfyEL1$=19H@? z8sWKMv{98?q#V>o#*!Tbu`y5Ba0|3N$xM9tuKT-2gQ%82B6kV_Kd%cJePYO5K9!My zc!yb=O4gtHwSs>OW3!6u^z(8`tx`#2@^@L%%qYlg5xn&(R?f6Ft>?yzdYaoBB*(<2ln4sZV}(sxC`kf#s=8f0wp#HYVW6?8gyU6po zh$BFhftCd59E0K_kVd?ATl0gzS;uJuh0o_Y#v}Kf1dvY&0Blj9yLD^Q`>Ls-p$~+p zl^gEap)AeV#3>qjwf)H{%6fxB_5rg0d)AWm$r5*+Po(WTGvgo&!kfav!Whc$fnqL* zdmn1rTD z*z4|w1%*VwUwhhAehPTOI;!irzrj^L6QNYEoco`zz^5%zS$bz#SW4@wUZ*=yxRsq%@k64MRQQQomFlNlA-(6DTX{wm9LJ4?@MZ7-A0S_!nu#4NX-`R>RCCjNScF6`nO+u zgP@#LZ7ViGp_=uKdSH`{CYsg5kYL$3vbPsP3Bz`gE7(1KE(9g zWNH(Es)Y6{Mn@P8m&9{0&Yr?a0q6Mb5_-Utvu^8IVg)d4oxnfrWk1nvIW)Eiw&A~k z$yD_gSvhfj$O#mgYT_(^AOBPL{i9s!(aH4QyK&CBP;_vV_y~5#LR;(sxx*Ypy*U*X zBD&S12*nCND4k8cO@CJ5ltP`Q}UP5Q65l2J^6`|3n24i?6PiT}c4B^q^++?8S&C zc(mg{Dx)G_7X8%R03E~6M-Qpr z$fK_2t)~8>qwX_HSF1-iI6`Y%oZ;*-qQyQ%^y~t0u3AD<51iR|sk;`mLqN6+GOFqW zTHdT3HXfc{bK!G5&`ba}C7adOOrSVXZ@c^YGU7V>xh~_9IJ!6>ZoWvM;sc<8ajQ>5l9R`m7o9rKOSPd9z>e|N;--VRH{|O zK(tNU29M7M&#Rkc-&>rQsMzm759SCk7Q)w!qaabH%35aunF9IQ_$ur_$EcF8zIXo8 ztNm@~=5Ik$eZMhS&v|%(_c=D)Q0Umy2eX8m*HqJRq4{9;^5Kd|T~08a;U&ztIw z>RmjwNM^LlAm5nPn(Z!nC?wm{0ceG*x`7oUS)0tCKH(sFW747*+wBVP0FTnA0jSf z+akQG%Qa*6w%9+g-EOv|_n6ik%oa<>kSkm0f0wlH?JQI_y<(!p;_#JGA@iwF;r?(b zrj%=)@YY4gwZl01jV!ki_hZp#HFj^k8S|w6cnQCx9rXLejN-pdJVHRDiZJ?MO&j9+D`DrG6eijy*NmKM@ok|61;ql%gi_p( z%!@)v;~D%0jONO@VuyUR z|Li)+b#CFC%o{MxSLg=S!-z{wCNUW~`i_sUs5uSQG9gW8-Dk$<2_~-cHQ2P&HKCbY zx13N~ZOMHxCu4tvwN|EPZ*k5M?hP|GV{iV4Qq|*ZG|d*<^JRMf*b~WmOK5e(*^=Y^ zj?A%+{mW)o_xKqxzRZ%U>L8(i;A>=J1MK`>y$ae6DN~mRj4+hMNm!sz?=tx@Lvi{d z4D{yrI^TXnbg)-WVR8F0U2UV^@DvPnzV={YfArP$ws&^bh964Tb+>fh+ldS(2#aa0 zCuJ^oyPzM2dUQT1Ob;G0jNfAH&_6)q1V=r~^-M5#G_uQ;6Wt7} zoG~tj!WJz}e<#4}$%*f2H0kzo9qwfIhB!Z!l$R3>Y^^_3P|fn@IW}&{3Ga)UYP1D9 z{h8!sP#2h?EU|JY_a0BkP#4$KMS0UQz_i}EOIeXj+veQnB84`~&{i9B(Ga-cFbv+t7I}tEF9f#+WJ3?kk;}|N9DUV`yJrx>I_tDEn%p zk(Yr}l3POCbA=^pkaWu8VHQ++T;4WH-vB%Fjf~;&EoqXj+IO4Vyp4cxrr-+i(f!wh z3x8GBahZq3nx2YGTle?9vSe^bnG3{q;v&kEB=f^vDVhQ^az?6Y|;)Rr!-+-vrF14(2^%rFQ{~up)Tcf4-&GdQmZhFIs|aXwC*kSiZAb{MC9h=udkxZ0D8v^Giemes7Y@>m=AR zBiJ-rq!S(ZGR!w^q3HOF7&5PA3D+CBRdy-HG%(g_C6FSi-a-iDy2A$AF|>>bNIGn=-S8g&YrP-*q^!AR?sLvQdtcY@ zqShRt4J2YDD!zNC{F`|F zH!%XeaEv+Wy*`RoK*Y<=?~3`3_LRhmUxXO9nssGz5wo?G^fD#0xH0qnL-p)h2{ez0 znHpmvrzvI}$Mj6~36todk2%`?Q=A>eLoLc;>{ZxRj0hXNidSX@QG!kNi*nF73Loj~ z&B6k-g_7|ow1DjkjRmcqA-sS&OV`FFVP#%W36eK?JrJYx2>BnoQof0uO3@j_RLLKP ztwa^y{Y;M`75XTh8F&7SmB(pZDS!bzhQX12PGYp4-jVFR3jCgnLAgg)keL{WtxsiF z3672Yxv`|I*;PKrgv;b)ZgGwZpzGF4>E$Ygtv*6V8;r)5ap|he>rS8`u><2wz##fM zm#A<|C?;At>KD}l5~k2A4(g=Va z&7mf1Z@qoz7!#Nxg-9qRtTYSeVxi>Z;raa2zH}UZzKq-b zl(vnKk2T;7-I?vy?0;{}7MWmBPTILRL9ANq6XqWkqMa)kSMten@ za4MEfeRmM7Dm+p@waZ|}?HA_MWBQr$cb$r|mM((Mps%Bv9!@Z(Ujn34!2zN68OtFd zg51K^oh8Ech1!O4IQ?7VVhfB)bP3GeRUBe7MVe)+H+bwrg)Cc*>x)$N_5~A4G6`~4 z<#EY0DHos#pjo+kBcVh{DE};b3qF?snhEK{B2#}+f@S>WSb&>Mn!tb(UhZ#EpirRs z@^ok2iL+Il;Z_@AQJ}t#nJZAPK(vqmoJUR-Dq}YJguz>Lz}Rq`8(fQa=7rZ+_t7v^ z=;=`RAaBs*g+7|^lTo*@{73EM;L$q2_o1*Ry`Zv&zeCZ7;&@KtXPl)w8Y-DMd6Mem zP}H#wD`a`qMM!C~B)?XYE7AS#AVB_ShsP<2AoOuE!+-43!0V78c;- z=k;#qv1yK;_MVoO?i{1ZfeKD>KdK2CFv97{kp2v#Bex26d6Ow$wkFVeEpzsC`FaWki=d=XN=PE_5D z_iD|?8i(=n@dXl$&CgE|7!ZfQAl76Z1~KIoJNXndks;bbDK_>D!IL;kPuWz?5A^wA z5*$Q@W($IjWCDb%Y%-EESki5ANG;CE@%hehgwAE)!{Ncd=#YQm2iqyP{712EsZXWIM^;5 zHno8%c`3owddo|F)vtItt4Li0W91RxQTW08MMv5Dj&j-TqelqWEy8c4*%dV?UPBPk zi~l#*1lO8Y3+iZ-;GGxEJdqkAUvAJB>%E&8Y_3lRBMJ!*-v67V;=RXayfM7ir(|9& zc6nHNIIbuu&6-tUkhVc-{D2c`?E8$kTkLdP@oK18Qn3z(tf|SeF<1YRrtjtL@E)r4 zqx$HVo=gFECpUX(9R<9wzsN3#7Ch8!vMl39u4ynogXa3=__PcGMk*ou9F(~7Wo<;* zOZgvy@iOsBb6|7khm*Zm3bbR4-10<|mRj-hs1qrW{TF%yFds)Yt|ANbKnq4o&$3|R zVik8DBRH=on#w`y2*c2%dW=zTP9V<{>>V;U!EW_m4NE7@2VEDL+JwR^xyLwfKby;z z!}5&E0}`-)zh}MOx|T@4akrg3R78dhrt|@I-o-FQ08JbrTx)TYPK{v-^>! z$MXA=gbbM#p7jD9Lha2{wr=Uq+yXJCFJ01Y>Qvn=G3WNxfq+r3M=04pMh3Uv-06DIBq7Ci9FS5f<(D8HAIGxW=u3YExX-ir(jR_>Hy6;AtQKAu9DGx6t{u zt(|Ur{IpD49u>2y?CbKO)k3OUkgyP^s-Z?3Ed7IrfMhmAx_s4yoRMWPPs^<;O0FqR zhDXFZ$)<-XZ}0AQ5~Rbbpq$GxDiRt*8K-MnZe ziLwv{G&t1JBEm&bp3xpLXn_?-uzYf4L#$o?_q#g>FUu1oeUC|e14d=Fg&Os9dk&8} zn~70|ZjsI^s)!zI8Oi*XVoF;2ye*jfjv3#(iTYrji~jWqW}2yKgb zIi<|@>MA9hZimcQtipD)G38gvg^Yuv7%0{hR^?>W&rwlT z@w{m9G2FrL-7F%eV?MaqEp!5eiFj64Vgv(9rSc~g|L^4{%EKe&8HaaI(6S?OP*Ez? z>vj{A7G_y8297j+FAFSFvsjLf6eX4PZJA_xwAkL#L6S`i9xY$+ggNfKRsVLy7<>Ce z7R3DCKOLp=@|Wdm>%P21vwgMhu{yxiv{!F0pmTpaDN8()hayUf$l#JY-jeE43X4`wbOEXE=&WmV72+vq|Ee zGr&;dWl_)!qYN=~B6lH!EBV98e_cYI!?vw_j z@{dQm!p&aIf42AY^f>bp=~CEoO~SVn!h^MxgW@vVKZby;Zby)M{Bh7V(~d1x{95UJ zuN@Id%5}W!JnFb{Y;K{@H{j}a%tn1j*09_b>cV(ZF=69rWzZgD{`p`EI!99Hlm-%1 zDqnNzT#-K98jl6jq^SQ!4;Prjdl@ulHu-dtk7!mKrz>&bxWfFIJS`xkMR%9eMadRE zZllZ}7jldE?u=k?ndx(+(u#{J_Iqf55Ix^*4dn9u{R(Qy+xX!*==XMnn<`!%`(3?x zaeXNJuU|M@A01;7K*lZ`H!Nh(CiLTUh~MY#4&;HrDs{rUL==?ikV*t-Rvb#g)~auu zH~!Kr`yJ~Wv;uAO7{pTSzR&M&VfUBk6P?QJjj=osEOA6vpo96WXyD=2!8h{$ULdvp zh)Dl@F#v+{JT%A8A4A9cWTX7 zrc7#Ir%uRir+Og+tW#%;=+6--_%c`)k(0CaS?r;GkBJa9;Jt?ECk`?^1wb9em~Xv( zlJ}bDzZ^-G6=#!`Soc=ETon{UF6WoMqlKcbIwkK>%Di*{3B;bm6D^@xr|Z#@h;NiP z=V-I*4hxCpp-)cRy{~dj4G7Y-rs#G=vjPM$7T?n$K2Qo(7&LW`WQktxZb{(D9BpPe zI9;Ez#88V$Q}x-+RcC4V9>4jjSBEp`l>Xs$9Q($Dm{Ur{N(w3)%JvQ6Or%U!XySW{ z@KJ<083?vKnP8JF(qehTnljsZBbd+p-ozw|8#gU0%N#T%cft68O^5Rz2`HV-<|6!!lO*hCR^JEc3xem zh}Sg;nr)F{nTQEC&A9v!ZPyF8af+g*_DY`H#%5$JDhVbjA_!{h>p8Im&R|FWXAACj zU4k4jZN90>a|}6yHGa#|tGXX|FR?NDm~>k{;N9#mspv~YYo#yke~`Eyk6rl$+%TCI z9*3+u7}GE-Yub$A!`QaNSg9mz)Y$1{6rVeva2khHA@vCEu%-H}Wi{Op8eADpV{-b9 z!v2ku-T6Ayn<3%9Q@o@jS;*E_)M6xY`AeB)OAj{+76|ap*a;4ftq=q!qc}p=Vp?h& z>JS4KWR&CzG*reaGwI`8k>JikD|tjsrw<|_s13oi??Ke@J5^tc~8`Q`rLV|KCMQ>*sZHDzGH z8aFM!pf!>?B5ajlGJrX%ai^l?a(MYxjnnX3C+N|;1Ldu^`j$P+|dM z;p3mHt^Z*+fVl-~X;*s2TTnn$xaX#)uU(L+n!G4rl{Z_nB?x-_8hm_)8!CRM=3rjR zt?EA=u_s!8G|Tj&=K{s|!rd>H`u>mg{Z#uk^~ctgRz`ikzl#JkK~hhK*MHK7$-(v7 zKYZTPfA!L(|4%=`oQr?*v|G@0P}?9loU*sZ$H&zf5lA6Ea10ktumBT5noG!jHfJpk zd9#QDt#Ph)B|Md}yu5t<?hqs8o*eo4~gVk$9YH9x0?Ow>0#68oruFX$HafL*P|mI zkWR;=M#++(i&;*YJdyPFhS&h}-@2w4l$(7LkM;=LKap^`lBkgfj8T5yUOAuQovvMR zZv0@c$WV1EVi9uQgk)vy?anquZ>O=?oUs-$2zwq2={J1H8-uO+> zwiwrQ|M{ZI$_A>cX*e#oUhwen^bRzrk4;W>@JU|N);Wc@)$Nc|lCLJN{a5PuS?IJx zTe%QJdo2|sRD)`5x1?dV(f1M84zI_DAa72Ua=qWH!OoE5cj`I9;r36SE;+|BpT3(~ z7zSWdM+gXhmln*Dwgu##m@4?4-n`S!f2x6A997WgqSqLbz8i0Q8H*Zim!L0g|ews6B@nr_t+**K#y_V1&5X_Q^i=P^C1>J z{o_Kr$n3Y`nL<}2DO~u3=mD|b>!$zCGEMO#+a-V#W~U${&?!2vDyP8};(>me@D+8VG+)>uzkuuodpIAs>+c!A7i znNOdX+K>AyX^vR}9L)mB;znw)}XjQz3zFSW+=gap{fMtUN*nm*pMv-EZHGVHv|=Bd8J(ck!#kBc~(R38U9L`!B^GezB#`HDyX87E2G zFGv6E>-GFY0qGaV@CkV&`3sZ&K+urJTe^l@m znZFZ?>AJtW`4>M2Se3L}BUz?vz0rU|0r%|L@E60)eqlOGt?Y1XHXr}32qGi*~nqO9iP|J8#(~m4eW}^$CN5@S0LJ;IOovkQf}*eLi#8j08NuoN zy9?hpb>U#PYg3I9fF^Ux%Y&DeUI5NrP0zc(QzGRY<-5PC5F;^e``?`Leadvk7Z&7^ zuugZ|M3ovSKOFLzK#sMSpJUo#_B)frm6D*{um0`HVzL($^m{^=Z7NM#8)q}ICi*Pr z2a-}cI;8ccuP8h?HC7j9TJAk%S$dM#bUfDjpViy_>h8F^84!Bf;V1(lhNQv&!me7s^q*`nv*g=;wMD$Xv_E`O}F-ni9FHu3)B$2g`OkATG%wIX?=SB6%bI5uw#5gl0 z|G`$9&ZZ3^$DW*q&HX=r(#O~{J)6S|Hu3NXn~9;4&FITs@!`u$qehzOpWZ#EwzkC&x3qv+ z-2>n!m2KCiS`f!ke^k50YV?KbFH@ypZElS`AA%G&xoo3sIK^|H&NVq>0#D}VY1*V5 z9J-wTZ~0?&{B4`Ujg5L;KJ{mRpD_w00-QkCIt6q&Dx{-FUBx+4e^OCz_7&uxfnpRL z&k=&!9Iqs!$x7@ANSy$d?EUBdX0FvdwSF5 zhJ)n|zdFI609rKnU%r&?e($+bxQvUmI8F6Pq#JkM^vGOG$nm9p(`6h}_{@*S z<4DLrtvDOvk0Tp|GU#H(RtpzqWR{meFk~np)QYh>!{*Y+0sIoZ!iby>F=B#4M9hHO z<4C2arx%uwH5c{+BC~QMapj#2HpxU7*s8WLp_6o{vN(HtUq?6pP?CLjR1JEpXH`1I zyPYWe6`cp82=OwBE%$ZdBnj9AH-Pk^a4exOPSC%SCkg`pGO(o|mY-_k7-5<1ldjui z_J&XvQ@5y>7f(3}hXZt3sp1d*6b?EzZcMYZoh%;k>Ssz-$Is#moo}-Ibsf%f_kFaC zPfqayKAi4a$Sddw;k5d7p-wYZWnyEJ?p^;K{7RMcUa#!8x}W?ltDI$$% zcBKU3E`uhoG_UgB^-Cd#wj;(fWxVLk*`3N0fR=clL6W`md-kdS&hM5Nd0Wm~*`i}2 zt1dd2X?8eWkgtX~>*+r+bAG2Tc8?nKLR`H> z%VJ@=+`|a3uL>jp(F3-U_jyhG4{#N`TDo`vT>i0RGt2Uf88WuR@m-aCA|gL9_m}!M zhxNm!WO9~ww)XDc$?_ln!O5a$)e$K&U|pLQlW;k>8^*rAJX*s&t=v3cY)Q>bT^}kz zczg)<_ZNu5H3qom?Db#4C!lbgTv!M;CkM3P82t}(z)fmmWreluKCn4~i~AKmS%lYJ zwL1JNmQeojnHRtsdigtfCOb9BFd{5&&h3BNfY*CrT!axzj5Ucc# zoOA4ykScyr!*{;^^DN-?(V|n@(UG;=UR(5iwgj(wvT}(GU`XwdmD4FB=|GzY*vHLq zsYTszSr`C07bJ(8W{Q9MSKCxOEK30EZOq!(;#AMIzpqn$50Qp=Pxz!I)YAD<`g1bj zq+0^S59TzJEjrug`BE{K>UWZk(eKW4j<1Wg;aaR+Q)PkQu7B9pHn;);a~8l_1VR54 zYef-Y6j|qLWum<*?=NK2#b5(6UKTWpyvk_psJE&Fib5=*1`;#(jJ<+gSR?f-*FL?_gp4mv4P4F&1?q&%f=fY$;D?SA6ob*e@)le?JfeSoP=94) zz?P>H{giHB!}XynXK=C@G=6+B<9c-%h(Es2lJ2$06vGcE;CsXFxO?gN4^9n2vl|cE z@T+a!lEyHQQ$O!;v}P3ukLhmE4wKss zFG&4&aR9Z_`LC+b<*U1gr2P@jzf%+;i5{+`UEE;>Va+?MLQm6FF<8JnlLstY5Z0PA zxwO>V=Ht$!d6gY$O#!5}`C18#o3?&;uRt!yKYT*muth&3g$z0rHKbWQU1RMV z{;wW*aD_);renw0_wy1`Z$7y+uTIsAh33B#KWO>KxRs*o^Nf+`P^__+zrDWT_)G%@ zGQoV#TS8F;-~){KMoshL(7*GegB!9?j67A}&%Xk83q=4Zj!Equw|p7Rb(}Wp9RgV4 zV{>x@>+AIOS-Q+X^ooRG&$y23O~Ro0rJ)#@AkLte1%gBMZR-Wdj|VC3>Q?Y~W;O5r zRS)=W4L^fzHN>Xp<;FU>ZcVm#n-o${4l8=%*}o#& z>SOAsr@nFf`$layS$#^yeDt(w&VDA+(;MzOJW+2GsHeE;&%A=uw&|Wf&m!wokSDn2 zsoz*BgyBg`t_~Me9(5BfW4^x&IRjhp_4HRj$b=VDu`l%2ss=E3bK~L;0v16KJon$k zC(7UlV}_GZqXRX*_#q9z#S{x2`lIR=1wz15qYDC(-8C=HiY>UF(%)KGiJZPZW!u5Y z-GN_DM~C#k{#b=!OKNsDz?n5SH@{YPJo{mO|Cj5YYN1}Z@!=5%2ZwIGTKPWg!~kbc z*q|ZC{GCg^``E$)Dr>Kx-SHfWf+C~GUO%N7ukiVPYeq?lbx5dUhV@LL0fF_y2Q~0a)JXk)|qbK81jEIf<8|szO`&%y0Z9tFqxsmuj?~3~E_AgtwD{IbH z`K0BS#Mr~DQTOW7%2I05Kt41hBS zp^R)?J7+U!_DG74hhJ--f&JGzQ}X6G#q)TZ`pEz8X12kPnv~OcbN2Vle_0SvL{833 z4rYBiKc1@e4t}_KxZ+K7p@?452OUMwh1i(tQoNLWn0%1`^hp%R^E&e2;KJeC2K0GE zLC<1+Z`U%#-Tfu+*CgS0y?7v7WMzdQFi_UT-5oK!2_(&wez$$bbQx;LXX59xroY@4 z_Ow{vX8UXsRJOV$zN~DOCJQ+|JNwsgc>w~ng`ahqFI+8#SkHacTO0*4_V2%6I&e!! z3=h0vvbMD@&~pv1lQIQ~&`$fE486U@1R?S&wxYftv#XAH>PqC8fIvPw{BgQfmB#YuTTDF{JHyC7;;I4>di;9W?m)x9+eIp~`TMCX~ z?V{r1?d^BbYeI6G-5Y}`EGdJj7M=MqRKlG{YkgNMn3B*EEfbJ!#Gx+;vKYEHRCI(+ zf6?yGx1>~!YjPSjt2X_uhOZUv)NZ!eZx0@^-}Ld>JP!{q*9DPgK9i zz$;qENJ0h)gL~U0Tq}^4=L)^aHz?&5e{1Gd3YADvw3UvMqMd8>d}2z3*lpT*RK@wG zR6D+?<8%nOE@NUg{$pss`y}P$y>WJy#D)N3{wlh- z`vhs_G`ZDY9ykQ991aNpjG{wPAZxek>UQ3lwT=W~RnWz9+QRqCZJ)U9pAfTvcPOXt z#SKWNdOpanWXU1r2;|K1gXWsbjyHSm@5#XCcZB4+!=AHyI$Bm^zwi{)(Dn8&`ERGe z_^rf+alqgD-PeWM@H@^)p#m!`_DUbWvXd=X-iWeWPPE}V<5UvKZAYlp(V zAZPOW!sfP5@={i8xvR?le$U}fF#CWonCD7{b6_u3S<`)|5N5sKXo~N5NZk<6wVrUB z5{#0)l`u$rS^RLCbHw$4%=#%~qb2G{g}Hp;m*<@Y3Bb#!|G0dI@AT(NHdEN$Us3Xi zxi9ubu@K+jz#GdiQ?@@_A9cCRI?rGV`TfQj6}u2Cf37svKX%BhEN$t|)%DV}(MXES zx|fNOWkmbq5JU$R7Z*WaHj+lGwzdxJX5=r(O(%Qp zf%^bJcYiY!6&~?E@w)!)O#3xXnn4Wsp88vL+fzQ?_mkYO(@1ZZ=A7AoBAaO`54UjNr zO{{M;CW|3zRKiX{l|Fk8b5%FmCj66=@?!zt@yRK(Xt3yN2@Tp@f|Z*TAgsN8#p#}+ z%VKT;p)Y*HP%)qWn=4K%FOT})VZN54Vp|omFtGu{Z517N{1&%^&Hh;9{IR7G`-X## zvZmVF`WnYc5+iZ%ppgpodi&*pUAy4D8@DR!leZzEA+yz3{|a^)r^N z-^)z|DFbn%TXR*WOvM^mn;Cu&YK8E_-T0r+fD%$3OPZ`ZDoXt|%M5u# zQPbAa&E>v(+o;aNxx?HyPf<)s53ZC7T+NbZ+^4bJB0SQ0<)0BFRa+yiVrT1bzMW1C zy12NFjgQOM$4_sEGxm&QqUA7;5xJsTdJim*(f(~KCQZXVY8*@ac! zx?WBqhbe~Gh~RyOV2Cv+tsNmR&0wm%%I~`2s$WfDF|q{o!Y2T=TOKS{vBO}lT-V7z zq`)Fmqj|@KO`!ZE)kcQcbT0gn%{vkhE$~tWVKzFrCG%~s;HE!Q9Q|_(oUig><*e7_ zKSmtZ+r{O3^oQTecU)M+rU{8*5G5mz#E^Hd)+v`g6YTWyjZYswOED$S`ZO)xQlmZ) zC8QR9^_P0`Qi=CDCRF-lv3idE%&WEPG@JX58#jDSXh7atSV<_EAR0?I>GDN}l9DEp z7(70bCP`hBBc+Opjm5Y`IxbPgMLgC(FmOVt)SDDKa~N6YwII4<8OxxnI{;J|I~P0X6*R|Owh`vjK0Yx z+a!vmDy(_^oq#8uEXbdc#fOaUvWx4EMc<(b@fMZx-HGKxxU1jg&2XFJ@qr)Ie#V}e zzDo7FwZzngDozPm((>WWTosUJ(!zM)1Sap4K0_f4#1lb@VC)Smahbf(3M;&nCsRl* z8sD9Co_l($@LvK#U9)UDqird!(K5(ajsQJ11e+d7?cBsZrJN)b0oX=RmLsuPZrlO$ zn#Q&qtuy6fZ0~l>@?l0?8K*0%y7VV{aq7i@?yE+9BFw;r7KXV zb8=;Ytd&ynmZaM-du>ypF2W8`sC(@qc4c3Gzv;L9%Y8HU{s~~SQ#=pN6ul!6e39dI zN{fp}LIcI|wt7r~APb~!J!EvCk{rClm+WkBJEayj5XY8MD7x$zd59V#lm$a#ZrN{M zS*o0oF#?)YaDBIghqq8Pg5GCE{BcG82VO!YT7gCw%JRC&ll@b>^hwpYeA`>huoBz~ z{VrY(G}@vt%7JwTnfXh2ly-m%qbx+l=8U35m10ovV=F}nZ5U>OFmP=Uzkcy(8 zCJe^zl%WuW5-}lYqae_5_&hVm$GbT0iCJ|D$uK3{bVg0wsq}@^{}`}{x?H~eG=!y5 zK@p`pzeAsaWXsg2^;x}6u%N2mGudA>ol548cUXnt8-?SYG+_{Fh^eqOH#_d2bh@B2 zv^LHI9+ZrM73duduaC zm$p#tD|*OAE;5`{LAQio8W$&=Ta}wWUVGL$RJk=KA#KfLJ6w2ujTm2$G1Kms=me6HKX`_!M`9z}P% zz(5yPdnK4hStSlbI(1BnHXH(-WK0?+vX)+a0wSedl5G}Mmfot=a)&`^)N1+1Cvvqf z#;_*dg_>BC3|2i0>Hbgk?>~r3Vi_@eU+;hHHWjf5b)ph77KRe7qIW**F$fn0rR}kc zFe4R$9v&>|`ncl#V5~_QN=AXvK6P_~5T!!&qO39XCw%0#@!+PYfHN99Mpnq@sX9m- zK^q3qBZI!oQ|pw(OH4+q!swz6L!YP(H~BarT>2r1BtVrDAGUh!o9~Ss2z`c^ zf|J7^kp@LHAAmMH4psnJv>X{p&m5t;V5IeeR;fUtb$*bPwe(lC5*G})&dfqMKO^+N zU5E??mNj7yPLQ0nza6)YB(4&Y7j$NHt!qhwG=mu5O<3DHFhme{@=G(y6j}omZxjkU zQ}E6W4Q}G+=AAtLLf$zuUXlbXZuTdmvH#g&c7Z3)5Sq54uhYvisCWb|tpfsS#E99E z0rm1l#t?tZngz<1i^yHY*a?#?K_8A}Si+YXsHtxF*ek=YtA)#PpuXrvw4bOgWIgn+=4b&0=6;@nPa2#U=DWUCa zJ(FTyv^*Jsud5TaL>sgdLM3w0u%z$Y_W8O9W%DsIUAJ_aFll;}fGq&y&*KR*RTDI( ziGsvWgwr4yq^VxwQ8FPIqKKhHl3^JUhUJ^^RKesuf*_u4yKI^;@YQ6Kn#@_Vi^>yp z&w>SoT?p4KW76)>Wide}$Y5=QNutS|VCl1;{}}J4xLtG+gls~3Ch2YydMJrT%)rhC z)qaN?AoUU%e4r@gM!}7R5=`AqRwPR$`?Z6cJu!KJ42FUfD7WX3b5sT3H`;NmAbtw{ zC($$!2;%?9q`xp!kpwBPH9y<7dpv{BV^4|fzz-}m_`;pQQ$|Gb*`HgjRuF8nlgjZw z%&w|T6vmyIRag^lq8cu!ZN&%F*I>Q zl)j?NSdS6XQsm+AkcC9=FeIl#QA5xe4g;~^saP~=eB~hz&%%0-W2xna8QvlJ<0E+3 zBe~U+TLPJ{Uf5FHAQ)^1)q@<%Aw~A6rN4LN5aB4pKJ5eqD7cYik9n;zIncCOL#cac z=%1ljGa$SQzyJ5VlRIq|nWoB{2ZMH{U;M~;!cD*^4S5-a4NX)}Rzap=MOM>dS)0ke zC!irJGhod^r^TX6VrEcg(zeUGTvqC`JB5vVkY;=te+Y_a=5e<6u~Plx8>gCEN{bkp z^2w>0EcJTeQXA%2Rr37b!ZkUd@+C6FWl98iY?Bd9A=^K3HWVU7^Br#lLzET zyjPPnlw#_(A7KMO5Cn`>gwbxw*(P%(a^xi8oun-Oa0cmYX^4M3bGTGNEdMv29)lYu zQ~EFySejkF3tjq;uz*6BO87I`iC6+CwlCRBWH^il=^sJKZxuBu#1lyr?6{h4mWt<& z2GoU*)MjWG-?KU|eIC#s!OlNu4X6q*HUJvo15@V5gPuYoYP~q|ssxWr_JZj{@HKkxn7;6;;qBPrjLq((*F9mYkel|-I#uiX{c8FRS5`s= zo>$}2CobP-wZ(38^@|$8Aa!3=b?#0a}xRyH{vX>bsCjxA;+2mj>pFVuT+q_wO*6G{0 z^2Nx*Tb{5F&&}1bn;d^xsoZN>owo?HxHkRO z33ufXX7s4U$>Y-2U&c;m9ejnsu{1}tHF{}%d1ml^8Rk1q;7+N1-=pDU%pFSnZS+5I zZc-mTy*x&t{2g#$6E4M?oZ0%mY^siT5U*`*q7o&2JRzY8DV~lICtu&1@t?_}n5ZxH zN>RC2gt_gI;6XzzK6|PiiJqbRBgM!6uLbyk^-36fc}QM{-*@S(!pP#G#b6~@7{wtW z=#?a)ZpEq9}XAf67a~xW7!(+Fb>;e>Hs~D#2XPG?@UI$IO zCCv)wzB-Q4sYfx~4R)Uj2)vr6;@m$jsztUR_eQ69sWaQ3l5=d97pf_Jfz$fn2T$~9 z_q$_=Ul@P$dGz;~l(TImEBYqKP2QFkEE43CxVW{w%_!opE5&^gQrB(W3p_c(JIQu> zFd}VELb%o_I?f;4nSrf+@vRx;mc+v;-_qh5^|^t|D?#x)|uh=oX@UBeMWwnT-H4)cqPK{#3X2< zADwjM-TmgG4n?V9jRx02v9O}#A|%xhJg?}Rvtr$!K@6lgC0mpUUfwUn z_Swb`4_4X?w4UW_ocx?T!Q)8w?8pfVZYx!Z9cmr8J-7VIS-C<=_D`YtOetTLp0&iQ z>Q8E?YJ%6JC%T{BtRPOraFCD6@h&%NL%uTyndMxP zWFbtuHy>&XEiHoHJpibf{T88Q?+N2_n0GD=Wm4~ z;wp5xQA(5xYbgxIl>R|*KtbTT%R5)^m~xXi_KK(K^f~4Dsvf7u2o>ZcS==-pjGYUn zD3xghu;@1PmmDClQBmbqXMdOdMUpRt%_TU7C%9E+q7OIA6^mPmF~RO{Pm1~d$_%^@ zdW+>FPOJA?sW#*yb{_0vF2UAlm(*}jc>zM=riG-qHEO`5U;sC*9(DqXOzC`ga3xA zD6h;_f=_d>@Md;qWXd*|e?3Q7>(iVXBwlo$ASgL4g(vehtD+j4wAyQ*FFjN9wPDw| z*%@EAB>H}@?w1x~eywu+?oqGnHSLT$8^K9F?9DHI)&Z*lgAsZT$c)2YaI#*jRU#+x z_U5@E+kQAYoA}I!txA0_yE*C^4@A#s#=@%yL;fY{q4q9;zNpPAq(*A{NMnUE&%;xb z@jJhSR3Gs?uK^7^87?gp?ZWW~#((?xXs$n$fdNa_-e8Tf=vff^R6@$qZ%fzREL~~e z?7pQIcVm8QdWH}w1T(5l6AKdF`V50V*}1Y|CF7UX{z<2-Q!vlNuQ;r@12p9^tnYfW zOeF6ex2$kbAN)SKzo4FMmGr%J9Wj%pqt*IiSW+%CK5uJ%*jn0CUiU%FtNg7>)BY5R zJaZcFk%QPYVT&QN@dU)!sV!?~@DBt(&tRr|4NOSXZoyE9kkK^_s$swn;Mo?oeCxRKJ{ zR4TLC5SEJ$>KM$oa^}Q@*r@(Jc;@fLK%IseidNVz+nk@Dq5A$9o%*8W$Q5#Uv~eEx zmTUA#K_D>2a-MFIUr|a+E`7!y>YlOLn*Dnwr8Q{HX{Ykt{95y!KnXLBM1(0it06jK zhwAajH<5EaYDJEiRa~fe`v>9~Iw9Xz%CEJ8V;WWVw-$Xl#4@O(S9)|^d&QZLej%Lo zpOGq8EQ_z~!POmAj*d&5Ze2=>C$n}!JPD^ zo6_vc7io7oBB>X;=_9XnFJXE65$#)NOa6lBB4mc&@HS}ude62Pa;J@R?u)E=!!?(3 z`ZmJPS(CLnKkw7dr1fb_n_-`hmU!t2!s_AcT*{2=0`YkT-v|6aLfl0nk!#7&9@o9dQ}p1kVbS8~@m)SYItrosulRiOy6lLGJm#KJ zyZ87m{2xXKz4h}fewV9gDo8j={>f~29WX6B@nWu6&Rg}TeY|}Tg_7#9xUQfrvYo<} zzmx96aaqkdi#lXd^>JHQnP^6kIA+iK0*;VQoKubp`@UHvLyNNo zs%5%3^BEOdK6$0%Tlb^g8zZCN>e7l+T!sa<^)s(D%D|DSdQL)o|ZzCrt)g(dPJHozv%VeA@LM`^+g*=cy&cV+aVHc zLAl{g%s-6r_T*>D*dq*(;1w5-$Ci=4zt3@Q9v3$q+pPe#h5$(tr zC4a_P!9p)90U3wq9RcO*A7D?DTT|835C4~-OKBZ~@eD(7V+G5=2dgJ2)>HA!?P;xGB;Ob9R54V@gYp{qNL-TYj}@^p=a> zPkt3)och1=zWX2R{)?Xy4W)#;2uTXjFe9Uc5X!7%WoGX}R;XlVWn@JX;v!^ZmXYji zS=l0cWPhL6=ljF=kNDn?$9>!Y!jm*9v@3Lo9 zt0+*V^`)}htP7wmqM zL7!G@F#G7iCvoe`aT1o|hv{U+;#WNv?ZyK3CwMfN#;d3+sn$3s-&WhGr--&|j@B!S z6B9e5Pp+{Q=pNWt$jx!ijZwiyJb%Swz$T87`AB+|oRB!Py+VFa@NJrnZ}Gju+s&s> zZZUqMct_8^Kf1xx>a{ZCIXn*!`zhg4-8Ne(UYT8X-4W4k zw_|@Ny%&1FX(P{)WD*$eVqX)Hu5ZOT(YSoVruVQ`>62KUt|9H_YuQ1SpLN9d^v&P8 zc1`J8PPe%6%J%bwD;<2Dw6y6B&t;XA)Hb}Hm&hvF<;v5j-5gn0*%S_Z)i(O{E5B4L zU(MsUyVCZl?MXlA;u^zz{z*~VhlfSa6H-gweb zDBJ1qQJtZ*^b9s9)EexvuX+4|?47&)&$Y=_ne3o_@TQU7MV?hgcyal(eNqlu5xsd% zmHgiqUXQKi{NrnK4G%NAHLp%SPHkTmPI&hzJ%9HLy}Hc*Le+~tc?HV025?(i{3&{_ zmLt4=GVMbke--VXk46X1l-Zsa6lCl(l4_aGvremBUFmM7jYv?fu_%?S+3FZJRx+Up z-idg>6~faSl&f?5(H=&=bkRSm)9J<>zWa==eJ!aJRYP43xi+}yRv6ifW5V;L?I@;bQ{7q%7TtS~cH5ECys%wK&VHe>(FRaGULk3D}GyY8rVC@GzY zmwj^X8Ft4i^{q5dJktNno4?AYS9M`nB&naN)qanQ!b*+P8_QX~iOUfdhRy-Wz{g3me!ThHs4R963*F8l0Lrvnfq$*wC#y`&Z@ccI4@kv=Vz+ zybl}7Rm&3pE#bq%Mw)t<_%n7D>R0>!|N7A`tOVsvag35uWS3Kjl+3mdUC#p?dI#lG&Gfwm-OA{FS%f< z1K-1D55-vFzV<0x`IA;vrQtPhtgIRD97z1Aeh%$~#&d%eRbv>&&T{tb3!CBU@Pei& zUgHIH0)|Ceq1&f;ZR|}O7L>P*(hgn2;XCS9R#z`H2o5ykVfBCE`d6yfm(Mr)zkipZ z7cjqTel+3u&|Eyng-BsySbu)uU{oLx3)w- zkB^Uk`RiWpLCR;=;g7fNYtMe+?R}V<`fE;;SRG7yo8}qp^%IW}=QMUaXtTDq7K0(Z zu>19x+OqjlU48v&F|jzb*L>0Xg10N(*?uy->fu51`n;B0Uy%dp-8@rTR%!piwek4X zE^H3xvMQb@*L831`)t90%QKlbO7|R~yIp8I`bF4{g-MnAl`jR#np76QJ{zJ7j>Khc zG@^L1@k(V)jY^rDD~YO_l$x4=Wv@?syiV}OI{L=;QcB$sW5$l%uoJ-H^9gw^F`!-?j% zRi!uN}1e?VH==H_A(*`7U@Y=$Jo)<%v>2hcww z5H9FinRYnzu^u~jC-a1^dzO+~I8IhMRhf-dl#T5fE>l0*4B*l!jj3UFk3sxckJTT~ z=gaA??=7@@85EQv@oc}PiIS2M6O}dEIZhG#RA-~#XX{n%*VETW1Uu9{Ss0Op0=+IH zv)6rVO2-Me*1p%)vRu9#sqjXi<>NhG!g$()Z_hVzL-)cTRk~EUa8B=M&mQnZMGD!S zu^Vq3t-DY*l1?bqLqwt7G8^25goON=#pBA$uNK))dNvrb^74kdqrO3T;_~5gGYh{~fQ65bk8YJOEeYju z9`8ep!WZ?cDVbcCTJ-8#N}fD67kFcn)Klgz-XyX}sa0hEdttQBex~=hhqpIbP|vyY z0$J>*ADWt)Qg7_-)#OzFI58h*Vq!u@POhA-Cxw`-#`?u?=#Ue#pEz9NynG5DV5*aV z3uLkj3k#0uTs3J=3s<5`864Eb>c@L$6rv>!4Bp+iS_BJX)pKo(ke$CrGLVG$@qk5% zCiJ-PHL|(32(0uv@Zb67JhMA6^jTUb7mr7f2Ew*<7qsP_orSMFo;i(o#N*{W zY&nJaYH^4~XZ4po!ML&oPt9M20XR2SXUAJ_i7)qP#)XD{!@va*&lYC)&ET%CySPQG zJZ-bpw6jTdOMEN0lfEM>>!R4^+;zCB6h8g@{5%;2MQBV+Juvk+kAX~Tqn63qzkhRc z->7yszmq-s^XJcpeMS6d6=QVghpJT5R9~XyV*%k!oYUZZg15Xo$2e89kS9YUPj9gN zDMkn5f(^kN=-#+towMXgPWX+iTFT-vTaJ_v&w*nYgsmhn9I*B(=aksI+W*R`vzs`+S z)o*ewe!YexkgS}1@cZkt6Qa&x#M3BANl%G)ix#lxnZs?S~03<(s=8P@iiAL%z{O_Y?VaUjcfwcdzisrZ1Wfc|Q!!%sl#m79Fn{VTQ zs_;_)>Vx&ANl9sG(D!j{B*a}vwzFp`6k3n*n}*E`ryS=sYEHSuj0p+ zBZfUn#NX$?_5!dW0#t`=`U-5k3hl;=+S`Ov(|o(l&zw7VpnO7Z5rb9UVA}ikpY3-T zr!wYup_D`yRPym&PW8Xuwlp=r#qp-2M~_}lk`D0k^V6?;&29ecbAU#ksm=P5Nzm40 zQ6pw|y!7`UneNUZ-n9gEcVuc!%^&9QW{+wE!8GDsKWOA};xw10yF+0yG@E_Hn0EEF z&KeL+h6X=IX+`lEqW@7V5iU?4#hcP5*f1XVBrt!#?Tui+qZdGv_wkG-2|d4QWww3| z=wtT)s5U##wzRa=+uOT*PTsGL7m!90zh_Iwxe>Mo}T_=Ygh6> zb6q_TvN|QeOA!GKg7jYMV*dtrO9!5)tqx!aa0%yBOLSiTLu7QE^5E>O72lL;bTytY zpwv+jzwq9uA-b}v>e9pJgj02cJ?0wpjhjW8ISy0mLqkK~>*|JoS(T0UJsucsa^L3F zB^YjFMmlmroO(!XYy-N}`&RO>X_46X&Uq)ZK2geVq9cQ$lb~b#Ba8!b7&&pUF3&TmrK#;2ALmhsVF`ZYQXV0L@crWzbDVEwb;o{PfriGnGaa>_R7l2W*nGC?!yWYPQXblo&fru2rBi~rD6iW`?>5` zm2JHqt_fO%59NFpks7_g&aT^E?BufCen&N3Jpf{6etn9-Kst#~m4OtE60~9hD=*FT z{TeP-&(u5~T3ZQeVNTWsJWD|rihR6SY;GofvB9o7Rl-v8rl@4y|S%*m|P+a zD^6lw2L68%z?Ar2L~CziVE2C@r$j`~X*RZ&0vr7xSIsiF*tRy+4uVco7>7zE4!tFU zmxbjiDCbCeyPSpwJyggjHUuO~`OzV#h;C26vpA6yL|>zpsVS7EmQLPfHdi7_7Ab!Q z$TT7_$Z_S$8|*Qq@6#Xw7Aj3=Q&3P0&(7YGkl2M&N4zQJTWUq~nG6LBUcA_xF*||W zWum|2N_Tg+ZYLo#ajS`g!pdsY0+OR6l|n;3jO4X!w(^v6huXwNOJhd z5v8;aYL-e1qWEnLVY?X#`*~4N8U1`G3odL0=@C^tq@oqyEjp=Ahfg^<_wp?ncau|+ zBw*SFpLy4-*ej2J5_HOx!;|!D0yRsV+y5G26n_)a7hIOM3+|(csR(X2WfK&P0KT&} zbRSG$CnY7-{PO4^-1O6@PZI-W;ulXs3dD*-4^$smAy?h%$rOC#+eDL%B$ekU`gQ=@0!(KEW)cbgqz z3kog^KbpR4F68%Pwufxv-*8Zl{iJevf2V+eK*!!{FHcXTE?K|Cs2GJSfmaRK((Zqi zo1Z@%VHSg)cZSX+Kns|>ZX)xxMqyzg<*|z-IyzWBA@psg@5{X`T~Z*{I7s=15)EQ5 z>n_*G`1ny88iQg1Ztei!e;~8CBC^#;tUcYcXOAjDyYGW+Q+@qAV5`)&tI&Ypl`9Nc zO_IMizx-%u;QmZ*-Tlds$omr$4}-9YRr=aB(x*?KRx$0IBNTtd*6l7VcR)kwN)h1- zs*$`9Ux!XyzSgCb1LvT7x%@dG-BWPniA@0_D?6`Js zuAEw$Dro`&2`gh9rj)-tvH&C8`D07u?|V5$L}iX9xa*FNmvxz!_$)SO?EaFF?9Y~! zyr$a2mw&aDA*b8F+gxB5MHWSB)jecr$Xm&$TStjU36oqh>)?X7H39gdM4W81c_}?a z*;kMxeSgJb-dhliSbH?ndvD~R2$qk)L`2mSFXl>&0Ehu8B^tNwHRGVod-v{Xn{6Zh z@9AAtiQfG0g7%0PmDnJNO|#Ucd+!OHRI@|LcPH&z(7?q`i~dTpijAoOI4euCFK}b- zcFpj|X?L?vVVDr8Xl}lSnb&bn7eY9S-;6HaWnmwNl$?f3!@q)r#9Uom*xA_!k+<@C z&H}DlKN;Q>umj9XJ~8AIEE{(Ao| z5_J!%7hfR=B1NBku9@PZJK*Hxq#aacn&(WpZp+Eeev+Nthv?G3ezvwo2|I8S`;|d= zk@D~L#$VD(6oh)Hide_EP9hgn(9=5wGZEi*{2+#qq>$*MbNl~ncp*^QQ0$W#+>%4vYmP;e|dxl>H7B82KDcroN zzqT+6J@p(Jd%3pCSji8u+GUS(fD4wXMDnBbO7Rg`2KcI>N z#s;)YoLgX9{3dV^bvnF<7UbY@2@i^jRWN28} zo-2eH^i@k&Zz;4h)^-}DO%m9`c7|Qkt|w#1+rksslQX$h)WYHS7-HLq$R_5IcmWTa z84~BEiHh&RtfFK4T_@hY@bUMz|Ml6pi3!5I61ii&`_8I6FOuH!e$5i-83O4fYmkVZ zW)ASY88XGFKJprBLr9HA@gi**_dAnhH#TO=#wSza1>6Yg8PQ6-_kXGyX7VYp0tyfw z4Myh#Jhl+3{z^0b@^1tJu=1iwKAP|4hY#%fU%JhWkbD3>1Bk17@I*)G>E$FP$w;_0 za@jv!aDaKSuNT2?J>7N5wBw_RJjbdTdHKHigb<~bp{F*+S1;O*$Ou24smCS{2qFq` zWI)+#vB>!4iE;~$fnh(_Tluuzw;YfZIL#D}%W>T>HRS~N@kn2OJo)n(9k&L_$_yDM z-{|9SKw^2u=kZ2cwG55+q_T9ghBz||L!=wXe#ssFv|UqETbb!Y;-KZf1UJdS0ue&e z`m6ySl?T`!2ms-A+jL}Y$n%FRreqXu>zbkLjperlpX+a|{Dq5Ebh*QZctY!`^+A`C zsjsAL;n^QHF$n9e%i2P9c6D_%{isEA0_j0|zQJ!);(QBMJ-Pc7TC+4V9!5VW5C|=u z9YU8=QJodes^vg4N{XM50hKXen|qONwb+ z)4WOVVwBS@qo_EB!pgVK&Ikb2@f}DbL$aT2sY*%YvzV0$Gw!}6wsu<3vUd>CVd)eS z67t~=feFfrSV>CmAqXM3;+y%s2q9V4~#bZiZQl~3T?#QJVf}DmL?Z?697H) z^@HJ$x;lN7c1eoY|D+f1Y;RO4rmHA#11ByaMbgN(Q~(BJ0_gbN9HWB};7r8w6;bCS z>2}#(8xOmn6GsgCSFg$;q;9K)!$K{IQU{>0zQTQx#^`_b-bZAfBdpTRs3ysuISR%S zAlKSjCb%afMh4^(9n2iPC*DC<4>UTtIC+2hV6@2gbqH4d-T9|Zh-4lfo?a&1 zZMSwcL;;6{)2Lq zkG%L434}_zI(O3Mi$jchlRuN$eTiMg9AE~1{&v>e1nm-GlribELYb3 zL!f_G@|9M|!5Qc6I#gEisDtyuepQ}Tdh@~+Md>J76YIAqRuS7gk%3c8^G`wKU%DkS z?|ms;87vM>oM1IjTHW@5gM*`Z?&|@2ASHt5c)CiS)j+>Rcq)uL_xlAiaf4F+syK#$ zasC#_U$mlW`7+ytb3||}&iWhuaD9h0AoTi#80eb~(5vKy7EfjO5#Gr%OxwtBg za)A0jqWR7I#WIN%oB68$A{&gJQ!&qU2zE{a)zO7`^YrP{S@0ENE}Sq`bpN)Mz#HVv zyN{lc*F}a6TK@3euGnSGR^zj|EZzs|?I6&}GOr4n5%zxrtzb9#lWn-76&NQy{VShP zP`9^hJT$=1Z_!y^V((*O(ohW-$nG{@LJhLA7{88i_}nGLG#j2s?n9IOp*>RWdZzBII(FL9C?_T}ctwTS}+8A4x z=efo58wGx;LxY^$3ate$YoC-h?$SUNm>Bt~j*Of9Q7(FViJcq? znh?fE>F6HmoJ|pTUC-?_vq_nro~FL90Ehg4U#)pX<6F1AERs8>`)?P&y2G7=0309 zpU?fhzsK+X!-NDqVA^H0ykAw>R^Iklob=kjHUB%!S|9e%?Rqqz+ zzgI<_Df++Zj~Qj#O0-4LIxYUGh%=D85P`Ow!))zm!-iQqc!fO zSLY?ArL%hKJP!#ziSV-q2eoT0^rpq&G5ED&^H3HTRGGB9!xa3^*4~`^zTuKho^Y=f zhlzxQ(%WlpT`zG2*0~YmnP*_-Vk7=8_ zn69=?hE0{z!=3SGIl2{gxm_3t2PcPew!)>4RzGkqU3+i_IfIQo6-fVFT1SV<>v&tU zuTWEI)$>njer4sY4|-+z0(PSflM=q)OD&c9OFn$yII8m$VtS9Nle zo$KW8>&c`2&4-6ySk|_-{Az1GbHDn-JhW@AM+>ljteEhk)+{t=$+pFX_u^71^9aTxWtm=#y0X5s?;KNHK2VwbYLnUCG>e@@MB z)9_8d+Trx%ST(VUdvU<{_+T5CfS`GEzFTAF#ful;bDb?cddoQ(SH`aOif#`*(9@&w zs6Qt2JlJU&uYK14+T7gSc(L5}md9Sv!1g)bxo^orgEj8FTn05cPrBAgS&B?r@M}Ew zdAds`D(vOjy2aX9Y)2SHMeB&W^Y-?*wO@#O9-6d-T)LyE$k|`@a;w-aQ?m5qN9pZ~ zaZKcvkWePv3x|9-)y_IA?u zLH^5EuUgpy}6ow}!>!-KTi9EeXL@z2G$EB~FtIE_r0~@9FfRNhAIO_O$ zb<*kA{InZZR#p`J9=FhKq%Y)ZvXLc^ZdUj5=!Aq|LFc)Lqk(nZccU|EUKc*<$-o|W zpQlX{b$;7kA4W{_JA_bypVhDphl%ov0l&Nq|HDb~rLk&q7Nz9IQp;}TavSY4bho@= zSg>CvTf?dM(loAl?2ftac^(tr@g&he1Bv1#*>bVHy?gS#CND$OUyeR7I$p3-oBO0RX3S>f&Fm!WA3mE zov@pC?vJ+&Oib8(j|Q4|L&-BG{qgf=<4%uA5#`mg&TD~$)B&)gr{TP**J9Kcq}_P0 zStx5}cD3$sMW|-Im0BnDQA0=U!~VQW7Yyp8@7)U!tyA`$xK9^Iek-W? zmcS;67qX|@Ss6QLXlTfxU6R$Xe1=vKUFk47KK$9vxS!9?3lerfFqk|!KD`2*0Tf@FW*V*U*;)kz%lnSb)t%4V`GB|@NQsNP@gJBUS8hc%dYTR$D{pEKdECN z9D2eYWPGpo?mPzvN18f22`w$5oSfX={=V@_#YBc&BwhSXs|zobQd@&bS+3hGDBDcb z(cZXmW3b3eWc=wO=V-O7(&Ao$ezo|gD^{uJ4@O}t|RlmYrq!(+Y4${=_2DKqDP3d;Yw;i0EUPMQeQVH0FS$3yPHTs{cbl+qyFszR_*j~(Zn(cTvSj50p zbATB>Iz2r-IWyzi5qoVWF#GQ2MLXo>!Jl3#UBb?g>Ghemyv2k34Xx*MTM_KM3g^L<#l|!v8hSr{R7VC=H?vy4z+jp&54LH8{P}_PIyT{xGmo4Po!G2 z-xXjItoq*OACz;ec0A2vZ;j#T=;-@YY4_UVrza1OKcBtjITw~Ek?_NB1UA}vTH&By zzs&MyHlu%}9gR=ae<$piX^Xrv`7U)0&QPV}3=X;hHr{Xk-oqm$cAG>V;GAhVJzRwy z^#hYS21D#P<{gPPtc0tp>j&-X2g@aGNjS6dH%u?bb)Fk#S+n;ofq6rB#d+G>e!-;7 zllz>B7zXicvYX&1N`NyrBPrVHWV;~)DTWBu(r2u8g9x{T7o>RGs|LiD)?Qf@t*8pYbE?(`%k)Iy%*vQ(HRr* zI@!0(%FZ^PFVK&lSq%O7@g~x+dvZb{=2bIbtE;1fiLh%H5Fl>r)7VIw^Sk><33oKQ ztY+=yW1n2xQVTy- zR?SBxB;+ClqGy3!zsBZO$kN99=<({+x==JO!_896%=+8uS5LpYbZza2 zl9+K*Yk1x|kG2av`@84|-}f3F3N+5$@}!DVQK5k!pmMn(B>B@4|T2E<%>7n^;cD!M#m_@JS zOE5Y$zEgZ_Wil6!h$I{)Q6i4?R9)GWvxZ=4PKPMI-AGG>bf$VJ&;xd3v)kNIM;DxpO3XWNzgY_ zE;7T!AOE%htIra*EJoTunqH|3r`O)pS)1XHcxWswC@8Srgs2qqBDE&!{>8%DAvmc< zLmRV26%}nCbJZ}+$W8J6G5a6&iCb8_{d2JQL6f#5sS!=&m9DFF-%`a=SNC4by-Z39 z`|doCAe;utmoak2KU~Deek1S*hlPdZ=y($2!i5WHP#vkTZ~F2D&vy9ZXISiW@S?Pw z+{|c|GXS8Lw~C3xl#~gUx>AAXWgs*-@^KK<`ud`7p~>;?%j{T5@#T{!J?i zL{}?pg4-hL--~XaJ9iEX@i-W=L`sA{aq4_jK91XzUH>Mu`m3stp(3f%s6ek4AIY=( zP+Kc9?6rZ1#&!;xK#WZzSw}19#OJJ$zC}Tjt*1Y5~-<{f)*Z&>^dA7Uko0>{L z?lwcXSNCa1c$XUyY{~S^%p9n?KoWaZk+5UximW)!B)Uhf4tK0)`1n{isSPQP)%al{{HPh?~V8LnWBIQHH)wo%Z#=N7K5F z4Zj^OuT3?PR6ZAj-5LP#{ImUM%>JFhw5w83?fJW$o_HpSdQu?{Ym*XNOa14r2n(-` zKU3_r|HW@Rd%{2s zT{WoPs4=K^S$*(?=coN(+B#qC7qc7)WGD=eW>##ha-Lr+d&hG7@j@EakNtjg<`qNF z?5EBh>j#e#Vq>vSSL*{IwK6NFgc0dfv=%P@%v^lm>E98<<}3E%#dVj_TVWJ8F#Gc~ znof@=PIJq5H~N3xsNbJUq?*4gt)4WPX6DNy0O^|Ii=W#QpOwXPW;`f1%bJ&Bz6t>I z{Q2`#aZm&>KwQ|_+3}~czXOQsxJmb%LP#87i}W%04;RB{sIU5Hw%L#P~ttnPvNaft2*drkBT0 zJIqRiBhN9sjE~1nxEBD|<#KMqn#5kyT$`{R`Ceo!RhvqlkYe#QQL1w!)?klLuCV&~ zsi;kOMT>7D~@03zAU?6*c-WPtaP@+eM2s?tKnI+Pd zCpRN#i`~{u{QUimS8Cjgii*5_eX)9bd#^tm;J9hkdq#X`LNig|x#-FMJUx^vnVQ`x z@jT}EfMH`Sb!PyF4V79No16Q$gp$Aa)VbC6libJ0XD#7|)RPImmt!8Ib*5*b%)<4T z#JGF+?nmo>e9wa|m3+hR@i3&upFhcWS0>Pv2d3ouWGD9xr(f;Dt50Af1;CL;(oje( z;A)rh^P_VdS5axHuWGI|6rT>iH_Qnhy9UO^#aVX&(!XK;NBv&PO+2Xp0u^1cg?5s% zpH4lE{!rNaO}xNH|GUTR`~Lkki?2y|mX?+@!jEx7$v7o{yj6^fi4U^uPHlpbK%m0A zT#Zrf{FCcms;K^xDkhS&k!Li(;$YpCmzO9UuZ4=#XRO*KefoVTN0!C*8$JiyaTZEY6>J@JXsm9J-6$FHTCCD-hqyJ1`Wq}`(Tm87aS()7&F#SHEru9@{Cx{4h{|6 zVy9siU*8z7y<`CVqGY8c&+TeA5dde-;ql|<@99#ZPYgR>bGO~Jx8GXnKX>=&7=9rw z9q`hS!NS};c0TUl73(OHW;0ZxbFLz3_JGVzd?%koBTrpISy?${1dE`hwG{{U5x43T zj@k3-OqhV!*h}o{IcX0n^9@Rw4}Y|~Z+GS9}bl;ofBZc;I$zut-}_p;QKt2B1&}c3w6|bP)JB)$!sSH9o>0AkXyYD6J^DT zw;UNIza>inu(&bbe{9ua4(aKZ*U>G}hyD0~`?}QzNznUeHih4R@7l{Tsrslt~K31EL=>a$LY63hSRs_6PV}x2!h=iZ3&VI6Yg0Q z*#gsaNyB(zX5;u5a7yj!#VX?1#!|t5uX$|6x{>nV!POl#}`B})%v#Q6nocl7^ z=q-A0A>^R~yi8)Q#K=o83q!VUzkArcGB9HGnyVT$Oe`!jXpROfj8^sJ+y*i2b#|kb zK8L%jSFT+n+L80y9CodZt4oHmK!*R?BQ<~`>>t~8S`U!7cPE)3^ z8ENgHDJ7+(41W2NxVfd}cNw>Syvf@zCSLI#r_9bzDk>_so}UOqp_04l6%=%jq>w%R zC`MKkMuFiS7e`)GTT61`!V5}Xi-xaX33pc~xE*TO)*RYrosxI?Y=>{^RXJfN3fRj+ z)Im$MkM=fmO& zTbPv3lWz=`hbL5-$#KPHx^K=678zsNP1J=0qL_vq|8%*q=pLV1>r2YCwRr+X{6tDk zO--AzPnRm}CuB=4zB&MSPTq~RtWFOk7Aqo|KIs2;QutiIdArbek0E^B+7EZPpr3)8yfvA(0{tjEs!{1ms2yvZe)d*;Hh1+ekh_o z4jXDykq<814Wpb zaZKAHWQI!2iyfvU)e8;u%esL3LyR6h(rwP%D(o7GyR1rT{9~F|Jl%U~KH;U|ZOo{s z^9f~BJ6EvZzM*~e=usH0&;vd$QBk_>KmFIHdwRbm0jy4dO-X===c-S`FxPf=_!~&D z%m&I|YHQUUNZ=%di`eLR;M{o3d_nV`?4Om`BFE#t%ZIN%B{7Z<43NPRtgWqyi;E+- zpZxI?a$U)(eOkai z5-47~+*7MP5BbY&M{uC@uibsG_)UX}Q7s~@=tukBBEg5mGTuEe1>YOyZ?mXk1XrD( zA8(UG;prbiEA*$VnpJ%wMGm{P;rvMD8x)-IY7XJC-^YM)-ZrdhyofbpXd=KoKE_Q!`LF012&N=izP z7YDvxKdTtZ6FzY-{PP85wfMtbC^^Z-{uu zuE}^aeQw?&?;f8JOs>Zhjo_K@2@UTJzy0W55lEO;Bvtzs_L({+JAo)&Ml@8Rf3VoJ zr7u^lpYFZJ``5SJ*3$mW1Cu~PMa51-OREv70XqvKXiok+tI@^7H$3JcK$tUfaNN6T zGpM{YQE!OL;1?PiTIqHCiC8k|_;5FrS@BKIz(}cOq{EXZm(HH2AzrQ7jA*s3uB;4# zNE93?dT?fT(r{Uh3U z?<)(bf+`tKRi1Gyu1`$MPv|gu{W|ME9FSgWY@^+o&gKjYMG7_M1xQ$pZEbS649))M z$fd)n_|#3EEV=3(3s>I*n`5%GG?W3nlF8BDIN+zT* z_HxsbuG4WgN7t1}AI#3&w*R5!oDnQ&!Gcb&-Kf@8X68RGMfeOebM7PpMN!Ic-{G1o znC!UQtW`_0DgAhs*!r5q^h+4=Y26CU0gN7nt3kl=E_i$}uw3w1ct!Zd@ExGzpywz1 zXIJYEVIRBs0DLk9eD4PHl~UmRts6VMQ;|9P^YAd0Vj{l`Q2%^hFBsxF``MpAd-e=4 zIRhWxrTh2q>r{-rRip-PdAh*|>yxN$t(hK?56`;bg*Zj=n(A}YWBM;Ct}{Iw>Q^IX z3ufXWGBxfPl2=k{OOx;|db(}hm#1;9zDfD&+-o+qZv;r+2W?V2JG*!QG7#r7pCmDu z>2;o{QjbJFy}0OgPvXG?GGJN4;BXp$et``&gb(0RNy!(j>;AN75r~PcAGAv+=jQ{V zp11C5%T;@)T;*i0K|TWcR6;`H){{RMp%zol*Wp9Za0KN|rj9)@2PiHta$Oz2P*oy5 z!t^OZ$`TV%btRv;gxlH?Q@Z)<3uzd&z++;649Nz*4ohWaUv6q% z{lPceML=_l*m?e23y|8yprJ|9lPW6k(!aVkZgARS349~Pbt43}0!mKZx_!HGWJIW2 zZUKT)ULxftbzGuquKM9Vs6eeF_Vvk@+EBGQtd5JoRAaQ)sW1ByiHbwAaNL|zgbk24 z&|SMMFz$v0k-q`NF$W;S^EcbOy1IDDJ+lJOG?sgcsSmkmE{lzn*D~<%Uanu0i`q5r zf}AKSDoO#t9Hl|Ky6$mk6{R)IWD==$#}u0}?`}-D-}CUO(MgYg{rc@w-Cp5 zjI(SEaYiERyqmn)T1x2EjQhLXt1Rwya@}V5=-K{WyqfpMF`Epz)13VLWKdbjI5=Fd+n=K*pynrl%)B^|kA>8no*aUdqSsSTkK`6BX@EMviEkA+V{LkW zC^#ab6%yeMvvy*1C3|{Qw!`lSnEgrMdEJF5KN}0Z!V6rG*zp!AdcR$%V)RgLwPwhK z5pa#oeQou;!X!$gBMwUy$rn5rcQAr>1yYuW1ML)~?!l} zJLNZ>8ceOP5=J|-zo&6*dr(Xd-!**|6$Q)6%g1&1{(Y{#Tb@u{Th*jq6%o+~^@!rJ z;U|Uq$Lh_I54oftJQ(*6`LOg1^Prz3gxvAAt!AEJkKa&_qNACDwL4E)7b;J7)?OLf z#k@(@v8B%7N8Ir%j&ZqAK@Eel&N+j=R&JT7|gvR=mC=R4^g(xi#i*q-E@0v|H!`J`k6joP26|nRD)IA`8fk zjEq;Vz#eLeBGNBmcvdD!$CJP@5h*G!>30DTBvC>cXGgehp5vWf9r`TVLvEV0ih;-E znfSFuxcO>ADNCt5?ar<) zsIGtP@r{FG<>27J>X1|iq@t>-s&avzU|HL&lOX)Kw0!q8I)7A~bVJ=tk5IO^o7Z@3 zi!^3ihd`T>I=P&sKj~rP(#44Oj%KxPGKV)b$l_c2_ne)$Lg9YcQpU%r{H$X00?8Ge zWx@$M7OHA$K*EGPjx=+em5Q^ubE1T;{5eJOh#(~Xj<|(S*V?t5kJDMh8)xbn+AF=z zBQK9eT-(ENeSduHXA)C+MPLy^@Ok5_4uY6ZZ}uh!`TeSsIDH~mf9KN8`-ZSl+`XbO z5o+o&{EX?>&cOxBtVlNIYx{u*`WcDQg3irL7w^kzT{nCEpvdmXIK_NGak!x|mxssB zPcng+D0D+Z!8m}at&hhvh}q}HFW;6#O1ES3#hYsa_H6wzeMjFT)nT=(rc5z+#A;a%?Vo7t z%<0=1<0ZbPjdEG4ze6;h|07nx3^VL1{i}n<3yh4f$f6Q3qMS27Nn%8?1u}9`<(~DD z`7=dWl(WUWRQ>Gr%GEC)+s$4M4Vs_+NT;zG*$MFM?jhc|nMHe47Q-Ufx-`_>eVIta zZ|ldibsNb;;ZD+{fXmC$JDOcAr#rL;T$F0PYFVmg9Q%_Z_Uc!=@F*{An(6#X4}4kK zLCq+lvFwMOxH@uHz;o5Le!UkY%{OoU=0Y`>!dXkuxCSWwR6)=F@2IY z<8d3hdI`^2GN4&FiXWtj4b%3!kNXEK@3(u$v-HZw*%X03YJ9)_CHxf7LLH0qFGAq) z7o2+AS7=!dUY(8Fc>o!)eZqGd<4Jk0&Y@Jqol=ib0k4mDv8R|2vpZd+R%$ddBGlOG z6#ooXro}$-DkEcQvn<9XKSCz-O&@!*bLK_hdrLw0}#quM3Wkj~9;Q6?pr;sA_6I0B+HM zg;WwZ95~X4+GacvG=eYapC18}^S4mtw;xA&DJ$C4q$C2Ubx<1F&~y6|oagJ7-)LyW zylBd-`&D&cgG>ONpDC0u3qS$liN1ejejY%v@(><4GXN5FaS05^KTUc3g|J)T4+L+u zZk_Y|tf8%XP8oRAF#(q6-A#N|#XgxeeGqd;nIovJ0^ozE00^RnqGJ0A(fk=&TH2m0 zc~Vs7{GKL(c;jDUPxIK{po;4+(5H@wh+x{#%Q2&57qYM2CUZ8G{rh3+>Q#x@SL7l% zioTpd3=9l(sBx;|5~P|MlHfucSHHKNfxx=(Jspev!H0OuLjY_tkWExzKBk}Z zsAq)m3U!75?qw0ETKACpWa9g3s|APYw=ZGGE8}uQtqsUDgCiqNjf{uH>L0X70QUJ3 zV*=?f2hJKW#-Pd!P_;S78=l7pPmVS^xheQ~a5)lC5^Lt!w~1u7Zc!3wgD zW`R{VJP+mq=BaxF-&%YIh8-~zICtB1B`huNGSENiFuuWZTiq1fUpEP?`*NZzweL4I z^!Jy!rQ*g`PIsMmHvJUxhC0O_zuP8MfI&Lt(OphXPKM|&MpjnAfMpxIyNS+`b2UTZ z-`83T!otI!1+;)4H*G4Q0znH^fGB4lJz6yJJg z>{tA3cD&Rvhn6Q(UU#XkB@$yhiX-wI_}4H zTzveF(y^ofA7DGFahUUNl{Afl^oK6_O4m+w#T&jy8Fpiza0v;q5m18BA}Vio!t0O| z%I7t(cA0>qC9f@3A)7sEwj);UTr|Mqkv3G4td&j5`tp6q*sjZ06g@~=vDMm$_$u=c zq1Bqqat_y~H0@H0J4#C2CoED-|M_#v-LSmN9{n_dq5`ed!TErmC8Pl?UB#}e27URu z?nK!Hgg|4);?J>iapfYk!P73OIGo|Od`3c79xJGYZMXVRY}3yjgiNd{$E7J#ec z`m~JAcnu{u+?vrLp@ttY%$y~nYmPJY3TC?dx?yaLHud?5AS?+gAA{2RzWfp?sc*N~ zDGdlJ4=3tGAo>)$Z(5*wC6rLvdmN#0g1@9mrOey(oHN67=jG!@Q5vJ#b#-ok?vj3q z@lFf%CBlCNaE|eU(u`}Nj(OeO4|S?)&COMXBlhh*khW_siM3NlEU zq~zpmaH3w$dzTub87aH}CHrRsM`#6zqBBsmqB3*@ok+;S!UCf`F9!#K zLbmF1F%YT75b=Q3kQo<62Skz}P|7i$_aHw6b{WI%+f<;BFHF>n4HW1nuHHU9oH*Uk zUzweaeRt;(u=e+pZuvkl#@L+@6qIuvb_OGlzJ+#;wvG-e1Lf#f^AA_pM}mlM0&Y%g zQ()bR>FJ4(pvcHJU|rT1dal#}FV($+R_0KDfByFEzU?v48K3}>uSPR4GIsbADljts zFn`@LvWSLIsG|{Y)m*>oYN5u)# zbc_Pi!On6hFx51IPG^9cW;%Wh#C#Zp4QaDaT?dhmSBJ~aLAfgdewAXIAs$3rS(z9% z88}Lxftl!1G>cLzkPAlk_K}V=tyZHEp`quJl9CWaE`r7f0&4&v7P5D6@Vea@hTHpV z8)p`3{_pQKxoK`c#-$Z<0TX3yp2Y9z=@&rK<>k|plLzjOKO+Ke4MZ?;h_pTVx&jb* zN?<_hja{GI7Js}WqPqFe8{}3aVC+ye74UTwNP%J}dsql+7)vhS2PR1U{R72q-s)Gt z@KgPrdJ&7~LuSdhpIm?V{qo-49)ei^EFfe!1J$CRgfC7y_z{Z0ObF_tA2GIFA+QTT z$(}{B-o1NNbH+dGH)KSx2BrV02U0o{oH7MzwZSF@CzW;8R$CLIu0S_a3tp5K`ZvbX@|@w0q~|V38X_I1S7FByk8HQLkSI zU|``~zI+*h_@V9@BG>yGbTU7`GoUFlzcx5BQB1P zpWCCZYzm)15V zNr_w%7mBy@Wv4tmJU0ut{fKjObAg(^c;0-iQWTn4DrQE9x{50CVt-66y@6Cg?8_XCB7+-O>v`u&>?(kTZf z7FOtQN=kaQPBnRRS==Ap;lS2eYj<+;@Tm6Xs7T#QzO4Z~9T2ZFz+kn&D)~#M6W2c5 zB?F?J9N2x7Q-?wKWZxz4d8b6Lf#VGRq&KW;Z^Iy4U4VKO;F7Gz{%l<11XPZB8h627 zohhAaD9qyA1`HS->E?lqbU}{li zKz!#NJJ31eQ2wI+Q}A$;f@s$UK06~z%Rq3aPQs~fM#DoJ{qu(IZly(+ndxbi|46$1 z1i$k&r<$jl72Mc$aDZQU>Y`2)BE*ZtQ>)G_Eq&Oj7(=DUPc|3Y>&Ur8L}`FpF(u5)Wh|VAC;Q^8) zM?Lof3SME?T?Xk1C^y+cgWBu%1YXuyS->I?WWiy@M>n@vPw>Ykq!Ei9M;i-c^lDdSy>=t8;(NhoFSms$Z31FQ6P zaL)xmy2kX@DP;pC5@f$0`*9EX-`rFBI|_rg>F^v}i>`PdV9ih?C3u0P;3A+>LX^ag zF9PKx`!6qZ44WDbn2FdNo~^8`0H-1YT-f^Wcd2iV@j5P2-sVM|rKAJEnG7D~j#muN zwh39>$=l8R4~C6+?7QR*z<>wFBN<2p{dCW3onunL`-A$EpjL0WA(Lrd;Lam$f&BP} zp34I5D`W9$_gBWM15r+YxziS+#P=F^XVgG~<_y5|j=y`EK+B^;iY&Y7U>!1mq03Rt z4jC}ai=-6_@b*TQAoqX~rxpGgfw=+pWLJs^HOMd5qUN=R;cziUCBOlPs1xsD2PI`F zsN{25Yv9{Nt>odIvXOK^*;~h~g@qAqW<@0Ig9OY@2)AOR{HI%Qvl++yGeDYPP=)E1tYn3{qTqQ|kB{z9Hl2ufxYn&|226?X-GjJCEw-+prB z4hm3-)|?c~SxeKekP19fW+Tw#{HYEh&THx&*bIA$P33%->mgJIMMU5r zs6Guvkn-aG;bEpsC>fZL!O@)?C(V-;PYVWSA|j%$WFa&iIk>vELA6c5&(e{q&O7t_ zHy-FjXizouSjPs{(!5AeWj$J_2{H2R)w;t8HS=pxHj7posu*Sswj-#`DR|6qAzcPS z@IsIifSx7|-WY3}n@w=eze9jFGdG`tq~7d}frSbKC=ZGn)=u_jh}@n&&48$nk{AyP z^nw9;nLwG9=jrF?mj;+OC^*kPFHtiTI^1iile2Rt{t+F{BI?B+ZlQjKqS>14Gb~piJ=sCwnMu< zItaWO=ijpaCs`RJRb5AVb{=9jegcG_HQeW7X%mk5?^o6qT^SN=AKNXXdj3FOR%X3u z0wNu1u?MW+b+j($IM+o9tTh0<3uqP$cLjx!MJYx7_*tVL9)yS>`Do@~0DD1@hJwIQ zVQg#5SyED>zNi5}5$*!CN;Fl0MolbRa@ zuJOwyfL4>Aef}bJAbHnS%t^YP^Ha=YecnjSW z-+>OQIb5km?TdeY7DoQ#`j+4u=uj?GidlpC?-M{n*SkL`G5WMp!`Q3`&2p%BZC@x9*I z;b_lMN<^P0?N!Hp6{?th^FRO^?>Kp37Id7|lzn@NtJrKTaL&^NffvaHrYlD|{l%Bs zwuELDdq5xPO+dTQcc=)#{Xm#35=S zUS1}lrap(DHiSQpDD&lc@KJfB?(qGH~Q-*0+ix`8MCOU!7|-AfOV)Z^Od_372?VRFxKo#jR1GqD67&jB|y$l zl!7Tz;1ZCrQvOs`l}i=#w)JXA1!RjW?Cki!B4HrH&vppVHpSDEU9ql20U~JV10nk} z)OI(Zt^~6eY|gWgywO$xIN|V}4r(iAIpo)y37mLWsy1F!8t6NsjAQfP= zw>AZ#g6Bhiz9ZOGq-A9@o}Zpj+%P%AtdtT4qTCfAEC5sctL8RC=aVCV@9>F_PyQc* zClo#j)vvlD%14p!*My**OsmR?DS&_y6FdvBpQd4uOiz!xRJ;-d!N>+V>@|ykfc?0- zIgYo4Q>Kyy?0&C<-z*-RUj-m~iQZ2Y4Tnq^yM%Ey8KonEl6~BQlYNF_x>e9Q=FJ-@ z3njVYLZMFVpZW6TOEzD&>gS{dSzSB7>-9?y8-=Yb7B&G-g#4--ZT&vfAc zhD}Tc4hv{|T8HC_d-m+v8?GyQ#+H^W&{+s3(>F{VaopU%={7HqRLDTvNi%9^fnxCQ z_h9w&Q_a1I)`!qtNdnZzG`x)ItyS%kZ~YvqNOGW8FG0C-0sRLs@&b6ah#?80U85$w zS@MjxZfOk;4dFqP8OUJGP&6_88OXl|7-pmE6iVvp#lm_r#4j;1aSu!&FsGMdW1KSN zitC!K%{XOgDyCWV_aM_gGjlE$JfDNMp6|eEj z(S_&)u#BTg2~|mJ+&9rSMQJlLvoCbwBEMe|4!ys$0eRo*jnZ-2((vM8z zKYxetFLFkOCh1|Yjzm|^|I=yR-uK_ohTXtk@6VI)A!|M&jW=BP^?6HLD4h&et!9uywlUnvYFE9{>(05YLZ=z#UP1LFLE=beON^LJ^ZNY{NU-tsO) zc!HROq^CaYAN@o0aEUib>;y9Z5F`GU4Odu5Vd7sU|^tSJ{RfoqFTi{IY%hEr{7Qs-2L+Stx>u4t49t6DF*9x7HL?080Km`fdcr9?j4X>E)eg^}PM;wU!hG>H^+y_L=KqxO~ zg;t??)dVWYoCo<-X#9lo5b+*xw*}^9YHA7$pb}M1vnc(41eLsdYwfpx`zHIOY@N2g zM3k16N;qSA4@D813Qi!OW&;wU%98?6*C>V=y`h>d1=!x`0hnIfIzjEJ;EIB~zCN&Y zQO@_(&KdqJk!JzW)KJEI_5HAEG>Ds5;%^*)|H$5@?-Z>p z@8ixqi~PYN6!0yac(^o^O+Yf<(&Z*wxG-hszAWyTlc`-o4->Vlc1^O#vj>pKto2u> zr!(-Ixa*G?aR?~V%7q05wLy)_v(1E>V0v#I3IGPMTXMp9U#^xkG>EGJ-kDlmOT{A)6mqLsss@ z#~>y_&_NsCAFzfMne+@ zk6b|IL-8GRb)cUD-oJm}x)1$;s38{R>yb3H8x*XV=aMw-{AuNef1^7N2PwUB111II zaVH^fv{+_MWhv~BJ?OkbY36=Y(AO#*rZABle`Nr6C$;~Je{Q>Ac%Y~J0|*e6U=IeS zX>ws92nr>}8#h!I`KkDAfqALg$|tyZsqF|eeYyPvv5!6P7k zGSsv6^oCG&=l`4tPS+-JYFk2I$khLGMf!ZEib0vYhYwkSV1D;R6q}D=BT>_MUI`oB zcwK~ug`7#)ln2(rYibMT=djl>8lVObgUo@RgLqKbALQ#`gQG~V&Vv$y=wP)gH;6Fc zfsO=iW(Gb9eIf-31qCiQH#d3>ihCa~5TjiQK|#2vj(~ti(O|UBlNth+PMo%umJtxu zrxWAHXJs^2pVK_&yqnlCEqyy0`%3IZ^?0d!v;8ZaimSFqEVb!U7U4lm_zCru7s7k< zlMXri5>^yHaHLZ`!f%`E$l+zWgzbCLIJ<)I`<>zv*7PTF7-T!g$4#9EFGZ@Ktu3tx zu08DtxnZXabDOocKr+o73~0hm+D1D7K)818yZHIm-BZ&L5zk!TESxo8URth zjEf6|vG@J_iLyZ*8B{TUA8~o+g8l^#Q^Lm#xdA^VDTyMU&K|@N5dvMT2GBO1K$FL5v5K=$DRD#T5Nawkwf^iwl6w%P2CK5D(H_$AA&!6w# zxw{k`^KdM{Kxc7jY0E=zcQOu#&9O@FdcwV+u)aCYMNdyphbld2L&ASp^W(QPJi|bb zi~Qi=fS8tc+123wJ5q3LN+dil`khT`-}jL;Y(9B8hkPZa(X$St?+NegH!44H$n77? z58_z`i$uNZ`Q&!R)08EPX-8V2?_>JNzg66xQ-^;&yT=UC`x0wq@2B`+ z{1-2iKDhmmCqa^ri08VCq>hOa3OC31^=g9en>0)dmQ|J_t4fB8$sEU z_U`UB$T`I2f}VR*f#^?Q`l+Q8gEB0|b4MF60n0<@JwPrhy1Jpj9x*-KHGcf`QJbLv zGJ+>i%ZIh*fzqm{nIkPD3A~mLtF^lsZ{OkoP1d|zF%bdP$f$F-2-?X%3?3Q&3J|%c zz|7tVBIKWKH;^wrJh%ou{=at1-y|mX{P;n-=DEAIHCaAlCk2F(4L>znh67uV<8fRp zUbwush+`x)mGRR8NwJp|vZHWoBg8u08aOY&x~*jY6)<6#pB=e9;N2#`Y%imuebLUB z>^K7;>`0Ax60Un4?G=6dYQ{4aa;;!ZkQq=$+Q=KID2IoK)yG_2T=-8;cI!>y#AwyH z-5B>eT=p&$BU>m-7XO4Xc>mTy8Kw7pVowM)&bVV!gIH~O6QRO!?;{imUm>Af!E@V$ zUim3NZf-CQ!g1yn7UwCQ;Z$8DC(o>{1#Nn%fly%7dwkp=CN?%5EU0i;(GPUnB`_!bihh!XRQJ3B7WH>>|gP1HIp zD;aQ}Vl_sC3xPEEJhiyKfKBTl4nF~4K?DITLS06U1I=ngm5DxtzCJ6k7BC^UKrL{m zEk*nq9y=IAzv03lz@UPVNlFGR3}fuvoCQ41>i6#`O#^ose0+Q}=nzmfFaW4aNJz*7b{|2&av!vcB~c^{ zB!X9@=XSqliP!Pdp(1178Zdk{%{i=Bq7TydS_1qmxnTwgz(9vPHDAk6( zAl9Lwq28gP-%pab;WQRqymSeBughA=UTj9TH)3Ech_zxSpE{~|C_-RrK^_*1;4J);EvziBLm-4(~h5&p(wsx z`LxJoWoxTJLyG_O@Usis^246+pgo(m5j^V;5b4wJx0Rc>@#tBtska1ZfrZ@;7G)+H_{cNXg0 zKrlE`!mdu~JS#1&=N39)9;ZLItL5q{fHF@>Ni>M~{rl&+>W`dS1cj3C$A6tO-aKb! z;PdUdI9!81y9&s>>ETC(8c9F2ZoYE)xP*g@+@L_S`V%zQ^Co@`>E87QqY0EOn2?L* zG&C+Dm!Z%GYl_d0-+m*@vX++bEIr_{M04G#M5RMvz|i&e_wNfo(AN*Is}lv1jJm-; zPQ`QM3k$fzc5kQt`D2YfNn(9{9r0c)s6Id8xtl!UPDr+J3)usyBnm)FM~4E4*asd3 zt*`!WOJp$O^8$dooW+2zdv805IOO5UT>x;D4GdPQKIG)!Zf|cR*RM)ej4bc(Qrp*H zyzdWz<^Vr1?TRS_A)@7&}A#lu2vnCvPFO(^BxJ83_1NV-7vk)9U z-HA6n!>K<&XaI5;7!z&)zh-B_E`$lw2||C?bPZwz23M_e8%pq5 zg+i&%9zp$mU?2cu^kkGAoln2Df4{X1glE<|rhxQvG*W*3WMyY33&7~7OU)CkB3cpL z-F;bGG-hrU88;9rm`>v`ji}runy2=rj(O8NT^9GbucwCrN`q;aYAmXWk&$a$ad%4( zU90qZ`};4gxdk>c*j4C0efqTd_hX!!+<{Fb-*1WZ-enojv0|a<78+6E9u@IF{3lNJ zp>e9Z45E4`*agiYI+s9~Q^GCBjGO%Y9rLNrxqxm|Rad_X6oC`K{Z3HqegV8w)z!TQ z^*TIFM*$EoN$C&=+9H?ul^N_huM!ilF*3s9I(_B)c}Gnxy4w`GfM4s{*J{wYO=4(+ zbTwZ~2d=9qD1!)}&78noqA_&3N`b!#PO)M|oEs4fX!_N6KxJJE1V5sI*9^OodiWQISe?vnEn8L`I<~ zYnDWdkbOxCiHx1dQm$;bEHh(^rV?4RB%ar|TlfC%bMEh1&bjCL=Q*c8Dh}V7@8|pZ zytemil$WeYlQ|e;PjNhzoSt4kc$VX4Bo_Cq%l7FB#U+Xd!;;SmPfUzlK(9%{2O5ATD^6XM1_%&%<*r(4cMtO zytofLI??Vqp8&S=H~2ah z{18k@S>LNB6-jd6dno6+{wS&BZTp_2toXnEHmmEH0G!v=)fF)%=^Vm5tI-ghw%ba1 zvaI&q!gm+kxfJZXVnwB_#gP|3i$*vPs8>%36#UBC7~fsf7@N7s<&DMAoFSFsLH<)7 zl$+}hvZIzh$=WWe7E@HdL`vWr#*S0#Rw_GwhM4!<7ou1?IOVo>P)YOsX4B_-AD>a4 z^o&xdNBrX>rl|(>Ion+hRoXX|Uo5};#;n<1-YUP-gZarU<1<1tzyGxT6z8U;utm^* z`40o{KbJvZ!MxCY2?wg&=K6hGV8kzT*s{=CYJSp%>)S*2EobZqHPMP&D&p%%7do)` z+hx|q4`dTJSS&e9d)uVV&Z`;EBKBMj-KF|tVg54|=Ff}F(aR%3#DsJC%dulTB*}|I zWKigSgp1s*G>Jen{zZ7fr3yq@PkQwhUsb2i)2$>BS@0-n7h#OyC<*}dC&KPK<+c)_ zdusUeXFjV-?dH!IJ8HqYZ;GS=OB0J=_FzX30>oJeX=)!jv=)Mv{dDC6gC z^=kynD5>-&SVp4MY-jO0C>M5S2&Y7(wxW_D?FNK{seLASOm##BH97~Y0ZeeJ6tlDMr zO?F;x?lHLOC&2U{pJ|W_S$`^skQ&s~?rPqH|My})m9vz|w)JJ(R<4=9aG{Lmy+f}q zJ|L$=o~2pKT&Jti9F$w8r_01rrRV3-{c8L|m843ZSWMt>wi)d+$-`Zas6^V=%MWMA zbfC}LmKKCX7;T;u`ZjCpwJ%=0sA+EYNk~{OYnUg3x#rOh-?eByaUDi=P)y7;Ofobg zt%WOemf&?IqO8`KLD;ukFeoU9h-gLHZAHA^(5Ytw0mXE5bWnv#BBk2dZ4|e_@oi$V z1afzP%hzrr`LHTO$r57^4-b+nalmD>kEboBQX2;Cot%{M(?}$ok?<+wxq4^MDgajt z*Nl|x8LHEi&wY+E%%ew}t~0=}JW)8&a1v~|pSHG&^i;LgF9VB4{09X^2U1({pfYa9 zoqfywB)4vPXtyq8Usi|D>Inp!eFv4zCnv@l3tbBD`ELVFG(`uLO)lh=(N8hM2OC_TJiI^||TIj=Vs;}n|9YT1_ByrgBw5Do*TN*r#*KYf@%>6l!PBU2d%R|!c zn4FwnkdP7%K*p%@hSrvqfCoY0;cH-7EFdG`yI`fPtPnYHeB2SZvriw+yn%$v#M$@V z-8Yamc#asvyOBE_dN7PfLy%$W`%j;OaqOS6u;}}>y~AKyE=LY%*A@;IncS3d>c+|7 zZKvq?pPh`S7gard_ur8>sn8rXCQ>ID<@VvwB^e*FUEIKca4GAR#v|o^nn2I!2Xo_j zZY)uCs?<)FcD=v%Bq*Am>icNXz#2dTT8n=~SZ$8Kabzx$H33zqtF3JxK5uLL_-1f$ zC5EESAZ6CE*|Jg#FR{j6tWMptefwq1A8&h6S-DFsE;@QU-c)I?d5eOOD6PPT5}%e< z`$>Tum|8HdL1cmnFoSuB3l-vdJ?>QCDU{%KhMbHDMEwt|{w^~cIbEM7%iACe8Vp9} zIeYt+TllPM{(x)2Y6H;yh=I`yP!$11hEg#uU?l++OK1$ zTEaZb4R_Gc(YfXA{gK7g!fSamqGx6nk2$8Jczy^H2fk~D$2ww@zW6Wr3U(8x0tBi? z9vSr;sxW;QS{F!^l-}H-?DY8|+rGh|uDSWcu;ZKsvez+9wW1~ENO8a0{=eLZ7S^md z3i&JZ&HhJ@bvxHdMQ>{L_RFKFQcW{TS$fU#ZG7>WLp9hB-P|ZQ*-?jM68s3lu8!(P;E6>Tz zRY2usXJ;pgWNT|{gS_Q!xNOe80d#^LE1<;+<+k+uh=7rV6DCWd*dl@G~EEE$G(e*{- zd-02U7_k7B>$ady6gI0@lO+wAv=1LXOh`OPNue1TNfHeiZN+=ZeU>Gz|o^u8yg!<%BT7RTnL{r$+}_YP|Y>% zTpj>kM+>MX%MTZSK6L{u7tNP^SgoqT!otGQ1qBjCHKo^BJ)bAO_)}Y4K}0THntard zv&x{n;qNHlh$DqC;ICjOEE_zv0j}7fGBYtTaY>{Uw_8E~*DhQBu-(}Ch+rNVBh+hn zgk}}}Q(p?FN(8l3+6Ni_`-uBr#@@LmXL82)YEmfDN`kMq3iqKHA?D%3xieczW{T8H&a>PiImf zJ?#cfB(fgLy;;1sZr##*a#~nSOss~(@rNSVK@86A-8+Y<lL*w6jaEHU-hC zsH!UctB(NUXL07tp#Djs)qwC9;Epa{yH)@zA~7|!9QiI`ZYIVAWshafMdBVX=72c0 z@h3@V*K!G`xs2RJV`F0x27YiNV2$tws0_@6aEU*sPoGw4AY!D1K3X_AoceU)wTD3# z3lpb(&HSX)9=xHXoy{Se?UPywSh18{<^BQu`jcmsg|)1eh>hF9V~!SHl$&KSUgj_y zJpC4==I0&8d?e(cm2{?ZR6pifI&8Dohr3mF1;G+@Er+yoHkVUZU%#%?bSLyFn~k2% zi~PzLOVzcurjDCBtlhOjxqmskXL@efUzabuVF#ePu`=zsty*Wv=CDL0dWsX>FJz5-qyH z>dvH-hY1GYy)T*VH=Xkb35~Y=gM=>llZ56nxodW-N7u@EC!XgLDWJ^%*6_tNy+koX#pPc1dMs?esOKxx>M^s3{K)I5Z$ffbjxbls; z7_5pUC}s@Q@EM%~)SKUooy4QR4gMJ6``?==e=?B2v1ForOIa|DiRpqEDCeZU+TD^% zwr-W&I?=bY@$C>MJf-k2Fc2MaJ1iTOFCWv1{=J&F1X0;2e$6D<1-eLLa&jpYV#SY* zSkOcUlMpJlhXosoq=g?i2UTYo%@P|kF-%>YcU~FIAien`hQIyxTO0J!EPycLF?Z_C z{>ka{$L%PrX?&{$^@(WQBqCYDDGsG)TdW_zX2fu765$k@AbgvJW^=EJ-P&4O z0`%M-rJJ{J7n`S>z|VN*gz#$gG^cS|Bo={fJ0LpRs9Z-wd^2q|6$s5q9PO~ojdIYP3U@Qdg_tDH#a8$m0PFgVssO^rbXufD*o4u*Kc?Mlt zh?|1_GDOuW^CLU^kjCDRc%;N-0>lK?a;{OIetiC}%6ob$MS6W~f`5h08Zj573B|WKi@>Le;6BDg zR$;ix%xqp8aauGD*vl2!-<_HN15#dZ6I@@pn z;X-|&4M&!f+JKYGAY9M7@!TCS8KyunmyNM2p9VuGeuVyZKx0M|FR7@TEk5rj7+%_X zdfr&nZ;YnK7sAtRD3{m6IZZM~P<5vqQ%@G>*swDP3<*DtL;wMRAYejxq5NJYmmj3$ z%m#!C3AOg`eIFlg%(#Jb4SVpC9!pjxKM+YuHIAG&{)VAEz?-6{uy!^Q@q5huF2>wX zkq6fSHw4Zr%BG$5xaNu>Hl@P4ql-{B!gctS7#Mb$x}-(9yh2W{3=F-UkxM4`7cS(1 zOmX7mNvE9jCd>0*dYB5B%yLFDiU=MMB!N@})Z$I(_tmN+;<5|&77?_XAcq94js>kw z4byJ$Td=w)Ffk?NHkju(?_!|yhL(nlOCf%AB|LE;_xSi-5Ek*5f&xRlZ7K~YcnSt< z)`uN@0v(?N$Z3zOnlo8ls9_1ltoMGLSj$$fR0l{Ae@R2jK^55lgnZI3^bjLT-lPj z;0oMsM~iY@DzBXg`{f?c@aAiwbhV*YEUyph0#)AbZ=IzT2M9?2+G_fj|JG8G2wyFysiV}!v8 z-z_CYuC%<(KlQDen#8416FC3#$$?NV{z`c~y|4A37+N=i~wJJDKjk+8}N%U7*lZ8p&P{Gh(RY-wp}5VE@H zSsekHtie~7sj6}YhlvrduRbFk*#>#%2Zu%E5`>!JNq42>_6EIveWcn9I|T7^D`98F z<>wm!YA=+yNfm z!g={0A6HJ>{2H(nFj87Z<|h*2JY!;0|7;87X!G<7jpARctojPS0vdzu5VINB5e2a; zBy$Jg8cht zYVYms?JouB=<3F%rV7C3)_K3V;97h_0#3(hCUfDD2f~F@lgb|%xeY9m>vwM} zLhHdM#>YFY*%%1m9~0U{Jk4^!XBt(oVWh$AfZ9-uQx_@>NzPe}gLARXHk(9(8ABB7 z%RH+EUHk|6&a@_ZB8U~?_+ceJdZmGTFGDQw{|)~kkz7VgBp;bqiJdSv@4y-;!r%rW z)sC^7s7W?VK{C1h358@xC_E(3jCJU`C?o)ldREx1S8!lj`NL{k{#8`)-z88*Vn@vt zU1R8U;XaguI21{@QF%~E;ZxaFcWxehG@OFdBtF?}eAdIja=^I8#hSaT(yssREO23JmLgllo zf)I$biAl7pK0ZM)F;ax;g>0b_CWfW%X@&j`{QSj>pff4iw9wE{X9+=a6K1>Fj@`)vMZ5wPsP{oOp)yc<_X(Wx5mc@~CbGc< zKkR(__Jt=uWho9YV3FvJ%;Mr5h-C$$VX*>FuW&j4XRxtKV8d0U6D@fc25{>6dRKtM zl^##qg90^TZoKq(AV!?3?ee)1PMVYB4TUc-P_))%tkS5nb!yT`M}c2H&uIo=}ou+KN$AU4WLIQbW;G>d-;aK#uMt#2&;5#XY&IQB0#O7k77u#ogT{IKkcBArRc%J!o*Z;IO!B(BKvz1cJ-AdG7c7vDaKX zGu=~NT~l3E=k!FYsmP)t5h6iBL7~daNohbq!DK;x%>V?*nJ)c6A;2QrufXivWP+%m_qEC~X5oV`Dr`4nI;@Ag$zAdYxrAepr`x zSD(G93%ef?kGEN%Br6Hu*&N+!dF$x>^>}}(_1n?WwPztsJjNbI^ZgJDCH2>NKrP~J zlPMVe)79{~%lC7AG2)N0`$jr>b8jjKJ_$~ft2?w6Fm&6_cld|Ko)CBHO-B_i5EPOl#(w-)~gc@4{JKbaEeP3Hd2{ z{Zx*9F|0{zmYjuB-x6~~?;|kS*?%+|KvqgTPLqMj+3&;=q)PrdT(;#LfrW=&-vVZ0 z5mmQ8j@JJxgfncPr!CuhGVV_3CseQl{AA)MRDo1q{MzqHSh}uikjD z=V`vjRq&qjM)$kjdEY{nCnb?!$g(i$?07t07U?WQbk(CF6PomNU;PM?sf>U+!SC~l z2wr_J6cX0Dt+!mgy*!`3p6l9cD<|W`(S7*xQFly`+}+{gqSOe71PY74gZk~a_N&b* z7^Z};znPY=b$i0&@Ef*Yl+tk2hfVBfd-e@_B|w4~MvA2ktQ)L1wlG7KNj)19Z& zF(u(w>SbFKKGIQglwyuD1R1C62ncYt{4`uMuugnbiQmguVvJ|ePy)gm4N4c7h@gPUJ2M*;O^nPHtTL<3Pd%?g1Aeo#Q((4en)50iWnG|28@h9sV1 zR}(HlQL|E3g7G0@&fdV4-0$dfAjo;^yRuS7ryl|Z58jcy6`~54ou*~|iuQ&w19zn| zQ;7pTPKc&$q`s>tcJ1GyH+6+%YDBS*d>>b)n@|`Ii{9`gv~x%GfrA&E@{>zdFkrhl zo}$4J-0HlblBNQZTN5?@2>r&~Qs4Zr>5)EZ12sku%Eix98@g)~qLM?_B;8mEo^@L5 zt?^NB<+n}XYeI+%EL^3rY?Mi3Uo$AGkk^UIF>g|E&q_?=2}J(Rwt(| zM7MKMO|~@uK~&73p{JP>sMepGI0WH_@I<(!9Kl41Q^MsPR#Un$?tC0p%&_z&ptCNU zV)>*Yz){6{pYI7HB`1y#mzENzbc{;N*Mh?I> z%^Iy}`6gqCMv}|@vs+DP|X>1pFg;e_b0W>)XvR^DX;LzySXK#CaztHvv> zf!Gmg6C;~X%<_w2(8r`96D(aT`X%g?$_r=hBWCj?6&g17z{k#?HDA{C7^UBmQrbJm zW{Eg$hF>12O10sCO6ZEEFHO4mhNGk(UL#O?d26+%21*66#NP(f;1h=C(b zzfZ4}ycV`;Q(E0j-5Dx7N;;9y45%TZOM;>=L?Bkj+S)p3zXdy%W{`cDQoUG0PCf$_ zpl+`8kqh7ao0%-bN0Jz&lsGd6=-mjzcn$!f20v4N5==FxM|q=eDN+<=I0w#oW@XG2 z7sJ

>3&r*id#TW(|3zPmy(XA`43gB@>8R+31hG8T1^>xV0@`ydjW9OEW66ZiN`x3!G zM~Bx&?t6WGBE)nEiHM*9LqG~x3+yCY0KADtN-0^sg&dc*0uVEndNH)JP7D}UYAa(- zQEJGTVo87+AFq;x9h;`0^3c`g&Ed90Z@rZo!&gV81|1lfL!LAYuZP2=piLZuV13|v zaneM@z}&QuKnt7yXSqHgeiVCJv>`8oY= zp8D)(Z)QgAmKeTj-8D24fnnahM`c>2tp2~N#0$^*F0mbvQRLZFV-{9mh7M7P)B?DnyiI0X(eRBcg z$H`Qcul|qMs+WfYkwG(Y1kI0R?>F@}xoa8i%l+8M zAy)lQH9ln&ZuTs%udlc~Ha`nq=9~ENJ4~zT!h*fgb95&IpydCzVD!upl8=Y4bqC?-Jwo8s2d3$12gP-bc zhy;mq37WWeFT1afZj4_rM>L`%B4nJtU(1L*%_o9f7pU7Dwq|DWga%*lcT@udg;B$^ z;)y<4J^bDcIMXaNdwY3=6Bo0#rc=yhJ)D;%vwXh0kYo7KY>i%#??w22qghxU_+*Q{ z7sWiO`#Px5`}c2s(@A4^OH0eb(vsZs0fWcgU32|Dz&g*9r~T!P%w_vW^B8uRxEQvy zuKCHy$>g-7!E-8(M3&H->U@klMS)KewyF34`ple*JB1*~|Hzpc&dtE=y1{YAv)6>nw z1U|(Pe7_I8I;{C&Z7NmfjB@BEanoQ`_x%qNX~4;Gjd33-@Z*4AOSt*(?01Ew)zz=9 zq!vbrB|29v3Pg1B64=s)KD*%%+qfP?X8V2eHPP*dWhO;gX_CP^6Rs*7NEqT$(Ubj! z=!C!Y^lq%Lcbt^mG!8Ze4Iy}4Zq8_`vY5U`Ok1pzr_sny3N@KPpRd+ho*%K4R_&I= z?o2$i@j%ox@cuWuZ{PUsai`;9Pw@fF+dCr~bV=6v5;OUu%aKXY+lg)x6ODwgKi_+E zJkt4DGQs2i_kH0bit*b*=3}#JK7npd5U=<9!>0s~zadF^fp^4pS-}iFMn*Nk zzMPun(?5}opFqYBdws40kM5nvmt@y?@1w>|52uH^yFzgs1bP})wERbSBs(7k@Q2S4{c+_eYyCl`P~aC9Au0Z3vOHHycUB3d2z z{Rcz4a`2QtZ?h{ntd?B%=q1LWaQL$cAkkX1Oo&m=1 zPpc1eks`yZeb&y+_Q$TGHnp3R;LuitudN%g93GyY*PHH>$r>E~cMkfIiT(K2 z(4LeNDP@SW!rf`kLHp+~<7B~kf>$rl67-?uH7c%hi)qq*etB0x_kvS}qJ{MVhfD#N z?uF);KinTTkKd9Dx9>SiD#h@_bnP1kOSJmiY7IJ%>E1`aCJM`V2a5va4arioQKoqIDQn7Lf7(-`zRxm<YC zfABpTH^!{ewwmot+NF}=bX@1E>v{8=5q=lak66Y!2_o%$hwlA7YfNiLJhHLvjch$5 z80osd;j@bBe4MXiG&ZA5^!VrfO(&yHHv|z!+{U)5S!&%xTB(yg!exG; zL6Ibv_riKNrPU)HPMbl>M%^?HJG2}@(SD#Pi~?B(*w&_QQ@OwC%bCR)NI7!pL~8Io zjs&uv4?+pA9grJEdNl>!Yx7*Jf!iFrPlXot5e#a@iM}*t^loFGdy!ghuTb5T=YRlW*R%3P%JGs_wjUI`1-~4WpeBm!}%5oa8{so)@L!d$pyF%&C zzyw#L_Y5N9aoo*AW-aktvT+dkRnwZ+jXLcUobSfV283kl!=hZ-KdAPMQ`z zetOyl70=LzweW4p*!3@t4u{t-d|K6<{;Mq?*kmn-o!->9H%#*U{j78k;xn_|(8y@V zYzawNE;K5v3?*w1l1q~x3p6&SosTPt>O1Qal9E#&Z`h9ZkY}xzpIBR|it9dO zc3S?>oy+mVDG7ziPAWYpI6#=oD9tlrfR^9p3SIh4OVw-%s;+jI4LdO(TDRQ1zSz*a z{-v)V4a?YX(%;2DmL3_(%wUR&&w`;YXT}-F9R~W0vd|*+oW>)QNH|bpEUXe79DIrL zL0ds-`|dI```w;JSNY>LB$WL6Tk_yv)>1juJ?zV^BPoQ0I9Q~GNQJrWcZhTA>FL_h zow;nk(s=b#1j!W^8TT!P(~3? zoqOWw={10_OB4+yA#Pj|L(!Io6ko;f)Y)l38-u;1l6njv4QvL9Uh zC|~75m=)D+(Ups7l2Q`tCmUfqE!Ftn& z20tW)ChHBAUf1J5p&nnhMOipvy?ddaUHa|U0fUae`HSpjl2Tz&5?EW>4W6$8y^pHz z!^nbn^Be4;cQ-S;s@vYMH^+H0JKIJtf38O#A2n6y=awe!NFuYmjtn|>%g=q!!z&uS zXRUBqUI@-tze}Z*G8;E$yuVx~+LHX3xZ3i7Kh6sjz>Fs!nPx+|c|)M%q0!4|@}0yj zc|wqhBaN?f8Bc;X7WjFU`OdzTXwWbx!NPfRKQ`CF7wTq!7Z^gCM3|pc;{1lc} z8G+jZq^F6Z3c<#uGS87wonlEPOh%WFbd5W?qB=b7lzgh49?$W9K)uc`$2(E zT!Za>@y>zAeLklnct1K^i71JNIA?42z}5BAIOr720E~sXq7xRc`GvKKFjsTF@12Q) zz3*h$sVo5xlDwSuD|&exHz-;QL*;m%tTtv?O1q}UlFji&0<50|(>#(UNpocD15|`ZW<;++#~c&;;O8 zIfcWpqTXl@EHI}~hJ~!a!(d-P@?rJe??%ygMG?0{gNK#Ow|KUoYcI6BG<=>w0q4SC z9>JBmgPpg(OfSE5m^u&Z-x3V!1Ph=0=BMw;bO)z0SE-!rWRJY|-1KD-v$#x|t*1p& zH^_qWZg$>C>-wIMW(xT8$(gPXgWnn3-yf{MUqC`9^Wa;I%h!3~m(@Vg-DFwP-5Ij? z51h2Eu8-WSzlZmZe*_j4y3YzmCca*e;;)q83zvu#()cmQX69nW%+TY+{#tL1WmvSH zTUt5^v-~6_hiDTjHZS1E6-OMx5mB&BngoMG4-6I4^`MQC%)?S81&ytv6l1H3_Jk#W zl>vEg3lS2YHwwVR6Rp%+k4&T+`d$hlwMpGns$=iL2nSlqaEEd6a&vfJ8sdty#yto5 zi55PrOq1vxBcuwLT&E(5IAMoJmv{*$Epjb$oS+2F$e=!znN-9{uK&#mqOD1{7 z7j$I|hD2dSyi9KIu;|zQiKH^zO8c6Hul_l*O6Ic#Tbn`8i9QE!$JxR2(uSVOkeRP7 zuI|n~&Jdj~m|@*p3A3%(ilE*9QIUDw(@jR6W=Vga?7_7CzMIJY4rWT0pkT-Le`erX z#R|s&TPS4eci^bC2FE|$>osHi8x6Es3MDJ@TvMPlY88Tvhpx~MI zSryzFxbOAG6Kr=heQd7&(dH^>t8emVsdGKGFFM}*BKM@2QQn2X+WB;0=(3aQu+<*= z`pk2^b@d`xt;2fs%DV&pyV{q?;5bcudJ0MGBKg$TrZ5#w@0_>hF0)+sG2e)%ia=R(TwWuI8hzKOT==uPP&b zefMb#^m}vKr?LmB(6>faFJB1;Dys~GFSzqWYQqgg9w=yMyK_46j6Q$tp*~FGi;4Ou z2l%zq7a57i{4+GR?&r#e)8RKJ*76arM!RuP&~M}WWCYZ_=Zs1I{V6>|&r?=hp<5>H zn!xB0RTlFZ$E)JT-cErJ8jRz&wnNdB17ZhMdhuj>7k1`M^Wa8YG%}H?ymFZ|lxhMG zI2eW-{DO78cKI#l`55n(6$E=`IM(K5WY;v{DtB_4MyTBNUd$nL&>o^w*C{P)#|b4$ z27SWV0;VdPZ;k{ur~fv;$K|%fRkBJP4;S}vsX+1ET>n+i@m8AUlxXn&`LE5k5cRg$ z-nuVb+`Kmf2BI^S82}nXTJls|HKg2f`eK3~8nO$SMv;7+ixtwW_IqQNTjare$E>7rF%cw+E@6(QBM_514aLuBxSY%jYjX7fyrLTM3u z4H`;XN}2>VWm!paaWbU%(9)*Tz_dzMU&AIX;(56G+T$BGroeVaqSUHF3U zz2C)dI>=mSCGVR&H?(otKFx%D33S+4nJs+1X0Z?$(O2d_mn;I}zU%=~e%WQS~&TmieRKJWycmJM0EULaSWClH?D&>jiK`2C`P+hcoEjp<5PuVr!AZV2yrM%Pr~ zf=05$6hQZG2zW$F;j;WQ934l>nW1H4mG2FGaU5ZT{WRB%LdKDDxuEFbMQZl=C!P6q zzMbFYH&pN)`uo^N9U}>H5IaHQs~fbS02;g71RvVHRgGRdbaL5JBupx{-tEC+z^|2i za;>m5ig1aLuC6Sqd;%)ju(2Yysivck7j~;Vz7xa@I0EjZ3*z`Dak-rg76m;r@SQ^# zKp99rs)ccP&X^z2APe{bAk&z?@H$n0Zro|F3jt)#ZlhriNH3{T z6uMiJXmj2e7!`S3<>KWvnUL-H^R4~QLkf<=c1L!ndqrv~4HBhfC6o~iMkE}g7*W3e zvF5bff$*4c!Rmj-^YNl3PLx0Ttr>ibCaukKZ7B9f6OWlqZhvL8>vY8z8yW-t%)Y09 zO;G`5H$oc`ZaEspHezWwRAAM8)%RcfhC#3Vo36*`J_mS-jhAJar{{fzv9tLjm9%Oh zlxpO)TxQnUxOddzPYS7+(T)k?MJ(>B&I=lI( zIh3XSh_=%RS11>BZL#McpY6v>qO3I+j=yb@8RZBO@wrj)*lTGKrqf*Q2_}h0{#NY@n7W?18=>&=eHJ-F(F#diDOT~zlb#C#JW%GE!Aij=G54*tF)$nze6FO}E! z1T)fEDvSgnB}-LpK7P;ftfXXhC#nN}3??hX-Ur8*wYL-5W2T`PF~r9{M@wrHE0+Lj zXcb!(i5OTEK64X z-q}6l-dnOw*HMx@-9J?@96Jyz@Vn$5F3D@X9DHfZaZI3%>0YGQb1T#0$Z; zg`L9RzZURL*SgdBewmL%l*(J!s9I@?4+b za>8kI)*_N}NHwStEZs+F;AC{^+H0UFZcsRL?(TM{3fM!|Y-$)%8N}r?F(jItM{#@q zuo;_-$Dld+tjcy?NEVtrE6)C&Qza{#w2=au#nZ54%3J4tn6LB}CEBtn{|BRBN z5u=ttP*FHjOZEgCl>O`2+FNvZ2>m5)aYi_kXxkOOu?>YxgfPU?#~t>{XQS0Hc-(i1 zND|0BpRVuGQ!0`)<0`{Yni3X5tsDa&v!er##{&3tQY=|F)$tjd;9xB0!42NdAH26b*>DHQUgu@Ag*+KS zNhd$J1ps@R8_bw2fQDn>*tADtsO(z1)9@p z#sqx2sN3s6K*Vb}Q68UbQ^*zF*4Bu9Ru-#~q|c?M5(77(oQAFY^yIh6^@WP2^n^kXRO`_U9DO(kj!#iH|c3XDy2eFgxZ++ymPmq{{I!NN4T; z3k5+o8Kfro_!Ve!pjaSBo%h?Z_MO!#Wz8wz6Zh-l z!5J{JYp2>x2L~S0VJp&zJVf8CuM%>&zId?q9Dpvr-(-?wBa95+F(?&)BJfu0tY`9N7*^Kc>o9SWLMigc+oLEqD=QQzMKbOb9wq&KX+X$*^W&5l1L zxmFp_?Bx>^Y;5dI_fE9;)SB!^dC6tjn^3j>R4DH5ox3W5YuMc-U` zzIWu{t@Mqd_udDt&t?t6FOGujFMWqagR<%Z1^HV11^=Sn5NPYDTEPi-3uJS(W%uKX zBa~)OI;EDrS_n`mGZ)vC7749~+Ohy}G+622Ooy|r3kK@8x_`8|Qn4I!6%R&nDI&tG z%B)*BsaOFeI-`)V72x4~MHQ*#6g6h(X#$0A=OiJuNcS5SGK-@r&SYF3hqbA$>5YE{ zU)x-+WYO0f(GNJu7#O*v8NzSKLBA()Ah8)p>tzcR>*FVyX2FXA)VoyFH!Am@o? zqg*bNJO;xEC6(cy%@4il`kTB@za6pxioH6o_)0J-YA9^4&QP z!aUGG6cJ{ZyM!x8j$}AxqqWdCsg;l$If=&dJul1rUFW?u_VS3guv98Wlcqo;mRc^| zG=Qr6JW}{hF?onlYHxunYAR6{lj{?xY(1AH~2Sf3z~g#_c<`}WzQ7N z!{c+fCtL4u)3LV3&gO)y$W!E0w(#O~RSR@Z61f*;BQUav0&w$1jwK`PGYUl%OUh%jZ{3sNQ#}e9`Moyn(#<31m$nw56 zco=geGtqJvo~_pf3!}4IT{MM^>K=!liY z>&<%pNq-39N1!sl8bQhDP?kxI^-pI3sGgo;AqEGD01`2q2vz6+GzPp*dywUgdJ?2i z24eaYkZh?~xJ!4xIkZ<%P}1IaqM?bj>$YJ3MJ+~xf;Pr1#VuP5(IW?Bb!&4pojZDW zvGI5CN%d6f`H6d=Daq`?nd;tf5SX^Oo%^P;7 zj$MS$LRmcnCkk&qoIq?cGOMk9e$pjt(dQqtZ{9kC``1fquDJDa5lFE`X`=>-ry@R| z>Bs`p3fT-Lf`72PyAdr~%^VCuK$X^2<5AlRRdINl3|77V&_a>1@@e5L8~ptZ1AfN| zxPm|rhRFhhnVB!${F}?u3uUveJ6ob9J%LEUFUN&PF-*r82sx(}vnDgY+}9c$MJEe` zBi^;5%phc}xr&<`_!e^VfRvWZ%mUwtaAZ=1Dv)6y{Ve| z)EF37yWU_Vr&ZABE!@*#=S67M*qfpIj>KeRz$p}r%gTR_QXWqtzPUNL&LXJSWy5j5 z{Yph@d`nLm#pl10ZQ<|rXNc@QYAf*7W?5>Z<8&&AKlzIw@69B9;^Mrf#c{EU3@RBI zb=7btuFaKrtuL1j0y|#%UmkAkbbi69Zdap+GZYLa#iC1~VIV>yyR^87$kgln10UqI z(}Pdd@lu-!Y7Nw2eS_2fjI$!lr5oFCx!bsc8A0(?CZWiXwb6CRuZh`Gq9AfpKhv>d zX=m15mCbZKHCC^|g@UbqCjuKI--zU-MsA}+{`UUfbrrpD)VuFK5Q3%;ka%y6wD(?n zUOo+=>)j5Ut<$!;UwGX*5-Gha#Q3<014Z#Bk|k3~5gbaMRJ@-_4hST>h)j8+A}=9#RQ;S$qBP zquL*r=CeyxuqPZpS7tf0kx+mE@ia-Dg!rrL)gK>9*4es?ofA2d^b zygKJhr&eeG)zJ@G$4DqQf0E~B;aetulIQ%~0un7%MvtNQmU4?ymV98oxRtP+eR5Ms z0_#xE{f?yZG0$1}pj8TTT}O`Iae*Yid#|Xc?Zn%bz3$5tRn3NLmc+SKjm^&zU-xYP zbz2mBJ2CnYG=CtE^+NNkCWt~%A@q)O=IGlEo7qd2=@`3s zR1GwWW{uj_)Tq#t|@y5g{~<=sX_|%u&Yvrr4R(R{ zvTLpGf*-mQOr(WPi?hj@InLuw4c*?BOKr&@&LWT7o)=4M=!79teL>^$;%lcRALner zq%>ZEs-{s`Y1B-S4eVXt_q+S=dn=X{lHs9zFhRYjylG&_I3x4V*|aGLpGD zwsvh!e-1~(rCxb*ezs31`p5vm0*4CU4hz|<0%2tE=)+P`ecC~c!10FlK+_9 z^cS25gmNPVL3$Q97vN-$8)b|4mQuTQKUNGrnTjPIul+AOa#%uAf|js@Gtz}aoTfKd z*Z*oMXUu4uLTGUW>K%jniUqU$K@VfzxPK+S$QVh(GRlz*wQ7(s1Wi%{CX8d4aYUcK z8sCx26C`dMJwq*kB&Q@};?FRKFeZ@##5{HLk0eB@5{tsD#1wESvB3f3m(JJ#kxX&G zNKwy87P=%R&G=Z1U1j7&O6CiZ7ffHzB9ezaZ}r5n$ZO%VDIG9$nhJoi%-&z(I7$+v zY$wX)sE{ng%veHj>ES?g7WfnLV%VLXMOCd~U`#Kv0Uq#eL`+J&O%inSB~1~!Jw&#w zAo#!KQZ!L($wI7n7u+I=7M3bMNQ`ICkYM8`Nm>1B>6?4c(rQlky z>3@hS3PFiZ!7WBz4^>C9H}soPqt&I71E`k`g)ve^%eYq(vwt(eu!U(0i=kA=rbLuz z$apHvByT7>JHenp45ejOFIb;1C5MSl-}3l-x1hfoq0Fpp)6@{9hE#kG1gkNU9;qFh zMkEqSdh6i5&%VE^8v2d2e!mgs#gqvxWu_0KSinx!PDzK=vY;3f8^+Hsau8jYS*ygz z#X*$gkPc_&nqw1>iVI~Q!*tl_BH1E`uyGQWojS-+XvYCm;o}+>zytTNL>BfQ909tXHI@ z%SypkrYFV~I*1ENk(eGRHgE)^ zlwd{w3^|E9qD#y)e%R&;>O4N9`gGltZRKN)?xW+;$)fuCLPq#09hHIMAe%`*n5 zv=Wt4-X?~cM6msO$Ui8Qa7E(2cu3c@4(5S2!*$Vq8nGGV*O5KRfTf&)pMqtMWpVw)<(Xr=Fj4^PS^ z9uNOs2~0e;kkNWWgyK#@))S~-;c^WfI}rb|sD%{)UkY&bt)tP9C?X$&b;bIO+CMIp z8><_wrjh_JVWun%-QjPalK}*TO@Gxvl4}A<*rdT=@SQVI!nl|rs!0?nN8rpPkLX8p zz);{wAmODhNXY%n(=LTMcaSP};ot~&p(G?QRfp3qa_AMUN}_<90H$ETsRV>4$2!{l zA&xC8{blB-5P}`bt~SGnBg1OryFKAV0xb?*DkWcug&Q8i<+(@8tM`L>010)l1SSLs ztu0d|L8rlDVSCgx48V&x!4bfxp|MR#rk4LG7Gauo-!6T`fR`WH)?A9nkR&c99fHj8 z=M}#plpW0wpWYF1h(0(8iUCgU+cgOj$BVKRaB!NRYX#B494^G=9KawBr)#dRK^ejx zEC*zyoNSr2bsFas?Tm!QVGK*t#Yj1DSKSK97RvG!19k+l{k^|_xtYD`>wB<7BNiHq zbbf`D8so$eqoumchcLrfLqi40qf_d(i;)@`OAS3lQ9`7?bv!j_^II^acRv$EX`K*% z4U64jETf*xb63r<;+8yseLcMP`9vftb$OlVu%z3$IlYFOU;q~Ztl{J$%scj^zvyRV z9U_sia1s<4M&iv}1SIi@C!4y@+l9kW4<0;*{+VMLgwQrm5#t+lb31pnzxFeN5DC9v z<66Qm98^(G|K*A|T&bj>1)9&=o#NNGz-9tGOp@MrN{!Rp~~WlSu0 zrs#nK>s&z`zB|aUl>wV8hdMlcALF(LIE=B91on@OHbHXbMVagczTo^J6X*6W` zJe@n;)b2e|O)~|KY8Jk_CFED{F_KskNnM6gVaqquCZ!`qhN8C0o%ON8AJFDBnK`|t zY-CW#LQp6jdW~zwupGN?hQrZ89Z^~7(EP`(tPq=p>uk7Oi}wip3XBqJ5MD5GUp5$D zH^1S_TCt-WyV-W%qWdPgIKlhL%TGx5A5VY(8pYBEh0xTcxa8MQPdImjEgW3cro__1Oimcv(Si^F$MkR`$Nt5HRxWAMSQxFo`uqbPLx=6u3>_483b zz5dSs8~5LH2nN;hMv9RcgG5^2MACl=_C22YLZp*VoITiwNK-GZ9H5ANV(6kBFafQR z|9W>0F;O8phJSl6AP}j^O-qX8O*9!NPANpL7pMP|51l)-Ntb!iw-nD@$uql9@C4EZ z_Fo7B8D78Tq{vgcRgRhDj~-Zs7(*%cI7K|8z}X^SqwgRe*IGmq%YKw|IL$c{+a>`Re%pAC_449-qMau?;4TtQG&$e8T?!CfuF* zml#?h5?FVETAV@J+??vLiDvT6|JyO78#>ND3S_H`)V|=Hdmo_+!qHwQJ$v~DY?|WU z-UPGxl2#fdoD9QMBvCa8>vo&CgQ=M0cJ=yC7yOYr-rS3Au*p3_tP4RvIKI{=_KqCM zY6tsI|8%k;Ln+2s17$A$6)2H}C|w@A#H4KQAg35;(e@cby`XASRLx(gKokFbDpUi| zfB<}~DIAEYDS7yG5py4*#||N@@6z^}JJu1hAjsR@FfM)n7z1#<73Fk~>)u`wB-LZGeL z;SiQ|YsUf{KehK0cOg?qwSrdk#ms7c_7AA=Tx}{hYDp-_J3F(5cZlJ`S?EQyS|#<@ zoS3mBs8T@Yf7ThM3Z~&Qgntqg_W9`vLEj*fqlRNp-^S^i^?jZ2uk|01DKQXk)Wow2 zL>ZbNm`n~%I3UQ9>C1_!9HYKc*BJiyUZ6uCG#y!pG)&4AzJk1h<|2E!YOYFP{?tfC ze@=kU3%=w5&J>X`Kg2}&SwW~FZiOsK)M`=rmRL+`nBYVL@Ysrs#ao&~ji-C&Khwq@ zfMKiq(J%g$fIk4=wGQQj0XtJ+;yd(H2mDcEOEn)@Bez10Q>-e_?e|ZN&`L2Q3TmW} zmKJ#m9UTMi>>mV?^q3N=a*Z8-TxW$_}} z-#k1?b3(RnTqy~2q0|(JwfreF%>iM;>M|fwe-Q2Qx1Jm6|M6@D!f^2bHnkDh<=^GP`HP`TC99A=X?ahc9L>iFK%YTh@cTc<|Hy(df&s=~;HqASPQ=V=<)kwHvLi-3WoW3M8E?pV7%^Q7oy?)T zxGwJeF6!@0N-OKR;~zZ3|8ZG(vDrQ|X}ARS;uqk110f2S$p z$3w;Q6&~AiEgF5)G*W(j@((&^AIi=~iyXRMU&K#zN@mMJl<*agYT2-79ma#(ob&%0p$xRxpZkpJYQs``}a zI23BgRj^Y9Udq;q9C8&%qia|(X{p-a9*8}e$^;f!Z+@}W+;E5!xBo(y+Up`w$yLW1 z5q_v^eZ*WibPcA;|IPjM#``rWVL$78ll%xd(iaI>Z6s=7(Lg!LZ1`Zw*=V~uN=OMU z7iM^(RMzehm)F}MTRIY4WBBB z@$`#ri}-k{iLAod8F=KRF5kRWSKx0qc-JK_)dJLX8A)t9=g<`%;*m_4GM&>(zjw=x zo^q_5#cGziVoMtboR9=WHzMTwJr1g+W=1bH;f6Jua8+h8Yksd|Zbmq#j?uC#kmu@Z zRLz?w=gzUn(KCUrZq)c%D>M32R#~o!{Zmse7X@t-AX(Bf*2N46W6pwW(4LKpSziei zm7K<*Z}OGA2P*oQB7wU%Gs-27wiJnnqN$Anabb@6}CTojuX&jYeZwhL`m>pOrkWcdp7(S_xE(vR z>w-cBrK-2bN1L!uZC4U$TyK!#hksbcGR}mZH3Zg`<1gteTSgh3BteVZZ^`TGB7Rk} z(g_g#%V!r~l@WqpMMxJuzU0qu$C{-f$1r}Fqs|zaGW3N4#KLfPF)t*>&8Ou_X~%L> zN+x5s!K_U^V3VG$k^D+~b|sZ`2i+DyAJafPuEX0%5%VqDP7Bj~*JqY|{c|Ixdl9Gh~Q!ZB1@kY@VKi^>s{0n8voMXIXAAsoVx{uJf& z=tZH~-SEFIqKR7H(AXX^^xn!cC5JIlxDJae+6!T~o-3DfvU~@G1iJLak>bWp_ZelD ze)p7HV2B!yFS&#>XJzT5YNd)Xierx)d=GF-s4!HG9NNVvQk7rVH?To+1Bg}W9DR8S zzau5^vCA7u^5(;ciV9ikv&w5MBmql$)VIv2$R<=aWdY;w@dZXADG@h2U2p~* zc?U&yUp@giY_ z|8n6YPV!+3WXJ~DQaaYc*C@kP*fcmHvIS>9HNhXnl4t;uG-xRZbF&Op74(t$|AbWQ zc<>Q_<+l_XfP5_AzwZKk)F}AVr5t9Yy|?d+WR61H#;o6#7mj>n+KND-E>TW8#GJ*- z5mh=!++aFZ0D%On`=0CzeC$y5iRR>A+i|L7L5`|vzo;T-VPSb}o2|}|GtzK>U_560 zV1==j(kND0mmUkP2w=uc^(E&v>t%jwrI@)hp{tx-pb?B*x}q$2@vE}!#;aujAW6r0>`b$A)1ycu@(-2 z)hWMe^_Nc@oSup(sYrQ{iG(GfG^!jFu}6ex#J8%7M#tIvIHq=(TvL{};PI`z!rTWv zzwcM?yr3s6q0|bPJ;FEJ<_qLHcDK#>??EjbWqZC!lz(DJRjuMe9mD*8L|tW299_F4 zSa6rc-QC^Yf)j$f69NQxSlrzqXdt*I5FEnd?gV#tw>x>OzPdlCqLyMf%$)N`Kixe# zQO8Ryv8SsPeSHEW88btXRq@I82WE$Vhch_Kqxq*0O!;dA*q+cyWo-wGBd1$T4t#~t zp(`er>OXINxbA{d(U=g^vKo6Hyw8Iz2Qfls?6l{q{nGLZO?LYNL-E}=n&5;xTzFR1 zVoTGA@tIo_5Dl^EQLiua?^cI9{Z6u(KVfmW&1sDp>zdq-TwSyiI`BZ5kq-5jJlZ;I75W?Pe0USXA+Ku)|lN zO3M4Pp?X(P8w2z2{Oz~rmyZZ3CRQK0e!Cxc4Xb`HZ-G-~YCa{P?M(Bv-lL3Jv*br}CuU1tO80BV zuS&G4hl+xvnHgpQ=u82(P;d86ZxT+^55C*&Ke32?;@p<+E=q+&`{l&G@&SzUixVf` z5R%^>YCpil3mxe}uSmxCked3hgD6@}eMJ>>=Xb_0q+I&?{H-4NB2wC~+pe85wq=qS zjT5t})_13l&x3of8K+ypckNqx{#U2jUe_J@7fm&95grE4sLSq-1+HT_{%>5Js!g5g zE5AK7iDUR(_A#>goM`90ME6wk71rZd;;5YQQ1B6eT>PGTth-ek&rG*7SEnzxoAI*l zhu~4Q2E`FwGMpt&Z~I)%0C4=M2*#KkP`VIc^Y&=4yHXS-r)6F5C*HlD4hKLEzvpeB zi``j2kF!0m8My7>YE@AD(a5wb>ACB8Vd=O`4cNSUdkWZ_7rn4Y$r0|3s}ce+*PJ0{cF#|Kbe55^kQ3cyw>AwurEykBd_?V zt$f7zSK!bDhEz#J_UDe!c;E96#XP=8`fuI0Cq5HA_Z#T`f&J%^YmYedMy@o#^V<%R zBP#+SqLGOVee8VXQEbXsdv(g+H9YfvACz7stX10bNu&IlgBxdRa;XpCdpHjZt@hUV z9rE$}w`Kp6)qyA;R(wQ6#yEUr@3AZh)YL7bOCCdt$sM&l+2Q1!uHD%;OLc3*s~fOU1dlb?_BF6vav5 z4B`+gk4*N4^Lt;zS&elhTv?6L{xQc%3 z?2Oj~K@-x@NF>nlLT3-xeZ9bXeP(+lPMt@=iwA_8TG3@PVJ^5S?B9kxA2O=Pbh2Cp zvh)RYe|ch#!r<{G8r_a0jTd{+^zFg&WjWHyI;!n3|%6n5{vrxJ9hZ}>@{?BAoOcOv^LDicl zTNV3qtUK)|d&P(_QipYy`)|*Ehs3=ug3gouljjJdUi_|aubo$euP{5ps~Gi=Smbx8 zio;XWSeAJkET7b0cVC|}h^2{7M2AKg8ZLz4`U_K}hQ7DEQVPZ~C?9Sg{!}ixTaXY|RcFL|7<>`iJzsr)kij0hmoGL{ zvS$pAvje?*k4~~dWc=U}wn?d!#=6(`sbNwUBMegmDVSV5sxd)czS8DgAfm3i9;j!y zIn(?+EtgKx&q4%tZ7r%~2xY8v4z{FAdpA6t>zBxOyaE-#Ryav_!j})ie>74RZESCR ze>5=)j?y!uqnz^@KfC5FP4}k1J+ftHAurzatOYk|^)i;Z!}1+JJ37xWT;Uwlf^%hbKD(a1(kF#|=Tdx*6 z0}nm;UI6NxGrv6_=4>y%7V(Wwzb;C%AEx8|VhVosR2P`b3k&{kRm-D9Vd=Lk4qoU( zIM_hcHa?tZsTuz0!cWW=*7UuRmne?=Wi!VVeODLhKIPFBNC+m!lqp}ii&DNNXRcEY zaM_>wvi^QX@_$_5sx*4RaV>4U@V#@6i6bD~FR0n0Uebks^2uZ`i0=J8$HBi4Px0++ zTj97;K{-b-bxtw}#s}?k3@p(_|?SadgoMV%YKoEifv*7l`mi*RTuaXO2>^d6Yi`#rqZ>%==o(}Cgxu86G!25iAh z*GXd957`oR2D@DyhT9_Du};4;v+9UNTq0KU{7aQ{L)qa;@Vt(qaJlzHYB^--lQ*9x|#0{0?kLQCGX~3qf=xgNKw<=d?F(6@O3YIY0=CLN3k((xmojX@f$|eo(L>5Na zH7ORTiI*miDVAWh7@&<`)y`o-IMi__|Nd15u8jcwW0p~4=<&fPPfk@8-O$ibTmvDs zeec*q-h1A%Gdev36R5TQ2}a7+h$JCw6zoLsKJSV`KlM60(y~MLp*hApwSNr!YwMJY znq(u2ztLn9TE$2xD&WWfW(`V8$a71rp2-@(pX>*vXxw+iHvt$>$Ju;*=J;NaX(F#K z^VHl_3=$TH$Mygw{FC>Es|vV@uwPdgQC9*d6oF*pi8ODIs;cs>JuMBdaZXwteD=i6 z!$Sckk1A|MKnsSlXOY0bfN(tciXObr%8TZ(>U;VzYe!#lI6d7s2Qoi|7Wl1G1lJ5i zKR^EV+7TO!q`iryFTTU(08SGoF(m!Vwn|PouvKnCFB+rpv?N7i(~DFBV+QVHv!N_8 zgsLx_BW!MN&ccE!xck*VEG&w-a~rGlLuSubyja{Ed{y_7^n%xeusqzsuci_GEW}Y| zX=pc&{U`qw%}m6h{yTDT8M5s7)r1~Z33dK>JjT%C1=qM$b1twR9xpFNcFgoxb3N6Q zMsqn~3&9`m&uhJ`(x(6j1lOO@dXCgv%Sy@>RF?9?hnFZ+kG4lPJg#A$=nqM;*=(PQ z88``Ss(g1rsyIuC5Pv)Nf%d~OlsRVqH?Ry+NUcd|7bT`-9Kt8QsBUE_MFzQ?il*jQ zgJxs*jztcW1)}-e*Z-*f5)(aZoF|+X{2ANRC z+^V^Lk8=Y)QjYTqWVNiwP(EuX&v4;K210AGueuPf>2RWyWl?VmPJtFnm($OTk_&47 zHbtpw$~@OcUxBGux*Fd2h2dp6R-iBwVWcfKwh#om@VMyGK3yXUa39xX`i~liMolsXM88g;>DuO1M9XPj{-$EdXkVr1gu5Xb6)iJ znHX||;hC148G7At!s%>VRka5QO6%q}y;c$8KR5doA-D--pg|VJ+si*cJ{`dAmZ5Ea zFzL{!9~$h(^)$D!X@nF`LdmIv_q?cFDvTJJQ@mI<`TOr)yf6Kl1E{JAr#JY0KrED8 zvOZ8mKOMKf*5sagQr^%Nr_nupjM&ggI$(|LoZ?2Y!ZFXAJ{UXN$r(Oa9ad@wu%C-1 z_8jx7=|4r^^r{kv;cgJI1|>Pg85Bx@wz0gNbVnR1MJw`N*~yk6EPmyeJV}L8|Kh+A zBRf&AXp>$QD<0Pwn4`4A&S`{YNEnr1@lQ=D*@Du`s6+lpazZFXmT0H0gPa%*LKHOF ze%hzBtq_a$S%5f>4?eTDQMY0`B1!@w(?$kaz4+pVoCA-S0d1sFZfdeeiN_|*+EG?o zi*qF@a_FK^VGJo~5yTt30ehoS&Rysiky1~JH+(zjKgP&q95w0mlS7MFN78TW3IIca zxJcYfy;-AEQ6L=J1Yd=HK_3cRz%ENYJvcyXOO!&)DxZR-Ol)4M0H#lv&FdYQ$!D$? zB>g)0scxov*3K>6X^#Jsy^5x$reTY9g|9SnN2K=z{yS=Pd~N%KvU-lbh3N?hW8%bTu~rS> zEb)iga-WWg0t*Cd*hb9F=~Sv9y{3F$XmNcHkbxoF2l#bne`ayAk}12{Ibn@9*L#+z z=QT+ky6WuXa4-! z_NxF0;=t2t^9N*QT67FAi*;#$=45Sq+1DhDa; zMshzqi>&q}l2?cJ<$koZ&J;foQyFU#vfA4$w*w2&PrLiygW!b9CBubn*E-4v1F%Y5 zGI8^UUgvT20a6ArntWeDt%9l&6BGqTGkjM;5#2*y&6^;Z_Zo@s2D0(DlB(DowhRtO zN|-0r2?KiSl_*&H%+++=uW9j_ZGlZ$Bt&x!Zg>8>Y%M7Qu6vU+DRKy@x+wN_2Yt2E z&dm#hAB|1oBIqqgWgEgv^eQf{xl}dFQ(9ghvjK4;m+2_=kkLPWd8%S)M~7%wSlF-I zCHo`b{^Y1s@$9&?oW5hhL2A3oJ+pYY-0?k7GTy9%kZ$F_J>+K!xYFi7j9A+^I+j#a zL|f$u#OP7vb6hx>?X6mY&jkomxZ7;=~MGswmsk>D$^QCiuKPstEq?}_4GLJPb zZb4~gS=SM)HthiIfK#aNSNqMu1#d7)2fFXWmmpnGyrq zft>^mtT{W+j_?6t7~Mt=`tqdwrv8uq8t1mj^I!~J^Muv&o;khbQ!(G%!ZO*_yTd7t zI21|67`SmwU1UYtt6@LY*{3an%mr*yUuD#kdR@~lE(BY49jruO1}`YVOiqhXX`ggve0w1gX$(GO!)uk%9Ew^yrOo=k0+71)LA1#2SoX<<;+Xc;(b}XvuBt zN&E3Nz5r;^hFORA1CyJfYo=DiL_4tZ1_Kr4(kI~A^3-#!=5o^5>wRJZXb~1Ap-8$) zW49|vsxK8Qw@PIsiz9UPmGcQ*G+ympgY`Hq8q@Jwd-7NspgB3&Eda`NwaS5}MlQc4 ztvF(Vp^GgDRQDfzwr}n2xK%1kHGI(%v{kVwIM$(z>iKW~itwzLChx0XePwpZ+lKyk zzwcabW|{b%3)89O;y5jbv|L&OB?|~jaQ>JjYFFqa4)6RrXC5L$84;3hX7VQ zNztsW5uMM&oze*1k2gmxmqSdMqJDzvI2S?azJUkR->3in9r@=+mg})P7>P~yYcJ2| zzJ2WpMX1?vV~{RyefsX1)dQe73STZLf-ir0b_*9LSvac8^ghr*Um4hhAAZTn>(8_Q z1c8S#rvk^)r!z_?O0Q$e;jv+WCo%k9=nl@9Xel*4$zhjdQShDw+^<2Yins?4_Y$O4 zRKipdn-ONZ-QGyHb!gbnwh*hn#etRd~5vh<%nmu2&vl#0G0ugTxLddoNk1}&JIU-=8fSCoGZl^Q0 zQW}fp)h>(gY5ZG6clW!;4|(gEO-J-PRA8;^>+4JOw|jJAe$RxPqq*tjc?jHIzN%{h zVzMl?8BCtyqf;J>$H7qs2V<8a;I0)im(^rHU+=U=;eNIRdAWPbAorx3E>$VjWxo9D zI<8)&?HyS`n>xv)m`C;3W#AyJ9&Ep1w& zb_6ORb}f4j$Zzxp{}tZLZk+0lL&YV*tca})5+RRTw`JN7#AL;tV%wKWHJhc`HCys` z$j2*9A+bli8&7a)#{M+;Z2IC#>*@^YKvMkf>HjVN=ZZU%=5N6QjUs+6iyc?{g-#DP z^}2y=2F;eI)87oKiVjO{nLPIM?EL%#Gv%5sCnP_yWia2P5wAziRscVstr}&~tx}f| z7tL1{i7FM9fS^Oi@JKuNO%}-k$4K_29ho7r7Xu_f@cndF`v75pTi!877Ha4!qH(wD z_2v1x`@L@Svqp96A!7;_(BbGeJ6Ig`t6bmQe2d*snP2OfQeu5)cf8gR9ZqJX;8v#S zV^24~>dVB%mKABObiB}jlMT(XFYtYB7AjhWHn|KoXMybBtsOs zhn%7YDw)v1l;iO|z?9Jr8=~3Nou1{vTvKgJpS4RhVEy=3>9=D(X=7eD7ZbfZh6bq! z#V}!(PrU7Kf@i{IA~S{qDeh1f8dw~KsSp!@EKa?gAbJCE0-swq;PJ*p^56D`-@?Pm z{4>M=e=yIpr&Y+<%9G7!R(8jwud6Sscb5li&(uP^HF7*nF2jIsY-96}?`=b;-1<}7 zTlH_<1}jt__cI_&hJ0=ONm-np6JL4fDrVm}c!YB#zuK;qRHBrA$wbzY{j=jnaCaoL zH->=A^J&@1baFEku=;CtV*&zPMRh9@1#GJ zfjn6*wh@l{KhGD;e)o5646v`a0w1kkY-jOFp(%+KoT;#8*vM_UboQ57R)#Z}C+{@V<)LATAHoCiG zW`T;)J#`Z;tj%Dj5ExTkIJIHR=6(RC7UQ~|uL56*XI1nx=oPXGixGN3Bq10`kxK7f z+JZ1Y%{4+%U`o>3X~NA=j^;#c#U{@x>GOL8raJQ3URuCr=I~ztm)=} zQ{z_;4=$kWwQE|6(013<#LnBhxTy)q)vJ=N)3sP_^HR>_gd4y5wG}6H|F7uQhyvgu z=<%z89T!-MF7yCTGP!tSv(>hTKPDANvh;3_czmp=obn$Uu=Sv%9eQ<04 zpgy20m7&0<`%qle0K)(~q@-uRedU$LX8gfbR4&1O=e)qE*~ur+t|>~J$J_hEmx~^_ z?T~Vm>r}+v3{yf8F2JW9vNWzE}e=8;sxGwenr-y~2@1uu{(N z1{wgxk3K@qIDoYLgFA`nhhnOpO{k|^l5Lis9r;I}TjRFEZ!eR-&rcaYAe2bG7ibJ1 z<6C{j{M@!Hh<3INiT^0tBPV)cT4`5^C+D!#oO@G2M$4GHUgh!k&s;2^d$#18U;ToL zJ)YeY#*@8x|JR!}hbvW%^o0!`K766p6cFJtJH9W#fl7Ln9*&uPKX0L;?3>>RG*1rkb{->T1?3q$H1y zBNFBeA^brcE8|-5?HsQ!vt#sb-CZa}-&is@Q5;FaqCz;pMy&7)>F8(`aB^tU4SK2# zfAjm^vjc}$IZwEy!}EE*#xIo|fj(7HxY>n99ducWJAd93@bIyRe>YC(^xMrEr5YNqFa#ij`{qu&X^^-Swp-2X(s@Thx*e3exI=bg! zq&Bl|ZJ_?=me8)N+NBAcvR0hB{?gTvhAk_yE)G&MILT!{FBLa)PGlNV3`C0UX>Af>z9pG5__(9*wqJ1gs zY?2*mvBOU&JTD**-GBXaYwJ?k0n*jpnECC8ilq7dgQbZH)Y{#_(NR%TQ!4I9&Eom{^=cHD9fSltLf-Htuyz3l zNBsNAcz;;x5Q^%KN4u}QmdX$y`d>cKHpU%MJSa9visl1#!Pg9FPSLR|9O&Li^A#Xg zPb=r}2mS0g80Gd7H3dyBbHUa}>Js(XB(SqiFC~31gM-B7NF$IrNSDt<&v6W0(Wgd@ z7}o{@r!mAJV3Beu8!q5#HejpW_?}&^`S|>kwUMlmfa<#g*qQ(Lu^`L z>V!2{z0wtiN(8inJPUX<$Q>KJ0wfem8gWrT&{^Hz@lSmd~aNF}My%)=13AFG!%& zP!U|J+#aZ+qSAGqp0P(Ggo_kval}!2#7&$1gsRQo59(pB#D_jvs0-;0N53jp^|Sl+ z*bro~M%~cke5S6&aqw)8>57ps5HQl%)?`fm zH?US@0JhDJOD2635P5-a$JLb!C|rQlSDetNr%8`<7!0)GH5MnX_78v&a~wu696p-~ zke(~`e*&YL3Fi?L=LDGdXy^Cl@pY!tw8B84SFG@FO+i8LUU!UNLpRkhGxK^ccZMIT z)?OV;Rq|jDB7Plb!TBe6vnC@sR`H}>VpQlyA}f`rxOHdP4-eJ3tN(Muyal)q7p;Sd)P>6my6t&v} zHvj)1SDIX6aJSRvo^(=`D$&JQz?!K+RRF()Q-oUG+7xN{NMA-Yn9J1}i~)?7IKuu_ z&?RhswteZF!$NH8Z?+@pByoHgi&{(|BUrnt@=)A360z>VJkqczQb=5GaeEOi0X^V6 zK4dNy5My7{4j3-n}X`yj&y(;%iTp{>g;l&Kq`md z8Jfs`uJTiFo7WWp(fzp+-euG6;_J9T{ns3>zTWG=oKHux{=x1x>7$Hc2Ay~KR+)v{q=r284(Sjb=@1c*o#9oSir3_zw)nc-DLUN z*hop|!Qr$4=dfBIM_@R5yyTw%v}3Zg9*vjJrxNhqPyF8Z{65PpMDsP)V>0-FNp^!; zlhNa&kJtTV_`|@Hn6kAs(H{+Y-DrN7Z8-Pi1%(ogoy%diy%4f{_H;vcxbS#l)6HVm z%Lk}&P3eBhm=Z#BJCpsQRmnOsNA($6~BKQ0FPIv|mA zSOZp9jojGbm{Uq}vUbT|C5Rzy&3^1bnjvG>bI1$(mgQ@w<#%Grrup6^Zb{I8t>r&~#<@*b0t2sWN8tMUF}-2GFgdao_nIN^Z6 zXndoQWgrbWcjCS<8Pw1t6$Gk!~8Dy>_>A||1~D=?k=k%S2lKb zio&HX{8>pjl0lOkMoUpPz5S@d_v_>QODnN+VJtlS!s9gHQ1`MywK#vS2ddZ_cCtzVBg{U zf=5nw5ThL0UA!o$_>M3$4;-K(FnSO6{GiYK_EwO8_&T6NYrOKM^pZa@gN810za6Zxiqa^8y~;wB1{b$^gi30fr^S!BY~cd zLl{=$(}hN3_a}9q_$-mUmnSo+O*s@I!5v{jV@$UC_Fm`DQ=Y1pp`!f&y5S#3yc%6A z@HGcwlYcdqt*rkMTganI4k4uJooN|8&QgY`AE(5sTm}XMt}Z$iH3x<^JV@9*xIj@_ z#T%r`QCHO!lLnob@D)7`w0|T8<|!S|kdU*cb0+5E)++v4gI>i$LPGNOs~csgMJ@k; zTDfvLH&`;^3Z_&we+-x+0pVXt4y^$&&{};t^}ybS&dSQ>=>GytzZG{lv47J}=-3nh z={V@sKc>mx%j?5^%Qw=;u_b&7%2s=I`7x!W#zx+2^lR73Cu&Jr7=mDO$o61zB6RC- zV{+#7M5CmiOMgX!5H)F&ixhFR_eFW-4bW`a8k4fwQ@{P8vVJ-s<5w^aP&R1(+U!0x zvnu17E!Q+NJlKJ>lO+>M1Fc_TKNfnt>KqvPz)Je*h21r6WM^pS9CQsymuIArPhcwIR+8>Fqy>JMX3I!c}X#*7@A00kqGy^^~<6tpJDy9~mK^V{k%wSTcQ-y~|F(*bw3WwYX zLo;1eC@cur>6oB&q-5w8O%Z(8448^IBqN=fWDKdBwx$;fLB2foiGT!_#WH@ zPE8=k53EJth~QP(rw`vlrO*z|I#{2C=u9%AxZ)WrA8j*u(koXEG9mVVQ{mjyAU~oA z2vlr}x}@$nQzt(BUQ&XKL7#}j#!u|T%^76-&eTtfm!p-HoeBjb9xnsW%${Aa|4tk! zT18GpuCBx&7BTCRUX=n4yn_@(mjss&TI)p}tHWr4tC-G*tK-$p4ukx$!L&{Ghk=rJ zz&rdG(e7NJrvZ%)K!3Rt?efdP5(=Q)x+O+$C6fDh2aTG1}B532CtEs z5;aV~vPI{W;(d5vnpM3922HFyCgr?1! zWEdkS7wv6@8noE0|D>zq&@2;#oIL~r!q%8NH*{Jvt)ajq0PDYO@zoPRbJnXm^?FyF z?7XSF^+0M0+VDc6p^=q~F@XQ_gqaJJ%sEWvPaY^16SkdSzs&~$L zn>P$(iD#F#B^QtN>@o17<*@SW4g&rtTaVPZmx4ysIoz0>8K&Q3frQ!Y^Jq z0CLF3@H$_gF(ZJsz$Ilq8eaSTC###%HP&)0-Ixfv)r&bM`E~@7v&lARH}B^&;98db zXvUTT@kN{k22G8<8~oV1(Pev|55uDJCxb4Er{s!DBz51JRl=R$ZxCZ=)KiH0Z@=fN z7i`;5@HuP-cw~P~kA;4l9?I%yIOd`PM zsHxSQ!g9C+(m>gstd4rjpBqa%BtaWKpA8g#vEc(e{xA*&+%}H1g^b3H$NeD>fZpH< zr#lsgTihxg*tFmJ*>)e|ho=1yqr{YjINTp_G|gWhuCjcxxN*||yxsrA?FA5Wl(>Zd z(D6Jk_FUhHasXnw(*&>I7?HdbUVXe?(o1H_h9P-eF~b-wijWS=(YRENgNUCS%J1!y zs-5#N=u4)YohV;m8&=cD?172;6Utrn@W8Pr=f@SZN^yqF>)}*edj)G!fTfc8E$>L= zZ?e#liai*PA!)Eyha9XN)}<@7O0~T;9g-PqP4wbaXJB5dOEme8YcLttmVV?PrKC>M zL|#%mHj2~TNEuk2Y=Um0i1a0Soe)e(LS7J(Ak#i3babVU07Pg@!^BEn;PN^ih^VLS zPsv|CKAIkA>Be0f#qlF;J#zvNI9*Q_yBoFaD17cttiODz&Feh*_hf^;`H2rvnF<#;)qb$^>%vnUHud9;Wkwt= zGO-io#JX?SSg0sFn(=@+m;3Rm zs&O5d<6HmFtu8>~CxbwdeC{E2;fy7GgP4UxFGfCxmyAb38yaR^Bka?XlPe>Nx&}2z zYZu`8w@5~JMJ`spQftge3l@hBQ4a3vJXpILvKqe{{QM|ctmEDw+&?$5g4&n|XmALfcdLcL_#l)^( zw>`IxQwNHsXim!VlW-QdJ*Z$YF@}XPNk7dinM#!RMKf5=femL?W)*0>4pH6ml*6}j zEIhM5VqM4=)7t9)1qC9+PaKh__)ooG%*m=b0B&C=eXmA8<)o+1d~~nW7WOCfN^-St z>?URjn>h*8)-_$kA^5-72g5yE4@B7B`2U?OtI8)ag$^?F#!7(blfzMe?KCa>n< zlNdT^oR2MB6vG6RR)Ee3cO-@=i1cBeRMs23}t|700Lx*|6j)Ey(MTpM#5g)o}JQfY_ z-ww{#(&1vA@(nd}j*u)!Riv@k@;(#=*2_U?&aIbi0pG%f3;d@jNe4I%OGmQQv3N~$ zo*k;h_Tr@{lVh=XGVCAVO4S&hIT3;|plK-PFk~o_=~PQQ1E8v~-+$LaqUh?oIPzNp zF2M{KqDN8{viImp;V?9cejND?M30qnq2JOgsRs-QRBDO<%VMH6ED4Xu9)o=6SBlkl zcG0y^4Be`uqI4)ln%J`^06(5un@{)T`7_`L+*5PvH2OIk^MO4VaKWB%2JkmxIMWmu zP(KNeQ{lsE**AUlwJ6ja!)@Udg|mWLd_OEsF?-90y($9&sFY;A4*Vu)`ZjGbFTn`N`9C0T!F&iufMg6d__K;ZI# zvXc}}W&wk-_%$y1`5eUM|XpB|rpK{+9d7m?#P4ci}m**1ldb>eCaKG)Y@ z*IQ{C=TxLd{#`JGB1Jx{FOz+OU07IJNhxgX1JS%&xfUbHD=LDODu!XAwfreN%;rnS z>r*1mr$@d6P%&W;I}$@LOCJpOk}(=88dtzBbB=N#ca&Lyq}*H&@aB`ocbEj@{ozm+ zeRc5`f&x<++D$}yqyaHEhS{19*x#XhI#?4YtsD+G0->O*oSAS1eS|B+Nl&h->yfzbFBGczG=qezCY2a%J-H!>28;Zg! zOKNEvt@H^%=lc$D%SoQ37Q_=0MUo=*aVAhKz5P^$&;6Sw67v2pP@KG;67(2#$LDQS zU4r}Oa?6p|=Wt_s_R1y`wA?`V_Dx3q*Gqz15hb55frubNq1+(tpu;9k5C#vjvdV&o zAMua`W*d^`vLli}_gwCiZMGOHRTgYRWHQ_6VVEcdVbBUA zl2gM+#y!f>mvJCqW8AX3{f$AWNcjjOks|kw9-0LamK;v#4o!mcZl6+dWOC%%4jbi?iNJO0zbxx-ai zKUp+<0$luMKMKJH6&6*60=!57@$`Nk@cHY!sRji>3KO?$oI$|;sCNI+q&8Is1D5|o zSX7Pe*}lcljIDC!OqlsRiwasKKkeKGwld~hGI?RXk6sZNrKC&TfN@EDJtWEWg@MN=P8)OE9&JC!wV~0z+t~NWPi6I zjI+v6N|<$B$$dF;A$5I>gBX{RetgPQXL|Jc@)OY-mkq<0CUW+}U)Rov7@qVDwJbyj z{M#f_ci<1SjbX6$K9WLy(0}Wd2Ja+@d@)_Bx02<8F8nUj3UR<*r)wSfR5-aT1g)+~ zb}u^m$?#fR`q1G`_$}XRoC058-_a`Xo7p+BEjsX;K`0SrGr8O7(WfFpc+aUMF!sUh z-g!#A*+mUhA=2cyIUE(ad5EqAq^yN0J!;1p5Ltt746a5P6COzoREnv|mxvXgyAAE<1hAa~h7I#FGy@_(PjEZ0 zvmjNKi6T>2&v<`V5Dd&no(PdXBCVT8ozEVrPDdvu1rb9g5MQ=?ZLVtOHrnV*y6PQ# z*W?f+0G4I4x8Q&Pqt@&pJN0_E6aRCJthL_6UurPYqU^^k0}GYvS{vWU%a* zW2><|!~!c}3Jhtl-371RZ`OU*?bRq}5*{D#Q|v0;+=$EW3l27bp~=Nxq=!5M>XR6S z(k^nj*@jXMt6&09uUY|E1CPr}nbvxl-t^q>%kk2ze=hk=hQ2wN=sv^dAr*NL@c0_d zP#amBHJx6Z%&VL*!(HSUmAn4Pekr2zmz~novS7Q;|H>!~nY6W+dIKTuz4DQUv&E;qUd7wf@nvP zJkocY9$Gja)J@^ig14k^VKZb!zBvkkqinv?gr|_i+r)mQE0(YiDv^Ab>L^3?;TpRr z&gsBgLVQ&RR$MgM^sd@)WZw~@YYQVz(2pL6f{hkdw`|f%8X^VfKo^3O)CFc$|KZ$kWR9~DQMb$p&t zNin5q9X3ylT3)%ztc5s3XbDaT%zFfHeR0yT^Lra|$(vu1^`!p1C}_C!xJ)@-{h8Ow z`{Ly1A}YL8lM>rF+U8o`{NuurQ~AnXB7d)At8*DGonuy6W;nsk^8VitV@xmm&{}^l z)ypz#t*Ske^HOT(zPS5r9AzW~%r@bv-Ov zn2BnT7%GiV?_nZezC*E{PYQmkXrK~>3*;oX_Z$q*siN;{jnKM_gT;12CAivLaK{$U zRV0;rkC`tj{mO6m2W0Du_#+0SvSVfM#^57yq?6v1M$Y6yInSlH1TcbbUXHi zvix{3t#uUxZhaEPnTSM|iv7YY-= zRHMt=I1Uz~$uYX1V4#ybubN>yR7of(^fwoce{+aDBT9*J;6;3rZVLoWj%&=z=PJDc zTli*PR`}`5G}-3js7Hm62l$Lv@6r6?GqKfU|CtqGDIaZHDNO7f{BrZTUu=xk1p4p1 z_|gAv{`qG)O}wIqMI>MsN|wN;h{RWJO{~uKHyb|DYeNg_1<^zO;@vPX&QCvF`G5gi zyi&O3wS4855M>~1BC}KMM;0Xehj;GA0`te-6r0Uqbu5oxYrmafy8aHX#2G_r3US4tm9VDpF#GrlnhOTE^hdg)S6jJjJ5280EJ(SOWkf92yvYgF`fb zj0%TFEsHWqA!Cf^Svqo zoI5vadxYIO+U8G{B#J*;1(y(@r6zBRNU`k>r(B)3=Y>v93K7??BQQ8#y5EGZi;fh# zxeK=9TF*G*!3-gV1vN{|m4&!8r7KFLdU1IeBL)IHM8eLamXCyKMbsdI|McSvm$LMi z-ryuk<}BSCU*`5j^jtYJ1!4Hwl&<+O#S%&0Y3+t@KThCpkb(E4@PEQ&awUwSl5Mdn z`;^H$*{2Zm!=Ei_Q=Mcbwu~?&a=-wILM<&8A1wQM<3Z2R3?cEc^L9E?LVgJa!vrBl zRt8qE*j_ug7_a_u)y+d-p{1@=)mZ6GWsT~EucH*RIQ>`b6xmbT;g{}jFfmi|l@m`Z z_4Fv{kZUeP1)R56H7W}!T(5SVQ4oSJnbIeDbw@RAN-VMq)J=qytzpQqZf|j`+ELSxq2?5Fxy>jr8ebgVU7GM89^d89f@O;gmuUSCv zLHogNMu~H}2Yh{VZH&sl$owaY3@aKFEx(D|(jbBgi>qbA4+09=vv*iVWTW#!hcmI= z{8)qH*mzugY9M0jkRsaQ&abpQIYwe@1W7WIRF<^kzW%_gRG|BzL`8r*zMx-@=9}&R z(R5Z(S#@m}eo>Haq`SL2r5hBLkZzQ2kZ$SjZjtV8cxVui?(XjX7vC8FfhP`y9c!<+ z?>VoTV;I(X<6$u*2Cw0~ASFo;*LYkc&)OXlTKY+>{^@TN4jKi|bd0~i_AEPP5R8!rJv{Soc-p;gyqk64Mt4sa zlw?$}6x+2bS+JeH5h>?QMU|l@W$qVdp!IbGT{x{{yYlUqmJS9rBo+FSpPC$^@n;!1 zj?+DRzs3t~FPm3C=4S(zlUSdP z<|}xH#ak_<4$Ec#*eJCU=_8TDbN-}_wlzQ`6MNsNc}~IZ<^C-a%h$UHJ<5(MPKVp- zW-4FYUe0R$-v|5Je?5DMP|^~1>~n<1Gm13@{H3$(CPwvgn0}anKMKU)3m{crbFh?i zmXc_DvUrt}iEb!AW1h$v`pfJu4$x|qt0X!dvP?$lL4K2^_(1Fw*7sM`YY7mtrPWKP z;YGr;IF<-)e zz&K!A8hdNBx+detY6~5#PDuGHc)N1vo#Wof_@c-(Gzp~#M&gB;iwfroV)1qu6O4;z zzc$jBRyl|iJHgLrSW$1wg@&?F%Y|%MjgO-5BpEkyYr@$oe{1Eda_CdXMotNkNM#fM zA%!54#Ul&lO_XahCk~iYo0XouC9>?>^@Xpn3}C|t`d1_NanFkH^84d7J@=B{e80&| ze`8eS=dB0%ID|v%K4k6JUt#q(K;;+Lz8e|44)^qbMglnzCucvQnw zOylH@*)I2}O2}FlmGb$hU!vd_aUYA~e2SUPBG!-|!uz}yibUC!VTN1lUBWi&iPv}2 zAN(=@045tRRVCy{O==Q<;kJute9d%=BEO64{^Rex+}{GolQRz&9P4wCe?rZlexk(8 zpzl!>l@|TT61Ru)Bfzzw`#Z0fEsDrU)-M-4vB≶Uu+$TS{7-V3?9&JP$8$YMfV< z@JAs%apc$isZ8#ldQU?4Ce6r~X4|ztje=Rh#Yf1PO=bSLa^h=;A zl+<48pOdG|`R7rUC47uKaY=>{>Z8KMQU8_6ro`G(P}=HK*x?0ToO`_dhBv_vx5$32 zj!;L?ut!L)s`X2xHsFeJHI|S?ktxa^(6052lCs5P@_)c5(KPdaH->6Mh&Xn^D(Y?A zJ2CUgeP3EeU4rZB7Y?CNt0*Dm6T097?L?~jP5NV5iZmG(1n$j>w0Q*+gBC0FRqDWp z-zcRtNh(NwdrxN}3nlY^FOkqKl&&0b<{}bagWg zMO#x^pZN+8{=3!B;*;VU?^zQ?usLL1!jbRbKVEjjs?A|&zCMKrMi#zlfd9og|fuD=C6Juy%|Nc$M zq$>EJz0zd?yks)+p@vhp%AS8;oI^a3~D~<}J87e>^A3hC=rlPBvyNtxnw{0R~ zN$8lv1FmX#BN3L^#d{~yOBmQymK5*Z z+f{$0a+iLV11)#!ma}&+Pwg)}9X6ASJWyFxwiWkM5fZt%QoeW;N7-p8EyST}p}piJ z?x#>=f)_~EtykDUc4z>e1SwpMEQXSYX4U;otcrmKwu)R+bF)T;9u&|yZ5O0k0gnWz z9M5h3Y_d3*%3~{v6ev7-pv|Yn4n;ymz39PIJ`D$?tF58L&qZHs2zRm=s=jsMma`mK zekYH-K;KLK6-`Z&V9W-rX2-2JI>&7fR^aEG4@=if54<5S#iLCef+NEPuMt?YUtN&M z1l)gDR&+Verc%W@Z8w2&#BeZ<4j2+L0}yd078X)3r+C>vXj#h@<+b-dv6fkvIvQA; zhh=}E|HPblCde|b^e+{S%l5K@F%%Ff>>9O3X7OfZTR&2k!efY08X7TT%~cx00#266 zN}C5(Xzyf(1E;TORzOG*B{_;L*7s(Nc3X<>jzzkvwMOG_nwsCOtxeB22VRH!@i8D1 z6czFOzD}f=g3fsH6{ACw2;ViJ+RUgxV6t?Gf#o^{d7q8nf=oO-8&jg_@tf3s@6QY~v(56LTs6g&Us`W&3zxGrhG zI2ITbH23PuXuTnR9aX?LE4PoDrBbwVmlI6kGo9ittnBQ}W4}GT_G&%^g9yz1Q~$!* z-u2o3{z4D7lK8S;TX;_eBY{om?67+592mA>%WK^BEis?Hx zI4XzPx%2;EpvVVott>B(0^=F)%i~4kS|CBg{eJP@@v#yo_nbwZXLyaZv>0o^e{_jQ`ay|70jF zE#+!greK;1xIN~*q&T(fg4Db zU+wwEL)fnh)x@?-Dyx<=DKOXl$kFfVp_0<#sobpkNPF5%@*MSQQ3KDm(&NDi*wcUf z+aC$&tP~Y&2RcXaA9y#yI6#EyLgU4#0Ps($hGQ{ed*}6aH7J4W2ZH#`g_URSG2sVB z5T{#$C$izjc~FY|ecgqZ0Jbl54?Ld=Ae;qD2qfe^gL=ECQ0CL2DX_8-q5Eu`QTB^@ z8wV_?6JUZ_xnJO!(uyL17|a-t~4Z zhz~fUG+JD2*^_%GVqHkXhWLe6;mK&R5MC_`jGA>}fUK|~zg28aH>W50bKhfZ6ut)PT z_lI>3f-Q7Psf$ABPTty@z78;#02l*ohsVv5G^k13Yf%KvR+6Wgi;rT+vw_*YSgl-6 zmNEF;ULumW6b%uP%wfs}e4n(~h&7w`gwY2HvZCgeS~H5m4{g>p(-2%kr=xjefbJ_# z0<;SN&IpT}kf94V)}W3Z=s7>%Mkh*EfPgImBS`6^iybghkd_X*3vIteU}u3PPPzbp3Bv>!QPdxs4rf#X>se4$&mlZX($WdQG#G_3vNxr1;WVmN~VWktHO;VxV?7+&&yG5D3D*fznPk| zv$G{qaAyJzn#@Y)8f+<6fc|!_-deZoeFWr;I?Wm?yOIdT%%4?;>M!-;`~>a?e+)h{ z3ht@H0%TH*XHyM~m6=;lv;bOu_A_hb&MSmT+WXqeRhf*78>%CcQz)k3s1#Vwbnf(JZ$OkgYHvxtM(4y)$cUlL(S&WoqaN;S)HOYe`e2oO`$o^Pye!YuO zAOd(?jO#zcM(l^ntpXZ*y~Q1~+4*~1d>EBWYJ%v! znP8?_sJEuc9HZfO|1O(|HuY7)ok?eHDu|rlPK*V9#CpR}(7#uR53T;HM$Hzuv{i~I zuM)160&Un24h~)=@&kGBQv*j1+Hpk6dE)R;vbu{ct{mdx;_%5~N7<8z!74>@ywmwa zRatdJoVFIx)YNA=^SH5SgRd>!A5(u)*f=8I6ABoWYE-`)yNEgCJT|}LP8{JUgn#=b zmx8BhKIvz{(d|Ci7lTm;mO#lEcJm%W7nfgG)@10h6J1s8aYOO*C6Y12hV1_$x+-*r$?ep#@vG!uEENVEy@$dQ4P9B(Qpb{JnDO zYm52s%uZ;3P??u{f+a1gVx0U1`3JnJ=4_X4P~meOy!;@PaqbR3Q2qtRDpX3ak&AxY z{3gFGoybTc{}1D~JKlgBetXY*+ucPBeL;(xrs*tbR;fuxF>#s{2^pE{$E5uFA>0wEBYdb4GlH`!O|8t-Th?aV0SWxd{$8|`P1qF3>M0lp>w!>_+ zgGRai2W2b4-iD1#kN?CMug_2E9eQZHmCKfkIkK$E0us!Q-#6l6G&L z31qs^=Hpv^p7~`l?e@Y0n)4*(jnT0(gx_<6&-^aMNG%IJ?RfbM>NUzZP6a6q2y|m9 zl}kJwWjKooxMqZHOO$aV&92)fF;WVcwu8F|xPE8M|4J8{K(V)N?TM+lG{Ll$sr#&% z?`%h^_;LN@C_{a<65gd6&;n&Cwm#K;9H%vY6C+Ey~?qyPS53@u;% zlD8F>nwU7_WG7N_{%b}`#DZzG$UFIV$c*=stL5e5_~1!*M$L~*wF4OS@|@rG-}z&B z3v=_!)ilDlG7LSeD8By#0ai+esIyWtkhc?Cs=Cg(bB*CJ(kd%`h_JO+;9MCtK3azIJvAx58(bpD%gf8)ES*m~!ztrjRiB&P$ zm<4ksHjOjdoY?~-PAY%vA4^rs{;`IpvCBadqpYN!%p-r+BFQ|KplB5{mtYl9D3Ym# z3fhVtGp)2lq=S*0f;_~k1lacaD|C7E+!aS6^Ww*;Aba8HhJxyke)JHpj8m8teT73q z@|o|r>duC2l}fveeBy?gvFmSkr3J`Teg2tm5-az<*Ivs^5buxm9tt>Li7vneGyH-{ z^DZ|$fMzVGG&+jfm$H{!JknfX!53|fmsYYL(LN%a{BkQgA%OFZ@!aejV?w$pTyNe$ zED#&fmo_4)Vo`jaf*!OW%-Wp|Wa9ss7Ds=sK<#(XBXTBt zQX?c|!m=blkJGo~$Ffo8LHu_t7s@`ppYB_?@K0GHmEfWkiGmgnr0?XPRYDQ-@7&+` z$iDZphLHjOI+NNwcg~25jeq}u;V2GEH?qCZ5S|!m@05*Z40;08WjNXJ4M+lS?Hz@y zh+xateXEiLUHLgoN61*;NZ)S8Q^(rxim>)aglo>Vy752-elX92%0*62z#dKUpnh;V zS*vb$#c?&hUF&}7Do|VyH+Df2()eZOOpdNNJ7w`Jg)rSEEe@Ikg#jZr2JC!J!o^h7 z6XKx*M4m{ay58u+y+LK=jR-&ZdfM{Cm6pmTO)y^tp6;szLaWhDXk}oW4IxeCXL~{# z_^7l^YI4>(OBzIfKXe5{q>P=Z+0V80^L^t1R*$nIkC4KXO|O?+5tFBTM|X>Xua^#v6;$L&KEd0{`KM1V zNbmIw$}i4>Vq^3Qko^s>;*B+C>(VXWCf0TG&5ph)eEWvzKYns2>;N%%=-Ijew0HFw zXwcbMpXnIrS7x^rW@IW+BP#jwxVs+}{b@wEL`~j~sa~p|#x*y^@@7@_x`Giy8GR*+Hg#R4`HkTc>Urom#<6h~NaR<(!{imm=Nn%$rbgyWr`V~(BaDIXJ zI;ZjKdVYHF`GZxe#T*MNoV>Q=-QC^r@RkM^GS-@SiQ0tksHv0Bmb+N5(d5sF$Iq7k zDt>hZL*CYooI2sm^hX$R?KK(PU-}_UYZl4&$}pd2vhzmO!MARFtbhCJ+b>vtWrI*l z4-_?zdsPzvsI>*gxTm7birag0KGSQw$ID=v3POTDcvmHU-k89Do{1ZY>JVNf=+9{E zZhoY{LL_3GDn-%^&b4rcs>p*wyQ(a=$8`JgOh?z!d2~%@%9g$ewwt^`qUo7$_`1>l zGlCdm#?Q~+_;8WAb5BraI0UK1Lg=oksXto|*?QbkP0aa!Ex>K1^jxDoOI>X5jr^K5 zh$o!Csbt3+P2q`@E9&1?BpCOJu;AQ?dnfCtU2idG*LK^B6iaiXQq({S9g*K*2GW`# zN169nlLZQpUD6T(hC}{fiP(Am;0NHLb^~v_FKw>cHkawaV4!w91r(GLw48}}Rvb8h z2^LG_Za`TnIzUqEjXu2E5Y3@T-ydW|^!eosE-%0oQ!t%`AY05f;O))A9qET{4p(op znQtQj#C%6!cxr_u?3lSlEP)&gQ%4`JqMI9RqOKk&^Ls}+?6hi2tAWz^QgJL&!aR=}BZ47uA}?d@1ti&w64(5N&of2jDox8=xglM;r% zQrLLKj1useGv4dW8ShLJt;*Y+&nhLbXVvOI-H!~XbH-P1k8Ug(4{6*TKe(@b&NK$T z{lodzPywrZ+|p7@XrE3;p*T(%s0{e0pf`qpO^p8LoQ0sK>mmI2-F_fO+3qQ(_qJK} z^wPe(qFB#%p;SJJpKQ#0ti5ZfyfuIU>y2OjTd{mAm$zhCQU@Q;v7z;lq+n@_qUhgt zWw$zGzihoclRQq5cm?m=9Fj%70jfe9=Z|z$_zW$XPM@gL(%!-s*2pHIT_O|fbw>zk zsoS_7!lGV`p2urloGIIlm3xJh=&lmH+|&BCh3C_oQGA>etYQx{cIPip*qL-*>Rwi4 za6Nojz$2vpq^coN_x7{!hX@3`(lcnR8cE$3QmUCg485Iie^pUF@6u2p^XWl*8tgtm#9mLU5rwPIS2 zW&M&An0$b{lH#Q0i5tNOo#F^O{tL8JE(jI;;vMyyR9e0*bZprTXOg;}Eb#i%C5OfQ z*LAgaml*8@o=-7ZjKQTu^qw%;(EKt?WpOaUM5UcE2$q~G@b0=a3`UmFOR)v#0dAhL zYMEXsK~Bd7n?LND!i?#D7LKf!jV+B3jERhZso^YKVm;90gB-bUMZ2u@nk)WF;`n-3 zcNM#q7y{Qzsb?J1%*RUJ18#sx#nS^5{x(8bk-d+r*ZrHf&bM* zqGlr~=1negV}dI4H+Q^59S33&w{uxx^=f!l+KusvX-EK|hTQF>jhL6WbZMTHe2|3| zIjxL~j0)_CHA52n9)?0AZ}guOhw;3Hu(vwHUa%p>CM8h@c1Sg0i4{fHe z9|d<5Xs_@^7$f{0qkN7BQDDX=?DWs3c1wypll$-Q#&6pDJjWzuV7FiuQiS~otQwQC z1&NGLicJ*mTHZT;Y`e{1JrI#k54x9W!Opn^G% z>9-4YFGID=8YyjdoHE+33_M{3QJrDH(Xg5OSl{kx6EvE^V`O0;+?CEe_0~nMQ1}+F z9+s3$Sk&sh8D|DvPIx3|g`u(t!;ID1pHyqmOCr#2)i$#CJzC(&V(eZ$WsMlj?T1ng z7hA5P1gI4fdYLV$yovD4CSGRfNtqzg@m{Wa_dp_+!|kBAFbY=mpG`(q3mC@MO9A-* zi=!s?#7!kUVs(CQcy?#D%?PO&d>(6HSgB3xe|e;T(QZ=!$}G~3bnp9EHUlv`R*F7+ z1r}EAJN=-c|2Ecso&NmqyZ(L=EG9-!Oyw@iPo$fZLP6e+*hrD?mVu>3hmrS!*Z<6s zjtSSniFae)Tv)8ll%B!!4ok%A@IlM|;OKFFDN|qXi5^=av!i42(Z-8vagac!sfzc1kQmph=rSHX8Y0BFrWDH)7|bB1I0}7&Z*6LPC2(>O&h4p z#;06`y`#<=r}Oi%jP3YBPsr$h)ML6GC+_D?qbZA_#axkXxAO0_60!R_&x8`R>it(5 zPi{2su2nMJA8iwuvLUQ^$Q7`i~RJy#82k?Ac>8jTKtGakEbl zcg5dhB*B**-@m8oVz$ax_YBxDcDB^KdihKhsZP}Oad`|szNvwdmvv|2eP}_v+f2{Y z-#XtqT&_+W^Vpso&ft%3fAV^!@#__rX5~HmwcGSd5(Rq_EU(KV_vDC$*B_Ug2@LBi ztuCl_-1pI!)tm6?C_!B92HGuHY2)6{)7Nimg0rhjMi5c0VJ_G#CYv?$`N7=!bPjGd zUQYB{d}|MkPrdQg6vIayyMp6fv{}NC>-GcXRg8tfY(JIVj1Wiyim;B1Uzd+S8d+RG zXr8$k&g59ipn!GTASh2MP3t#ok}(mKzRiPEv}A?ilh%h9&0o*Od+9EYbHY`kW-qE* zpthfynmN^UW+7t;MIy$93@UE)ChBaOMhbU)5cRIA@CVIyRv!t{3MvH2~AjZZ+<7sknnxo&IsOM2pm z<97DVZ&{T5zx`{iNptOXJJ3FM_Ww49LzY`N)q6P@&+}}t+G4Jf1Uk)a8D`OD!*MvBgP^a@Wvy|?WqYr1mjG9RPzRb+ zX(xRkhpxB00gf!XPGSLDg`d=&Q5qfkU7t#t^Ya$y>Ik(wL(B8g~9hJ;YF-`FbbmkJSS6puFMz_DH=Ck;`-tt7w-+=RMn;@ zQ1|apE3991oQ@U;5=K(Rc%Cd0U;xrMab@OEr~K1!ml6CKIJtfHQVQ5uro?*9JjMrK1mf_nz+%Ndl8+ZC7a%iWlL zuW_QGDZBe~y;tgS265Y2xYv5P?o&wB4*Gwf5|Tuk1!#e9eyO{4S+2v#H~L)flTBUD@^O;+4EarmlY{x;|0v4&H--x(Nmr~H#_ur}8JzXt& z+-TDdq2OpnNM>=hmD^g-XeB|-o4tFupKWtR4Cq25hZn%qqYIs|iLNzQ<)}1$<8y*u zbO{%x%uS-C<@r$x&d-o9yKef8?|)%N4=J^W^VI~URHFZ3V?gnu7;&I@Qgz%0x?W)0 zj^TKwirk}m4TCmqs3pU?-g5o2lR&;*vbE=hW{GBVf~K$&2k0?EDh+nVPN$Ru^{;l( zF>a;Kr~@SPw6EY7F(6En3j)#Z%;GmaN+x5;VWN|BQvgh*t&pvrmro__<|crMGiuoR z*f?9)3!1jd0Gwz#%;yKbt|&)~H$>*H3Jrk-m3WylL>sUqP0$=0>MmkyHMRQifMH|b zuv2ekOvBNznR5Z}>#_N5zQ4YcNVg#9yjQ)0+|(>-TC}j!bI09$eL? zN;~t#<(nDJUVdsi9_fJbbvnng7~1a?b#Q3BeYscTPy^CZ=@xCr5_t`;@f6bkbr-Wd z#gq%5GLc>FQ5a%_IpF1!TW{xT|izqff0r&f(=uQJj^H_}c)w3_YtKNIafk zyT~AQ{l-;s+9dU?JqOk;oqyx7v4=C2)l8)gR+`KgK<5&nWThc^>VUiY$B{{auGVHr zC<|y^QdirL3Fjewb%o&m{sKr&2$4e9xTr4+?Q9;;FeTdc5p{Lkr-C&othC?eo06QT z1wHRBXm0hkq?}N{Hf+tCCkxy2e|A3JezYIk(rv%5Z>hW_S_biQRYx{cBRm|9^@%S> zB9CO%EbSrfj|VT12L@HN24*>W(Ch=ySvaADi|oFtX?zhlBK1eo54*7+gi!RdI61NA zL;!?Dh53P0jOA{sc)HSLM6Rsi2isPAKyr1#MYFR<@OO^F>eDV5!TWA$*Hs_b1^}39 zyiYOT-P`N5B?Pm{o1fGU_R}qVX>P}SE!X=)?oTH#8AqDVzLvQjBxLWwfuE1bl+k4R zF`(wyEwlY;f5z21GSZR{7xU-ditWzPqVt&PY?GnL5oTfKWqje?v2&ZG@dvx55t5x7 zuM@<6JD+9vrN<=^k)F}kX7FtL|@`fF4R@m{~qadMu zp`VQ~xGvFP)UEVQ7q~$Si7upjnf(xHYHBfav%e^HZTDLXpDpKd2}Suxbp6#*}ELi>8>_0zd}Rt z`qlv9+H|C;_SUBW!we}z0g??6=|J>kzd0idp&EnCtSX zAda>T6sFreZDNq?apO*BEnR{TpuP;k;OHu-jY$9v?g{gYcgR5w*Jc$q4`X8*d^HXL z+Y{@!t!W@+=s`3t8jdF}ZdcQJlK%>X&vBSmZ2R4~ZmC&k?*8DT3>$}bQI|7>w|SeX zQUnM@1}Do;pa+&*zw*RAi2Yb7(h#00a>Krmp*^}u7u$H7b76LpG3@i)+H$?9%=fYw zdiSqTxOaFI$;vkBed^7{vl{~d1|cR3c##!PmuyYp==4;&4+@i##g6C+U?XA=ug6?4 z7g*~h-RQc8Gr3)3LJNcDK^z0VfMNA&OLa0|u3yO!$3JJF1bTX(!A8pjppwFfEWD{& zZm41#3`?swC>&|61Iz>WgSI z6r-5R6R;K(SAuQnH=DSDN5bEE`ShP9J+uy#rcX2;wZoO(7L6a9!fx6xoZD9{lX-bt z$}3;J<#}Lrn(yeZ^n#VeAatUW_TKdJmB zvYhQB8>8pm_pm@jX2HyX&jn}U)}End34&g?u2k18?B zlVKqtqmGZyi{1D$Q!AKlq!hE5?!(MfHp8V`mI63tfP%RIR2CtD2wFovxwbauM+oU6 z`{x3MUXo*qmC4@IzoZVe6B982R`{MKw!4Zf*4o(2B}uGNLS8tM)7OF;^O!qsBx-2$ zqu8fEUufe(Kov~ObI;fUtSX@3H~tNDvy(uv548wDRvyA=-i z)?Rf%MTHq4)E;IynJbh;w`&YdeiE3GV z1UzQL!$rH#fve!%WFamtu0#fO0b`|mw+w;%Y`wL};NaRhH%8qK;x{iFG> z3aQJ8v}KLk->{kaV-vIz0BkJ^u!5?8PSJyqwO48z_@j`@9gfJ{;H^O2O@*U797834 zJJf#9z-_sVJ9i-~m(Q*u2dJ$IQ7cj>dGL$2-S6Fxyq?}R-@^_V5nA+#@?+~Z-RMv& zAM1l^CYZa)nVZkq+pgQ&Akfik%Wmy5)QQ<%6~n!uIOsb&%Z@wI+8J%H8B3sRfP1t?l41jXed~SFo4F#M^Dwgxja^B zrq41M14mcEfzs{g2S)`+%o`<*re~e7Bo($B)b#J`xer}_2uyv(`A(-#|0NnKTMUQv z=xYZw>6?s~J7w47qLU3HcS;O>I&O<^W4bRRFOuAe`Cst=TgzdSfte4|Doa=S6#MC& zW-|0kQmv*h==aIBeho3FN0n~ z$YRlOl5l!g;|{C23J>_&Ean>h0D5>ZpFB~=^F7lXqtFuOfD!xV1rz8Uyvnl>df)VB zv(MiQY=c*j+%>FW-*A>olHZF$rFo}?!nXT~KGDT`j$K&2F~MNGw;EcBT6|8#QPzYz zHoLGm)*bj?5m^k@z|GU^8)nDt9bbo;qUkqm}-`Fu2EP@zYVpvKfvDhzF`r55lm1~$Y6(=xkzGnL_ox5HUgM+ z(3r;9mB}Q9W)C)GZR1~ulL%aF8=qy@%km;&Y9w^3gAor%7*(ZKOdk#$S?Jod>d0Hx z+0GQo1oUK#+o_M*mPbd~=^4i3K(x#kI=USTP`Rd=t-nUgoEV41O6*U!#-rH!-1w2u_D3pl@oc=|zaOFc>TErHEHxHA`wHoR zxa>AEGRqf336kxuGOH)$mKe&4U0y@(SY2b2h9natR^&@2pUtXJR!T(oK9$FkEKv=d zufdV;byWir*NVsgF(Qt5_XSRrzh2oTxKS+?d(_stb$hE>5E8KZe-MN7F%o+xBZh(7 zHN<)$EK6;@OgR>H+7fG8CD<(pFaE3BpqlD~3>>tDp+$$w3X^pV&Rk4sZ@)&JQ#g?y&8oP0gaIkVt-#`9S_Q(2Z8kTsqSoet@NT6x1euV#+iY)(DI|zhj z7qfNv@pq-4aRZGsAefQXI~SQx(yHZJgEY_WFNw$mJQX{m4}a%b`PsYnznb$sq;cGK zab<1*)e4lg>(JOK&C64+)=TRNyD)QF-LV5WrL}iC&a4b;>@4IP^5Z3Ci$D^LpGDsW!f#_B>Eq*{j8&;VV(B zoW`J&25#~YT7-&Zm`}WgXoN>Kz5l)-c19WF2{;KtPP_1LtlZ*w+Rv`iT&I)W*UVS8 zM+HudOc`IpcT70LUA7p;w*F?A{+`CM+t%2zf#7L2-bp)Wg-gMtFv^?NraqodFEn~C z&*wJF0J5Ok<6Bm=^iYv)8?1(Os|Kr^YWK-qB<)+ zSW}{x+xT);?hMuzBcZVq66v&!H2b;=i!%hz)9%!}OB~@52?oj3C`LthDW24vuRR?d z-ib2&qUPfB78sECIkPs)uH^+f<@OulJXO}Z(z$;zuQrT7unJ)RZ8eav)v5Y@e(0kk zl_g7axB@+6FN>NolW~mI{yzF=f5~%b^$r?MG5g4DYe%yyWu;Jv*Aq0YHj?|CZML?` zw;Fex4D%yK*yn*v^f;OBL-CyO_{eDtIg)rvIQ((jff6@BYW|sG$}l&2>^2qdi+CW( zmmJove@^=9s6VnlMM#LZRzUKIW{D+h7;@0|K;(HG5-MA=HGg2Occg(+<+=1j3LtTv z%UdJYkoU-FOYV#+XV4lcgV^qb?HxgQ`h*&{yF zbIBN#-0qC{w-0n*Oo?4?(IM=;I3iwLC%1buww*9LmF740g4eULjJV&1wQm-~zn-4f z1vT6SiR9^&SGx>g014+SgkGd=3p<9>aB_PjjF`XwcGF*tgI4lK_2SR%O~NptenkQV z1HvGb)LQuA|3n$J&ga#t4W{VZ&I6RudfBXh9;9lhXbvAaFAYLCc&cn{^zphUz72um zsA-z*yY_4I6T`z*(KhF9XN?M*s2`3L-t|-V!XCT6oiGa1@6bv$xLcB_hE(lV`<#8@ zzI|8tn7yPV8{-cOEh^1-PJ!4g>#MuCK`2V(c{Q=v=BnknD#7Zt4ty$jq!If-dlYHy z^{|lUdR*Lij;wY*9IITp(g1ZJyX`eNpry+nEME%R2mLkn@8tPqYhqm>%Pxw|UmXE<9DCn>H*Q%E9^pPxv^6eIdSc!UN zN^r0(q>tLg^Mx#9MQC(Az7SoKj6tp3I4fg9CPVB1%@$s%;KE<>yzf%mgmS5Z z;T7-DN8PT9`G9!2@wmzSJC7!#R)cqR^rw=8LDF2MCr0gwYG160VXe<5cG5=B(MYL$ z7W3~mSW^TY2-Fj!P3XQoT%SjX4q7jxr`7V(_(R-sGzsU;YT)YNYI(c=o%bSoI&r$# zuItgSIVNfkLy(Ib)*Y?En6ljP4sSfHO|)H`OLgfjw%U}gUmig9vca@=Upkm|na4*V zCR}Tt(H`pe`J`I|muj;Ni4s!=h`EbQn}5&CXB zKeb(5mH%Am=?Kb_`4Ui6`Kd-xrqZH$$1211QYX`7oKB3fZi&6TTM(`3ST&9 zcGb|BQPPbdISF0ye!`96S2TPiHNwM#LS1nqam#dprih?a#51Q9Y_-R6)_OUa&Fk$n z>00r+KY^<)nEHX11n~N;`821`|Ni|8%R1%2bWhJigEB{l$0f#JPh7rJbVC!fm(6J%#7V z%RSLN#pmC&dO36CA!0SES&Dl}XwafcO`!p^!>J`}`99)XKABygFN1KbM9z_jOb&?9~;Fsx8_Sg`1sgl-vyeeAl_JL$@qD z$F3?t`}{LJ)iFVVAD)%cIpgAGcx%|+?)#2XO97GIx(JP`my%^Rud~xBTIKV@Y@D~A84vY$9(Ni1{}zOIwYMq7 z4dKrUBqVXOAe#-S0iti?L_^1@3o#;RjLmsrzV75ygeG3bw!dW`3v*=f=+$lR}9&9caHpeBNh4$u3}bAmo^{ID52z zkV%D4MsGXsEkE@;uque>9LSTT`cvUNCJcd4-yMJ|1W3c`$rca#D5u`&&Uch2nvjo# z^2PPKafgn&;JUG2!N*VAVmPn?=7o z_%RSe`VQUGWkLLLuJ8F@5F|NG&&AAppz@QG$knB?gaci`jf4|Dg?YH21c3E0G~CA6 zyDsJL*mO>_*xS%=X26nczqs#Df`qzU&PfD;%%3rl&pVOl^YS_%(C+mx1QJc0PL@Yb zo{vxLE=G9lACBrTI#E5N?8k%>O`VR7%*=je-X&+Q6@k-i-8?N32=jsh)|Fn(<#X)i zdlKOft;A=otlU_Hd zhwl4)D2Mi14@(EP=`WZ1o(E4a0ShM$k>=$OJUVUz=8dmwP+LH zpOsm)JTzpAwmDh&XMfbvyFq@=AOTCW|BCyI_4#8D<&3tMkS_2}C8t?%@Uaa5Q_~%= z5{^Eho~)krWo`m4{|0RR;=l%ogK8E&hZ>!&@iBkidQec}zFh%x&e?1PO;SqQ=8?4< z!Oe;@i?h%pbiq1>by!%$d6BYLjGhe_h_P8m)O~)V^qskJQw5ytd&*lLmb5OyPpaIH zSiR2syn1r(Sy!5msoQSzy>iCQ&aGFTdAKvLJcVE8l-b9}AO+Qjd~IYyIBt=2cZp4(k^ zE7KpZVTC(@Se$H6C|1blB)w=PValM3{jSkE z8a5X~-fepGXEIvrdX>hzzF$A8polY75quKQ<{EA8jsNAuVSK2WhSAQrz{F+JCq#&E z$_oEdo6z}F67KD|T=3bVSeH-A?JCYMwr@x>RAODMXmQvIl=LNVgTLMsNlVec8`trq z_=x_00GvT%zEmKgLMpKmbSR*u9vi8E7?fb@f~tttN~#K}fdrA3uvR% zO3CWgtL3Vzt`g^*WLYN8IdRU3h={eeY?7SNt&i|_0?A&U7afb5c^Ny$4Ov9iK`XC_~)mRFGe*lGlS^La7Wc^5wOW zFdh&HB@C*fR4fW3VbNzAsi;5}1d&8lgeVkPD27NPkRTis7?4OI3u;D`_I(!zS{778 zsRl@>5p9frw^ZcsLx-Y3LWLN0{QK=4?|6qi{q)mizZGM#7?;jDx#ymH)z ze2(dJ<7~%|^s{p1O1bK)t9tsYfOAf^Z{IFI_j5ldVHh4!eM%t#NHwYoL0xpbK&k^n zV(`zbBQ0no1_|(MOb~{mjS>}BB(BwDAVQ)j5KKivl*AzDikQlv7?8pG0ttgqVthR) zCFqI-wZ#$zp$u1i+eTp|X#Bbt)Fehp9V9RdB&^gWs)te=h(&27mDq?@p~S(EL~$S{ zMu-rMk$7;qXdTNysHAR;L&1Q2(za0yvuc5nk?UKtczx)Ku^M0LF z1fnpa(D{d1KQrd@Vr?wv_G#~5IsUZh?)6#~>#F}0*Jb)g6`x~!zG5tPkI7A&Hp%|| z`;WPAPI!p2%=*axDr6Y06P&THtVZOWz#mmOe#0yb_h6k2QIxQfyW zV>CW?xgv8yyOsDR(~7A^14;1HpVla&aaM>c5h!77Y^+BmnIs8e5K^s1IO_;PXf)b{ zLFmesp~TXfJcJ6ogF~7&QAU+P>%%+_V-PBI7-E$ru?a~V$Q;HfqRHB> z5l*1lbfqannmMMLDK?Laf`C%~eb8Z8wnw2-JlSECLFabUsl)+kBD9-rvPOd}$wzhI zGnYk?L2IAMDGCi~=7=jH&RWvcA>!~&u85zWGIr8rBf9|aX=Ut+DQsZa4x0QY61B(Sbwh? zMG#a#2V~X}7$4O#X|-u5kfj1jqm-gn@tJTWNze+WrY3xfTYpL7Y79X{mO88xT1g%s zGjpIdD1%t9r4a?0ZIiYW(soLt*(Qn&)#^e-G>#M`APn;DI+pgtI7&HEC!|)PRZOF4 zONni}l~Jig1jeAyXrqYZfGmTlsW#3Dhek$F#s`d^nwp~7Y>?SbzX=`bollo|s-jrm zinX+}BF=`MsFV^+KQfO1vTGexc^2|n%KjuQgD=Y4;KOrxAN&lBXaj*Kftho-)S|T} z3Im+8IE2jl0K!^AJL01O~M6&JwPj_&nIk z_nkHx6@~NN{wa!LV032^??!jbubJr0ZJQ5*S<6korgW8;Ie$0LgskB+JK<-=HOFi!^KdbcJ|3 zG!yv#cTNbR0EGp~Kr4bUz=^jX%2IHNLkWb&XHG(eI5Lv7<-1HQHfi|W^9lrw2}1uo z_;DVXJo#ZBwA$rqVYOC=3C(fxz=ox2(5ODFbGN0vIlPtR=epl z!Z-!W5(Hqhx93c=21%NrRfM%EVQj!Ul+q|A1aUx6@rE&i!{!?ZZCfN3oc8ZZ6h}Dm z^LDYxX|-BiPB16YU>3@?MJoew0Lp=NXk`eDCW-@}q)8jB^#sFv?K>oOm>}{LLi-@) zT0x`b$CJv(k`H6(&g}$w{R%jCtgoYsWc6x^n zO<_!oBE`9scFWs#`ZZ5*`6ZMN2%-=ZcxRL(Nzg{oY$jyZ5u2DSv!rQ;3G$l_{rjtx z-yj5mnX%D(8JJ#nVK(7kFZ8reXT6(+D5~B+6pBtxo??CMuI(fmGe>|EPB67nWLZX* zq$mYOh5iL~7VRk@DhhGpNRxIs@rY1{K~P3}>5SGW6XX(0Pe23h2QnhWaqNF%49W!g zgs6$aJm+zj%}*hDK|r!Rx92I0&faO-E~@M3k=8Q32EWUi`6{WNZ+f0 z=h!I^?ImBzk)%zuXvAqB*w}jMy@-Xtq9i0R6$**5(%`K3_>STj=Ugc*Qc9KH<;G~z zG~bCU|660cM#kEdEX}+SMJv*_kHx07@_#37zu=Nf9F->%N#@8>4TNZup>X+JnSsfC zmK#+NA%j*q!8G3JU5YWPrpdUqMxRWCWKQ_@QwGwuBb7WwsV)`||Lm%0OQmur67NZ@ zjlpIe!+xNg69)zcd_Us*u2|fPfCE0@v&z>oMOdxk+O7Or8khP0^uO)2Wf&S#o8X*A z>lkBvTMLFD3`klnOc>-F0Yy7?G+POXqf&`-NgF8VMd><>0Z7|zp8+b#kbHhF9AJuf z@uWe%hImQ2K)Z?8W_l^HQrg?Z!M5q$*uR{Nk5?@2HUcfc1r} z&z*|jIk}wVo7`wz8DCy(=Hr+-Xtwhj#ex?GVa4Z!&F6cLd&f*~tK$GE8@zir)3rOA z^)vfzbjaFVH<*ifXZ-5OAL!^>RHl8GXp7yy=blA(2gh?laaIia-q!d|vhPC#@J;GAHk+y8&QckqP{ zxEJ=G`Cm(^L5st{&pWA?E<5GPJ)*EhR;he$OWQ5dH1*CVP!g~rwqTZJo@}D9UVn~t zjxdTyZP7jsYn`8KttUK6<@u&@D4>(k1Q8>M_| z&UVZBXanNQfnQEd;LAGa)8rO$6pJxbP8ERIeB`PO>oV^RUJQdQ^BY;n!|F(RsxWox z+Sk0O1ao#-;%utxnd@Qixw(!V&0Nx1mnHx7uFZ4QC*5Z{dO?|`3}u=5Xq$AEKbmJN zWT$Fc)6L$W#a!UiFT>-1K|xx+gy|<|;1-PO>~|sE~?ReUpa? za>Z}0L-NB?5W~_%-`ADlcY%KS%i~U!x^oNCB5}&A=885~8Q!Q*Xah+KqP%+DkB%d4 zjX9osmh-Nw+zVT}G_H^o7Q{pfvOZs}{#BU%8gv$N*Y&sRJzFL`6}lg`_c>H&a_wnE zm6w&C-}R!Xv+MU#OoN3~xijR1u32%GYn^x;TkrKwI7K~r+W+96!E3VVVPt^`c{5va-b~EwhDj##s zxw5I+NnwiN+qH9BF3-=cDTrw|p*-2hrEhN#Z=mHn%N91{;)zur=f6$n*R6cPO44@O zAHIDZ*n~76NRlLg9}7kEB$C^>TZh;t{vEeu0-7v;F97A|ybMSkh$JAACou7KS!w!t zwkuzwDyGWZKwI)BDed4Lfa{c_fw(pzN!NSlX{2@jcZJh<=S}GR{Za`oGdvIR)W~9# zfTUEbabBXx`d&~oZ_jE=GIwlq$;`*qGmfjSf6Ga=bSmgA+1bRad>fdry>ql{_olyd za5{;Z?K$RpHbtysQrq_Lp7K1;DTfuWfv~CHTq@(+d@^ZJiDF{r#?gl#(yu1IV+u2MfHM&C@#pFecwwOlHgjwE=VyE3z2D)O{bzg7x0NI`K++DVtkokqF zhzU^EueykHd0Vp$imnaR45C*+_m-XW*o?cM=Xi0h*jSY!sCnv};|fyL)GiO^ty2Eo zMYno~z+qPF>E}D)Q94)f+$ZaN@4AQ1O->(&Y1eJoPF=RUer9PxnKswDIliC#DA$sC z=5aS|?vbvwsk2>|X>HkCN7hq&VPo4}x|r)+*D-q6!LmDMX1MA^xS78%I{lU+MKbLk z%-(;qttKx8gu-1IOxHL~TAs9ffQ>ubFh2IgS;WYc7~sR^~i6$9&gAUZ)FR zjs-{aY(i!eG(O{7TT;JlDX7F15HQByleORsL}7H;yE|fnSvbSf*_5J-N%C0UvblK8 zvEWGSIuWB`t~&ERG*UVrdO_(izAs+LnnDp%lKF?h^jqoUh2z*>pM1KI>0bQIvg160 z3(uSv=0106mbqs9w0EYD5nU+z_;%_)8~;( zFa>n3fz~b;vgVql`I_ei2<=X498PXmm@bqgoEO#>3ee)Z1pY@(F#9+@C={tj3pJNr zkeV(jnQKSQVU8W?xuY$Atk>oQ*MGFnR-8ZFHT&qJkDnCyHPKI_K3cPQXF5>?T4QwJ z)%{A9CMb@Vo7el1!{H_C-ci~gQ^p|VPJgL@NFJ8U%Mh~6K{R(N*dr#Gg<@?k*OFcp zLgzQ9D#4u1lA?Qg>sEeFSBxGTTxqG%UC)u!*&k2G2glxyl9SA7$7XEK=2JY)ckD>d z9c}qzySD044<7&ekM7xuQP{1%pFT37ca)y0vsNE{oLW$HX$6(0NR(rOnA8fW(0e;6 zgQrh|w;$+cFfVj7Jm0xvEq^>W;zv+kKyX-{JCAygE~4rnNv24x5Gat$p^SGxQx3wz z%#%lDgDKM{U+=sCbLDr=`})NRw)qmF=qfkuSn=%Mtk|DbbQ|-&u7a)8{fSc#?Zm{y_@)w|hOC`7sPT=&ANM9oqjr0d)ZFP~pKKQX<0 z`IG78^AmHHpYPcK=PV`)y|c7dxGX~|!`yu5eQaE{iu2An1Lbmi);xTV4|z5>j+kJ2 zqS6Tt?1VBb#jI0ten_M{Tg=M`1*!9%_BkO}3aivHrasqLWqLwGbQ9Ux)aIRKw0ozf zr~QJiU(R+;9cB6MyEvK3PxqQTmbRFWcBryM?=j(&&vkziV|H@ceWtT1=y^x_8uUK; zIJr>_+YWG`QLYhRj$Xm)#Z-0&bczK zT^Rbz96mjqk9SuDBrd~w=z!E|ASlVJi6U&C)=au$Ru;0EQf^j6+J*e>nj>_96tNY% zpYJHkmxOeBdFi~_GhX=@TK*XC^=Qfqc+cqBw@cPq;yBLJBDy>bkRO0bYqZvcp`QuU zv^%cctkv~#T;a0@*(`-TvyqPv>Uv^J`YcF(9HnWBQHEA4@i88?E`x=)+wGV3ar!9H zYPHBRA4a8n&Mek3Yi*f1=;aUu{A5QE1UTo)@$^C=h@Ywvf@EuyRPtidDq z{Ft?qEvRTR1d~Tu5Cn3^s=3fZFpCZ^0{te54}YMPBC5tX1vbk=B4|)ijHC%Yxf`cr zIsrSCFrPrHkX0*{yWjhQX_kW4K4U^Y$YvX8-4kMwDz3g@A*l*5fTTWvZWz@d&`6SY zuG=H6gbvB<9g%gWs5MM}*u49k4jQ55;qn_6S7?UT%t00r3(f}rFX0PS|0IG!(};!FtQU*;&J%Z)~ZEX&Hx!O@b-t{RbY#Huosyj6;pQ?xRTRTWIU5K&PlqmgYR zst^{;wS}E;dpkqlf6~eT03ZNKL_t*Xd=%xUpF0`KYaAM5LR8MX#kEP(Hi;OVms{rP zPb8ODsTs9TM-Ra)2u+cd~o8J2v0BZgKjNl<(1zOxN)o%e7B*`D1-Hzsq)3&?eu| zIg2))nAB=DwDyBmn@%8jkzD>SmVto*mM&e&-o1OV)~DQ@7kw$&2}iLhFU+~1qj_`A zVXehl>obpZoj>U^2))c;tz4{YMnci&ur&jNckhZww&PdU|ot;AQJebF3zVTb(wgf0F;vALZG0SR{b>0 zsv<8WYlW1pTCK8i<0cjiF7VRKwofM&s=%kZ67i7$$m3EK*OX#6(Rt+Q_tMR!)f~s> zJ9o5o9nbRJ&nn^_dODd=0Ot_x)uc)(aEbuKlEq7AzN4p528_v0O@U9aTtFy-^_-Q_)wth|&@IfvA7*79@R>(Q1!zRw0= zv>|CHL{Wsb86u7_3>g_2Vat{+3=IvJb1T&ww zr7yue(J;mk$1&AvwTD0!Qn6y)TDNW;n>KA?cz76N3|W>Prsh6QG^VDeSh{p+DRDj) zVhK6D5uN`ppi~(r+6Wls2$W#7#b>Fqm|Q(?ox|l?7AdtYlncC{OQhVdLa}!(%J;6R zrMGse%{iL#(pA3eSl9G6Tlwkt+FKr!xFdcx5R_}8Rfeb-tpWlOL@NRfMjRT!Al|1+ zOsC$t!(h%-kryPVn*a?A46tS6CYBB_W@>B#n`PKQQLk1Zb7+A;8;o>_7xx zy5fPRHH4O~bF&>gO!-d39YI~kQl6RTbl0;Mx99RQ0;oXK&TS{H_}Ec4a4e|SIc?oK zqA2Q75ftcFn-|B6U7x`sNs~zR65Y(%QUW>y1^exj%ohlSQ*)~Xto7r@<&rR$2miGW zlrgN|w3(lO$1k#G^=dY4*?=jClq!hR$+M|CTwNzy`T3p=yqQ9pIHE|C<(d`&wrzWe zLkCA07^qQ1DpeGfh~FFpA*)xf=H2gpH&s#N-mMvR&)0^H@s?Ym)>5wD|-~RTux#*&c%C$}@b!;S4@-I z%FlUiWznjEQ2~w&Eip^=g&W zISx!TcK?{0P1xiU>+alX4QdPk;HUF-84<%@IvPe;eprnsiUbZ?OIdv$c( zD;>#Lp&*}L|E%{af-&9!%4e9%yz~?62`Qc|`sXjC$7;6b@4*Zk%-Q~r;s_VUNNou# z7uLD_^mVMLSV$ABseua!twLiFosntJkOLdw$?mB~a1@}Oe=9TNO^c0alnZbeQsq#g zCA2Lv6|k!T`zJCcG9jo{P)bp&)q3mfB9+~PEet~hXgh@pVnl1-;l?1DMH@3y+zN>I zB4KX1TOUV*&cxLnOx+{PG6YSn5~F}x6aeBiH(Fsxv1yA?dmA7_XMA?gQGJ{MC?N;| z6k01X3zaA&jw2e42B0uH7eFd0t&^O}Ggw41akYvGLKY4!!bb$o$7%U*p}IJh8x%Ux z2^6IP%=BTa<|;prj_M~GMbrgd{#7(d>V&v9fHKBs6;Xg#l-52%913L=sWPN0#43dr zFbLj$36%0-S^PCre;ghcbY{kG0$=o-Q;M)sCCRK`*Ye`W$}I~%Sd0g!1nUe|gHr*P zkiPT0 zZS1-yDdwFn;t6QgT~6o@r8npHGZ$V;Da6ts5h4MZ7|;fzENDe4c}=;{(6?iTr~pxF z-YxDC2U>S%G8LgkQ_V64(l#z@#=H#|-*bR<>^dcwj^hd0S7Bmtem4!?N4IAiIUnd-|1-C46h&1fwz)A8k; z)+LGPg-^QN-+muYbd#;=1d6i1q|nYDhgV$y<#pxsSVk+)TOjBnkHx0NP3!mW)REJl zrK`f8Pm#k=@+X1k&2(Rk>U3sTU&oIC2!HYC)^a*Ak zee}`COO8Il?4yqt4@I)bPR{RcqbFTR>UvDidb8yf8p4hpWTETuB?=4aGHvuxj8$K2 zM^Z{xJt`-ba|wS->Avc|dT-q`rL!jneS+CXAAR(3QsGDzqCTFpLwKXjoDkyd3T&r5kJcn zdTKpUvq_&|_R&WleY~XTwpE)iod5LS^wCEj$AXgZNkPtXrFr21Hbe5~ts_OsU}pK@ z=~ndJ#Lbl>+M!G5vZF;|_uskfEOw$Ix&5a;x9=f8BK7P_Li?g1Bj=dGr1QEHN*Aa}5>0^1eu~vjfJJLG) zI5Nx@ck^)V+uax4znMON9?jg_$22H~6OF=Q@ZR1UL5cG@%Ed<;NRyN>iV%EgGe<}i zS99gMmlSHe8@xC{6;WHn`MQ+gobmz8r%51Ho?^SmD&*HYf3C5cS%L*VUt29IQ;QunJ=FpYJI#Q6v5w%Nv({>IW6z+ zd??BlsoaWeMa3sg(=x?dmSrSKa>Aack3LRrNYAHxoQMe4x}NbkYYighSn3|HlBcb0 zx7+3Ko6RObKb7KfM!VfE+jRPzHy2v1R!_RiqHK|csC)h_>h8~#M+apz&RN6>S}PQm zKtq5q7`MU{jPhaJ{L(trfDvrN2E!^a*AkvtqVD z?*&Ap%s8a0^~RNDDIAoffl58>Y1`C)0lBjXqw!CXxxfC z&&HT?>=pT+i_A7@ni9t`X__9s!aj}|&N<>ZF6X#n&O986uT&}}VeBT8MZXmr2cY~v z48s%qFsB&A`E|t@4PtRwf^sRLa!A^Oq{%(E{s=uWO00#U!78V%S;;^(pxrn`Em8!M zqMav|p*Si=kfe!gx2S}Q!HS_dHp&Bc-@(Y<-58gmT}o_(Y5=Y^g|=;C1ClmNau`TP zh(*~Zwl$7xO%N-KwkeSjluP|bGPIJZF-=1XI&;pv{2hoyZ#NyHxQJ~S< z2UHgknynUTmJx&@K@@j+sUJV|Rpfoli@6A%)|w~S;9~s)@h*KZkH)(gCHo$skJ`Hb#WYgZtuSI z^2DJa`o-sPb7qmM*%(u1d@JV3Lh@A1ozO|~+{ckY@^?MZhEOYd-5R9?wq30PFT5W4O5L4t#*pSF}!#Yjb?+fLkAeF zSD2a{WA~1SX*VX3q{Yzi5ai^p-E0w6Vupu?7#$r&Yt6vG03)NLRN|QBONKZ!@;nn0 zQz#QqUogz#Wy={GJ;eC<1dYZNg9A0zu3kwpF^brX0|%a`*-luzdSNjVHF z9Q82dl^0#efdeD#eBud)7B6Q1$N`2HEM(J$bv*sV4n_|iB(uW$&1X`HU(FK_J~G*G>mhOtT~BP zBQAK=1w8iPHb!LDUVb`7S=1Q7+y#{5YnmDoO9MzYSoC5=XP=WhO=0Ax+j+p zJ^dtW*R1BW(@y99`|o4d6WdudG(>aq5X+YgvE{Ti*evDQ?GH0`U>_G<{2C68PqOpb zrw}q)?TpjbuVvHbO+5P0gN%>vB~*?_9=wN@%a<{q$75G0I z`}gnXLm&DOQ&Us4T1~FL`WglX2Km;vzQq^6_(j&PUF!)=7?$sXPWM~3VHO=$Jn!H58^Cg6miZu=dfteqOOE{&=rgZP^ILv(P;3MuY85?fB!}v zc;J54uV2qcKJpQ^ZQI86*ME;Y?zo*l_=7*-BOm#Q&)m`-L1%hzN$1SVz2mYhMPaB! z0in{+YLg`ijmZg~xa}6UjU7O0HL~$>rdFjKV-(HiBuj=DVw7Xw-rcnJ?&h(_A7#69m`a5O z7hjA~j+HBxvT5UKtX;d7k&y%3dE=8j|IAa|^z@UE3F@?stX#c{=IB0l?R%aDwTMeE zI-gn`@zDMEaPYZZOg#Q5+JS^Ii?*D>ri~j}ziu5{&v_;5Hf$mhP+=9c4`t--gT2#W zKTJ^{FB0-F3kVid=8X+)gQ@*H`NFq;%#ZGVgiT8;G!7nM<(kuZ`!D?}r*Al&I8dN6 za1JpcnHT~f=G3~B%Y3t!aES<^_DBDKm?bcbyEJ_Jk2F8Rwd#+MtNDNo- z8WB(q#Fim0$j?uVPts^MNfXPGB}=^eZhVYJV~R?p!lI!?gn>bDAe|t;KKn%BG}d*$ zd1wxi&fY}nx%=%@>`}oJ10{tvz~YnwQ5Y1hv3*?q4}U{TmT}eRuHoSB9sJL~{2RXh zuis(a`qNlASVJp|6GJ8tlA**hl^LQipxv0_p1ba1qLp&tg%?qY1D<{M8NTt2Z}N-p z`W05LSjzAJ{zqvx9VQI@J>>6#Q$F@zK-iV%B!8=N4_pyJb!jk>ug$66SNymZo2V% zT=~W~v1G|oc5L5H>Y!2|;HhVxVLVG1TD6iO4B51069>l+viJG@EM2;orOTF~;<^vG z9#j}TILh$wFh;?O&6_#cIUr;aRbqk;%yate5YoN4<6vyYh&0h@ra8qZxrU%_P}!8X>r#fyX+#t{O$khk$-WW_Lx8RivR zH}k#QAK(}FjIwO%AWuL32x(Ab)%vXr2TewHKh4ugosFlhXX=^9c=X|iNaID^ao0U; zK7Bd&-FF91?A*onC-!mQz4vkUS*xj3SMkj5=h*w)bJ#|kl`EF9V&iI3Wf?%TXU{%% z@7+t9rL0-Anw85}pd28A)Q+fB)BOc<`S6{Ka4XF&j5D z`1?>)<(}}W4!XQQy64F94Ar1$yHYKy8+(hE zQAQF7l)wZdGWG%nuUWIk_ImgA;>BtG__2+R7qiAM#=JNK1{)Aa2xN;Olu(?Y$r??% z6K=jIb$3<0e{}ab=Y|;}q#2Dg^L?Is&pF-I-PIL;`KJISK$tKQY8#0~A_N$15kgH1 z5`J#2l_uq;B?=*ZVjQYgBa6KVG*adnA3H!4dz_ez=$>07mOka0W!K(=w6%3`Au{2**L85+)Yg$o6wyf_WZi4h?YEnB(ls;hZ)=feygdluEbfNQSU%;4TVJhkg6 z^A|5-<(xX-yXQ`JY}?M=-~A7&s?G(ukneo!PPPr@x$B34@9UtWf_dUYM zi3$8-o-3~2ME|^QtgwuXj_~6jJ;mVQQM$U@xagt_ShQ$SBNR&<#|;~%a}i24vr6dL z;<}bND)abbPjJ__@4@qZCMGNRL6JAVw8pdH7>nu6BFYj$W&TltpF2Yk!YKwViQtgtVKxCh#KHH ziYU@ZDbV`4?bBX~Xq5~m**8qnz`(+`El*IdR++bO2}VG%n5TbEKL?LI#Ne?L*ox+J zpZ+8xlz88-{7;tqqkQhuf5wrHOL_mh-bQ?IFQdalOn8z<9{Dl8UdjHwd#P4yY~8kt zMFS2iS9G)IneBZ2u6wCWj-$euurk3NAAAo>Rxac5N1x!^-@cbhSYv!*oP0jdyWjmT zmMmF}t5T-#97P(bG?D7IScVKAKg_@1dp8RgzLA9s`|*NfB$#< zu7!N<8+UTUwO6us`7%aM3~}EN?`O1JqoaQgn>KHzucLsglQ^8)cOKyJC!ZpYA{H)M z#1)%26XbH|E+an0G$9FRZbU+6Su2QeIWbnj$(0zHtTSE-DRuQRFnX(jFk=(53?>xY( zZ+`09_`>J^hG%vUa`~p~c=XXHc=qsq z-uTwr=SvvBQV?qd)vp3WW~lFI+%JKEQPq;}-H5FcCV=5!wLXh4HcD z?B4b$)}6h+NJmj?ME)*ZYdW4Ed3e&BSv8#wROiYiVyQCekMaK`u`%tPw_a1_tJF z#pcWTx9>l}u@l3zIVTwC?_={VZ({M%e*EHkR;*abxYx^@-~1-#_U6g8<@oLowsF-} z8+q-`S5het^V!dSo^lB9`?>d^qKM!B?T_=7ul@@k`PGl|5C8Cw2psNs=N(K|D}3Tl zKEYSM@>PEA*M5~S3>yxA=OVyAK}1}6TJQHZ=~0O?N2|=XFvZ%`sU0B;G5sRmvXtr z4L4j*KA&T{^zvMof=y$9rfs@S`_EWGzEEP(@)gWkuz*sbK(1IsIzE?O-b=MSfwl(6 z@yHhnj87)vhK!Z;4a}vdcK|zbC-@IU56m>@pC!y zT>}g(S((^B`##n$(lvJx#m;`J(thID?cT?38;gwi-*;R~< zjbV%?pU>0Y(S`E!Tyt|j#Zo)c^-?n^*&?sB4g2cTf%63BdCY>;Ue1a}X5>W8DH9tg z^^mau03ZNKL_t&(&qG^*QVz;dw6&EuQL9pF%k$n3e2AyEJi*o<|B&IKTiG)>%8jqS zf!klRnXcj(>o2>4T=DyCzH9@x-tcNV%ovwmc0Y%o9Afjv%hKk@aif1Tg_ zjo;2F!NdI^s_Jjqx7;ZiPF@O_UU@Q7pGNSSs{LnLk23Tp($fW#z(xf|g4K5fMu zz9Z@D@8{OHzJqU^6Jz3%~G$$_Iwjuu?ssF1WzW9- zeDSOQ%G&i8GuLw)LE1%2-J8VME3ab(Agl#3HASM$>{O*BvYPhpzT}iKgw~+)MFJ^l z@93snsURJPD2~{X-S4JMo;SSyHIy6+%E9mIp{u8t_V#vaQ8}@% z)QJ^Se{VOQQtaBXgYNEb=Fgu`Skug#Hy5on2M#>TJ@?$hz?^>i`}+YJG2%u?M;j^D z;2h2Xq%~Mg2*fFGs>4a1+5Hqkc__b=*cz-3S+QU-2lgN0(BKLF=uiHXTrSVG*R1AC zU;I4xe&;@}zT!5n*myf%{?b45sZakoci!{w{OO;4nyWXzj=%ogU-H(szlr_(_VCLe z`87W9!H=@-$tM{*a)>v*?ftCZu$k*NUBX{{>dzTGae``j5*)#{?K^nmTkhb3i`H=c z^*8XzPyV0OV>VHZN2eiF#>)Xy{46pFX2Rp)`gx>OOpFgF3N0fT9~}b>`M||mLoQ$9 zjyvvP(Yyir2IexbU@?J`V4)TnJl{vz7{^ImjfE9y7%+uWaO~JIzWUX#@&|wL2V8jJ zYE~{=&Yyka6C65pkgZ#{a?d^Y@Uf5m7R#5fV)N!J`0|&(%#kBUICgC4JW~LGq{)sa zOQ&)J%9R>%Tq9p}utwl|K3?E3(BDaWUUA9AoA}jV`3T>>^Iv%D+uy~{{Or59>4w$h zJP+k{5af#VwigL}52;*KF2Hqt5Dv<*K#j+K^bqUUZ6H#X@zG;BwgOwij$Wqf# z*Pw;V@Mwi{XsBy}P(DKW42_l9{nU1H`F48x=ivoK3<@h;A`M87iMnPY)Py+Ht;5h{ zjj_pySov6$W4xvrtwzLnsC(m<%no7^<;B1qH^-HO40^i8Z`%k~g*)`;a)9ovv;_FTp&I*&z~-!^{c8Snz@Z zg^muMIeG+_h&Yne%QYs-lXP`;;|BpsxwLopvH6nqJhk&#q#sbJgtT`D=xUWn8-|8P zm>eIcqtJ#kaf~2ez*i$+4U^?bjvX6h>y{_^_{Tqvu^w6o@@;wg`v({r8e;#m`}v*U z{_SLAlbWusF1ot98eZh*uKlG=9drbSL@J?mBKfM<#?TsK;~<4gkn_>?I#wr~?t9<= zA+#Rmv8Vro70c%%sy*EB>f8C*cl<0DU)INKUUe~XV!z04^o+efYs|Z5ClcGJoPv? zUcHWJY?5aW9AxFn<#cp*p`=TFa)QSmeT=?2^V$34kNCgt zDw8;qbppSO_RcQqdWc6Jeu(ewIKuZIe3Xv%4yu(&man`3Z9$tf#x^a{$;2z2$V{ZO zBBQb_Wc_DIoS>AKM<@sBCHslRqK&55*@IL9S31;UjpyaL{EDl&^zthS!-)2d4z!U- zl`wu`J;KlBP#Cn37$Gs%;Q9fc>nE1G*5dgA+8UH{QA$y*R>4>z42}|@9IQ6fBaM;@ z$4e!xT7y)n?Wo1`b9kOh7)3}01_$ZpaFjxmbggJ)Xh@~Fq!QiJfR~iO%rZ!1X|A%I ztuR$pmSu^_G8bfO&{oVA6#P710Frn>=t!eHi9}Fr>tw;=RXq5^Z44bc%A#fSIe27{ zY7}wt1uMzt3dHp)-@fykRAiAi|Lj|N@`3Nsoy+t3Td$|R&BxRxDHQTZ&nHG<{TyMn zM!i-+hc$9uJB#MeW5tRUeEj1dXVpb(h%Jm)#?U6@sVAS{=;5RM@BjV#EL*miFb)|T z8^iOwM!d`{xbe9uSxMAe27^Q;Ylr|T4aPvRR3gTZlafM^BbU!39hYLU!293-^Ze1D zZR7Kw|7!-iFXPp(y`9w;&BYR;jUh%6MKLyt@I8kxj!;Tc$mcKyo_cBvk3IG%*Z-&g z!Pxi+j^i+A&P=^^R2yB`_1#h=xI0CI1b25&aCdhoMN6^bZpGcTxNC8OQ?z(-D^lF` z%l)qJdEe*XtTmZQ&dix}u50h#eh1^gSX@J~#Gd=^1l;ej&WyS;3ks;by}f^ESDq}@ z2OE5DCw9QqnilwbFej~``{VaPELr}r^|-}A^0d{TINm8R#f*u_TMEyLT> z)$z5rTUxr_PEyeN6w8fn z=S&me?A4M_X>rQ&2mrCAxrjaAs|TTo!{b{&F%W==3PiH}l4jM?S-{RLUOE@c7~G-B zE5n$$a?P=OzxZ9GMFL0asz{d*=*7pXg>+pS+QgLrCp->F0us)?5Tcfd z(Ly2{sn)G-s>Btt5ku&YfRj%Ao;^#D>k9C>xlEx`Ig8h$S{mB!@b#;Ae8dd;X990& zfMt2G(&E|(=GUCf$=Yv8MTD&8Q*#D-4ep@-!Va28)w*w+f8J;Hy!iM%+`T1xb~gK>t$hUJEdMeCA2Jl$~$@b+=}cr;j^3c|WIjJdui z$lcc^Y;F(xJ4Ab&`sCaF(W&Pvi|f#ryO)5eZ>Mg5oL?##bjB%}VF~Lt^A%d)wJE(R zd6EJ-cM|du7pjWHAM*?r?l?P|q)P4T5?~q7nJNGep*2m%=#515A##c`ZNlPk);PKH z9TF8nccp5aBtzr^b`75GM~%uwY&ckkI`PMkR>N~D8Wdv6U#%z>bRWIFkx{(j$VG;h zmiS>zYq8ZUvRHd4cDCdp#rOPi2tjnLN&B984}0}@NEp4_->KH_`L9YV^ECFZQd}@A?Dt8Slw*S2PX1^7(Gk zYP#EvHHL^!fQZkn+RZVUux~^ze%GJJ$5qeWB>zdV=ba6g`39@xip+10sJfk>(NP6` z+D*509iOG}bXQY?PN_~1rhF~NaxvN33NtfNsaLni9SZ1?jN=gs?&%e!dy>h1IJu7E$va2d@}%yyy`9CVKkR&I@WHzs#p3QDIttv zJgPZ2XJ*%9zh2w_j`#qcC8ISlUrKgKuQ-K8S&79-tmu)A+SnDjR2_vXvCUJQ=FQ&2 z7_vMvX&yrb(LmDA!V+2jvixmwXHb$6c@EjEwir4DC&u9NPzvkow&QGkjaSb%Buq9R zZ75;(-9ReWV!Y4Ep@etxJn(53AlUsDe)|W@$#YexO>4qz_N!{3ikz8<0wEjCdSGh3_#`w0xZW2=B7<|sO?IPC9MG}&)@lN^10><#c_pF3ADntG}@a< ztd@}c%YRk+tr<0w|AeoLeA@R)OVG##`*&7bU3ZQ*CJGKcJ%(LO!57@Ta{Csz!*g7|L%h`8(0s^5Naa-6262 z18sVGRetQ?d$I#EV;@q|TlblGgyZRjRCdi{R%0nO!L~R#RpxhzsBCTVRtjP<*d&W= z+tBxCZ-d`eC-q!&spC1u7ix+MSvV(YK7^+bnvB&}8Or@_#oiSOsoF_3{OtL!a@n?a zuzbO}S)rs6b*mk)GtKA!{><-y`bbT>nPeO3J*-$1m#ksWYW?lI4jnTWLTmpD2!nk& zt$Yv-?D0P1hao3vajLT%`qLz$fURw;$0{W|OYFv6mH}P2Cs#zzvh}jNxmNz%R4RE6 zU46F84AaagJqV6r_-3I;f>ZSv;RM`B=-|OmST&CN6GzjpJQFJe&o(3mIR8;=Ae_0e%8_ z01|UsMtwKJ)~;@yJ5LWxZgP<^^@3a5aYP~*jj(SX=*uiESLSO4grJy(vO zz0Q!9d}s9I^7w~px>h}53(Y|%zmuZhDkob)cYc@$7e&l#&O9D2ahRRQV)bvm9IyXO zdipxOqT8PvZk{h|Uj->%er@b4Ikm+WMzvpdkb2!s`D0DpEY*2&z5QGC&*^!dFu9no z^@T;HLywK`1lO-i`LJb3EV#SRx_-xc4pEKFdSz-ZP?1a$ApTHUxG=)pItK0p%EK*u zS5cfcW~PczwQWk)%@~%j7~rf=lY198Ps9`v3au}m)D-P!EKH51jiUZzNUl>3ysJ-! z|IE5f!UA4ufL5jXb_XQp$0`vEMjz)Mixz=<^vn{;@q_9NrJ9khZ?3n8A~i`sSiEW_ z-pcga3-3RuCmdfR7fZB{zL51qp^e`g2Vfw4RxM^Zz=EXdlLez;xqRevW}tFL{Rbec zlHbO|B{64?b4Ff)xHr*0okEx3)lpU;gUcH`hS*julJW8+q#=1ZsS+IZM)esVEsG-c zZ;4ld|D+!c%7SJPk)3d(lmRo8_A(Fz>w^Ynq4+prW~CB8CfxW`hvYPno1jtB)9m$u z!s%|3)wL>w=l2@13v%&#BrFcMvgrE`aNa3JH>Y*L*CpPOQ62bUfg~6Ur9c|;jc#aS z>~5NFYnobPxLH&itjNp`p>%9;v@dWjmRyqlm(Oz_7fzH1FV;(>AQCfrfb(78kUv>& zcra@rWUhiZNFBp zVpmkw{(E#%Ktk*qisOF|RP9K+TdoSL4pajp-*enxed31i&r&=& zf1Fgkt~4a@xWa7-V~+c^_1+V16aO-TD5SceSdNI8JGDg}IdIT6iT^!drU~BN5FRU( zLozX>2>k13agcX&kh4*f8WFufo`wLm!wfGC2j`)}S3T_R%Y)I7Jsj*SmtbjhE?uBqckF_%+CW`d7XkVc=n!f{JvQ0@$j zm0pDw4Cu2nN@DHkM&l={%E!FN|1dWA1z6)=K7U;97FiIFIV;kdg6%Z&kHphTdC;!n z--&88q#eY;t%1UuvR~aGGv_MLc{60kovKaEO-odgLWvd>vW2A)F|sTAOUUX#|43}_ zp?Zo(9<4tL6ykXGan?dZzC@2j-GqJeUEnev`V>}=4LVCw>Bp>WAQ}y<_;XH%ggdO5 zIvx}I9e0o;R5Ca27I;>s9tCrPky4at*Cvb;{yjPA9rD(udK-m*0}TZD*63LojM>OY zAOFljo=9bL=dFyP^IJiXgh=2G%9q4LOq&tuY2UeL^MAV+HB*3prveE9ZyRf7ljYVm z87QGkpyyGeD8%5=rT7M&zW}x3cXodKHlr-~G`i;op464@j|Z>TA;|>0t|3Y!a*z{q zxoYF2Pr3bg=B61heS<$dPbP?l1OZT$CXp<~SsBbrs8tE_|)gFB&BV(g*kF8Rzs1yvLGb~}}y|BMY?#H63l3+xN zmCRRzLbc6Gf-NLN8le4BcF~EWoejK^!?wjxt-}RN`2+2a89f~O_sm23%!rE`0AK{v zeMl?OceBi`iAUxzLso%;hb&H?D>=JH+EXI|lr6(sIJ-p`I0C(IBeIBmuTo0dIRn_E z(!#(7v8zhu|9NL+PgD}2#(>(M{eeyvq{<7n#~K=4-(&2B^y^xXA=y!#z2nUYUa%L| zp@LV8`#!h6EP)ql%95K${JWDVT{O$O=ght2QXzOjznEkum4s*hj|U?%S7^FzYMSCp zPA~AdPTtzRl2|fTK)&e@c>?X{Z2j6&MR#ldD&VoPThn-IN3`CMpCqIuRr$zE(AgTG zXjU38OD$y0ZOSgGjx6QZ=|(t^q*b%hl+i7&PEN8FnIq)oeMU}q%;W9t)8>7J&zvLn z-MbmmrERgezV>MirW1t`L}hYv@KT~{7FEaI%V7<1cumn)Ehb3fkOp6pjmmbl??#|U|r4n<7vM{+!ycm>A!Y^Y9~sBLgO+?0z3oYXsv*)I{W zTv8kgIHX8m3&&@YL-qm7U? zC2C1}l}P#69~5Ny5ZCDzaJM{2ob=f|p-z8TWe3)?m0=A1?2_3Ki$wbX)nfe@tSPvE z|2Z>Zc)N{!g>LbXK{5+kX*5=v47?gv*uL@6wV2hkE*sMHUrTD0QE(_#@F0;Fs1}#H zl5PO=d5=UPX2ctbU5&CdH&t(Vof4+wk6vl=I?3FUhJ1i>uc(Z;lXAm>5}7}mM_mKg z;zGnBp$*g}ln9bR^>F3BRp5PXYV9j*$aWbHZ&v9)cjpN3W3u!nTtFqBdNEbs?xEG+ zT%T^GJk`-SmJs`E8|{0UwD__+`>JM~koX_&aRK5bmI}Q7WGQhJN%AF$&m4^9>5xZZ zWO*8w^U)JH+(&A&bIV6X5Od9Opi*s}T`w?0ONmEcrua#hDz9n)B2d;x+#rD4$h=6; zf~W{Cxl*Ura?A>YiW-1QQ3j-C*{zWb4qlVLjsQA~k%~w0ju}&|Q9@Eib3bS5|5?(v zuOGbmw%r!S#4<~#BTqx3#WP2tr14`~9s!hT^QlPta7jqYef*G~y^&j*x~Lm>R@&Sp z1P)&Infj8w(5hTod0bImyQ+WIsOSwU z^_@IPJE$lZ89f+{v#MRc)|nt@n$=qbijyk+NZk1>Dxaz&$8)qNc$)lV&6ozFso$d| z<69&@%jEWGiTLDYjC#Bgu`=JbGgwKMUff~4VQ;`dxROOl&wUJ5C zRz8{fli&;x4HyuN#S6-7aio+_N5nR*_l!kmqT~s7ZnXY7dqD?;&=&pR@ZgFJa997? zxr?)iDW2VVW}H2LMW2ool)OE~c&8p)vf#}-Kh0(39l0XlutkTQ(Mz2$r+M_QpCox+ z7f-)9Cge+e`R^I*AodD+x&R0*T0Wtvdjvj5zkc%Qkjkv3cBy0p0is-Hh#Ie?qSk2M zuVtNTW?qd3Ecavi;RZE#rGNbt8qcK$~Tki_{- zxKw(msyNZsNWU~m%YMbn)_arV%I#?QcT~0r_wH5ir-o*DdY_!RhfKC{I^W#%myiDa z863xh=nahz4iM+|JnfKW&b-p^J{(2R6F2j*s;rmXUli47Md==Q%XtDjylh4EcHYEW87+f#*`&F+LCI_ds^=N}u%&9Npp-)VHs`9{$7nw1(UqG&H|LmbZ-+UZhhvqV z|Fjk_5Aq&S8CkC}u3hdkK9JRFmT%m!)U-e2@Yb}aQ@~QGggamCAaT0`J@*nd%kBvC zkQBpAuzU%PLd3*}lWSO@gh5K_iWNcRnu2b#j&Lb6dt>&vXc^7}uT_017;5dFlcT?D zwUmJT-QPpgmu?1_?uhW2b((D#WHT((GkgB$N@=noFDmI%Lr}S_(}7FJx#7#L>v52x zez{EuEd*f@JxC>9CWMm3Dx`lTwRG{bMHK^bs9pQpl~?N_7B?-H-3Np8 z&)ge=DrgyGgL=wk$cy~OdpM>g!ojpfV4dIp?Wk<-nn+O zZy}t@gs;0keva-1T}GI-+FXw&e>Hrm?Q;o@GP_lMjbUd~h>8w>t1@A$9WSm0R0^_2(|m{`FlE{cu9RX-uhpWrO9bFKaGWcwnyazK8qO z$ajj8lm0&fS3lAm&|+gRCZ;)LE39hT?$re~0}|loQ|S*LHEDh|hJUYnn>Oo|Bj1BY z?o1q>(lOxuSUAEf0|Sz(qlj@2uPvhBc7X?3>FxjWhEWGj;H8rsa;iIX)EaJDb7qCA zp?cmbW@Sb~t1s5aYk9@bFh0a5rZ?YHo|k0B#cvtQuwVmgETXc+j%iW6-4pK@Qd z@4?R2+ot-_cuGZjOgNa0k_96}<7_sEp@i!7b>H5oT14F9b&PyIRvz4PaC1TzSPZ7? z_qTZ*Mg%Z|8v~(&wHYN7j}WX5>x_Q3euhWk3x|j!9FT{ z(U1Fyb8sbwW6j_n(&>u&s37;6f!JJ?vJII{ z1LA?tLDLT270dBB$ZUt?*mS7PD&+5VZssUTHoC(j6Jps3AIS?xGm-1MpGGJae>Bm@OeR21^s>optB(&CfV-romlVE%uW-+`!%DS>#twT4%jxg z{;4?cZc4Cr-y;55!qSxi0rdSXT561vH3}ZRW6ithOyljgL7JKDI`BOJ@~NNoT@2R|vKc z|1RPQ+VJXh2Kq==NZ5s~f6~h@!zP5QOXZJ!NDlEFD@I7wH87M@K0LUZ9iNLnbVCJk ztiU?$I<#u2Ay^@5F=dH^dSx&4DG+KnJ!ekzgQln4;lsWdKdJm;DG{`pAv)i$f`of| z-G3uB^>QrlVXeTyuRycrv5|8Z*>JgY;WU_Hf{uPXMkO_gyT%dWlVf&5fmzt_c+=fA zJG%{Q_c1%CFYKconBPv(at2`jkJ5<3Twyb)W*&QmokKA2_~Aa3x_c*(BSf1fL=rjD z0^u`Bm~tNNhbJ_v%lby&4-TIiP$JStFI&LlDbu z|BHKLel;$mmiGZc8w~aT&=-v9YI{7l^x&q~Y)>l^N-e=SIXTq*K1R{89?fQAX84`D zKuAJ~HlJr)uNpE{VRN4yvH-^#+>Wr#>$VwhP3O(iwIcHnod*X&pl0Nq>5ef$jN`4g zs}UD|dL8eD92S8Yt#*^OjpwdDkragHG3M0Uwo{BhAd*yuR{ z$&{RMO(_pqII>T|#+KPt8@)Jo!4$iR&UVzlSZ^+|Ot(jXOIa->32|ITdBvg}6Cdu@ zrF`mpAC)#T=0!P4&shxx@~;#mb3Ya>AeJDFGRp*bhI9EuL_tyZJ9WS% zUq1_~FJa=uCSufO*uhGTW+8}5+th>>ho<3%XDk;Oomy-9ONLO5J!naqzk9fZiPd!P zIaEBcL6xMx?o|{^qadk&a7==-sbqvK2=V=MXmF6((Pl|(vio9>Uis!b zHsyD^XY98x@bLrZ+Qhq}0s`4c9r}rL%2sVG(jTFbBN}5+s2mket}aiWm!Dq_dA5Cb zb8|EH?xih@sxoJfA{qU1kvd2jkGPP54((Vs0f8;g>rNYe`oYh4i(jjU*r8mzG5{FG z-F*ODE}w)m|4T1X#Z&W+7Jdwc?EPTxfQLte@3MJ6gXMa*=%oO~$IvR1R+2K~t#Hie zfb~;W-YTQvz9Oj;A8*vHU80|U&scnaU|IFItmNP9k#Or3eiR52tD#s@?+N>*|IoL& zzNh>*2q##jE}$m63m0UL90=#&Qk(>=WN(sP@dvwvY3^2InI-|x{sJt}={TVTQ4+b? zI~vvV}k5l8yAN@ zlXYfltivaYQ^c%=n>cKy+%2sqfwyq}PAt!&(Aer3sy0?5#bH93cZHSk8PN^<4ErjXHlhLvZ9*TS% zro^i`jvq&`btEDtmLrL!NxWe{ZUm+oUNZgicO_@Tg1z~@tK%r(lbNi%J63V8s2r#D zaqmwR^!^=$$l#EoL$(1}{if{vaViD|LT(4YcFwm3{tNMo97TEg;8rJD|Ls6Ij$E|= zJb~t9y&fq@xINeS(Os-$9VXPwl2SeCUG7Gu4o;#I1Qam_%iUi54#s5f^ue4t=T|vf zn_8D6w|;%RVcuxMrcWFG3l0BsBi;XyD`PlIoM5V-asFD36>x^YU>+0cf+bzw_cvY~ zU^pf9m#EUB&^uy&b04md0UAM6o~THW2z)7um1JxNET*)HOMvWCz?UV$X^w3n>Z0N3 z7MAhFL1;|)#hTKA{rUB?s@371-3li4N$gRP16bT(y67-XX}X!qt(f7ys_-xW!QnJ( z183y9A>w2*3<=7XGia5Gx-pgC84&@#Wk;)*}^)4=nI)HNe@hmnjVM z>fmOM++)SVEDe{}ppbW&qWdSz!^&Syz0zz-*`8I@yUYLjpV~wp=)D$C=jYH-t=Zn}8^DVWwYzDJMg2%$f4KVdjCg2x$b~HQ>`8NM50tgFjN^8ig5r>M ztk1jA&t9xux#h))Ev}m=d>o+3SU&?lG)(X5eV`1RRD?NXDU+%gsXw~t|Bxjjnn^5p z5H{wwKIRJ;2>*WG8;r>@?JpE~u<1EDZi68pTA!?oi))}nW^c$12j2LDK*sNyY=en` zgBQhobR^a06=Y6`%BnwJVWptk_K9|neS73$2aK0}p~l#ZqL0#4O_LH0q+ZY>Q>ioE zqV8B-O<&^fv%nOSwfV|csa-n+BIvtwag(vX5ftQwhCxq`fY><3DB0R@jRoG@K+@!9 zs0+Mo5gC#rcfY>xRFQFQ5j+4d*VQ>2h}p~=iSm$+c(RS$-vwx+x&Dp7o=2l`CE#qe@6{Ym<`A@a0K7fgHTpUo@>%wWyRd2*g zAS`Bjm}q6_c0;E~Mtl3Ie34DQ3F}~Sl#saWhz|sW!LoMG`#t~?_(dVK>@Bo|hk7W{ z;;4kdP?=5s_}zf7&c#$ZIKR!uFA`i>Gh5RoefT&qLTg0r8BOmtk^6m-aOWB8BM(nc zrF}3~zdA~R(stx9v7^W=Xyit}-cqF~G?Q!{to}VBF+GU;mMka;YWj)|j&u>0MAsLT zN5;lb&t(Cz;$(Xum&yQhrX}sHp_$UA)zEYzv^I6xU}aJ~I608w4{Q=u97k@5WS6=` z2g=4({Yt(?Y#m2G%26{G+X1e<(&Sw{gF7CzQK)#~4!>7-TCqXHLcUUrc#&`@HkMv| zTyR4vw!V1jBoQJ~(tdDGLA21Xc=g$}wb9P@58zX^Pn@9YbcqoawZ`0b#_qxyMYsjc zP@7VmMwiXlAHKZx4@~>0hHdu5gvM<+w7{CmX?=RP!ccjIpV!PNX-}7-?~+6LXZhnK z%Vt?)r8}Z7q0pGi3^EO>>H32BaSs1iGL%qrE+p<>Uh|IvYnI!>e%`RTn3%@%uS76b zWP3(4Hxai3j$4Fc@65Wkd44OG8SjX@9e7zWHACbK_EhR4Pn>X}B3ZM*$|Vg>8=^5B z3_9lSoP1LrmT{SaMq(i;rnEzVCIZ_c-Fk14*G8nnzd6CzSHG#1@Kjn@Hs3$-pMpMZTpsh;YoS%Fwa}?`3W= zqm4C;SWXr~GgIzituNk^hG!GdtBH=m0mgG`a1Ma3n1)J1C~~}~00~QYg8g9ESfK z3{noblsY>C-e{RZl84?Y+;lcx{VSjzJjpb*OFXuGF&;z4ucC!}QX6`Bg7P>2+jZfk zn#%60m#XGl=Tf1m;Gs&d7OQ1~A;i^&KI<6d!}vfnV9t5RWyPVUahEsv3tx)+mkzib zo$~E3FeKIs!Zg~Hp1^&)} zHpgvh`5?RNF4OOr&$kCVFf`0*ftsVA=Dl?OUvfibhdau#D~^7-2XcK7qW0%Phf$J5 zZrX{^T~{jICFg$_+YJ30C=LiikbX&6N<9t>7B!NexC|=9s0)DiWzE@p%T=P;;9}4) zYI?8H`}x_8opd+<>d&`+UIMlElIA8uYMY%f$OiXFJbFY`p+=jx`07$U%5LQV=9>--gFG)!_v8igcy0Ge@&#?0&hO7vj7JRe!Ib8Z43%Bc>5ZWeJG zVW)8|GmqWLtBIb{&wxC{*ai?xOv7{9F%jVrn(p-b=aD=Wyt?k4)1=Q-Hqx{Dzs6~6 zF@^M)LhD?(u#uSWULe-1D?ZXeEp@}qzLb8;-?D@Z1r0?RS*w1hiw?G9}A(@&hz_-h(eW3KECSu-$Db$j6m z>H-j$P2Z6){z5gC5JJyeoA)3ZUZ>UPX|LS2gt$O3K zl^U8|`QK6h{}-g~pmVSv&@cDs^FPnFQIZLptW>_w__nOFBa@99$QKoyPNVJIe_g01 z2(K+4GA~w-{qz5v^#2@wJ|4n1)H{*L$!Z0#p81D5wI%84J;~!0X%FxTJh~p65i6k}v-xD2-IS7?CiZplfBrw%Pa%!v zqeW`m;<@(CGo+fT#~nWWdnD;iKJQ8#O%<#YyH0gMfKD;cjIGclUbbgEYhysA#qp@phK=-@a+CB!LC)C2v9IcFCt&W zwv!|ZVc4Ll=NKZnEP-<&(}+HfThi=Rv`V$tq~`^-@AF;`Qs1m_`%z6*@hZl}a@bR6 zu6lz~_2sSUb4Vi2<=unm37IGU*B$fVDTOwn!_+@Yc$r+O6;*+TiJXKypP%^#wu{My{;ho`cw-R%=!*gkGY=BQll z))-}HW#_9`CfdhlXrPWTE{67E!ZkGm^(6I2%veO?NST9gNY@KH4Fwc>JxN4vL* ze9za;sL|lyXv^pA;mvx-@R?=+5JyM%Jc_NEvagA{QZ<^E4@W5xhH;s^M6{q5Ziz%{ zET{|gdWk_2qHmyoAskwt3RD_7xI|+mDXuKbTBuR>px}q*;@ZTU$+N_HT})G@8ouzh z7&RtjB(YuOP@HT-Ga9Q%PkI3oRp`0RsKV+0YldMPAhkA~M3$YTq30Xg(8y%6CE!9{ym{=P}c4=tX2iMhDfTNe{gMwQ!@uddlhnT6?aH1Xm2aHlEgpE3_(qXjYzV^yDopXv0$9rC7oIZXO{-n5uEx4`{zfv%t)MhX$aJy#hhRMU__)(F{5-`S=hS(N>%D5iQY-V!AD$ll+K|S7 zrqKFt{JSUZ)W4LOFtLIkTeN~lm5|=GgPi%!q2 ztP`u>Nb8!I)`>s>6<`3XB)JF((ZCB*mBMonrUD&@=z=P41UI_gg#LJ4VbrX7@=z1} z2HPdR2jlI8zF$G@ z0aY9TWOZ-uB^j2W!wk-nQo0Z~W7WE)3PEtigGZwm< zqU3(>8UqI^HijXCXeD)F70M9TDAlxKB3}fOn5x@CumYU@X>v1fy5`QqdUoG*x@94d z?)(bs5_85Bf@S-UR}uoYZ$^3W#m-vG=2uqjhK}2|CIb6N6tLjqg0%tDB*k1S%`*&B zZtmt8@Imk)SWq?Td}eiU(*m$u!t1lIiqh2d@0Fl=L_4%x`WZnP5W+$L2LM#RkXTGI zg;~E~jzxspO@FZVeH@ebX`|3(8*4ey)TBV{c1(o?b-_I3I87Tx-GV&;kJI7h6B#Kg zVoaSbEohjdgi@NQ^~ZdXpc!kiel7O?6~GLf1W#*7N`FJ*#|jS*#-X8QC}Gg4Oh%FE zO@#Fg%8BbzVPZMnk~LycKsbtWHX`zi@H2~BEQE~6c&z3dp(1nL}O&4CQakR z7*UqM$B91<;Ka?RWok1P-mHx(d}**EQHX6({X$`}B#K0rF@4&&K&Sv!-NFreF(q%R zCMldrAQ-!tp?q3U762x5D8A0fEq|ZM&M@;ko90;Cwt7Z?=joLU-?ZJ34o#}}C3lQ~ z#{x|fFt*33q@+Y-!9J9qJhpP@`Y}>WtWDrSQYZ`fz7p9tv=+W!(y$imo?KAL*3Qn_ zyaiGiMI;>c5N}_im|41uLW}dEA9ZFW9?Ij|-J52bM8xE)&L)=$-4&rX`>0j1dx>xa zjv8YiE&3q~qSyqngJZ zFShW?9&2q+@BCi!^605cD@b9|t^Y*)Knb;vM!~bTwvS_)L-ke9QD?v-A|osQS(X)d z>k*|yd+NXWp5W%jbtjf@=J)Rq&BU)g$7`RuP6aVw#u+J<)9vN5ysfZG?M*P)${NuG zgWaecM-IEh_x&a;w)lUv09CZH=6n)N2!^lZ6FLKbq$MpRxovZ{L6}A8>hd<5hsoSZ z7a|lO+6Bo>ItKhr7_q?q=mvh{4qLLQ7>?>fGqu#d(I{o+etFlD89tC&iQ8{8fn+C} ziFjT!)4q2bG`RFv0H*p^HZWis4^Q3kA)mL8H7tl&K+G9}&y{`{W0`~@;gR*dJp;ev z!_mSUZwAgxreo{$PHt)mn=MQl07%vulB^$w;7lHp$GPxOWW+7A;P%kErIS#ji7aNy zB^+!{vq9H3dDEPF54)7t0d$@dBWJwXTb2Y8M@8( zv4ppx3LCwYFls$bq(u;=IAm)<5!Uy~*G!#b7Pkp=!Tz=6q%e5Y6@(_RX#O>Uo? zCl`%9@l?O#82@QagCEblIUd1}GDQcGV9I3Dg{V_i!7QHjPE)AN#$8dRlW~fd3+Ct{ z1zZzu4{*(G%2c6!i-=;z(xqbfNW8*9iamk1on|GB}>>_fVrUTytw};y|GNWXoo1Yw5SW8 zcJt)oN)tE!Uo^+8R3g?r+y?42okZCrEE$C=)E9$PheNQR3l#Z|D!amzL@orP${42X zI8Bm#iG@-Hz{W`|j)PLN7Onls@}>hPs+Maq?4qKv7>#9?D0m(%+sq7M6-9=~z`svw zMk?Z}Gauid}QY|JT8rIl5eq&Vt0?G^RB zVXu3w3K9K1ra3^$7WNA&j|6)Q{?z4U7k8ji(XY&}D*0KIlTm-AX=5GXz!L%n;Y<3O zY$2co%Vu5w>ii}~7@^2|wOgL_ymRoH07E=bhXV7aY)}*2Z1-H>59t;%n4hh`2w#pA zDXRS11nqTlNEU=hlf-hs(FnVfSbTzr@IcE~kx61;HN{S5g82UY9mcsve02*V(Mz1X z*9jZX?L#B!1R**d25Ye*z`(SZQS~6v01RcLBJzUv(_~2jZ!mys?30w|YgC};a!>RI zZp9X{TQ0V9%T@WD&HbN)x4<-G!GM|gQW8g;5a(RFYIJo#2scb-knI1m=#!D2Eo*QL zMX%~3LYFkJK5|jMDOIS8HRd=NDg% zp==2|>juu%#slDU&&*BU;>V;wdCSXsqHpa}7tb{ZhG;`Xgd8KVNzY7FE*lB}0j{W4bcJaTI@fB%+J5;} zYws-E0L(BRuoZ;m|L4ty=&HIDpd&1F!q6*>{5>th05DG znEdhdMfiF8gXTC_w$Qhzr|w%VWipW%Hs-*l2yWSBqH>z3+>(4WX{%4%(GVthUb=Ec z4la+(CeBbN8c0DuVP>&lbnG!agic4wijP*~*mj zC@WG0mKOTL@R{uF>|Byy313q*gow$mUa;*G?Cl*%jX@y@{W}8adU;VyV`9juD{c)h zHH_05Pj%V62K(JFp?O=!OfFy$px>HTOBlrB?7N9M&^hX# zoC~@ZF68gO5-v`b2FD=!n$>|*C>aU^#rqOop4y&BF)x1lUk|%C@o+4O^%}Go4Qg&D zkx2Q>(8t@ z`1meApd5R=Uz&J2L8}8Q^Lx9e!_53Jm4JZ9HN$vVYLfl00;%vH6O*%=3^+Ot?#<0K z=!Rczw61S%IJmgRw?4qg5e`yvpvFDoRCJc28jZ=AY+AsFR2E}Jsu2#~d)kVd^u7|Q z`&mxkd&|m3kzuS z#h-}yNs5{kzQ&VF${*dJ3>HSSa|@UBc-G0kcOlzCqC&zvDT>DgCq{6Usc`Z0M>Lqyopn{@WGOtuR9Mc*E#OzS$r>nS>c>zj$fyy$SMP-2 z++_vi{S182U(~DA9z}S6!+d8mI9pPz2Hk}MtuJt%eMj88B(s5@V;1)2K^gVP?zGm+ z+q6W?7CRO(-{WRAM{pTNM=geR*XN`RG&E9=%_EYCa7p{w<+{{ICEXJXXcc};O}g5? z`SttevN-58n$Nr&)BW6aNLPCHCW?D7$+i!R+H`N7v=ozv!dm zvNh`?%Wg5>zq}Jc^MgcD=RBM7HPu5wAn>OluS&- zy36iQTTi9rN4K@ImaeWXuA5<^nj6QHm9O!;zl|3@tw0NZEpmCkl1+&{5dG_lZudUs zz3n_Fqo2yQ7)Y&#?v&k+rM=RtkY$KJyg%-MgDv(ej4rPya}={hCNFPv>c6aN$MAa2 zcH~&LPcF}uy<;Fy_JAOG;BR`&_PTrG=94FlmDwnX7+|0o=W{^4Yq@+sXF^TeQTS_PWNl}q@A7Q z|Bt4#ii)dQqHscR39ca!+}%C6I|L2x?k>R{f;$8c?ry=I!QE|ehrzk$f4I-A1)P~a z-POBxeLIrEjFJi+=fC;$%Xq`d9HAkAqz^9l7O?=xd$TquJzllra)u_uE48+e z3}lSz8|VKtlX|uCtkrDAqoZ+)kzDdO14HO#dsYnmc}A!usc~^5_*R6=ha8V2K1cCA ze}MjH6Ef)LD)85TM-0jrE)3{x>?u2k5zb6+n%#+PHhLz!v_|ca?E=Zx-ATTs$2G>B zr)|{bE?+)X;M2VYy~`cKrIBx6_K2?CrhLIW{j#;;ePKF%%psR#{xH7zF2J*2>op*w z09;D*N{2@qt-1Yvv62GvzGlEjfxQTzPFHT^z_O*QqVeN54e>cNcBN62ND{;Lt>EzVQj_S@U zd6r7i5wfm-fCu#1&(KQG#XP)-)Fs^71xT^gFN__}WlV~O|YE%~&c!0Z*>Emr<5BM{n7$ zrVVkdRqrbS@xsQjn|pp-@wVuWG5hcU&ylglKZT^JW6plJ{PHr}-hy-~sLJ$v()qmb zxy4RsiM#Nd-j5l(t@{e?|fhLw!6%Ugi-i=uVZxZJ&*nFPgln- zDmy}Nc6a$N|G87UAlF!)a6|(#qyOuT&`p@_&s$u2at;%vt-T}X3hNV+SkkVy3HzI- z3A*8^v}a=PlsHs+GiCcQI{Nr6T*Qj?hV-|9B02RFHKU+}NcNB^Oy_OUs_?8D+1rXJ z6;_6(+SZW{BgZU_0kibC)mESc=Wo-n26zPg|JJ z&1$Iz#rrkWruhlVqQm_Q&)Yp_u1VjDD?O2J|E!|GKoF|HFtCVtJPy%9L;@h|uDC)T zx5{15ofl5e@~hK#T3xR()wA_(UoN_jtP;FJm^HR;53xQ4A@ItNJSUV8djk`_mX%ps ze479{3172kYsR#20lWGejPMpFY^Ae?9yJzl31mk8=@sgc{Oly2M>4r3Q#gzm2rP1$ zBJF(!uC?zKs{j2xz{{!NEy>4c*P3h#AdUcv5SpS?6L2+^g~h$PED-vq*>})r4X6=Y zFGuzNvFcCP9+5Y_4?i|-KKuYO%EmR$A6X^ih)mbZH~^W!99}MANkMz+SNlhJcmE@z*w49JW#ybfci&rLbTW$9 z+%J5QD>WzKgf7cFzycTh1;nq^`Y$`U=pyK$J=PoXbOa)#!G@5kY;wo(7_Rl_^5KO>%nJ=og)or!XA(DOO=YeU1@#NHg1|81Vo zK?Ja=Wp1{`Sy#8m?u(8+miWJs?rSH1*>L)_`F7C!SHl|l9x^*UGx%5!rari_>3)N~ zKjZt?bkYQD2Wul$ozLM3X-3ZR`ks(%pKandLq;3oP?8+5a`oaBe;jq>K}SZ++Ngw| zU#A|p>-l^a^mYnj9vsKd=&nE$X}Lu`iKJDnMBo>9H>a}flqljK+neM5`txgW7wX^+ zASoLGW>19tbOhKZZ_Rc)6spg}+jHk&t=Ici3o9!#kTYlpX(FMEaS%jgZe|l{Xsj$9 zQ|uF~DjDbGw#VP4Z(=dV`NM8p+2(|jC3LPO1A%VObYILxiDzoG;NU zZ8F-vkEb|(D&uD^b&|$e&5*fL)x9WrtSIsSO4-S5zU3OjPe26;I+)M_kftTMei?E8 zFT1+_uZ?2L{QyM5!rFSfO5aoH{lZ+ZFNSNQzwspXdcY$~xjMC7@RBb27QgHE&R(f} z?&#vg_~t;q!)25r0l-UVh)2Pes?pJJ)Wljh*_vJ#@e)6y`pfwoplwg$wr&q*K3qQA z8@t_-qx!tqr={f>{%H@=6@-&U<{bb<3IhsA4@iIb;}|XXI)^@E-^HEb8>~8Qa|qiH z)zTy$=O^UK%E}7uuE32hBBFI6d37q( zYMQvY0q1{?zJ+~iZ1(K7wf-|fyL0P2a;DyoH?pv^%qwV5JX@_UDX))8N%;}YBBl)8GNB`w z3#Y44L^tJveIlK}&H35d^RfpnB0s#mx{CmGb3i*>9Ua)7D-i4;&6{&URzWU*jF>b*VzKwX-ip1$3A;mHJ`rG{1z06Ynk!_5Sj^UZ{P z?&@^wfWAtc74VX~F6xC<#7)o7%jbC_$cyJ5=@OwWi|wo6=!)ly=*SkSI3^$GC?*sK z3x8(_{FW&N_w)=%5yE1#SV%C?jO?)-nlxy=pR%_?NQBYQ@TD-K&_dO8=5$fE_E}&2 zv|IQmxT|)bBkRGFSHoneY@94T>kv6sUfv06@yYDWV*45d#U8K_gkqsmXN>QnB}Nwy z?SVuEu}}?YCzYxh4NRdG8ATKqQ)=tz933C;JY4O1uDjsSBe$#{C?fNtmL z@2s#flL*-Yu;dgKRcS!19Go(hD&p`xr#9Klt8-$?Vps!vH#wP^$pd)uj9}UrhDie= zLPF?%!paFIS~WBWk4?RbMxX0$e+=wk0A+Zc?ACqDqdSL-|9=60-mSCFYJ zuJggTr_+q*FS>bJL&1v!{YvQ_==6!PMs4gOtVZn^nIaK;b1s~ruRno)^p`JWxggc* zdA7*>BywpW`t61c9G*Wsjij}!2T5|SGdY`Ha^U(K^(%U1yyQpu)x&Na<`9efy6d7Y zb}QHu|1RNO*3tlKIfH`DiZOsVlw3OdueKosiD_zfdNLAQbgm%Shw)EqV{)TT)AZ_k zkhu{ePj31V&5vqb@zt#l#$@2XDPzF_l9G~Cr7XY};ON&Dt&(sRfj~K#Bdl?9>UpXR zO{51hD#UU=v9J0~CXX3C4N!s99=b`)ueGhXVq{tdoj({d{eGuK>WyqQij{cMD)9PY zLWITvUhwoK5=U|lEfptarY?7ksK>D6z>t^ujZaOv3SuHNWSx=;*B7IhyQ!U<93)OKV4tmvunI_2^eFYDf*J=!N-q@uqJv--Mc$;i|d>mtdrIeGr)YQr;=_mr-ib_$b ze4bj2V}@Pay6^UuUAa=CAaKPh=o0z|ycrc$#BLfiY9;2(+_z|wVNZj)(O|lkCn7cLji-#Y|`~<1s&8SR&Vdp19=l`PsFS_^)0rr z)Q*_(Z1BhpnOGu%Z4=atsI_Pjfid7TRIzI0rJRSB;VC0OJLH&*$pV=9FTY$*7HU0j z%yzgXWI}3bgty3ARbsHg>JCIDSjNa9J`sSZbU9zW(U;@<+`7NO2cWC5%_p-Afm1TE zMB(amFoyqjD~M3YEjq7g>~ROTTdGsr^mWBGi{CX8&~WQ)2GFP!bNIw_iV<`ki~eobN|xeJSD_-hL#3Y`PN{ zlt1AUZ%p*}LoCt2jY>lX#!{5a2jmpwulg|+Ys}7g&;R?Gpil5*tlMWI{$Cgg)(h3f zE=F0qRI#dS>;3%?(Csz{jGqWydYXY} z=T5Nii9OIaZ#<4J4O8fKBp7qS@sfVuTeZP^%WTncIp*(OzEYJup4ZUQIF`V+HlJna zc`%L-lm`+CZl}u+z@Q&6W{YVV#SD9-Wn??Opge48th@f}+Ty~(e0pb~gWV@O zpl9Ir{#MD#Rx&eqiI$Y?uLMg3%R`YFY-**!v(APL?I(%ilLi+TvzKkR$%0c&O2%BH zVZiDYyr?_HbeF=mP7u7>5xMRWAg#}N_(4C+-DC2Dol>XC2DT{&EQ|<=ZFF6zTEwCh zePXO`18k=#qPmnpk6!73xf~*rRe`O zn33~^WIMvfE7%kD3~{_$DXP${&+#Ve4gBr(Xm-zYk#kfN* zPBS9UwehbkSrk5x+6@O!yDRI!Cl<1KN7vBQI6F5p?!5uglaZGJx=S*3(JmLh*nKZ4C367%E~Wtj-qgy~1)rwl5{hXG3JQR$#mvl1 zFJOE6zzwMEXJ==)@#XJzp~Eo>x@%J0B0|P_Dpd}*57LuaU-Rk5WBK&SskrbIJF-pRudO z@|lNEOGEHMzW~|52ecdd#SZ8Y$wLc&mvu%uS*PGP4=9h+TVmdBd^FDzZe+?z_G z+HAdeg1y;&dR=?R{ryZbLM>q9P4E0EX7k{{y)!O0z*Nc_pb_5PBGc#TR!z^&kIM7e zl`PGPILq=au6wW%U+710gm$G6YHYRysfDm(->ls>HP@TnaJaa+17aQHUvp|{Ne!yz zjkcgnw+_s5AHeD;u%6Ahr&h@;;^z7ojK&xvK_Ugv=oK}@BDZ^7*HM<-|dlYHkcJQ=>eKr+Qm$@`n}5_>TktsUmaMzyKwc?k`3 zy7w#4JJYdty@kQAEGZh_2Z(ehe~|Bb1I+3pXlxOk-E~TLoNpcx>4$ZO42)feA)g~* z>($>E9#k{5zjWkc8y0*HXKn$k{T4$Oe@sLX#AgV zQ76Bl18&vpNB*X~;vG*L0As5{!!lTBbVVw1M1l@rnz86U7D-i_&9A8M@e? zI#IJxqKHu2b-ISpQ7RuhX@dRiGA;UNxanv2+nTOf;@C9-%QlEfk;fF+VG2K05_Q+9))w&)ZB?u z`I9#UsQo;4W1xkZhxU2=ogq;*)83s@v+O#eSiCXPvq|Lhh1#kSMrm2F>;YglJRId# zjG(a}%sQoxb~b@ZcmStg*xX(yS#x%7L)==DDJ11{?|}kFdY?yv$|7k-TS;13QN^jw zctVjVq2JYq63L;XW4aoPE29;@HYrv4EOKfJ-N^U_c&r`Ph}(`*{Es?4UA3C|}OOR4_;{N(fvCA86<%uh{Kj-o{y@~%t5y}8<(7zLs}Pl1cCOGQOjnbmd_V1#6&BtB z)j$k#3=! z#SqVAri4W*N-dUd=H`XxNS-FkLAc;sflBGr+?pK5kQCF&^Gs>I6jEUohUQbGb}{m< z4k}3&R^GpSk&-l%V6q8~nXSBcK z(PJ>!dp9uVABtiN)PJInqX^NgQId?e-l7GlQen=F5OY~<7ABqh(l9#)ViBp<*EcjZ zkrp}i!YoMFFIYA5c>Vc%ew`(7glLC`vyYI#PBN1rQnf`LW|WFaQ}hiN+QQlqUl*1P znpghH2XsfV#%~dwr(KB=N&*yF)J17oS%sCA6F;@cnwiErZKepcPWm|xz)o-1|F#ge zvCfA%y;NpaRt87st+m?y$ht5TI=+9A8Nd)etoK?sa~dF3HpKx^HeiV!&jZd6ZrR!* z?CL2wQ2u_>ig&3F7h`5ST0Ui{+?YT2!#H%N`~Xf~mVeDzj#i&8 zwiCi+eYvcaWxW-+{an1I(!Ji&gIjG`{fJ!!HJ7`qPM?zTp&6-c{y5k$Amsq(L-XuC zRIp3LmI4$?*?ikgg=PtewouW^$cYEFLb5`>=|gLNg%_6Uu=keqaU-5Fdx*+Mq07JX z#)1FvaTl~RG9#VaIvlY`lD~Tq?K_32s7A!z|G+Kl;T2uP+tJ1r+6-QxkqCVd3=T+@ zk7mhX_t0Z5aev$0nP9OxE$8q47jmSg9<3wBpF5Z$EiH+XSRB9V3dfT_tQ=jqLU96C zH&k#Hw;lqUvzo$#P^FGt`AaW@(6ZH2fYW4$oMfH`&_kRANRWMfJ|=5NCroW@1j?U~ zTgr5rQ72_gx8!OtX=bb4xjv2z3}iEUES3xM0bMvE7y+(c@>t2(p& zx?wadohL(+2Q#v**HAlQHgE- zM(%m#D0HMH5&uPYUj_g-!i(l=H-@S>O@5+wK-4akMi8ay13KNKa-J#0DwrSG>e)Ud z$rQC-e17?mUC8*}p-C=d^;h>77!E!?p%5W2weQBHcy70!30k3zH5Fv|kqI6EgjFTc zU?DE+o(<2ra&A~R64=_>;u-&yL=W-F0h$TOn~&R<%r4?4LU$M*`=?moKm4hvjFsbv z*f3qhQybG9iwlgp*%%ZVR!K@WmL)&p01n~YQUS+2L)qIqD_!DLUW6{ZtRf; z-*{;2?t9Tv;6ydpnG?}SUTo{cpa;%*c?=3HihSGLLMN?nJW1|eY3YgK1KZ`3k4f)i zA0WhJ2?ppO6U>ns#LFmIS>CqCqQQ;vyMNUi}fj3pS#;xE^G+FAk}w1Gk}8HW5c)c8r11M1=rndIb_k=Fv( zAy5&VScrDDF_3IN02X$zs5__1pWa{W($qLe-;jGn6liQHnW%&R zQL-53{gO_s=ze)W?R-rAx#$Xp0Mmfp7v9wpSY}Yr2nwX85g4XAv8K`~XXgrh(p2ZS zqoc9DgWI@fowQWPNIU> zAbQwk-vY$~e(8QGzbxAjaOd3>^nUQetg8MtBBP%2z5jrRT#Fn@$w8uKu$XHh+$tXv zg=Nd8P2y=%1$+6J^DB1-+)wkETw-Mw+qH|8Mu1VLk-4s@jWj;~%pN1ce5&Ssk6+2U zDTpp_@4eWvDewm2J&0@&CPs!0r)Ht;6ecj2KS@m3WKU8TM-IU2S%M1bkjC|~ID)|8 zjr^tNvBZ!DSVT3yM>Spxr6d%$%hWdET~%jKG`OvcLxUKPXcJOk$U;Lxie5%#c6BPG zrKv*bFi4?C3+)b3VgD9iZ8o6npopuR;qYbad3W2+Rphuf)h>vcukyKH6eY7YDfq>Ec_x{oN!eJ5?I*T zW(0hh1~M4UHIuF#;j9Jv?BuvBlRPC+38x3;4M|=f>G7~-kf-6GgS164`8h+Ok%V_b z<_X^mzca%|33pK8^+YK>rdW`!Rux|N{;{;InBtbKj=@VBgmT1H-~Jf&M-|4B_Yc^7 zxz%u^R^0W*OT#71L^gsYw8zMC(c!|hSr^hg@vY-$Yn{fpod86ug*H`@ryDV;(~prZ z923#pP4^45wfW+?J5tG>JVL$n1UHwjtue#Tj54UE)ST(l7EZaC8B)G3jr-h{gSes< zUrpuagbUY;fx0v(O`S;A`3B}OV!4m68JRr3tF4WZJ9eh>_IczcP(2v)^4dxmemoh|NKhve=s4pw}17 zRe>{1Q4*fUPA$sbmhqY<72XwyEw|S#RaK+qeHF!u!Ar5_=qhmT&YfMWnu>AmL2S)M z4CeY^(vW%=_LM5?`k5l|$i4|LEi@}(Bu9Nfrbrn3J7@Ek$uE(&JVK!dbAw+$DZ6Ph zx#wa#uf4onJr=lwK6sDF*=BbyoENl%(u6o;5K{P`u3?uoqiPZGD*w*tQaazLso>2X zjGonT7V$79Gi0w{by9>3j{9r4I`6N!n=<8P7v^=}toI{|+r4KulHbCu^Jm9mr3;ro zS4By!l*2f4?14OCuJt%tPx>XbRaUiCe{UsIY%3&Sm>OG|{3^6aSlNIR=eX*~vYDi@wapEC=CTK-vzdcS=t+KX{!C;@><_ElzGkp^6P6OGLQ`U+@Ls~laCQ$%+q@(irNaF<75-PDa_}dPi_fyK3kEzF$-}{*j;>QS#q+OEKDQabFOBGvUM%c%kIat`Nb)r zw@**X1(96n%%VN$0L*I#?%gaUJgNe9c0CsY59`UZbt3fJ`s=6=RyyOe=b_6t<*xvX zoNT`eU+Dbhrps&UHO2q;qF2%=sJOfkKBCY=^`^G64^lsu(Xqlm?0NlX%s<0=;HULj zP{*4chvfa6*HG;m8xhBu1?sdf_F?Dq{b_sl$VAy67BgR;_ZTa|yCFS)$(#W)wPfIE z&^G@Ii#^C|x7IS^u~yg6Fm6!ufrVt-ow4Mz($5jCow{cHpHAi+ykVdJPMPL4i)km; zC$Ln+h1%HJ)fvbt&{rz81*X8N$6=$H7cVcgUlfqbO?tk_m)CpyAzzGrO1j;-F;;Jf zTUVy6lRWOpBOJ|JD6GA$@Lqh)&U_`YF!;GeZn_U!Y+G<1r@?df^0{^6gf z717s%;U20-i@=`cwUwPau8pmU=8c2>RQ>H%u)e|6Ndfh1{=a7&^`MazV|I}S*jy49 zqru%{$a6y?fw^r)lFuLJ*xw|aYK9mBTw!E5k%C1uEgomIo8D*Ydc5!SV@R@i=J=9v zEeWL5R&2#OQopbR($X+QoQk-hiXHl!D0pRUK828*#lvm#oNFZ`SdqUIL5fbivS3eu zM=zkR7ypJam4#hiIMAE%2*diGfQe|TAve+4`wk%}MXh^zEq>x3zRo>fFW#193k-OK z`l+h}k8tV*M?P~)u4O!reaAad zV%vc;lV2<+cVyZ3deu%#Z5&$JGo8_1R(v~W>$(ZZM(4lTlAOKM+F6^Yj4uTY3LG4@ z4$#4x*cPC?K7+|I1U z2{RoQ^ZOZ-8d0j(Mg2&`kKLG578a>_)}zU;x|+ovN-R9%cJ6ZqomQ-0^uE(dMehEZ zbN96c43`UDpS!;C!H~LqS{}=ReAquhDnS*MWbD3aP8RqD0-xJIoQ6ov3^FU1c$rs5 z^&@)4J*%VV>7vMng7?T;;R-}3dLg8PeWEh#~sa`m<_@>yywuKUW^MLkNCS7 z6dyy+>ou(uoRn7A8`#f5F%CAiF~Zd#H&tUX5Ae=&$J+*dahEHNIv@|qKL=Fi}2I<$aDRU;&9`ULM*BDL)nf&xNuUB6G*Uk&)*9BWaNGtB+ z(_;7J#rwvErV#BRJf%RD3Lz{=h7rbS&Sl2=&zhDZtt4=jU0TOwx z?_x&z8_2RXyd|*dE@Iz$#UyZC9!CPBPg6MwFYzr_PkPHGf`%$m8X?zYt>@>>UI8-% zIKEo=?xhd5Du{(9_t6T<&YGBnt= zzR#w~{Fs`GC*X%dd0#!6ofz|#exQ}BOKAB^S)z?Ts7`kco&LS{J=lN7x^6=lXxuaWb zd6=dUY`G=L6?zAp+{EBi|HsVW0;HE0r0UCo8>Z{ma^kxCdzffCO)c&1O#NrxcOc^T zg1_;e@cq^Qnd$M&{~b>E;rZf5|K(a}e~ig5UPIqMs3g}bayLl*?E&j23(zTkNE|FI7ix}fcroo-w7M7`BAz3_&Q;6yjR5LF!5nIaI?#>S?`%OrW)BDj`~n-r`o zQozD9cv}ULoy*&8>Ur+JHLe#itmp}!lB2{!_qhzGv=BF^XQ7qAHfM0vVZ)dI{%4ce zAcl;eG-@WGT+;O?+dY}?d|xt*(A_mI&+Dz{q`)itqTTx79qmT@Es6fq%-G9eCDO}b zr#rXr3p8mjSlpJ;txqr%yzGpn9WZcz@GswAZb62+7Cq(1@nokUTiRb6C zZOgdXGO}-t`&i!nMudb|lEXiioZ0MY_Q)-OY|F=gNSifk!CySH!4AtdgjO;xm+eX6 z=B#zP7uc=CvhtdJxixy>e)?xj=+GTgY8zh6Y*Lx0!Qic5MuoG2BbqAyq*)?O?g%$< z1~5qYvGCDl{M-nd+-W*FhG;87c<&=dFPvwBs5ig1RJ%VzyP}6^bt&R}tlI35R>tDa ztV^y1zz+{iMf8LrwGAZSSkQ}}nn;=$#MSFsnj+)ky;LyO z|M82BEeh=AeW*lz`c&uuEE86O&n%=#>e43y3j~u{e0|rWh~OO0(B@6g%n^%zFi2o5 zJ+Wk&0QCr0fb#`M=OlBj%Qvc^+`8j>pXp{aRX?vTHfHstqN0LzjX)(Ik0ZFvw4rrk z@QJspO6#Ytgj1-xs^TFwMR|}oqGN-rXa((@=BOUAPSPz->JsDmW&d(L@SAWwA45`q z7n>S$?*YuhhTUN|fjqD9v!x5BnpT0mouV&zP_Wc;+Lvv$%UXm7Bd0qrh)d~Y_gO5# z?Q+;~%5TOXgSdb7W-N$yqx3Uc0_2Kw>kYp4%bp4e>$zc0HTmQA|Hi8<{q-iKkW2x( z0bTRo?pFaE99(87+gb9Yi1eleL5fz_AeRU?w%?cQWnz)rYx{0pl8^0i6Qh#6a2G*L zn*t{lFLC}0&%Vu_qwdXDyrlp40=SkZusWotC=7+JerX{2RY(qRjx79X>M9>81T)Jy zdWa*ndX1c&BczZ(>QWK`k!jBl&D}zt*tsghEk)A2Y6YT2+}kd%b=gplG^D$RCcZ={ zX;*1K&B-u0%wD^Xj)4Edl24EPq}zJ?(Z2JF7YT_ji{CM!7jGd2cJ3~iF14x_=+;Uk z?UpF0R8*jg1os9O|B6e~U$FRNsmPyF7FPr0=ul&>2=gp z@40JA2d}1X%KUkf*S_P)_sKMFKri>c9|4vsc3Qy-7AcDPs^jtCi%qrt_5B2$Ziicl zaVJq?svsz41QvJ0D~b)AyLVsba5BhXqg3^?Yy25^6FjpYrQ7WpV^nM8=@<|*rs3hd zR-<``K!Bg?ol&$ws(?7h1qZMQkI}yLA=vABI!^Nxz)aTzvyxNGzi4x9s-} z1$gh%YHFN4raice0}B`P*3eBNoW(eP0~Agh&{{DBP$-CYVHN=+tetVkN3D z+r%A)1^MJ3>PFYFS7JQ&C`Qajw(MxsS+UO|g{l=|Q>Q;TU^m)4LK^o&Is^{Y-nIA& z7i4R_RMb3Fi=+2@4V-nzzUKAF)yhreXghV^C;7&%m%l>jx;LS&09G8r*e0m`OuZ}0 z>3nb|$)zBQsUF*Q5-%=eu)IE{sxum1*npqt=KPuX8oc@VF*EZ7YtjIIye1F@ovYDk zV{`4san%2*6`VKOmwUb5#?TP)6-AG?5Kj%+R?2LD+d&HcBMl)b1S$4TD+1#sI8M+f zif?gqJ6ZoV^%h5gWvyj2o?`$0NnG!FRYR-0Rou|($70Ik3ey`wl{U%L4AUR{xJx$# zos{A1s1C@zx6j2LM5``m6qvoboPC+Y?HYI3rL}+ELSfWzizRWmIuq1?Y_)f|KJ|=d z_&sIN7fyH4HDF!c9U+<~*W|hF47z;5^$WE+!pn5$)Y8)?9YogOqu0aKk{x$ei%gz4 zD}MUdIPpn?+4r)ctH=fW$Mz90b#gyQxvSG$i`e}%p}(^?Lo2Hu*Em3t!|j)_Yb~jz zrA;&_JB zoRJ{?^$8>^wW^Vf@$Q&#iPut&7T8AZy`rzeyq&g!fFBU2n49DGH@$b3bMDyOSn zh{ce*$KyVe;R^$>%DQ(Z8><~(MvVWU$Tev)M>dDzk!>$fYQuW$9zvy&P7z zUiH9Gf+y?VwsmaQU&5Juj<9j$$G-T#yRUUTp_iBB^d|fE#~FHrHS53Xq~K`qKz49j zTpw*Y8TAcL`dJpdd~s-_?s8P<_42B83Z+=8fBHC!D9*Iz!qEZZ4lkIx@E_jTbb;jK zD4jkDRN?|ARxF`FXx!*C?uOY+LzXVzs4Pe@cYP62!s97|jZjOw*V@F=G^Cd&N8p+K z&OuHqse+zfMV&%yKyxf&o}=rHO~2@#NCU?JrTcO|w}4(|G=FPp(J!F-^;Ux>yAQ9A zO)V6gvtp#$S@S!VBX!`T& z=wcUp#FXk2j+Ue<9G$FrQwFFgCa1j4Jv4Z^$$)3BS%IQNKH7%B46#^SDJX`>uC^&MAyW>UiYxpM1XP>ih9isd-Vefow91e>CKT7^DA6twr1y%*!P7N)D=o z($L$Tum-j!zmVx{o&Kin+jO?9bMKAkH+`qOW7AkW6fJF?{F(2au0a!V8{o0`Lm}`( zddVRlNGDYvJeVA%yPQ@tr85{|d^XGioRBeAjuDuOIU#jv)`>yMLCpqUinE-5?Pk6+dQ;)DY&({tBtC!Hu?Q(q14?()%k(z?ZWId@Z78s1q$u zZHJrqlmMI!L9_{MN*(rzeYC}}mn158Pd1gCBemdqz+>+J6NhrYk+&9CSQwv1 zZ&8Q_XU-t5OzvHBm<7YuI(#-K?zcoN*tsVr74i3A=|{R2Gly42BlijG3G$z*1{6~* zKQqNw#{q&cDdAg3M7t`24}JId;bcSfNI@_=9^tU2uC^hw<~iGYR`TtB=$1o1S75#E z{&eRwI-&lg&tG)rzLe#gOjS>9A#@G2LV*#&jS7WDVi=Hou==sN zKb0sDZm-Ge@API~>%dmtWf|4tQp_tf(`Z#5ByzWj*!DFiS7Bg)6SkzQ4T)CY5<)Kkd~%#NYRsp>Ks zF7q#+aC+Q+2w@b6UJ`x6lRtb8spSTvC82#XRW}-7t@`rR^sg-t4T>5Xi^@{;fSktl ziiAzj70Rg5O;`}J(ZD)P<_M?IrSO^ zc==Dk{L&-rA9SQ0GsCWr#H8k|2l4U|r@f<>I!3ZUV4Zah-xip zVr?}Q*3`d+EQH%iJw8eaBh=&*anr+uh~N8{#|yG+N!vSHo#S9DCgT#5lhtuF7F&EC z3Fu1Vl!ro_Doe`*%Ow?<2{;-mhte@(0vQO06bTKNbHIvz7ppe*_LsBW*YxHJIa}BJ z#NT&oDQUJ7za<5IH1!V{>@(pfc}V%ezk^u8hKB&3^EWly#tCn0x8@|B0 z)*=c>o#}Fa%Mgtjlt0;C()5myKgX68lMBxW+e)nDMM|SB)vC4_9bB^mdz-R)WLf_= zd;~Bb%^bFJYq`n-weo86EQJsBBaynR3-F92IYQ*M3zJv}6`GO5 zc~LJU!;E1fpJRUitO{)xmwpxM{~t|f0Tf3QE!?0%gG*p>m*vA1w{NSX&ZyObW*GXTQieQVst$)c=K?|M`#0`qQz%*MM6$|GWMpW^vg6lGJlULU1@kvFtZi`XA&8 zR8>BCNB?FaJUs;UEr&9ma^cRAZA0Kq7b;;RUw2%SL9ZwuA4ma8h6vq#5tZ-2;aC>)|Var z^~dOUo0_5ea4f8ye4jjtx=Ho7?6(OkGfBY7)7K}zyWB$uxlLGM>r|!*Q889|eVIW_ zlW-Q&-Pux!B<{0BWk50b@9~q-Me%Fbp+^mdQ~UE8`-bm;!>*?X;#>($PzUkZA6kQt zqJO0iEgJ<+1tqS$a919juwabbv{kbvN534rV z?(;xxaC|zksO_Lii4_pOSmh14KkF)Li2tQ^0Cba2duMuVd1kBrgn@KjvMYAH)ayO; zptaQU490SD`&@(6qFyFE-cxj!9Imbz3=StN!JEE&ZVhFgZwH!joA!+t+fQ$zwX!yY znwX|PC=m_ip-~$L(fzt3$ezSbabhreZ3@rfMU*hn^`XTOg0TyKn*tJ>0(xUU>#n4D z;`%YnyotZ^gP#i|3aC*yDyH4r4B6KF4w|I{MnpNjDwzG)o_yU5fdh?N(9At;Q4qTz zeIP6U?|k?n6=Vp`PIkqucU>+*6Tt+@&!<&tmRItQUFW};N~iAEuZg(R#-_PS91dAS z*kH+N6tatnW30r&6I^3yQ%Wbhx|1_?*H=NagnvEXR!UE*D{9{>EnIF(Utn z2~R=pw@yw}?CO_vXz!DPp-~i^h;W%wWg!OO9@U8Z9)c#0#J z!)MGcsnXzfd!u49Xq!+$R3X~wS3R1U#c)EwP0`ll4Rinp9mtCuGHmG|^!AXYfLa3S z=)*I7&e6>x?}T0h4bz;T2JL&7-6B4XSyiKanXshrQU5A=vE)Z|EoByz4On@xLkwW%S1m0KSpdobHpMuuNdhZDTwLidp^}f21vlVY`kioF2(tC@m zFI9BB9@jpucKZE7zon&RT8X(z+j3C2ETa9D4_>hDmuK*Fx66NiA;vXg6e7L+>FKAR zRETvqW`c7N@;@SyDOvB}%bto^^}5Ku$8@K!&kpqt__b@&c*~n4%Jcs( zMaEF+jcqj`axIL&3WfEqqGbP`=^=rlp?Rzu_bdMvT==V`t3^(TAY2A3IV4$pwaiul zdJqR+Gf=*ju2J*1lF9tG9-0ld&6BM?7bDK)pPT>k^NYdow( z8q{Rn?$3RLO+%4|Whs{Yunat6v?D0RYAXgoPy5$O*mCu3C=@}Mr;sjj-c)sGqtYUx zbRAN8kL=bj+$XH|H?0!pqec7I1#(x&WXVw_KB2ZJa*AF7^o6V+8+`xoyK$x!Dlhm@ zl6Uo;Q)`|Z8Z{?4LjN|^ssNCAGA;*xtqxl<5~)&>G(sA*3yL7Fg-|0=(-zoGf?2pJ z5S7J9(^$8b(EUUyMnwX6$jHhDj4jus)Nk=aaW&P-sEaTg5w8`D#iXVpf9o;zw6o%* zhxG--U8ftvjQ>ni<$B0UtI%?n+5IFQuWjy7Qjo1kyl&6~OF20@)wX4J{;SP(m*`%t z8-&h$^6zl`|6Tmv#*s*c-%Heuslsu5qq%EI;RbbpydWoQg+M-g%cw9#8NRKunJ1s4 zSqMvD@VD4V7F?S6Z5S3L{4mWPXi3~BxpoT^%o;N^ix5`$-x?7m#>PO>T7x3I_!AUi zj|ygC9@IR-Oopxcn36uFT24?wlOMOV;7YcDgKu(0<=FxK1%&V{eA!}j_wPg2Z7tim zdu!VXNcyO-=t~6l>1US$xW}|Z%Ba8Da=A|b0e`3R7{QMXa(zxxIDsG(r00Gfxs8_* z|KfjBCMeJjp(xc7`{|_da_D)(qnaE7kCc|MM5;sr!e&9IXG5 zT>RjT(M)$?`GbMSAMmJXvX@g`>pHd3SW~~@zBTtp_3P29*V3Hg*i=at%16!)$t?Z) zz54OJpL^HllG@i>E=O)cE;~#llJ1=ozI>BH7rp}f4&o#^g~Au50p|;R#{Tu|n+Zcu z(3q-n&+A0H5Z4s#$MdZmG|wfV(X8Rw{|-P~Jzo`?b`{=SaFg6DY?%1JOtt+Xt{Pt& zjAdi38LIvG2=eH9eWC4Y>&hgupeLGN@l9W8pPm4FYl0ETPVMWUS zC9Z`FFTDEx6<%WrVL5@6YDTe)l9VOTNsNJAxwcanNp|-;*Egt4D}EF)^Wo2RvZcHT zJf6{nCgH}HEVECrRANfD*bR3TfAMGsFsV^PD9=_S^C~TraLemZVaa=FRX$U9N^9?P z_TdeDDYHRRFS0L}L!2RH*``#XkW-3Ag@xYarM8P=#xwXoRB` zWSOG<5|jsGLB+=lY5i=8-W1au0Mg}b9#VBSBnd$CWE zVNgY~T3PF<137i*NP-?5T${vE+`_48&GMztX>;h16;SqN-dewP>K4ny@079>PK3qV zFM8(`yfJ9Vp0K%&ZlXHXMd%WZl8xUGGzeu*uPSL^C6$xC1m%vgF)mp?YeYBVXRf$Q zRrrwop4YJ(ZppWzJkr+mA76#+$C)~` zuLVT6{nii@`r) zrI+sK3DOCQP0%}r9&Ao4>$d~~;c6Q0D|~+A#H(?I+yyMFh*``ADk~Tk!avs<`nJR# zXkUr=9g)om`N0?_u)11VBa0(tNmZscE>Sa{y`!s0%@-9e`^N+adT&RE9wm~C%5yKOnd-cm3Bq&U~IWvZ1Mq4DA(pt8xo&Zu|+Hl3Zm;R+2oaC7 zPA_Ocp-mIZw}D#*LghW+-d5Yv$&v@%u&`rmgy$Qz@R%Ca^p4Jw7dpYrem|L- z2;bNxO*hkM^ImF)n#tzOLs?(f-V&0=b6WiV{TERIOWk(LRX+6t!4Z&G4NGIGoS%;& z#Tf1EK`>RxYXeXBi>WZ*D|rZHx{f2j*9BU!wNG7NllM66WR=o00-+DKdb}1-30HKu zPC)}Lcsp&LLmbL1d3(453Jc3de62}tFj0)uQ2wjyk8}PLr(ZiDMtDcPfJhl z%eNiJDDzpBI~h4;l_k{UXjoA;QPeNW*q;;RN{2)cBAQfSFR%vk>LKWffto2eiB8BG zEE2+TUP!DM{>E1})1 zAj59X3Xc++0Gen)CJc}15u4qJK{2=M*{q4SXm&*9zWZnt$eUF*mPsdLm=vL!dXfy_ z!u2rN8+|u6!pM$p1#yo#au*T&bz1mvAs|0D{gb|c!+^of+Jxrs|#S0^t%(r9gWEkjt_`EFdhO7B_l!tVi!!RF_3?@ne0XJ|Rz z1q;xkLq|Zt0{@h3Hho(El_4{eP^%oVWXP~4+QzRAKf|<`8G&4ekib|fs9aq#dSu-o z6}}+JsUz@)HeM0y@PV)QwLh~X}3&3%t(<$I3p7y3qj+^@9=%g&`I%3 z_j`KjR!hQgGFAe4%Tq+;S8*{zb^>UT1%}#1Oc*xk5WOHadJQ9|@>mBfiiB8jK9Q=r zfUR~77MtJX%zfNPhgHwPepp?kb}6AJ-15#D*n_=k|<}vv>~n*@;vn@+s0I zSwsk<+c*wF$&ixg%Lik7frxZ@M6d*I9SJEC7?~!w7xs|y8D-T%7MrVBLe|h>8$4_)q41&EQ03l1KyZb4DEdJ$*8J zX1^W0ks47c>I9bTM?>T*3$M={ojUIM5LkJ23@9>^Sgyk9$$-`qYq(SMsSx@f7%Yg@ zD`Gv(;N>rC5DXME9;qBybzHoU4HIeTc`;<4QIKSHmn;#~I*8S^r#-t%9+{u0wG+fi zsrfC{%lx`|#za{1tR!h=y0$Fb+`1PJ)2fJb z@;I;ga9A$cAPQ)dqs;3GS&>BoU)%NTo}2jIR`pBkE=YX*IGSsSzU+ZGGWXN|uNHv+ zQwb#%g{NXTS^WB1Kiv8QuI61h%jHhxnyoFW*J*Y$Pr$iV4v$ylOt!p6Y*p>F%Sat} zgqG&?f5;iqqFujLZ&A;RB;aJ0N+WU%QG^*gW3Ulw8PjZIKTC^&gP8;i7`fdJ8D%dz zraqGB1Nglu=Rd;)WNp&XF0e7G{1a`PXL$@4P~qV!*zh9qY={qwM&Y*WtrI?})h@f` zc-)<8=q6DqR@aE~$O?|?b;j`0_FNc_+&^-P$=8y&pS#DT&#GdH zXU2ra+`1XJj*C42>CUVU%8@ zsX`mJ)y=-Mg^qYePq46WHYbV4Itdt=a2IHPwpHH#L4Q>cmL2Z})cESu$UEKn(DW4=3T22uY)U8;nB7UHZLjMdLGO18n!V07_gh1O7w7nW;9t=r+f=K0T z$sPO-pQ-Qk4_iC+z>ksOzxm^WUDe-=W$cPQX=KMM@MIcKFN5&=68J9-=s`wh-mu@? z+7)`@SU52mgV7wp=+kB4!403UwFrI(p7wA}fmJAWFSn!qQ zc(Lr#$$yMae;*Jt%tcoIJ4uGqfLYWsmNMd9)EV3}YSJTElXV;#>Vwk4-^04?|8+cdJewsH7!27v1{M)5gdMc6=+hNQUOLUk@GYTK zFri=h!jT|SIc#T&8sbt`(psj8qY78&Ox-$ASgOgrx}6xMPmV9{NBR)Dwj{VanH_pF z<(qSmEGW1*pO}Gfoz=jeD9_}7`KgL~U~WoaXjrlU4F#xyC{N@_WQlR0(-+p}HkMno zP{YI`UOB52*r0gn!4LEb*NdIoBPW9*Xp4ASp;`%(9fqn4u z_u9o}2iMl_t;g2hQ;b_i?a{wrn-s^|UA>S1pO z99-@*78o+!|H5J4L!@-EJUjFqZ$iL>>+`d@-C8|LQM&6vy`^e}KKa$MweH(0(Oa z@#Tc^_gVvUSU7yHNhH6Zw}@>7!54PzPeDVb24ChD=k4SvU2OO=Pgd&u7n4js3+@8=!?VM0%ZLOtQ+EQTB^lm@7YJDi&T1q?d?6yc1n=kqPr^;PNyjx$rS z6O?7wVQdc;&nz~*R_73*=lb_pO@miKiS6N0`XGNa)bHl3)S#wCl;c|nbS;?kO!mUnw@Bt5D0mCFOJtXKQOv2fGTm@v8Jw6v#&j3@g z{c-S=-A!JX3lX`>3hMZlo^&@eysezK$AE0(-J!8{;)}U++&1aJ{agCwjtb4fBaCi})#c zcwQG9&8?S%50!e*ntLGrORcc?Ge&4K6P ztgvK2MJ}>7y#Y0~>g&#h!7~}~(`;9FGz9K#M(9<&^ZhWh{i?9JrM9-mlKb#)Jjc1M z{nenZLji5qWsJl0>HWi=&=XclD&9%5!1;RT#Pu#Y4J3EJFY2OJV0B;Uaj==&>ri^r z_cctf?FpkI%iQFZ)BT2k=AYe@Z+!A+=lyHN?V^4umz(xN0@YX@rECiFphRez5;Qd; zwP5}MG$I|%y5n_L+&<6!dcuBAqDyXO@EA`%B_%pD6lORoXRkPC6D6MZtmV9Ukusrt zZihv4bEVt6mQO4to?dtF;h&2esrs?Dt)|V!MTghX`!++m=Jiea)C+Vq8$-Tv-Ilo3 zO`0?&9BF1OpCrm<_rmF&z*8MP{@Bh*qjohU-N0gO`YPop%lXwM!K3{F{|&uFu=tOErMziRZqcjNm*?2Hzy z{-Z>yq>89H?MoK1BBY}HWaQ^&J41`z7I&n2-@9;w0QVy&95PbeC-I?FA=}*0Fz(c$ zb4Nr$UEoBQW3HIl+EQ%9t$X`@+fo&K#!ZbvJV3o`gjm!-t1;Ri5v36+;B!}V^PS{d z!{Y*4K=hsK`E~Q0i=oKAvM8M=Q)GUl2%Wg1Cf-lY%I)DDDE_7WcbydGD@D4ab`Rx^ zM7rYs``6Z*hXJ0n&Ld-^Oc9de)2KN7WXoB)R7yxRO6@GAvVfV`7tU<++tK7KA-<65 zNNxlr*4{>tSV9~n6u=K-)NY9T-nV!Bv@3#un(~FJ1YzV}RgK>46Nvkp-CBiCM@CYv zh)nn%Y%--*N))Cc4--9NnFfO?tKflige1wzK-b%tpR4;_ol#$-XQv{*x_nR0SwSLK z_x=O@)o9h9-WE5jjrWk_@nT>O><_*g9JC=JuddH!D3)R-s!*w9737fK>V~##{8>n~3b{G!?c)fn3jL1I&8mYx zK2KKEf%JUt>!YvteqpLdQ!^d|taSk2>|vQn2X}Sdd2S+_cx7lif(<1bRN{7ksdMc$ zSSs7Udg)02fi5nE5&>HE%lvkXwcgag(%|XVBzD@%004CaEJQ!(>5guS+@wZ5l<5!m zFA??fulR6x9|duhz{zPjIb!Of?Ro^wg>au4=&{(seIuQ*nOW4ybH@@-Y^gp`P){kw zSznM94q;Ia*`u z`F;leB`Oqa?pcZWX~64oeK5B2JP(xwPj>p9)G7bNC?<1Pb?Rmgai9+B5NrPStnC-x zDd#;SC}x*yA=!VR%0rgY8@fG#jd{rH%o2;fn@;vuhh%(2+i{{|6}Vx6A|Or zrr*7&zIL+_UvW*d4V!V*=&&QlQ^vR*HhkqtL-X?}#XqRCCkoYKm>FkgGm0CF;h?Zf zXwtzcAEb&w-acz1<|<{}%y2L%;sw7$tm*T0s?bwJ&5?0rinV)naHeW!l!xaZ@SQMK zDwC~jZ2kdOX|cTkWMTMTaA)V&>q@ZJthsr~7cdH7!OJf$Mh&LSol2x6dqx9oAIDQH zLqu!!GRG8OR(hFL*k>hnxl1&DDl?_hrH%n7{hFG10O*`4HGD6vP!a;DV*!=spfi6j zbCD9Q5`A)wT_%84|cr$#YXWpMcp1C^D*(r#6mR&K&_>K83t8lLotnAQc9O9 zBc>c|w+5JNlxfFnY?dfK6sZVybaZH?hyyZS6j9*&t0eN95BwlY%gf7)PeQUY-Q$nM z2A32W(c6vfB@r>A+ep+~V~s0W9VGr_6N=Z?&?==s!Mu*(Oc?usj3LW0yw9X9XOOk^ z7kiFJ;NVWZdE>JB5^J_vLnTn9S-8F)d_nAJ1?D&l_Ff)=gJ%#?nwt`l>E?8MT|T z&JRwtn!Gvu^^8sHx?O9(H83Kvv6-rP4I<3}Pn5JtG;n z-yzDq?}2O<3D4B_BXlOGUSF5b1yR4#_-2RC%JcMV7BTPS+UB!O`*Z4M-}tiECt}ag ze?-fZE2mYTUl02MFaJCgdo~77tO8@WdqsYCLND9^{%#MjU3o0OF7Lf;;Jrf{Gn)(T z@R#eOY??RvB?F#S<)UM+#`n;!9JU@mk#7V7B~>0mSIVnwpQLK+5))5(1?elC0S!gK z{o@pyvpp=B5h`vOg0E0A)+>UWZee zL#O~2{ZFSKh{rz*<~0oHx_kKCWVdD>*a<1Bb|BW*-}ttjZt-dUr+|SFI<(%Hv9)#d zcM8e4{TiazxePl;Gy&d&iLCd zm7rg1Ei*Fuh)Jh(Bpu0*g_zdQ5E@VV%S1zcv6G0~TA zZGzo_aLBY1xGfi(0VWUgbVW()e)j-T(-Acc9)7v)S@{!@e`F$!gy+wiZW| z0f(mn0VEgi-IDm+ZwQ4)lh;umFZ63odSf1)H{i~vMxV!9G{5N5oK5+1{(-j5TX*}8 zg9$kWg`3;zt-kcRqwro}+2y=K1{#u7=n|)ngb^B`hprH0sCu2_he-U>!aM|nBdJQ^ z6>Hs|V=Rf-1Oz5b+K7#}hd;c&e$;OC#_4+Y=^8@w5bQ=HZXp?SM+hVUoYlhJ4+`C*=@x;CbJPYv1_I^z)U3&z)1GY=Wyv9K%qK1_DK!SNy(}o{3zw}FL zH5o$o(tK5d^WMAt|Dne78mSXUE+;)Y6G;)I3gQAfk4{0{jvvUtoA2M-wA=3JKcS&q z&Z{c^W8?xh?yi@yu5k`PhtcK#oVo6E;n)7WaZ%9Km0MnJC3sc)9 z92eAW{t<2;{#v~~#J(r};}AP+K@s~uV1$M#vTzDch6%nH*>@TdrX-d1E7i9)$(L(% zQ;ltIv^_2bywN-H_ocg(YIQgxD=QVV+tgZIVEys(%`8_ECKoYaEvWjRbl6VAM?lBrP;^vz~){9@af|l%7#6WZq5+YOY5;1(( zA{TAUZ1h2nA~S>CxW~t!mibF8Jlx}^B` zsk-G0moL~(n1z_)OsN*m#tE*xH*Bq=xwuTS@v$HFUeOVivFi)d3?{eUhGYF43Cc?+v)UMI|ppQ<8fLqKjdh2~- ztIy%=@W$X3KKA`s*?zqagUql=g*&X|SJv$jGm(T?oQ+!x6IGLBfLykmz#og2ov&zLaq>ARET(`^^@ZXn<&PjDAbyYH3VVy_m1m${`g?p6o!NB z)AIg&UuW~q%++yVM@jMVak5#_>FA@-;58NU>qM%$Q7&XjHk1?y1OS#9CEunu@9(3#K$WG z>BrGIMWKlyp*JVcQgJ0mY$UY(sz1!ZE_=ZHy#e(BPZ9s#?bQo=d6s0kQVFwe5l3qN zSCEf3uz;H+Ci1^r_Wgrw-gn-2{9`tghL?pvC1NE4z7f=alcw*Ltiiv~6K6~l7+Sy^ zO6L$T#M${;`4LcpC2?0d%}r!_{mJjk65yLG^?%>vf7nLjVRZ}!I@C;u&bV$~Ndza4 zm%ZM$(cUzPy&wFksRzs8IQ%bzNSJ|n&EoA?5ue{bI-Bp}-y4>cYwYU_EjvH-oilf` z>XZ9fKn9?z%WB^A=i{<%O9xi$+?|~{0F0QPQ&e9VWZ<>+pUd^U+n<%Tu-aOd^Y$Bs zlG0Kq{oMOaFPgnQED#a@Dn5EP#Xz9hcyv>%^~9v4@!^W*tU?vDcU^LyK>%eRFSFU!=<>k{_do4k zKw$LGpmT%AXt?(en||4cZC(Pfp-ru=BY|gCV>0x~{d|1{Ab$hHlkLK1>-k~xzEiSM z=K$^f5)D9ScMkTv1=;>Ghq-9GQFuEB#-U*DQ4q-sX~31io5S57ufWMk1!`*Q8pcdT z|LbNTFzDqvf23a0Z^IaC8Zob@j3AE|dGdbd=3pNc@;kFxze>^dJmPaWFzC7g=Xg8E z0fsP%(kW#|>{dYC_iwyxy(~5#UtCxK%L)MSE=<}LC3!>NGuitm?c92)+}dAXaaq6b zcuof=BlN*8;cz#>kdsLp2ghlpQ07jMfyX=zl*8da=KK4B7Xva{8ZHk5X}^8>ESbbP zPA`pL(Aet)nuWmek|EM-$?UXrj*P?@+X8!e=(NL$dNFFQ4Oqs>B>=zWPiSu&6V-@ z4h)xlNr2(EnQO|#8AhNaw@hPfJn~zfib(@+-{m|4!(wF~vw(E;K>s7gXb5>oIUPNX z!t9pQw}>58S2tI{9wDt%884OUY=pbztkvmBm;H#FKuaBAoS2QvF_GyQL2D*MkmlL74atLXS|TF-qIPy=^upwA{R?lrblcE^>4xU!y;i26 zk7z1c>4$4uFBVxTz~Hqo9N~8rh|tr)O-!5{zc?}S{)txL2bem@*q7NTaxmsjO3O|HGo4Go*^#06b>&*|)X zu|SYQ1vpm7lVx_eKOH!KR=yvO;La%oJ!*@T2N#BYq?J>=iQjraczl5loyzH-qC`Q> zDW*z2s6uN;9-HxfQhg^B9g3~>9Ux!TxgPKGC#3U3wHSKi0~+W|)G66s4vn_mu>MC6F|Vu1>kL6iQ%YhY^B7Sk+08 zWcd0EbsXCqAD??X@_?b$dP3)Vr9EG(&K5Lev{G06$8T5oF5nqM0abA>W$jCX*m6^T zjn^~LMM=G^$y!3yqfkHWPO|FL);V5bUV|(3TJPwAI6Qfz#&CzcNxv)G zx-oLkJ6KrCN0(3*7i|9i_WH+v7ZD)V_W_^Ikuftp{qy1dgvpSdLyw1mb2{Tmg9Gm3 z0jAAjh0)xhJa?z4k0fEaYor?W#2$d!Dc_k3ju%0QS`mqm;rK$8q0$<7>V-g;o{?^D z?VZ6KspWP+khBPd-nx=BYy+6(aw*9Snpc-qVLTkZNMlXtDL~B7n!>M){T;oC)#?zO zHg$i|m3wnE#m2)S-l!vL1t*1RrUg@!2vPgx-A` zq@m_kX56JjY;}#i!s;8g#`#YMp`;`Yj4jO|%*`Rbv(9530^O7=3m>3V~q)u=IP+n2+SBWzGz4+MUi-`hMBc>#^xj09@d`kxl8We;Mr2G-}CMId*6^$ z@f-pj9d=YG2@A@y(Dan5;(2jlVIt00mEra!hAP=4%veLP4YQ*k{6jp(!qLxu94vSBg+? zY0$KA8YwhYN#a9c%1zo0{AQ2O&GHbVW*HMsoP#^VS?M4Gu}UYJsWO z(#5J;O)(c1T7CyQt81(HpLt|8JxD@!VU>$&ieeNnXLBSmLyCM!k}2in6s9+4g-X_zvAh94Jx(w~$Ia-h_qz zjxQo}EI6Vp*Vkp`V;h-2rX7e-=HC+i37gOHSjA*JX5?)inx`U;_0*w>0jk_J zv_|Eyf5hm=0qa<5Wf|dpb?oEu!Y&5~bIj1P+8-n<)t?zX{(Zl0E3|3@Ns(e0HG#rg zQ2V4iZ<8(cY7LatO8=N1x=NU-0Fv zjW&cup(#1v1g62f9`FTxm(Q#!R#zK7TvP6)`hhddjjLIu7vbo;t~QD6z*-y8VA>WVnqTx;zYj z=o1wM@wf-??!!(I^A4+7rDzC^rC%vO#S&3vkFa_ghhwps==r_kLUQnTySvGFtF(sY zYKOPCou~`aY?{B0b?-oZIuA%;(5O86VHTxb=gH!8|A#8z8l<3$CVS}NXul7V{P-z8 zot~9baHO}Bi8UQW$Z2nU^m>2&{<82MwO5*!k+WkMAjF_qZQR5@b}ryETx^F~3Z&W=$ElP<(=4Yb^qTW>K{XM8~4%M5H~{|$pGNp}|4 z7w+O+#slkaI{?u)GjmmM&k0(i&YifPZ>?ARX%@)5{V-x;sEJsJuIs(r6oMW}TcOM} z;cRO7jmG~kerC0{;@YVA%W*l38ojzGB!)~Zws9~%ZVbP=Mk7LbsdpH^Kpw7512F}= zp|NRtY3`pSQ8pTql1>lVeHLsaWtP!|m{5*0Mkv_wuC1L2d45|Z;=|A79vg10FPhVj z&f*&aLN@^oMuRE9*OrdYCyO0w%1TE)NOKrz00HrgFLn8&omOvl199TRsAgv%_V#mC zxpRzh@EJO+`iEJ6Bsw`_2atH#Fzp_<2x)TYScl? zK#wnAHskR03@0C$`A(4~(}t46-Lt)IHQMNs#pjmt zOyc=XcdIF_L-E{VS8lw{3^_fEM;1`8<~aBUHNW;&g7}=%%FCS=tMrF%mmH3A->!)7 z&ix|q?i6_WbY@m}=gToZUGNRJ7k_LuK2f~v<(EbcL+Xl)E1Hva!Q5r2Er{%l?iWR)$PIrZrm(u~_SBMOI)u{?t^D{r^ z@Tj_t5|Zzd+23_5V!wSd;uD5(u#aflWWF?+bpLhfvR84B?4T3&~p3O1l--$4_^2?|j<>T)JKkhfVcv zZs#3Gl}=k)ZEby)pn&juzCZ8N>SsZ>j4%%Y5vI(6Ixw-{ALSIVfrO&Ne|#S2Vmb+O z)O|f~{?3p5A_&yfG=S3C^x*gH_~~hH9XK#=^m0X&|FQq80?H>9R80Q&pX(2Yx>~i~ zI4O4VWyh%Ym>t+CeIeB4lFX;#Nwgrc@(J9}yx!qECSmDZT~m%3p&04C>??XXSfZl9 z!Nu&#TG;6W@FL&_LuooJ4;Og(p%C#6#=rUFg0;RSj<%l@Y5f;6CZbxD%);KtiiDSA zQ0 z5Y2G_M?{_1jX5r(j)cuUIj&pt)%Ui|spDaUx$gyjJI=UM7o><5K(;v`{7NPK=vmB7 zJl}4us+1#hP|?iN%E9E+7H&wfc0ZEJ_n3mDgquy8$qb7=Ov&Q-_wSMpsy-kKbAM$g z?4bFvXAune+zt5z37c&TF~tCf5{4KVF49)AtA~fn>)mPVRVbJ8&yancHR)m%p;Ky@ z==CjNM1IEi3>A965t0n&=UQ*i_KMQssRmUEVr})P3PjP;7B98%|ppPar{)DQTFm>=y3gn^znasCOY4{`uCp5XHb1A3c zdvO5IrORau2uz$n#Gc#!fRimMDFKLA?k=_zZFKo^jF573Q zQedrnKd-gA-?)hxi506*@A0%$DHarraVp7<6%-f8WZJhxFlbihD`gZnH^)v^Dd^~~ zYW*_hLB?egLFgG0yhH3IHT=2-eeU_pmzGX2;Eu_umraFo!`NDo>TE}x`-Em=Wpz^U zlWj`Z-jAlrwz!@_(O`YdLa;tiPL?oxBYWNVwDO@-)Wd_sruuhDWn)+iXTDuX&uG;$&bu|`iAv9LO|-ShCjZ=OMN zKH)D;pu@(L+Vmgd(_#+506wRf4(EWemHmR>S!1Tv#c^ISl_>t8l+}+~%}Sktf{-ZM z1(D#~;`+kA8lF59q7<|5GE6p=Quv`QRUrpj2v#>cv2XCt_ZN~3^18Z&0v!VFw|KVp zUN?5G_pXTwrLCvu216eDzkdCCIF=Mb!jJ#1Yu_5ejB@hlk161nV$`n-Zn|>^T*;5! z)vpAN*2yW0oK1So$?6Q6)3cir)R{XJB=7i*%%)cfRQ*UVYB?(9p{FHU?Ur;z*+jOh z4e5}{N7vi0!by}`+`!@IRTJO2p|hy~(HUnG1%9s5{+hS8=K#MTpu3mGlw3|3I0Wlj zIXFlnkGSbpmo|0;*>aBkR{wc&k}XM}O`bVY_gbRs_yTDq$C8z?T?5XTL(ImiwqLuR zerh!-RuxBe=6vnOUT*CSLlD`#Oqq$=4%C?nIf%V7rWO_?%b>EtIH#KUK$jbn$r(S@=zO@2kg^vj<4BaskiulVeW|Q~mb)LBZ1eS+7T9$fiEP4*gV#T<#tD6!k_gET1Is)@>M%eKR#bs*rMS9hfTcJC- zb4X)~EWG;r=`{C1=kBw1$D=u5o&I95NfnOSi|<|cN!bb0$cIwrn_Xf*($;NwK{xu^ zVk{Po@~i!4eMNmC8d+@w)OaE&BwcN-h@f7w2ICr&_7)LJJp~Q$o71~Agyxbf;OZme zxpjazDh|xn!<#)&vSGX4Qp@C1_8Y#&-$)0+?uU*YyNV<&yV(wT2sKy~8XOTEMUmpkb`6suRus_bNg(9(DIE0-^>z68kMSoVPz=n2)Amb5;BZ-Fao*N zv>+x)zG~Sz$kUb$WvX`wg_8Dz*mw;g^D#=&!$3XY8{+$ANSDYDQw4X`{%>$HqWQR2 zl|BLCiB=X@qw3$H7Flo!WND;aSZQH(v=DHNXrP?*%ziP;bFPUNk*n}Xw}LPhV8M2R zjn)`M&qXiTG9h_bYFfn$bJ4igYW2ug_Z;qKfmWr2409q?%)vIYCC0H?G!YE-%|dQKH!1qwS8E+8MJ5+}F)6RpUb*t3W(IX6s6$%OnPnLLMt z;?l7L*VtGU;hRH}k)AY2+!SbVGm@fD2C5q{h7ikLGk}EpY%8M(auO>si%>Rvei?QY zfL?1Ra=m_psfks+bL?;laB8rg z{7z}KsZ2{=TdKJc6oyr%iHdh5_?(P^-Amj1jdh2y2mb>zr!_A30K&S#`grOn0j*X; zK5>|5W5}-8yv=9aaG^PTO3uQ!AbH>rLq7-&t(Y@eN0$m5KMHx0M#Pl>CP;uHTG%zAC9pwNmjo>vTNYgxPND4W>#{Wq+gUBJR&v_OAx|q5rP_Y zb5^_TSK-Hg@$E-Ay(mAW*G0dOvA5uUw zD`;U4#Hw($74lInJ7rKy!@k zO5nTSdqgbaRc`xY)}UEpBmN(9RM37k1U*lw8qf+GWh9OHZ~V7qw4PqXr@9|-%zlO; z)*)zuL&d+A>dw^sP(j~U9%QW6-|dJGA6lxfksh7Glzt+(g9$)9!hJyorxl}DQVbjMP{-m2o5Z-#?swxwO*;7 z0qxAHi=lxbVELveo*X}X)G@-SS*lf=1qT0^4+s$A#)wolWvv~vI!bKxtfqb&O&yb@ zD?f4L2h5@xzdX5+J@Xo2(^~hx;{h9fU~KMspCf$ngl}^^j1Us30aOe@K9$^lD?UR$ z0B)kHt&^|3F+ysL`LdKaE}eF+O30EFKU?LyhNT;HeTtwlw=zglBd1+4c6p?@w3*&2 zqn7Ow5kb@3<(gcIwe_?s?Xe-Xf@|OzLe*|=hycRExe zd6{KLR!^4nPGi*axN^||6h2zr-GeJ!Tbc5m9kuB?-#3M{gD%-ED8uRQjU%fiGr1_4 z2h8A%s3(`+YHFfBbvl`!^Ug{M(%Dv__2A@(1GILO8;+f+7=BOZOHbgtac8uyIS z*v2H-@{Ypnr*`2l4{|a;G(}~foQNfCR6Nab!`rF&`Mc71tLxq5W2Bdcg^me0K; z?bE9SLD^%`?ajTbGnZkXh>27GjOh{ypLY`&KstSe?Zt=?e~OM9HJdyZvee`zC9>vT zE9+-E7P4>1%x}8RydV*X>FUaHs~IASFvPhB+5GLT3G=cr+!ACH9WDN$64{x;osk+6J((jD> z2_eL8cb9;lz&T3Iaz)eNDvLmrm@BP@`t~i# z8{ogIi=xl8D*Uh6iGe6cK6pWIueL|L=>$dx!Xa3iCqVTw|BcZY? zGKay!I~gN+<>i;&>aU>16QrpNE6~hy~>9m47!=hEwaY0b&bSvaoa?@7r z9oXu(c*bsTQ@!-6J8feeC7v0n|C;_OT>9HH1olR8<8mbp)14BoY>K??{t+ztQhA8- zlzNPWkhOe6I!@`7^WPK3Bn@s{1-xGEB&%vt0#;f{hKMq0lwYuNI+)Drb4+YW(DMI0 z^uOkkYnoE~eHiA?+zckB_bC1)DQ>o(xKc`SnQU~`!MMuwDuSEJwo}4S`e+LrR5Qfv zDH6uoY&%kQRwGlO8-4ruUpJsaoHQQH#}y#=c%gJY4O)ApVr zRSyi3|KI3>0g`>Re_r?bsd^g7;B~2a`wNiABp1AXvaU)N0aChMghv;MXKUlNBnP#M z>U)(QOscrc{u$S}GEVjZ{;DyQw;*1j%ReG7?RhaN%nc$I>6%R($-|>@^yjOUh#k z)8*8T|93fo_3fS)SVq|S@Q?N6D*o8$pb#b~8ESt9FE%}T0V2gHsy0H(@&bfz2H10t zH=YHY?m9_%$mR&jH%sAvK8)VeWxusD1p4_d zUnD;7q~uME@o}*77#3D*8XOwv$?!-p`Y(Y+f(T56&~y?s_LGsDfkDgKjSZ`)$|SSJt`<*6cCU7NLpECZ^oJT_ zuA`PA@!-fA-H9?UmhRb1DJJ09KW8ETxAQ|92In3ing*usnm>LUkO2(IDnql7&!41> zmYIvxs^>Tur8}xiIY}6)B;-Ols_+Is*yukNPvwHp9)ja?@WZDKT)p0n*OLEQl+P~? z8>~+fDEo0%786JqBlWcaSEl1o`r-;*5hE7n=^UK1#F#@pL$017??;DQlN{OK3kKTR zXN)ox1Q9Z6`jul%5xMqD@5WoLEw`9W~osclM%`@_#>S}HIyhnx5>$7XQ5XS0kwix4cEA>lau3k za6gV4n9P+bUx=Hci?_xMAkhrAPfbi8QAh*?VdH~L=>@h1Fjz0Sy4ncEV*EO08oyAE zV^7{-1Wltx6{?q|SMU%(@XQ+>319b9GWt{0Z}~nwe`7PM6tx6U5$~faJ<(3@cLwXc zna5z^wzsJdN0ctd#{Ls6nu9q+m73x|Ad3^DFBd391tbXSZs1|&d<;XZz}aaH5eJ|# z{h1nL>1Yiv%a3s#$(A&gU{+N(s@Jcv;vk-Q_IEIgckS}q;H;OK_9SPY>Ky_VrGRw# zm}kC{ND3?SsH0xB@TfE7|D?nfe7mjNkFq3I6NF-gTVp`ugn+<6Uyqj>+pXSD{T3Kn zjj64@0zy$Tv*tljrxlCwxo8cBAt(h?4uTuzwZ$|6lVRAq9z*v}F~#2gbw1V*C+P9sPJD|ya*OZz}9AEJc< z0wk*^qasb_kWhgUbI%L=-b5po;iZ2${AcFTBWJy{0Lq_n4vi0f6II!iRnLm%wp?VS!F=^Tc+aWCOTCV0F?yMX4y!bultN@os)HXG)7V_ z)=;yj3VTP@0eKteKeYL=m6uYSqtAef>QEWjQ3_C@&>k&pf1+vKrZLq*%>w@$_Snni z>EA2e&*DJd0vt?!UXT!c!GjjW4Ke+`q?#kYv&UM*P<*TX@4(UEM{jwPt#?VS5gCzrRO?L{Sj}5W5P(Q$yp)XW4$!c_p=fQppW{+@Qr| zV?snIA%es>H<_C*C$hHu(CM(XfLfQHHo{s1%KavB!KtjPsOb-)Q{&kJK6xE?%eGYw zoyT7~#gdU&&}E3qdA_`Tv278VA6%P3+@h@QEHZNH)?k6f+KGs6$?MrH}=fTK3q zno;T0=~etLizOTr#Rkf>q&>nbn?p18Flt6zdOf56%>__z#!TgjQS*O;01c##74W>E zJYKA_{OTD`d1GziZR9?H@d7F;es3YgKwHRRC6Mm*IkF7`Ge+9yuGn%a}upUr@QCIXV z;xhpSEk|;(JO_gt2&X8+q>010{_uX_gX#D^+0+?Te1_>?9el59cKt^YbS<@6tZZ58pcQEk3RB3w zr~_}vcuN5LzfeQQS%+&>DMbhZn7F)G;~YB>KN%aZ|6bVG=pnKM7R+yi!LW^aI~i1A zpQ&Ub*QCz?CH1Tf+qlX^?1~(v?jAM%X8FA4sBd)=V|0?QP)gUd_95JpTeFK@o#s7u z*oww@idf@cNZF-0!juWgPfUNjQc7&K0g!BGba#E&r9Q`gL^BK4x>rATLl7>$pj!eW zWNo8_VWZm53b&7ksV;%FL@gzG9vY*xdUj7=L93ZV-er$nORjlWFD5%LY)dQ>L{YQ& zwz%|lOF;S?y3UU=+FN0wGNsx_*CsM81S%Y?Uqv`7NfS%yaxc{~WcEgH{AkIoypSuz#f2blX~`gg z8DGNWWb>szd$PBllRd#fF(2^!Mdq={@Y zvvi-qXnlQsnzruc&H~7~w#ms`Ox<+O=EysY5|%_^ptn_o)G6sM30MTUR@D67x4KO;}?pMS&|_ z_}z%^M_Z#1?=zT5Mf4FDjLr|h($l>3!B||5!dN(-j)T}1?ZHo=;i$CkSG4yZIg88^ z+9(=Ub>(FRL%($4Nwj)E4|4`*LYzP z%O%nS2{Hs#(sPPlYbv~C2m{kY*TSpM9yOjFU}g!YK#QMh9omGCBSqX zF?vVvzQ)f=l7tN|&@Ds~C?1IsCDKaRuDirMc8W34d_%1wAKdwqiOpns-bPqWpQ#gw zBg%@XE)R{@w$;VYC=rvbe~HzBmg?T51h!RS6I^Vf)2XQ!ChJj>QcMcX*ddxKZiJ&2 zT`$6rM$r-$3GltPy0U+My}U|T#R-#Ac1noLVymzp!F})#yctR)&OB>Vv^2ApPc=8w zDry&YZC~EJ;^+GMv#-O%D%O98P#_@liwhAK=XN@BmX9d|cKz;Yz>a-sV;5EKq$?<#3zb!T&}6F$1FK$VhbBU_ zJ}J2)VG)a;1}|+?P&;QNCVgtym>{{bNrZ(~v-@S_LADq2nExY=87O}5anxB1zo}k0 z=kM?r@7Ix4!#^)cO)*^`gw8~e7>}O-E!~Xj@k6pn=gz+HKYygBq$BHwrP_!ht&Wft z=m7xov*<<*eV1heTET5S$odpW z9BWQlE^`>!Ev}|Lsx@tm!)zV;Ng7zf5yqrwjHz3h z%F&{R_K&UwTl17DUzSHW0y`%etwJJAz8qPhYNYq#{@2NN#U*F4hgZ<2cc!|$ZqSJl zb3;mr?0K9^?nrtRF{;dMy4cqopu+=Q|5y2B=8#1hT2!cUU_4ROJP${IMo$y!RBN(_ zJ#WT@YivKbYPa-*!#bii*iJ;#aDoOWRnewboyZgksUk9l_UF)61J!()Wr7NPT<*a# zqQg;_N$dZ0;>){=X&UG*;hSC3oo~L`h>#J&<^8HMFHd28Y6I?v3W0C|kO2MIdu2)d zQ2v&J6KR}rZEtiuAy3ip*$sd1;f1?E4Jp{fH*) z4!7iDCA3;&%>_P%N>1UqYcfng1onVM9rhfqhOAn1?u^=$-*g!}=^vD8&(5MIaq5hL zsB?IO?l-cHCYCA|{Jv_4a|rHC%k1yIp~u#Gm2C4pCU zjkDDiVj29a24C3GDpxAHcdYL?O4SoR!xf2r%`X!n%2@d^w5Vt|G>mukGnisXh_2WL zjvXnl?87V!98t|(-P?w1I2@vrlE15BF*I`TW7F$z&C*;8BYvBG@jN-8_uzP}&Fyif z5Vp>)6d8G*45_i-cpqjpFiSX79?KWQ{98DbGiexgz}jE?^E{t2L|89xI2SE2F~nzboPU@ zCgCVKSqqmV&NLhmneUld*`2c7=f2+!_&C2&NbKE}g6HjX8F`lt%M6(c+~1C8!6vFY zpJRA_x})mul7z&^143?vA$UKYWOb8p;`b$AbnS<;MfL8gZK$SuO{A1X>mc3o^)+Ur zG+N}vjnpE0IA1UYmLDUT|P zr!yW77kEs5UDd(i>iXe041He)pqPqv|8~$STRG>Kj9LBQ^%LxlTg!C%YYq^S{8pEw z-Z|8ev561qQg1htHF<(iq*>tKPS@pL0e~SN}i-3|z4p zlQ4AI`AZ>W65@seR@BZUkDeMT?zJczehR0-d>3{gdS9Nm1u^kjIAz#h)u2|iGK|S1 zD3)ikHW>W7`-d=t$z8X>?+i=X{pp>Mpy8|E=9zDTXh zzKxs2VQ3*A&;Ap5=Cj{#@YOopIV!sw#jNuUH_pmWFUnF2+8X>?prrhl=OOD+CA%50 zk=5)XQ4>Nx>mk)5X)31-p`BLmH7#iHP?56y+)XGe<3bxUQQh0z+P8%&8`-{sr927F z!ku!xQmky>fwI^boLuICgXSjsY|5Pu8ntT`X^JBnO!r>aB+qkkI9te!cnl-I?yqKk zyo#1@#%)ndVVTG>*AX?0rE||k9kjD$ptQvK>pm4ZgP$zL7^jI=jZN2+j%(C< zL+Q`Zqcb1Z3(`lgf`)WXWXRyPFcg>YR4S?grW`EI&xCJ^PKmW~zun(ho;(_;Rr%7& za~81M7L8ihUKrf}8HjMw{J!4HeO9Ao{O!XItks5Zbcpa%AgVQ{dK-!$gC%i{sv%qd zuNtUTPB5P5Jlh@{PhHl^(_t=%b2hj{gWlQ&sxYicWP2~q2$pyb zJ}d1(G2_S@A==P6QoG3suEj>YNSK$id*szrGnemgEgq`O#?bOxj3F_aq4-{Ke`Y&< zWjdu7?8#Td$?R&L?_oh9qHX=mM-Y3tTq*H&f>#BJKZB1YfsY|`!UTt(mCQ7|SrkMC zMJ%uy`GPXIt`KXz95r=8Xm)18VbwjfV=Vnn3c2?^73aJ`lme?7S5+Ttd;3o%e@Ewx zhCyA$vjnx#ceK{n0w#9mmCqyEzu@(5l{!YFJoHgMW}%eN$f@Lq&TVN(MDih+if;vR z5N4ThdZj=$=+bsy8j*J{X`Ec!(r^CVAGn5L@mOb4hqBZic%d>Ol__(U=A+J%GB8Y6 z34ik#&tLl!^>9sh=?e}YzV#EXRiuOtXpr+o*TB>Pr~tA2R49}<8TW@qyj5+*v9)1{ z9acX*?PNUSH+_g{XW)=)k;Ji=RpNq00I|wHL&3~E^`Z9FlZ2tk1{`b;m80@11I6D! zoS~`9`RC%bCIb7O>~`YxUWK7Dh4MVXY(TvP$tM)s-O!b1O1Inb1`_mSO)FEmSwy-N zmNMRqweC=7&%#^w*RBTs@hA%g_i?yL)|r&1xSvpI?MFd!M5!I;cniGK zcD-__yctUBu31({~xf=`l$ybL=a>)n&(X zofQzOOb)Rt4b)(`JUP0eE5AZHz+7F+gcULZoprU~^})`B0S)XjVYhuAyU&=3{V2L5 zW*TpNdszuB+0*;8=+{tIaX(T7pi~xc%sNF206lp#u{2<9*oEYfF-Uruf|WKht6o)=*;;{Cqk^cz{^FQ`-L^iym#O`;H^ zcTd`X#2E}5*<&;mj9t7_ZnsBe=p8vrNx!)p*x}Xgb4J}Q5DvTY{nLO93sy%BveV&+ z;gl=8@T0J1jZ)HcHyG;s&PiQ{#B-gjdztaT7cv~?7{^<>c_VU`Eb&#+T7O+Z*{z zGB{mNCY}W48#~#nsu*oT`4a4S6+QKim2klLeqpGGa z+W1jeCnygdEoS37m5Xpf>Z;*#B>Oe9lGs0)sm+Wxj2$vrD?B@)%r8W`x;P|;1x}=_ zz!AC=j%JtiEt-)@v|z*NTR}JFj<3hh7h?hw>I!{S#k{ZFZ&BB_9jTpX%~P@FAkwQ? zhSjZ~xZ$w=obdhxP$*Cpe|Q@+9_)gIxZ^Fq0QICU>Zk~Xg^!EZsM61*^2Y*H23jw# z5JpSk&Ta66ZukI3Y?*RGkjrm%z-)htGEU2@&;(D}h(41fok4|~EfM=-nY2bKlUQYb zLoFZc)e*hift_RJ_>jIt5Ch6HW)9ut_dk#DPz39DrhBT+bK{2I5+?Pa^G9tKYt3T- zuDsX%s3ah&CV^#d(PdOn&wB3XZ>JN@Q(9JKL!l>zw=#bG7kqnsgeUlF9;Et0hO7NtIhE0A&(TDLf)Y7&htlX6?f6_K^LYb;rC z)?eZ*U9QH!mIH`aCY0|J3U%BNP>lo6g__*6&Aig=rUI1 z!b95}@dQw-7j~dLN@%r|+PkUuWx|QHATR0Uo9PwSZz(SQ+Q+}^6BX{-DY_zkw}d=A zD+J{eY2Do2gNEC}Fthpj?)y0=IiyD3NK$o1FRlwb8n(z&?i!^RbB<({ zv*$kU=PNeM@G&Tv+&MeG#G3pdT{Z+o7uJJ9v@1|X=<5F|qSu0TYyW6yDis;sGYr8x zam$Mw1SsS$sjCZ-X_%4cxe^XLXrXIrD@jy9=E$GJmHd7lR3$uXx5h;Oh{d3d?~kBJ z#g2kg(QQiVv@gO zvi?^^#)(DRG#qw^;LqjAt$_`pR^fErX*z<9u|4m52(v?{-q&6jPx<80UY}#1DN# zg*0epmN8jJiPPw~IRXcIz~zdTFYQQ(K@knaWwbDxa_7pQBdI9nLnV_nl=cz31AB2z zUu|-zAn#%3X5{=%fd@_JW=FHdDe@_O5y<>p9KF2{Xc@e=d`O!# z@;G+;KqeEA*>Usl9A6g)<=MZQyDcwm)3t!6myBxXaUb60q4n%k{qYJcwj@36XbIym zsU_j8Hlpa|+GL2BB-={@0}OJ?u`l!qQfK&yfDB)MXH1Ic$mKebVRFxu)@~;ZqT}h$ zJYAa`M~BeDww*gh^X?f=2oV7sT~2zmM^9E7)&gB?Vzn1vfi2Mar9y|NXa3Z*-}VmX z4jkX)-^`*?I@8X{m2=G7(Aa5r#V*7N54LSwtHCqk<(O`Uv7>pA_q?><-r9swY+Sw* z6m0ccUG>K@)kp@asZeWbTd{JSq?1)HTn{$JwAsAXNp1EBwYWPoI9aJ9Q610g3SF)v znBLfkN={U?4XtJ@e#vUD8xkrr|C*n7y4tk+D9ZAs(vCGydhYNQn?l1YyI5<(eG8H6 zn~YxW>JzX*cXWB|3wGoCe(O+P>GDRa0yw>Txy^$>H%+JYL|A?=p8xxWvNZGbKFbhT z>mdp=$xx+bzLX=ptUYIu12L9X{w=)%Q+SZ;JEDo;&;3Ob;c zC1DcQJ*rV47zfJEN#92R|HPf~X(04BxL{&axA0Qh7;mW>?a^I2UKp`mYC$07g0}vP1A-q%j*^UYp=-NTHo+6 zU<-t1mTSy@9XL1l$xZiQf0hW0E!0#H$P=~P=J;vzal>QzVm?WexrlLZxVg@`8Qp+R zoB;#DXf{&AlC?2&Uc3Az`>A^5irtJ6kxfC%OH`f-8vm75Cliw~ii1e2O|UEXpeEoI zP8-QNcRBaFOEg1~(M~=97Rk#eLVFH}IgDOc0xs`OeI*^=ZYyC%v0yRGGHY zyi69Cm#ERsR|S+oAeiA)G2R$PUWE1+DgA$NjhJd_2Q{$aGCbl<4Y_Tgb*@XIsWa(8 z6*oa!xl*M~{If$~=8Qph> z=R%>S!+kc`qs7?TUo58XL?Gbh=1U?zd;br%ygHd%Okuw^Qrr9+WKaQpf&A9h787w^ zzh@Rm1>NFHVPXUSskq<>6!FXwwlVT71^k?sdxfBZLkP#kI=?A~_NiH5ZSp~`U#6qq zwHDl$J#WE`Qx`$_>Z&W+z1qpShdN&BIRBoJ9rT&O8vMZ>R z+S2Svh4K{0_?=Ux?(~7R-2Z~AQLGECoC;v@tuql@g|U{_q))@P<*|}Nji{`77nR_E zIZWCTe9UmM?z+bkRf-tnJ&|Lyg%52ca-f-B$xo*KPW*H~6nAz0`r_!j9sSxLj-f&o z7F{(li%!>(Cz#iVYbf%c?Gr4QMwO_+Oe{tLU%3)^M^IjZ(34cuE%0t*<>fIp^msB_>Ufk+AA|25yoZeLFdxkg(7B`Fnj$xuf3&csqjMkUQS&@B| z;*{V-!XSH{X}_s~$XN7`ts^TMYy!XuN)`Fzqa$ND>SOKOs=e>OxxD?kyceEhm#-(-7+~VN|QEnKghyjoTj9RlLk3E8IG(R zY0!P4)#ZLB7#~GEDV+7+|H=@p$O0XjDt$i?us7TMcs0;v;^Y+h2nQIfw|Q^|ya*RE z?ywj=eEd(JggX#w90Z(WSJrhy6~p=Oj&9JnUPebL8){X-ge1+}*XNcz=9aARmCKEo z+x4FtGBPq@8HCGzg$JTswrGP3ji^Edr&51mK|aC!6Nii*sxg1i z<6@^*XQbz?F#nMU9dPn{hGxuJs76zVM}(t9(}{D~|8tw2ry~QK%V{V%dN8PW2l+i> zHZQnuv8>1=jqU~Z6uj-;B2a+B;9Ax9f6osRWXZQ%e^nJ0RVb$R0}$s*RZKnW<%@MC z|4|uhix*&Zn)C!CwLhOamKJqHD_WiiIRzTDeJg4xf#VV#c^JcyY~Z==TP7MRi{)wN zoH{4;ZlTa3{ob#ah;AN@MVW%B@bf3YnguVaP|)9jb9;LC^)p25Kb zHqcpWRvz&HmF5^rl9QVZ-ejPEfT(}Bw#E40TmZH-aA9)Q z)8ZHY>v1}L_XTF;ICNEDa=L&YaUTsH@_XdNlS2vSI8C9bUvNYUT zuGjbQREm(!PXCwlt_PA%kJXROfB${Dyo~dQc-58E1WXxr-c~qX8yP(_qoo1&;$DBN z93JHiiut}=pR9WXs`&2U_`bY81RVW2+Yf34W z2*Ug4=z3I~#-T1Sejs`$aMpGGHWjGb?fCNIs16vtH;lymu3n~?8H@et=XmbS$m!-Y z-{#Zcr{xY;vA%a9?FXrM3H=z5nYFuaKi^BV*YQq~HqX1Z%?Y?9&iUnUz$=E)^JoBd z!~TZP`F2Os8c0v?z0u26+H!*>MVh_~6I|Cv0pBBfE`~9S)rWhf(R8Cb`ut>dQ!O_= zj1gokUs;u5ik7UlhD9@5<8+oB!orFbx~_uhWl|_`C+LPkRLaqjU0ocPml5|nj}0#| zEYX~8vO}M3Zf*h21%XTN8R!JZek|Cyd3?kERAB0-XDq}~+EVDvms3~y z0r_BBL5D8+flPRK@F2H98<<$ksjXCGXm9OrlT*+hZ_^N7MQeY0YNpdWnsP9+p;g${ zmW9UN8R@Zc!}s@Oy>HD6O+T_vTmA`t=_AcyG*?XtF+cAV@x5E!+#k7BnfbxjytNa3 z-~G6$Vs4h)U`u|`=ok=jIwdwGEBepb|8hS|U}bZv<8E_|Ca&D#VBcQfb0qBPkK>bI z7N77$0G#6m?79cVYKAZ0E+y&ThmSo>R|N!Pknml+KIaAO{3O}vg{`;2pD|Qh9R0Aq z`J#lHYj&E+>w9GM5(dZB1P>@YT*!(k*K|bli~-P)prMT}2|V`I&U3E+&9sy`RQ`4Q zErOca(GGVc@#kEhZ!9YC7f`G}OPa8HKC)7n9O+nI#^^bkk0q&G9f>`?o7DM+zi8-+ zah&U$I7IFrD%n@`H1c|@!`9-9=bX5Mb^&#*n9LDMm_=H{<*DW)e6G1mLLbMvwNiJP0hwQff`p`BCH zGor|ke`(xC3xcR7yLOb~rAP&uBYrZq(*7#)NtorjgVX_%_a0(|W!!@LrLS9W zrx8?i-C+6npZVRa*jJkzOm)xozYkz%@!6ZLHrhkMAsKZga5L}wvq7yu8=!(04Ij95Ikc$$YayFUB0JtZBia$YU6^!>XF63F zJd_S$AP<171~`#8dW}t8w@mq^x~qtyXv24osiHX1(f6VkR2!EI9@hixzEKldd}^9w z_dTbZ+lAL(oW|g=$pGIyF|WTFx9xDz%&3sVi}cHHl~+i_7qMX@-?OQf$Iiz?A>Z^A zIOfqO;9~V@qtrioU8w0gE$b9tyIC97;(Bm-m-m`i-_+oGuzpwbZ~O7#vPjHg z!TbxCryGFD?~j_4z|BnV&`N`f)283uWhxwIcToB2b#~ul05?sMM{^~Y{W!Kuf1k8o z{#CssTIT9Z{aN_swZDw<^hZ`yN>=v$>@{5YyE)S8u2So~D zA!|NUBA%nW>u@aQf4sba=fwc?iOiwqqmnG`x_#$F+WkH_yzL;bEgMdk$XjZ*<~}fT zq7wRcwsW|J+4UNcx4#q3Zv2|N?t8qtxgF)MqE1A#XWI4mc+Io#Gp%zDP(crWT)juq zGPCWhHS0X!(G~)+Glg<>e|O!0BqwecP>~1hV4bx;N1SYQCOt&sUoB5P36Oje={s%O z92~yjXnNh^gCpkdXb{&t&Yy+v*6Om||8n`CCUuRC3tX$obHR-zrYBI$l1QyX8P1`* z*p>wH+cLQxj7!T);|}2VViu88VMA5H6$ zp)>h)bxC5+MPfTML*%AoB{2{~4~!7m_eWN?yBc{Cz;%q|!`e9!f6$OQX`FVy_u zrH7v;&!6zuMdt1&?Kdr-HB_8?iqj5$na60tAv;op^6;55^!90ch<<%IKqn*GJ2rZz z?_{`0+3Ma9$*%Jyg6}4xca?_!ne^s=E4D2U`%O4sA|6&>pBEX8bsqb1^!=C3+n@J6 zE&^UI^So@Hy(bO4u+~LHLUU<<#%wW3r&_~(5fVPTuYXUL^<8gy1;A04zMBcSn+#*K zbFCbUI-`^8Le1Cjo94tg#8a($O%g~PJh`1UO&=S{&~GR#tUQzDi+dfP1{sdd&P>Mk zEtmeCcz-xqp4_+hc`&mkuJdWThXwehC_RSr`wV!Qy;~(DBHG#46YVBKvv56L>>S#yv46syc5(BswE4C3QI0!A#%Y1q@ptR7{|72WxOmBwD{+1c z>AOhVH>aUHM_E~v+nLCa$4CC-a&yLC{~30XyVuANzsKdeJIp!@w*6E+|1fw!WNy(T z@wKF=Oc4y+(vjuRE(t4Xy-tn?9fVBxN&1Eb(*SpW4%vC>?KWU5HnTIrO75y@Y7jB zkbf-t&E>x_wvr0{{yV&!oKwwTML?s@Y!Ii}dXg>NTM_CkJv_9c0r)2J43?k-ojcDU z5pejxNOQgaFxf01=h)llV}MC#U|N*Q$J(~jg1b=+@Yvw*+o}K&GBSH9HOPRut!>g? zW_IbXZJ-1u$Q+*pMl5bAWj^HDsyra$vZd| z@-iweAldKn!$rsW`XKC}$?10C%j}{D;gm-EvB9~CTYc|;IAqcLf;(3@|LN>$d!3ZO zI?oF&jh{UY_5(D$-4}5Q&F|`p6FP4W@mTZaj>cy%ocXc)o{oUoRG`Dp0adIf{d+U7XMcXz zP>A)0m%?V@t`nwre++RDu71lO7kprP^mIlv4R-1eLz)|r%B~l0d{*5^_3xkp0O1Gn zCE3(|;g==T{|;acHern4hq(w?N|Qmy$sj5?56Wq)TXa(NQ4tYeOw}`23M?`Iqi$!- z{A9H&LYBfWy)WY9jt{wYB0QR?T&zx|WP-4HP|ls^ax?tKWAj#0COo2M@bgYJ40`}e zo*9}frPdFp;r&>ImnS+Z4h@UvQPSgGDPYoY@s?FI#%S|6-I9By@_$(G>d$*#rno-y z=nTo2^Kmig4Q%STt$2c!ijL$Ov{}uwB!4HD2e5VAgZv*1&Y=~WUpG5D;AHLy1@;!q z%`b2?>+RFOA<@ATq7HO&kzUAANBj2ou?yimG`8lzIKQV|xQH&kFX982AlLX}=fAx1 zbk3YC2X8dAgDJRmvL_W?i@*%#2UmMxOJRRnx{LDmiXnjja8Gdd^ zEFoHuA7BMtt=z)%N|}&!QZG;HrVyOqKTWT%E0GSdWf_d7ww>1_hoMY+^+IMcZ5rgU z8Kh#6Q)Y~1WM#o~q3TRk@2i9%FjBI^gTLniah)$A^CY}~Zc*tKRA;I27**7NX;s7U zNI3Y4w9#|g<0g_;6OnaR;FGD!hzmENlkQkZ(fF+UCv}q`dH8h(EhGCy4sjr_*EW)5 z@lItG7uP6UPX{B+_1h;pYdaU+VWf|x@gS2qfOP^YxQSzs<0`!1K2TN3j1!74T+5*- zqvw+$-;kI#$|L-^R!3_+j`u}hxnkd>V2;PRn6KDs!A2~n8rBll$MN4Z%^&l!HE;O} z3a;ohp4h>cq8uUeIJ{IxG+S%@(OhZ6U<4%qUe|=mn9$|C<8F3waZ#RmUYFbBOrNdo zgllxqC70}+M+H9iUal6Gt$1TcXMghRI;4oD&D8pPp8v-olhqRIPgR-2%C}H#R!>PO1Q(_d+5@4`i%lM&OSmhbp{$$R;zgv}BhxJ{6HHu_f{+^feD6$}>=Kk=m1-fiA7;YSmi0{Y@#Ui@?Y|5;B8-0A-}<;Zd5?tbdv zS|0OJSB+zo^9?+lvz^bv{mHB(J z*|#HoeQDbFcU{Op%Zl6x=U&u0+XN!Rl%~W~kb;z5%ofzI8(pKy+z^zU?f2KkVmx=^ z#4DPy(L)XJj$tj^lEphW0$y9KU^szB_D#>BRan6`l}(IbQ3F=zznIsZ-fN?wYyp<# z)mKdX-9*|e?Bp26{pp@}!vBW*lE+T78|(zK8c*{LtG2-jmZPY>Ah{0RgG+{7N-#EC z=e-GfDjZerJVKW?J2xkpY0g*>nUr3Q*(^^}YP~;JU(!_-XHwHYPQ;x6a++)zBN7&r zq5{AvByYJbClT|tfs|opZq46ki1hL{rL{;(W~{!th0hRyx}Uu2GDKX7PYq*CY7pV% z1y1<~_*o)PIvO8qfklq#G9-RGK`mS+TwrZ;2ySK7Dn6x)n(}p)UNsUZ_b;27fqUUN zAUODSx$fX=Ihq6`E*h;4Br%cy`+tFhqhksQ00DAfwU>GXjQ|LMj2t_?_^Eq(3!rww zJVjVEQ#PlbtPbCbd*RDL1x}3)Mq}%~_Jx05@Jb<5*SgV&bOu`2)?unZ?dnM0II;g2 z$$dc~5gdbXKCZNpkr*7ZZF0WR0g2W8PviiH9v9S2m>xIU1B_-?g~*P)ZZOcN7dQXo zjUAnzAHeV7o@P*e?#_yI%UqhzIkG-EmgrX1*$;gymtSgnG)MfN<%M2I;O#N`sV?fPloMyCtPTq`TotBXL2bySuwD-6bX6^&Wr!@qS{!2hP~% ztiATybFDe2@8uOHr;yr4qhuleOzf(X#nN9(uwB$YIeIZYx@tvP2u;Wwr;BDthhSRWr}Bahu-5NAdEAA?Qx1a(FH`_x_}ts_Pxg#)AbZfud~b1 zRMD=rL58IL6v38o3uqPz&gT1H7ZNB^&4#6ch zuF3b{Ub_pHjXtvk7||HjPFohpC@83+u{sGAXQ_J=S3zGMZYtf);>`ETjQV4a?dDs8 zQxCIqygnqaJX~`D&bX7kMAaKbu1E82f$X|&pe>gqdw2zBpJn_IJQ=jt!?H22jUn>&wkn%M=bk1hD z!czhM!tZ8x=iBvf3cUyt+Utrh*C!d39=N`N1R-um<`s)ngBaZ?*Oe~)7cD@=)S;8h zw9z=K+pyP$V#RwPQt!z_OPj~0-S9n`bzD|n-UeexUAcPf&$KQ?+AC?v>kp+zgg-6q z<>kosU||*mhE!Ct^jS)Bt!6RcEGFp4X)>Bt3)}-(rW#^A95H)4P^E46)lZRz`skQ| z_`C{08wgTKgWYD)<1x(9d`9Z!e!Iex!euMwaDPX(e?n5)z(2nOvb{_FjxASVyu*$1NKNWT%LfpTnKKu}^$Y9*X$z6uL}%8_S1_A)dD| z4tviR*vnTp`{p#AAZPA3A0 zRkwC;hM?u?Zu)9(R%Ww2$nzK~Tb zOLBR*l}^(ZEXgbY67y51^z?SiR=dLJKkKxA@??O(d*|Pk=7n}YN}$mqa~P$R{*L;! zUWGF~S=P!(L8dpP(gj?3Us<%E8uhqbpdOF1_xr z$;CxFq~g|kH{0p8XsdpHaM*=rRu|hlK z1B*!QhBY+Xg=6O$OS9ZSDM9e0V=~8>!sC=$NJzK{et5Ll7)h{a@E+(UAq@W+V8Rx; z#8DA#jPZ2Yby}0cRxh7xbe^pR2pE;0Xd-BWYD|ND3r>0d@Agj|Qlj06Ck~p>QD;j| z5p*eVnPrj(z*QcL@y(U`mLJ1zCl+T3JOU3HJO5PC>E!<$AMXSxf=%Hikgs3Ap4PcP z;q?*kj%KO+l3dLbfwDmWtd|TBDZ4R(nXDeAW>njeOnZ3=JRDU6a|?tHn37nOLLYOq z|LO7r3XcHd)o>P)O$$O;9QvY-n1#`JxygE};qTn|k(dyWhvqYb^i5TdZT?ujFaXN% z{r%&eM@56!cNJC}B8yAH9^>rwKw~(C$MW5t;pal&7*}f?G1n^j=VY)y?FAAEheJm? zqDXieuNMLO*fbpe;h!&)`}ERu;vDIiv%cI0-RGnI>R@I9$JHV9g<4y%-xa@~A~7<6 z_0IzJbRY_)juO(|31Tah>Dh)&VRn?g@a4N$h#Vvg_X4uXR5> z?T!;go^Q7Rb6Efu*%)x99!` zv5vK;m9wCSoxL34^C`V*ICF^_3a0$^uC( zdKXmF#Qgd5r{|&tN;f$oh%T3azjlL)kWH^RW+Pe+Y&3=lnl4Vj-i;8f9|I35E90mc zYd9m?jiY0h4AbnpUSJ)QVvcog4B`smt^MjYzKyBX7Je~S4uCc}+Gb{ELDtg+xJdsU zuZVgmQ0KE60KOHd-QU%8`FZx(Ug>@OTjipO)6WH%WJSgN(^xeo#_Q!^y<2tx8!c4L zQNw630JVG;2^<_kpC~7qLn=MUkW|RJ+siKFJG# zn>hX&zSU3>j?tMhS4u`bs+LhZ>#H!DTIl>Yw_3(|xrO_VvS(&E0_BXC<7QkFOV)NF$5DQ7cr*E|}g2D)xCmt=BWlWwQsh z#f8qPM?*_rhF{709Vxl^w+sLmsW$FLuEDyP`%o>P&zG2(2;hQw3;F48B*erlWr1R(q0|KoEK>6K0BCB^~7#JA2xk$`>aG@AV@v-G)aw#b(jfbTsS6eEc z6?;&s35J5ajgDz+|L?G6{{&K%v9dx6OMx>0@DTsFEt=CM683ATx7u=zRpj~7<;bVM z*$OK<07K#zj9*4b8HI@rkJYuJ+y(2T+u4u2|5Y+iI=l&_y&?mWNT4G&{q6fcK2cX= z{8K_VcZOC1ogA}uJ)oafOGWun8yb}h`mS6UsP?-lyS6TY2!{9>QdZTTDD-Ijd0P?n0#8EJW=$i_0B3Y$Q52%&l1|fo^s?r{v@p;~zgygE;RHuhy7asK|I= zVtf)X5LWx|E<0&c`@09>%1d-cF)N;quW3b@dQ-GdJ8krXYZ*L^PTs0kSK#m$KdG7L zyw*?`uacApongUQQgEum01D-P$}(Dhl+)Ozk1{@U)F2M`OsiT1o&Bo>Ha-u^Bh}3P z&7kf)slVAQJn>TA0^cq*Vkno#9iA8aNlHRHj#$n854SdD4Ff%y^W^p{OL|GAEHLDg z;+m7(3L}#`S7mWpMh~wTa!ruXY`ar`C zh;cVjP)neWN_uDMw06d@mZSAZvA6+E$!MKGw|ad{237Jzw;VIrrU^x-qiFEo!eA?GpIP?L68VKZd)q^6bGUZ zXs}04>FXr;$MF%arf;IU9L*VSg-UpH0mruagFM~yebKxLLVd~1ikQ>WJTr%gN6UhQ zB4MTGW@a^1k_jJ7s(m`bfwF0f;BdA(dY>I_4kB?vPh z@qZ@v5enoZnNJD{^T%$in+w2YmK&1LoG_8x5A0O({#j`zrRfL(XkuN0*^lj-jN4@C zsutM^?Og(6mZb(RhL8CX@>w@oK!68(v&cIwybH!5pk@cUeyKrjLjJFkuk`RnSXec= za#&Gq?_!2-)-$A-w2QGUqhGVBCL!%Xm8sMeJ_O6wfa;dQ`%*Zc;(CQgT%=l8r4Omr zN?hfNa3n*e5hMxRdZ>lt)Y1f$<(gqqX)!@^xL_5p}QNyB=nf*>7_K;2^O=t1mRvm6LPqCjKBD1L~hRDAF_=Mrf@(xI102a9bPCbk}{}${+~&=$j7`s zg`K_jFTCxLaURFm-x!{>4IzgBsdknGz6%SGC~r`@aTqUT;23SOLl}EwJ4x{2FGCYXJt$T%8q<4P6hdPt7opVU;bg?^tiqK$;-j|84z z>B3vJgt|J8Os1o7msQ^07FTq;~z7i^rX4>^niV*GL_ozEk9DBm*B`Q&Ol0OeW6q>kPs~_hU?dfy8->{;`+-YN!XC2^5>+d3vR}X~S@hl! zMm6fI?-2vDqQC1ptSsTA;>ZU0!1 zNXiE#5L;RoGCP$@SdiEDy;7FjC2Z=Ef15-5RjqJVUMkbm%9ZDH5>G$oODYNySTXsr8CAj0I0ySy>@> zwwXNBd;u>J>!(n`j5IW;T%>@Gwu2;Xz<@o+rL5_lBXSPwsG))yr0zy75%n`&pj9}oyFnvjPulC@6JuN7aa+?;5ghy)awOF8yvL54uRN8ide~g zx=Ttht{SabP#kF}Qcfjd?k{Au#9ib)dZFLO?Awh}zd%G#t%|YuR1q_I^#rDH;1j{U z;}G(ZnB#PUP4i3c8;K&8g{GE`T7D(HQtQ{IYrF!%Btl}RxFGgtatS)Lm(6N~9^p55 zTRx6z>bM4SA{3?F(&IW>mtb7pLW+!wWRj2@ir7L;MYy)+^_k|s)YbKi*I04`x7XP{ zCdTFuoy0HDVL%^x&OizMFni+#F;PvL0cdJu9p_JjW*j~Oq!wzQma~cUw$}_EZxO;2 z6TV5j#U_Uf%Eubsk>`qh2hXj+8vZDkfi9`6sVGR@qng0WIrgR>bu2heq))PWnm$JI z?~=2iFbhK74@6Jq$L}_G*uOy5)+lqf{fosC`%l{tP0YWx{zgQs=*|qd3a=A(M6e`E zSM$?%w26>uicF`L<7UXrQgc?0@p@}HwW%jnqpomz`M%;YkoJZAH~vbYUz>>cgMw`f z6^_uagApOwjGj+D9d^7ZUD8zb+whHG42ii!I-Kog{9`6+9;iT(y2HEue8E1UlB?}T zT7KlWb8#%ck%dvHcok&xi#mlUp_dRkO8QQg!}^)|WLK=b$6wVC` zWoAZ7!sgk?vXv(YHrL0s6OU#`{)Wq&D#`3a;GjQnPdeSCeeN!=x$wCK(m@LsS;18N zgc@v5O^yhX)=kzQl92ji?bC>K{utrYC;d8TD-kB+h`7KCLPOUxpvn(0nQ&c|s4Ou6 z@L|=kEk^U?M%sF;BHlVqPyAj{>HQhiELM%=S$%xh?>N1!-CTV_30|4@(41Tl5talR z#JX|l9=$N~cUhO{Hp${at#nbQuC@2c8s2d2LB%iC6MdZ!m|K(v=UvwE&dsX#r4THs zeOO+j=r#MAzURr#&VH+bJam{lIlpZV!^krg+8$WdHspMD-FRSNtKl1*2|MwWrNGVT zb`IpY*Wn)~T4IZ=!lU8|Y0#wQLC)_IkWHfVpsIgYvibRm7xPVrn%KU84-p=<_co{h zzyXtPn5sANb*v+i@gh2i`Fc&rJ zmsK7E{5fn_0_Z?yweQ8S7|SKIu3tpoK%-6^Z4lozLWYeR+7ha_#D+_dRGlr zsbumx(89mg-0>{e2r=I|RRqrpXMk56>uj%*tVoP?tk+b63?pDp{Ntq=td!Mi-Xe3R zh9^Sh?qiJN?eIFE)~ZUIJj?4J)#7m5!QVXfrF!DS_xj_Nk!IIN&g)SR zcRa%_`Quju%RKcr28u~AU9W)z=gTkP2ki*4P9L(Lln9%f-Mwo1d-`Lr<>FYedjaec zeZLDN{Q}*MGEp7t6E8W7cGH_meBS_1)I9eOP0&eYE%)LJ@k30dl(hqlzl=CpZmwGs zI#UgIE+ImZrNjaJY0-`rju*$!_YZ8meVltiGm`?YMpW<5Tny_MX#s`d@s zHo6q*)c5Zl8h-#cc{GYW1AENF(w3DwN&GR{ zr_SP7eni`*5pUc}{;^<|vY)L-=^dAofr`FC-_0 z2YqYZle6J+dMHlGMWEis>Tvm*E(K)OnE=Ve^@0U*icZ`0AUm)LpRSx)N3e=Fijbq%TU%GpN~%_oetOx>X*NBl zJ|MMutj;E1`9v_EZhI1HzPRdnw0pOB9~XQ0BrAZC8aMz;hFqH3EO6P$srH6b8)$OV zOL3|HVEuj2Ot^mx2nTE9Ed|l$>^%-Ef5%p-%&&m;Tb$gH<_VP7GTH?c30mj!8<{%o zuVMHG(DTuaVA-Ez&e38Vn!r}=4a&N8G@sbwe(&PoxKE(0cl{vgwvFyuT8;XvK4JnF z^qEU!P;wp(Cs)?v=734z9yd&Pz-J>))Cs4wc7Vnpm-Q&41qIwS@@@aq=8q>JB*+Ax zCD(n1sx{4Bne=;BlBoF#;*0}uoB`kNmG@MEd4U&%u}s{Oy#nc5>~i2&k!b%3b-&t| z2%l9C6H^EpMDL=GxXd#*Oavv+miyEH(@G^4R7Ez!O8brz_E@XBJI{frD~yuMxD{-)uV$b9Q}6xl zPgB>iV5(V)mTEO%0e=fpb2Dn*i%x64A#r6CL)2)(b?wv6;NZU|v|Biq2;XSU{XDoK?; z3hJ3mwlR5ytELS7@7bG2Rxtfdxs%s~*s2fksbr9Cza$rwj=(1we>jLqW533y@4W22 zo{L_^l7x~#B;S&5;dbE;8`u_Ya%gW7F}k*+Ck6 z)9Z95x;^B!YMQB^Aj+gyJfTB4O7nHE+P3CFfD->)F+*}x=4fCPC8HSoN3mHE z4@iQzIn(>6KvVjBh_#$;(ty+yF5-T&1n~FR9ro0=g3uHlh->_w+`*CbLPcirv5;K+ zTM_T-$mcrQib4!CS}PTVNs!{UrTDORXj}q-J;J{%fAlqa>$EJrS-~LXsVKt<>%avS z9N2P#Um2tujj5<`IdNaURiR4RQFMn>e;qJMD_{n<-O})sVlguIhnqzABV!h7t0B0Ijbs>rAawhmw$u{4ZCMynwN#5c(3dOkI0|nj4vGJ&Pf6Ng2P;5#PhNPhA2rXHn|2@kE-)NzVF)dqm zqIdtc9!R`VIR?Z_I)-Y~6F~uOE0X$M#^5xgfbS!YBukX575l_*2R~2dToq0*O}_Qe z=_#jfon0rfRN=Jo*RM$cY~H-`46F+;REjWxn+OezZ%jS&)A#F#zsJ4iG`QpyRY|D405AtyOYN~y%zurEKCYI)Q6f(BK!^RX5Ev4T(DjG!a?_oqhzz!B~?oQPrrmuH%% z+?`v8*`^i=Hj}G$XDftqRY`~=X;NC6As-YsAdpMPS_SeqEh)QQ06I26RoBvjpklboLhm?_j0m7 zJwUAU2>3s^t%}={a`|en2a%XX#l~5{mP{g9`>R7Q=yUP?i9aFjKB#}_21ZlO9o@}w6jl_XA%-z>P9ibnEzgNgK(Cm3n zAz!aK{NFSEfvlYG)E2m>;Q4iJ;BGIRuWjWnZ_c;Sa@zL&d)%Xitqhss^$b|jduB(- zVj_!L68i4H&yHl6LMg`_FS$N+`FoYaiCg=4cD&B_3X%#&N=D6 zxc;~E^KnEeU(&iZeMAg?$eObSm$P19Vc8AWUuC&IOC2c8K`<1mF2`Dz#%>IXS&dP( zf>uBVaT`w$HZ2_LdBJPO`8^KpU3qkQO?D4TZc6S4$~NNklKpAS zB5I>??oxb2^L5;59^Mq9FvBwNpQHK+D&4{xnvdIPn3(rbF%;Qq($GC>EO(coz4D;D z&0UM^Z4yfCQ6R(==&AB$opnE{)jXv2$pIAzyJR!f-P9qjRr~gGUy21EEwn}$uxJv6 z8|{-pAkQ4hOT)Hn>IDt@I)AGNFK6X`!d5pdqg1l!Peg0v7Z`JXQ2pC!k{~|vDhiZ_ ztYg-kuLR7Z=2|#$qFRRdC6Sk3&K?w2>sk?UWpIcF52IErse%eGEHTtuyXVdoITDmB zBOXdE)}6H>EeWW+VmN5xHrXvhk(KpE(q>-Nk=|1&WMI))u( zNA@)Sm|=e++?E{>+nJcvG_;cldUY;=NT5>N zU8X1ZpdU5A<$&6Om-e}7v=hAWBayz;rY#UGb{uwGwK*esctg4I&EJ?mU>uvMW+nML z(JOg2f(OnoLS=8OltOOs)v5>|a0YVQ2dYvpr~2He3Qg#%{1mV z0^#tb(Ej$2jdfk4Q1KHPZ>|YYmh)~DRb)kyxm{- z9-Z$W*z7zt5;zrY8lR>AlJmN4xiZ(IbU*^qNL>eaC$(4oBoB|_enzbXpIp}AnS+k} zeS@QR5tQSY8pa!|eV=6My_>*}AH5bSV*tCpO3|DP%>nY% zzlw?;+mrBZqPFu$aMxzl#_ut`*LvdJODdqqa(xbc6TPD6Vy=^^w|{*WCCW1W)Q z=9$$|_6^4Xsxa>&>yg zv*;GGo?X7hSt%-E_0wf;y%;q8bp}}T%znu2D(ww4*{{4Vh)4?)z}lq#VQnCUX_Tc3 zn6P$RlyhH6z0RhvI9okTB)h6?7UHYNG$6UZTb!odCZbuF_g>qqV&eiv0H+7}l|}m5 z#E(#cB9A%^c=QVC+=4|jwUVwgBUy1RQz07l*NRw%%XE%^OlFNHM{;O-zmen+tUFm! zlMnwG2DdF3cx+F_b)c}*U$Vi#^lK845Q+*R!3CGV3jv+1ov57?y^PA6mb+&%&l0hF zrU{^I5>BeVz;iCT#1-w&~&2??NzkfF9_BPu@U#&u(5T2pKhNVSUK-PhJ-s8Mu4J0_zmG6PZC;N9h~?S>jX)sSHRX0{xhj-k(|2Q8?HbNI;N90W2%YH zoskL=a)NV;3o8~*Gt{rk;A;x{Ok~;YpRHDKws&+rBJ?$Iz6XIQhI2&MrNpa%|AE2X zlX4)YFgP(ctZRsLTE^DgwJoS)drD!+KDHof5bW{W{3-YwNDZxu4bwG8gPIl{@>;_% zE;ohvvoHGq9kq6n$__vX6}5#q)`j6w;p4mN8%Wve*EF9BUqW6ZWMHbkp&HP${E{Mu zzpp;*4BY}+-h~`Lh5`@tTl=)9Whq<#CAU|ssIRm@f+uXN5E_`A@Ru5#{7fwH$x{DJ z50bVbZMbBc#YxeuNfORB;Q1sDp{2Sf zzCbnBY3yhI&n0V@?Ne$Ci-OZJD#rnu9*=w~72$OZ9`!fmf{!dNJktW{ZdQh z!SNBM-&hCp3C3%BSXMG%@3x`(&(nenfYTGhC zN0<|+i_OU(8fxbWA+F*u`=4StU{0&6`#daRU+jQi5Vy9rq*a4z-);Y%BV`s*@CX`q z@{G7dphxN=3qncMK~BTHB~LfEqCSJKx5Ae8L*l?3aY~jLtHd-#6`p^x;}gs>u~bCw z1pKZoUlQ~BmE+u8T5hD{rQ^1^*ha=rS7a%6i(hUv7?hQ$aOOp%*6D@lC5uw*$}EQfH4tZv zTbw6wR2`X=kA{9ijml|;=4}{V44s-sI+3KJ(K$Y|2!{&dU=0>M(ux}qeOFaF4`D_> zN#H1Ep-R>!W&5K!#q(~xVrAH4AzX3 zMzB@mP0%Unw4{C$Pc)*eq85ojZ9QX(57o9Ntql?x{?&{6ZaCakT2$U@d_1vGAMb5E z&{fMPA%pa@KHTsKa>?Mo9{+m6K4xKMOl(Idt>$>!@!ynNx_z@u9@OZZ!xM_ftdzCO zYvbCKN$Bl%(v^n6+-3GIoX-=g7Ww9!mz}rB;aEQ46%8!jV@f&Qi@ktP9D7VHk~Tq` zN0e{yNBbrH^PJ%$NgGvy4qDn3X{KhRwCv1gP{}kbo~}nH&n(XO9nZW7_8a6q);l_< zd6C{-=6I}gEi|IPB+QP;iLUWo>XEcr-_B8=Hz@z^-L;Mr=$upewGN}<*`|_<56-n; zYqZ_o_{qYRiWpHnp_<$}n;oPzcr%HhjGR_Zm3+EUFUk6qT!Tot++S1k9EK$Od9f}s zK%CJqp?)}VP>sV+Ec}=uCX>r|MQ8F8Vru5`9oPuet-ZP^W1nJak<&44RD(v<7tt?L zY9a@lfa%}k8o3&p1c_q*!6F$_2WJy{Vp6NkQgaKhw2d5N(kmf^U-YPO;+8=F-B%vt zeVAnPE!I5!F%2L6sh;bckPh8Q|#2idpr51cE4^Bh`-c9k`^bqJ=`(% zSX1N!C47YRy&i?Fa}0l2R?kc#)5n==tSh>{rHtz?@>)6s2UUTjQ$6o14YQSZfFEzN zNr!hN9|^nwWV}#gjR=gt%dBf_r{qoBbIn_QisU6m9K)0E9N9(!1Bwilw1AyhguSi* zT_Xt`6Kf(ZoA$6yD*Y(+JM{eLkFVF0{kAzL+b-ch-QAdBC1K$>6D8Pj=FE_+jgQJa z^28*7wqE!tp#yb<>6AVCmR<#l3t%tJ(4{D3o$hZDC^8N_7!gcNN@4cR{yzd{8>gV8 zfUW)*&bn`+riZdA8KmU{10&n`z<6AZFgkGlOrcSWA_ihMg)VB_YKy;9$Z}0h&9eAv z7PP#pz18qo#cro99x}+2e;O5CV(N3wn|X~8z5B`iq$?u)PCu%SLw?N@K@dx zs;E>?q|wUbWw`L79AIF)v#MP(Yn1q1?>5cf7e}Nc$!uOL@;s#oKFgzg3ImuNj{R@l zar&J!POQ_Azg*kY)UeKbKvS}^807IvY5~-0dz%hh{E;(JUH$Qy@=4XWP>a<6zcDUB zzRv8YyX@+n^Wnw^De>{X(I2$QUFec`XkUue&|vrguc5%&{9<7#%UkKy>H#S}{p&zP zOsuy)$pHHyP6`E^hl{VbQ0$82ox?&{|M_-e>_rzkICnDz5Hv|VYPn}=Iu>*jf52b! z+$P)pa8danHaaU@zFxfc?K{ym`BodCY=ZKYDLB{OO%YD=j@aVH572h;hT2p~N-1AZ;xuEaAw7cwUiGb1G zjmsWp7;_1}ENMO3~f?QxBK zb&^1Yd~R6H%7?*<$4ob!8XfkKkdO(;z9Z>_V@~dWm2Z9<6fyqE006BTH%mo_uARo1P}Wv=oNd{U??~F7TSGk$ ziWpNeGE5G4eq1c9-Ltp2kPCQx7k`=-2M%zQhOHRkhQqSv`5Nmt-q%MvOW1yqfhgFy zHM`g^r`UpN6uaP;1272*34H|b*4CSm(a|$TzjMY6G1myN-_Ed}+rmyhWUP$xC55%T zC1Kq6uZvZwpyxTA-x-l#=PB5DI2`aOS9rITBL#d|eN|WpCd$_HN7nk+NpznFISQp9V%dxdt&3}Ec z!IU1!jd#{nB3sE%U{!~i#;5D0+dlsG-p)Xjf62mUPj{^c=Hheubh5P+`}ke9{o-xi zmnVX<_G_EATdkL<_f9t`Ys2UdfLz~+Z|wNvZo5hUb?Ia5%elDYhl{Kw2h)?kD@UGg zMB-2C{HGI$hI_q4*Jm5pzF}K{DBOs;N|oo97hdTvdOl=QM1eg(bmMFqgfck4elgZ8%)JpiMoaWmqrUaJdA{jxKuH8> z5B1+7*Y1xjQ!_HmJgma}9vq%Aue>rXvwfi-^5iq@oYvej4(Pq`9heH6XAaNg`(!?*v6Nbde76iS_`La zF5-0K(oRxc_U;XK^a~fZ5pbMaGjF;pu>6r+evjLMq0as{vbcw`vZ?8*oo37sIHoeD z&PE9;sWo$IYU=K!YpDH>5e~@^pKChkUBsJa8y0ZA$45uMcpMpD z?h>VJ3RUsD=WjT!Te8C9Z8TZZ{NKl$5T!JFnim50Kum}8&BNc#ro*!Clqiclii}mH zs1n`&(q*1yLVzU1>Tbsv9;md_cV$}A{>c4p=ZE;9w?lg%tNYQ6*3X)F`DFM4%2Fuer~mzZ3dVNXNnV1q zf5Sf^KMVjPd1t=5zYd$>utrs848Z8(ByD1PgP(Htb zlb(w-GeHNEHD_#5trvHC&P*Ri4WIb5?3Vf*zU}fXU#$w0P>@QmrwVu_$yxtx*b+?< zF<)yVvI4VJ02DiTY|MFc_5*qPJNxasz3VCK+S_?qu`WO+!DGLd=x#^FCt%X`5J)2w zc3CcKt?eB=D&oB}Jp$SHwTASEH46`0`bL=8VyCWz7M6FgSl^`P6ECpg^Ayp(n~+th z6|aqeLm*;aeTJBC#KXx8-XR?G;@{&apHD*({!0#MTp%%6u8;K=yZsN)3NZM$3FB!) z8!lp&8n2+~ca7Pt$$mF}j}%Mg^Fz}r;)CNakD`x@<NqZ4( z$QO8>n+dm@&L5z#3^7rOJi(4=en642AAV8h-kJ`Vj06r7`=)&c`_?N$3cp8Gn_$P4 zx-VqH?gpc6zF_CaTc?780=Wbv7(Ni>=?-nFy7rC1KnoV2=;BJo(V+tGeA(&YSg+be zIIue~Du%bS5a4QrNrhfdTVbt#9DDv@_(48e8uySCy_#{7g+Vim&DJz}W4#!qVdMS~ zSdY8QpHpMtg;N2tD>U|gMCc)4!)6zg~~26E=W11X@OEb@fKSlTma|p(>KO( z(HD_e(R+P{J{2CJx~zrZcccFQ;ZVT>yO>!7`n-caTfqWLjqFj4GmyrDPid8r_LBL@ z5O7vEKc@dM@bPc;&NekMNhsB=cRuEuqtWYIJ`w@cgtcp*=kz-Kt`m8-naF?}IQP0nKF?H#McOml$FnH|Ys)e-gOg)iWPXv87>zlH1 zb&_jZ!C>aA#7O}Tc%$z+`TI3G(vlTrlO5*FDx%Lwg(~E|4;cVfRAsLIcFXxQJ}qs3 z(h6(t({GsZ0WH=Weqp>u?euxIzRW<3Zos3DR!?izOblb zV=R+lN{zRQ#S17otZ1ZB4zY6Q{$ynSfkUmYknwgAaqazwi8KcuJ}%|@>hB4k%7Z85 z1;+Q)w~oBrh+L{&zBau*FOh2IL*bD6y^aC5uLYlhhf1M~t= zsbTqhW5N!WfZnRl%fp(v$vOV0KPh6MlEt3IyyprZASoT%cvQt6RZ1zN(D}*b)xPLS z+dhMs$IXgfn>qRtM?1L#JEVR%UMf_;aeWr2s9Wdy@9OB|G8;%St=?&sCW9)*cH|@2 z@n`_``Ks`RPq$ug%sl-am#CPGrE$oyZuxp)S##Q+!F+e+R)0!rrlfWF=PbI(oG`bFxcCI4!Q^bYUFwcTKjoWOXol6WD8+hcV|~a<34rZtRl4ui zJX@)X4_wjuhym?R!tPm*Shctrx~sJJwvjISNi}BHk*swFebCYLyN-vo@lY`j?5@y^ zHpEft^O1x-ewNt3(Bgy`uSQpkj1?|}N6%GVtxoRaDh^y2x3&rgl!lH*cmaYRy`uUi z6KdA7WKIzBXSu|B%`5paf32*&?6!0F8X|^9y9=iNSPH5ymD3_;x2D?`Wdl^i zdHH<{QEaxA-s7>iKOB6LgW(v$<*O2T&~>F4M?sY9Zpc6OnEoG4 zXBie%`*wY$L!?8xySuxFF6lT=XgKrfg`i` zRp)uF^;@F24CH;%82G#wWgH z8fDu0+Ca2%XB(E;)Z!@^cuY!cO9j0z8Oug|7T5$rlRF;gjasjpR$BgMAN_~`j^oiF9EoUIEn( zUJuWIpW~qimiAnZpnGK%wfK6gA#dVu#CTNGaUkqo8tay(TdGgQf~h(_+fiO|y4i~M zZF%gqGtj(Lj3O(i4R6E+6A!l6mC~RTna1sM8s1V)hiY9h zd3eY~K(LpUOJwVAnOpPp0tdLdXybnweyojuJb-^79#=*xUT}5&uh3VF)%xZ9FxOS$ zl5B8rux7r_9%f@2xceqFG&D|K#r^mWRqdPl=YwI*2qa{%{VPjc6P6TTD zcx?sK5*MJQL1yLdPJBkU(&V!JmxNW~vA(%>&17<9dx*Jm18|oP#Gj-9kD>Cv1GEx# z(Wv_OY;^zXIDysAVtt{ZNSIK#-QshYA+zZj&;Wk#jS28I-QAs7;Tl1#_`Zvnaa8r*puh2(Ei>d!lo1wJW&rqA~i}P9zK(1oox8@qB}$rJjhaAI?C4=c=+1G z@uk_p*6~ZZcXLO5otUFh9jj3)BNxc>jTCj_n<&K{hE3Gl){C&yb;5wj)?4r!4O$d& zgw4lFI0%5NEKnbEeccL2&&|)awDFB_uN<7-9wN%upE&jp4Y!Haww>Y@5gAGsIo;YU z=);Sl+atlSbOyG;-9HNC7A_XS02whMN$awoK_dFnpMby!rA#nz3jtH2E;NLp6*gJ< zkKDMc@Ol-{%V~4{7q!W$HMD+z64sBKZ?STNe1DM;)VrrjqTlGtH_O8#>()OBoZ3(C z34J`y#80~(T>w9@&&5E7&v`-Q;>9pcnCAFBI$@@MJw%BPKr36_8ps1&;a!4h=DJtqQ&`HI~pHlw?J3W>fE?NX);C8w@k0{T*0;9G2u zx57My$tEEZ3Hy&uowueCzZXP^|0T$QhNhuiZ0AXohmeC?L}2Qv7j8%$0yVDW=Hm%v zz)#VhRZ&y*2y~ADzKnL+TqY#Tx^~XO;ei^{X=M`VPM{WLE)O#n-+~;jr02?$OS~$K#C6x=_JJdbZu%A71gG3>en_bSBzns|4XV5u-1&dz%y1$g@ z1Br#d6TURs9wG6SFZREoJKyt{&k>mQnraaL46mbwdXI%7JS9Y%eF7q*M&j7-gz~IS zhEB_#=t#b8zvAjm4{r4li_HU;r!b#}XTx`{jkM$ugL>r=N-cR9}i5 zP3x)6%Bw1rVp>q{S!FRgxoG^Q?z;R0wtSa$`02?LM&kTPSeCCe1qkkJptKLK+umA)h4iN&jS)R%bhA{_#rX%j> z6)=lbDokQ25Oj`cR@+bBR$v{kG$&jh^7!wLb^mm-3g&YZ(4hEGL?ZwDC`PMTx{`m? z)&JVw)c*ynmMh%1x8ho=RmsC6F$N^A43$dUg4H_wvVlQ$xm)d@CS4%Qq2zOX!C=?4 zd{r1$9dJStS8Y1b6@c6Vs}cb}rKn@!#S#@=Jb$G`0rsw9fSb=skOhI*Y!80>mswF^ zP)|?jgb9+C<~im(-N*sml-g;o(~YJ)M)$I_Q`FP_iy;XaqU-;3 zeu&;hllefTQ6?fLE06tmX3MmZR(aYYkeehzszrr6vEl&yy~In3#GoE|O3Hpza+qan z2w%jUbULCCaH7DqP z8uR|JUcz?!VWPw9oD9H;X!Ceoe>1ID z==$8)PH8dX-#-9-e3tgx^ULyf;11BcAI(F z-a+G0lPOU+?PL1V?1iLA9b=?|L(V+@jvF+sHiai$xUu3KBHuw2@CH4NoMWVtIRA3- zbbn2b`M#-r6+14FGtS1UrSb?Z1q9P>77oOROh4v?zv+^MQ8VKGmrz9=$5&22Uyur2 zImA9pv}{#sHKmEh5$;U~?YQxs@P-k846od}>C8X1-_RC< z#Sk^D!Old!bWPMw?ng={hZl<&=l%C&-ZIwJX*KL>t)yh_5X(n=nRvbm<8J%R#qGLE zvyJ>-@hM>RNh z0*Sm^h%dm{Qw>q^&9V*{2{8wPTr3YFP}fYu&iysWk>pBAsGtc_Glu{+?PGT3dnAyh zxp$Y8K->qT#uyi(*;pLtKCXRiQ;212%(;JIzj<+ec$_8ChaAa!x{mL0m&y(8*wWyu ztuRJVV&GSe82uq4i=`H@*bEHx&W<)3(HW7EqFVzA-@F2<@q@DCt3$vzsKbz~lz3?7 z$h&OLA(iDLl+ZjJs#9eVSG?w;&76S+x5epxafl`d;MCUC7Q&V4ejN?q#mWKJqJ^Vf zuQD%boFSGr214n}^LT~DCTEeU?mL{I$L3dxGg2X?PI0B?1*<@d;P63eWK0Sm|1q9i zLO#GV^F?ayv4~Gt`)OzNoT*8}#L=wVqVSEje5_@_vB+3?e@E6F`VA z!j@g=8Ek6_-gkRsGOGQn`!QT8M0?F%uQ%#mE1!Qmc=@hnj+EKU%gY0c2T`T&0_Y3y zxs^s|+l_0k=g$;RG)DqXh58k4r%$}iuB`y8)c-Z|Ri%EeM7P@Q?%V>Zv+DO6kSpX7 zk3KuQ+U+dT$@ynU;+|>HPPfu@;`dc*eRuz^goN)EV|~5H_|z0|H9R&DOPH0DQ@rGa z6F~*N;GyuUo3@)T1xO5zX}RhyLNT+891v6{Z8N1(Ye>kusoH zG36f(5#_J|I_6fDYUwr&%IM=9FFv=OGKFfD?Rej*4ZDRhC=+dETQdIa041KVrfIc8 zdkl~09f78{#*g2Mamq^!VieB21~2$i9Dt?$5RsDBEf=uG95nd36yQ!K4WdaE=+IB2 zPIx01_SCVNFDa$@w&_4h6sHdau0ZeeNXl=8!MjUWQPuJ_d1|JQqrc0& z2KB0c-Uj?gBc`$12AZw`2vWfp7jr5VS>M+jIJva;JPbLPl2)5sa*gKW>Q3s(i<3T9 zBpuzU2Q?*WeEd+IvD9G?U(1A*ijFe3lYadL8)$UM!|SSwj{YOd9y=*kHbJyhHwiH| z9_E{U{xbC)+@TCuMhpI}u{kjeJX+~iO%;~aQSxeNx(k1!+&hnaN;hxfaP8J+B2%nW zqFZ@Bz#%@sKoOK{S@5+nLV-LWw_k8%G2{8opL@K}p0e~KzOKi$Gawv-zQW5QIA(zQ z#5>YAfR-*DE?6ZmL@Qwj|109YDob9rXe|K~{;0O+vI%g!5uRp0N=o$f!-kv{CkHCX zqXhtZTln9u0n^E*HC8^KkPCZ_nQX!AX-c@^MrS-R;_FyF2I4CabD+4m#%$> z;;R{_K|ZQY8$H;c-E*7wAjD zB$9R>RS69%S*=>3Oba@Dij7A)!i&;7Y%f?Sh@dDFWDti>WPEI~3l4J&DHVlY+Bb>l z_n@Q6*2+6>YZar(WfCdO1bYj}GUoT|Ymg7PXQ`DcCl=o$66BcZRog!qG0_pBYY8gQ z(VA)?P#M@YGNqS?En_htO>t;25=2?a;E|vON1Cx>%X7(-q^9W{74c>RD+P75+Iaw| z)wpEg2z%%v`Pk9`CwBY-wdWRI|Bvb#)&fTa0*qeT2ARh$7S)BpG2Bz+N_HEaf+ZIw zQ-RU7kBg@y>z2D0g#-mo5yZJW+KO1cY%Vx8a4f7!i~>|j;W}tkh?>>=I)0EyI(eh0 ztuV@SuKB`7^p4}>?e7}QmN>beK03y|Jw#OO{)&pBA8htHSq=&dlm$tC?+Jg81LyoM zu;8m4rB=~1u(3ugWtBn*5Mns|F)|$yWt?Rs3SV)FFCCpN|daj3mvV zgJ|mDhE(*o@_3qE(vG0cEgG+A*=8oZ@(QMpWeF&$dIO_apT@(?K6#GIFlV`bqE$nq z`?2{*r?N#GZ%6{gsdRoT+kELmn;pj8PqZAG<`O2qjV^kDaB&D4@Apn|rX82U_eLTUI@P{%TH0KbaYMn#7Ps;(Qvl8p zub>iBs;3%d0fI85pcj0=>+8&B7u&*<0>GS8VW39?`cd zrsYZ(oW7Hiq&lBz5@1&f`MkoE^2JTy*5GX~Oi~G_@**T;cF)tYLmD;DP7kR}!}RMu zdaodGWPqY6#(C(EZ5`M+DyM&BrAaerTX3rU;4lN+sHmAXY=^@U*CMWdJUkABBo*o{f|sr8JIY9L1#~ zR_gF&^ypkB;L^KeMcZ2VrP z+`1wkiN1SGZH1BO@>(4}NL_M*jCDr0o_y6zGSid? zm5B95x&Vpme4Fran`fYCXF{!uiuE=x1wyYq(-Y+|s?p7OU}p=wGMqI@P6=_tVdo4# zH`0u|{x(0xU>oVJ@S5F+X^xD>P4Eky&`x+N`zM_Tf_RPF%G%4LS$BF+vXa+qZN|&s zC~AIv^1g?0qVFAgEAPn<9W-Z^?#|%{r*y9$LAhh&Bh)MZDG6~>7$_d8l%8?O>Jr$p zZ{E9jtmogzE-yH(W4iwgag+@6)bga7OYX9bGnv6O!Cv(*Y+Q-kj!7MACmmN1Z<#mF zws8E9nxZg)>gSVQaCtP-7YtkPoOG&3YIeO$#|zP5)ibMbuPrFcs;>X{eFH2OQ8%== z|GlMt4jelopl4g{W&9>(7%N5nxt3E>-Y++i37aq=#JOHhZ+pDO z`PFQ4#Cd%`?lX>O3Wt2z4j7bGPbzuXzCLW3D7yViX_J|mS@}rld~Ihtg3exNz&xsy zq*ZmDP*-gx;A4$FZ|p8?Klz29Q{DO`4QHlc-Zv_35E!BTiW%=djW&v7Rrzwa;RHYN z-8QKWJX)A%7aqh3HL#^1MZO(biN&lKLj)h#*dMaJD`E%Rm3EW5;`N+eQX4zE8L zO?@%gP_$M${E{cWFt$*ta}h0B{G&5iwePEP#Ka3Bw0{~T%#(ITcSHl1Qym1K+*IN8 zVWerVZBGzxX2Db{WU2c5?Kjq3$N4Jy&TkV?onCvyp1n17Xf^G?oLkLN)=G zK7$?>HCYh+qo8}|c(VJ-OTH8F(^ptI(Vaj)mR{_?H}Hn)7)=#V4biWx|KwTx*&%~U z0RJZXm-S>#s5^Iy`@?^{eAuU>D2(WTK895GEt_S3sDqZk<&c^$I8_R{&9lLyXm1s z^B2dSn6d!w!f6J~3_?`nmEu0rKd{Z&99_wMO6Ck%I z-`e{L43C|b2m64;WE1-k-|CIyx_lsXxsS!1or)&IAB6c1Z7p5&(OqlgIFB9Xk}lfy z-{W6nZ6v;fP=p&X70C_wvrw(8QK((EbJF>l-1YK`5~*2Zqi z9q+}$Ot#|EMm1-r;&<57zK^^d?Kp2=#>Of`x5mcYt^Hee=h)Y1cB^Mxz3Q*7@O9a` z7FJAL{9~S&7Z8yK@4uf&ue+Q+si3u{Ry;klQaQRknofMFbXy8$ctot}ao^9uXPl25 zOrA)ecs5KRHV*?|(QB^wjP$x9!Rs>Lr_-w%c1L{J@3*c|>{*(}~K zUWdNJnd*YhHWnEFc-Qz#&%QLj(u2?)S&aL-t#QfnR8hG*0HIeHb8bB0HTn6?hpE=p zM-w%;hv``%D~xDR?zt{w#UyPX^*$3lOCHwYV|Byt1Nb=gX^HfOMyz4$N4BKKBEHrD zo7WcuiMH|QjJW(@)2rYgJDqY1aOVLVyG0bD6L5gB9lZ={mEtRH3z<^(`~a^$2EAUW zZJ3Hq%j+Y{vKX^w%r<$E`+S|eUoIC!v$SE{a?d@@{zpC;Jb>v!AK6mINt-EvHJXN2 zStFO+BKT?Eu!A=)qO;JURGqPk9KL@$*=p?UIgs$tQH2vZal$r3T#B`QQ^{KYrRy2- zqhYWb{D)=FItow!gE7!dnTH12ooT{&_2lWfsdv4e@3wU}dV3hJA=kO-SRjp8&j;4A z;;9VfziRK4!t4B4X<*7q))_ZxW1R&ph4wT$C+V+eEP$!S z?5s}0poj?xf-VoqQlTW(1A$t3SxlC5h_yR z%p*Dz)!J3@$?x%wYNQchDGz)1Yby)%am_RVYEoH0y{ z`I7gFXGNJZk#{Xz|6XeAmVUj1!|>L>6`(=b zu~J2m!n#9&LleIeHo+s-`q-KtU|rk5xx-9BP$mSD=hUXoA9BTqg7CRhMtNsd$n7?$ z!+~sV#&o6BF>C7b=q;>RZ-m*lIQjYFz7I7Hq+5NIJQQxu0_Ke@tZD99(gk17?(ZO; zSxvv}tc=~8s9c!;O=ARguriN3)Bs;}iUemoft3DwlXilU=JS%r!%$?)J!N=(eZ%~8 zj$k~ACG9!zQlo`HjISjA(cvEj9@# zrB+S~=}?$vDx~dI^r&VV;4AFbA96kf#M)<-#2+hjZVOUJTQy97ny1@*LIvuTy*^+a zmDGSJr`T3{-LTk077JpYiX!W^k2s9^pCMrT_ii3POTbNO$tZu^Jy%$*i{gJexMyY1 zsmf(5;E~-#JBEzcvUos7EjQ`ofJ_G z6AzkH53iUP7Usx*-G9Z;Hx^xX7{k(c)o(kg@LNA{In9xv08DB?3(qYe5Xm(uqNS9z zXH2dZM?r`5ai{i*Q@S`F8x`_RVs8e+?c`5xbF$#xc-Cw#BpVt3`zP!oE4)2!W_Q>B zsJm@^IPhDM@)EBIuzPpMCwJoqzoriJ?tdYQAeC?JP zglp`(D23npUgU06Bhlr#P0J~Y%H{q4-c}`_<3iOgpor{}O=gM^ZcV_03su?wsmNHN zAy^uZU~TpOB!Dl&{if*EdZ8qxs!`txH3ZJ>SSPU8u2g=sevh@=UGP4T2&zfMHHei( zRNxP|qEJ+ewIZMa_eWto;gTqSud(Mhd;&6iQxb@U?~S$J z3EyY(iY7hDjUUB!zfWSHe4-J&H|;&PRKXLNkv{2*e_?7Spw>p+I(4o>l4g=Dvx-QeIKi|S*;zS_*!b_DcAVVd_8FzdiJm6p}@c}jb3a)`) zAJ=2&r1P9S2mUQ1)ww_B#_g<}hLi&=!Md00A0eMLJP={rQ`KoWEB`pY=XhCN9y(>M*am=2?~<(54+e@MW%BMCD-0 zgn;3H!bCgX!rNQTsLV(MLk*2mJ4u;p_WSN>euG}sBkTA#kQKd6`n#$LJVS=BgN6&~ z#K4p#25QQ(g<2)}33P;IqFzp@PDcp$${siG?UG@`G!cfr>gLFAdI2xV4_DO98C0S& z#$*UJvT~4k;iWI+BOzdpYM2vlqL7TC%}v#-qSEJ?I;HrB;1GS)bt5_dqaM7FPb6BnHKV)2=?Z& zFEfAzv34f`H{sg)F=Hh}s8r!dr@=n6(Acu+(?N`QKI!Rp6&2Eo)1k5b?1TaRfaio& z&HTHMy8=|e^F#{apUh%N3BmXgSf$=Vx9R?)eBA0mKDfS-_nEA9LZ{F>`p0CHitp~a z>K2OHe>8E^2oQxbox+9L1KOWPT8I&WdB)YwzS~qFUajm@b3;+Obv++E$2?w~?N#Me zoyqsJii*_6>WXK{^nK*Z=B6xyhsAwbBr370ef80z{{^u7^CA_e#_mvZpIvt0LL2GH zzN_K<{r(`dTkU5|T|Y3vJ+}Xz>wHCtIz=GG!F$I4%wSdXh*wH?g%=#mqb2!p<~Bv; zqVvBMa6?<|*&GL&%6Rx28=7)x{m1f)@xZLOPX)g6hNDJFY_+Ti{%5t`+#h4#XLwe3 zXpkqtK~tkIO5%3ZWNsfFfk8oN)AXe`d$oNPrIcXitI|mQ*hkgu$;l-@19Xc;nW(R0 zkyLf?uXmDO$tD4fEmZRhnC}Q#*YuS)ANwPMYu$G_HK=hdY&Nt<(CO7q-pu|7ci1|L zmK#51qx=`S|KlM4XrECfg09wW{+;e4`wrUZ5@r_JcBSsYo*=9sb71mwG-CKV?u`qF<}S<>5H^uy4nJ<>cj z6Y1Z(ty$2C?0$Y@Y-GHD4ZcoKl}Q%rAGK2CjBF`UEXv04|64v(OmxL{oG+I97(rwi zMHNA`wb%QvQv2-2LlrAUU)R%A7U@Aw&YoZZ^hy6S*~){2%Z|p|-j2^Qpk;Xsinh4< z#2rp}cIW7IEfog1-qWdO$KxgdY-aL6lF`Zkxcb@-v_H2W zfrb$HL)BGWu}JsrY2?_-jgr-kFR5*!bByW+tN%y`%GmzYajx>w@r-cWOsF(a_ zm`To5rTw2vzonnfVq;ZqFZ+59`7GC!ySwc!Ln~MdY!Pb40%EIhJCA5qIH~U18hF<; zBePJ0Pfoym9HU)LE;7$qo~4mX~Gj_4a7&{MA=YT%FeL5t=m zi2VtpRgxqPPYs3BLTQ*+KBX%jpKZ6!im4mnc*H2LrI$j9O@$L6H5+1YDA- zEoUy0X|W*;u#M0jnIj@cJ_y6?Rq^wq(nzxS+h?xqXOeMUKK;p`F9-_@g77u=l+R9G zy!28>na9roX4rCK{$^}KwlxVX#pzehj%*O1|3?>7_|#DWLE6`*JcBLyr(SzhHjW8f zvsDS1`0!e=(Sy#R{lwouIA7k+TUX<_i1Ux_%~e#^-RO%)WMot?9BDGAT{g9^`g8UJ z6ZYRY9j1SBX;x0A1%JMA!lp3pFp2m;_+N_#W1=<6XjSw!(G=`FAm6k)LtR!A?@uXI z)jW|XY#M-^)ud~cDe^NRcSZ6=)GWX|GCst(G^c#@qllwdKKOYWO zZ~+)=24ReKmh)6;RFFq)=ybNFhNQWDqY;r6p!Dg{>hrS9K|GSuh1x!8X;^&1@(!hj_<6@mrP9trOT=4BTKkP!s@;S55{ ze&Z~!Uw1pXEOvxzum+rGdO2lL05)Q=j-e~J>$X~H%0@GA!OcpbsWg3beM$R%iKk&6 zECSqYziC@@QPV)-$*}JbD-^%{l*d)j6xV!Eq7I0T zxANcZ{YZ$0-^)2lIOl|O8xS;dYNiAtiqLl~(`BaBjHN8S870;~PQTwiCx!L#`9wpVt>mR0;KPCFx>_{7j<7qR6t0g}L8b}Nilt{UAF-DJ$ zaxO;J4Y+Gar+{RU=u-5gn|hF?Bui(h)I6eXcSj*f*P+03%h=wQpLa2kh$#e=Kgk^P z26>;X0K)-Zu5*p()YwL|J}bMyd41C`N{C~mIO_OmUS1AJvc5JIG{_BSz)FyzSn-w4 zIV0(J*KaqbKg7qF2JP~iskjGDtHf4}X>bkR&;J>-@5&zeYGxU&OksVhB%^#$iy@Mm z#tAt9o3>drgGo}yc5^eWorM+y4b~pJ@?E>?xYCoxffzJT;d_sI;20&@yfV?q!;RkV z!Y0i1o0%@Te_{ocyUB!^F{85u!t7M}oVX_9SnouW=*;TZX}Zqf(5S`i|H}uWj%OX< zQfy=&MS>v%2s<%@_nE@JnpXEM)tB1y5-{TV$4#TW9kBd*=GX5g+q^;r+M@eg#rZCS z_0rHWg!22s5g?Cq{|M$n(SUQp!Dc)UE2!lhTH>)~d=OU?aaG*H%IP<^OyvZSBU};! z=!s{GJoaw|do?R{v891*3U|vRXr0;#LmFj_Ole@M2IHM)n=?TUx~$t2odLF*7=;{F zY;3G?hfmVL0D%(I=c1H<59VpAJtFPHio&9rAP8fg86qAVGHdfMM&+r)ebv@$(!YT5SwuvZAg)SU% z^6+2~CDZmAhVC=@Z^)oTZKG5^E{990%E%WY69!RMBTs3UeXCXbcriIn7vl?PwPqdo zl4jCaK-6&{_v_o89dN~5D=6;F@527>jQ{J^&Mw?RRz2ciH4UsQu;CDm5cFCydRS>4CQaQ;g(&R?Rkmsb9eYJP$4+9AjSH| z9!rm(S)z-;wXakm&66a~9om$h9WJiin$B{W2gb)_TF>@1|9ALkh=8mKFkaWx^lWWy z;RMUnFUkMYJ6QoR58d(!uQL~key?Dl1}p(u!blspf_~n~XF;!zK9Hg2?q_Ep=@lEU zmlL4}h9{MHlB>#oJxnW`^&3~8I%(8<2XNoUYY^c@4A`V}x_105uRi(nN5T7I(JDc+ z`Xgtpx3@GAd#*^|E6l80LE{JPWaHihNP1N$ogE?kt-}4!hX|<48V%X0lC`w?YWD=VBN9Vs>mHNYS zHg;-<$l;C2+EWWc+*{*P#XBKKLs}A*NU(93R5nwb1;&aUFY)nuXAYsMPcVo7A9TQL5NcT)b@qr5oZtKk zq`}qB|1a0sj#m*!K@DlH(;&wO0zA7vK=#|yw!{k!5EQwcv+-oJF27W=4HyS@vuq(2 zKwy^tp|Y8!zyDJkWtKDw)SbUpI&qSY9B_^RuIKuHX>^95;mA)tGj2-Lw zRxF46X3yJyWq*ywK0DM?OTns+>jMCz`L=)WRIxxc|8+P&pB7XFuA2w2x|vy7e+awp z5C<%ifIQJucOY2$fDw2Sz$eWcxn2MvcmKTDUC$@3K%At+AOXpid=GGJ_(jCII@x6+ zpS(>klMjenx%v4A0i`v4-Z(eDRnwbK$t9MxDx^b)aJougcBqQAK5X2!`dnCcJ(}q2 zE1rDdLo8PGjj$;PHEQibDvgBPuMn;c5!F$*1mP+#;3&`c6_uj>s6;wj;=V)eP!$adG#<)3I8{!DON544%_}+8nO8~+G zl#C^Ztq@PTOA&Z3!@uD!67;ek1WC_18i#Ov)K2+uCo-~id`!xqmfNEpBXZi2Vpuu< z#k*~EU+@YwHzjPT4)?k7-JD z43ri`Gbi4tAzy*LD_b@5cp9vtleFANY}En;4G$$yOg*xG&Bw{IsUHFG3DzplNJtNI^DM1r&#@HCD#iY%y2T0^d&N^Uf4*QGLAYQ-}?9eD( zI$N;jfXxsA2nm=n4sUz`Zj2T)gWaxsRxBY0&Jb6lLz-H%a--Jd$3sm#E}*A)hMcM- z2c$y*D4Zf4W{b+=X?;l)pfyGHP6hxR3>L^lx;K__MU0G$7$>{N{n^bhD*jP#DE#@?oK28RC*Y0Qj$oJ$s|8i>cU!V5Nbjw>!T-w+6x}P#$!#UsG zrgF)U{GZ_Y*U_~*?mt6>{|4|I*R-@KCikZ*Tkq|g7~#jt#c>_FqJ~QcM@n3v z0zM~cqKK+fG27XdBYU(iV6}JK&-((5ly{AW_){qjD<{88np9hjZQR_F_92f#TFm0F zJA_1LjRZhS6~F|eiXz#WwG z;%7#2TLDwV^}{dvcNZ5x3Fyk$qCtGBP26D280YneFE_G49tGYow1!l~H`lE5fq2a{ z0hzodqc(}So+ssLYaoBtiN6&vO!)v56@6nT*l2mR$LSLoP_T-8IiZcGzByfsee*;q ziT3jbnF3J3UjQha#C|TCq9Rsyet^hAm?KbO8|WP))^27EI0qd0o%YgK&LmNlNfqz_ ztb4qMehK~5#nx1Q@q)ek-nbBR`8-WU$%^Txjjm@>pCdNrVw`-xOVInSXMR8L?$L0V zt(^dgXdMh&t=liA6L}qhYOxXKcG`YR-us_w=}MtiReivtcdseBy6@F86~y+J=5V#? z1LAg(6_7id!s&^w1nj8sfO>ai$hqf~AC0(T5SKtb1TXn!ixv6iv_PM+2Ha;TTO5Tq z`Cj=geSIe(S`o&mc7Q!?06s(q$BI?y#+fPY>LOJVH$;;WPG!|H&>}e>kn6|&KB_Qj zd|S+#{hmHTkehekb_upz&6uX-v|bbMYaQ|*i3M&r8~_emI<%)}DAjLw35lL_M1jK$ z9YBk2f{Puv72RT_KBv>(SBItKKZOwjR`fG~QLz=R9yA#KX&PHQrSyJotorlK6QaC= z9$=;mt~J+K6tzl&1x_ZX1q!CyXFR7|!E%Ma)cxe)Le);$U+lhBEh#NM2*=KU9xvr` zOL+D(+rMfbO4Pb2V-O#CxF!(uGGj*uQvj z{{FP}3kx#l@&018Rorg{U_YubYLAbkSeJ6F{Rt5W91)4!ux{u|N2X{?SaC5^-z4c( zLr$PB{_(w5aN?+%%>1_86^o9nq?8_f9_+^jN&rIY&jDR}vS9qbr2?QB9xpv}?@yVT z&)KCJxwhxkhGXA!)n>p_W}P}t)WjddOW$xzjNogdB4Dn4L2f5+%fN6PwC6XX9i;Xg z#(aIL=Ca7ycs$v#xV|H@AgZf57&I~qS#oWrJKm*<9MHzufN=`{InMIvxZlgk6$y&> za$Eq+i)y7yo2~iJVS+J$D%k(;Y`!HB(ORUC@Q+1KK#W1|cg!_kZ8o*u>1WTMgCNxd zNMY~$WiZ`t=PUo^!>2H)bBhZDIpL*CH$CvHK^y$>j!#%I7~NtUKUXMi2y;X~2F>eUUZ}nF3zO8!H^spk3?94!@9Thb;GLhGX8J^0^{@$!dO( zYsVoWk3B(Gip9P~yYT5GZj$**8>lH%M}t)CfgcxlTV+DU{UDD9u%q?e%zwMR&f8sRx}|9mEHQ(6MPPRqF8cx`@7%NKjp7Cs@+y6Pi|e(OHNz{JA3 z#7mqIws(w&yzZaZ*={DEl_}z~^tBGVRK26`&$H`{X{Ou~$`<>+dcOGvNwvq{J5=8j z_DcB_8CSBM)k7XqAM>3xP=s}6P@a}$u;h{n{sN&m6C4A#%&miAT*)-5-X9hD{#@dH4YhNc8fT@Y4 z*$m9Cn+t)B$8PX;qnX>*ffTXFEUEB0{p0Ov!E~kvU-`Sv8imreolPUZGCbOP?fnbU z*x2ts4jT#Y=3rCj^NtlInn-hA=X3|5D;E8q;p(R4I!`BC1RMgWSA)uhBO zbj??CFk5xu^LcJGbKm>TH7L)*yH~>1rfe0M4Xlh7r9WQ;zVPsPrO$7%5>9rG>37PO z3k^9|Kfx9AcB+K}c%9&-*nNY{{H;bkGifXu>t4u0&_LGgP$opU@8#L=ps8(KRlW9c z&h{d_#I3duvS3PcJV~R1td8OYRrDpB%=OL5fINQax>{;*Vavo)r}xZ;X^h=E)RaOm9TK}jTu~(W6zZsXlt|@SIOTE-_I{F zys&3C-Ptu0Q(rXtblJ;va~6~*=rFCHxd%K5OYa-fe)Qv)-2@@u1FvG9Ajx2!3xadUx|Eplc!bc5__YxyzFwEWvIoSc5V zfWCyl^9|0V9G;hl?w9VTwV+24`YCnGO3x#WwzHYuuf#KBR1ZW-oUW9genkEhD-0KX zwoC>;Fh}d52zoii41^24tOY&cD(#}_Ds()RXXtmku$lQ>g5t>oBH>*-wzvxJEEF(n9RzRF~*-BxYdp;>DPics*b zxG;hLEhu^5dX|+xTj$5yi2VFDz#e;eq-o@iDgM)n4Ejo)MzL-(}XYU;K+YSH~$kyv+dy|nvO18%oOeV zu-d)bz}MU9=sjSVRhP~GP$OG9y11G(D>ki$jq^wpuAJ0>VK(f>nR`d-K_q3=rgw9g zAm5M7;V}P)ddyniJoQ4EWLhMv+TQQZ!(9Pq=Y14Uxkj!g6Rq{YnZcV4gyXi^6ZoD~ z5a{Gs1J*HMz4ZXRgzhh^2LBG0x&45FH14qMgIa$6&QG$0%X^MM)YwA9%IPEC#io5cuML|8562-)8D`ja1k@#IIRmn9bo-APd1`QxpNX^#?L^oH`#}$bAo_y6(a`fYv3z1>6Pzb5>*ND+Yk8N)6FW8vrmsV&WcP+k9&c=rn2o~ zQzU+-*84P8{bVCq9=1#O2YGh5+mGa3gaAp%!(;ZUmpth1aYObV+jgomcK;sOmw}>5 z=*x|0rEaWNnQVc^C)nNuAfzV;e?ks6+q}A26`|Y>a zde#>Vw=Q^c2SjXHcA0STLfR3VdRupo#nn-3cWHg&R!^Y@4No)0YvP!gq|I;~do z8m%rT?H)XUQyWMWPWV@}TGv=_|8NYhn~RE#%}X-rkJv>+M|S}DmpBzCjCp8L-4VR%?*PYQD;hfHRtvt! z^-l4@(UI|drJf0=mYEq!xn^|&5D=uyki_s_-l@*@mr*~AbZ`$a8ycDX%56uA-F zJ2VSHVXB8{i@F%ga)#i{nxpfcN`gh-jW;kxhvtxlWVQI=ox=l7NrB{kRSZ}W7K4qT z6eO{@xf#ERR4h+IqV#xXwKgGS;5`7TP;yywC+MJ{WL4mx3THw~op5+Wi9x!oF*7;>-*} zLc)#5$)~uyy!dxJ@2?|{tdSz2l3FQ&SP?06F3e29>hGc2+}x1FaR_CyqCleYH;W(w zm-fDc1B7Vwam|!y4xqDClixsge`xxPnPeT49kFJS6u3YOE_J09$1R1m`~m`k06Bw< z!t=>qTYEWvrsopAun6QNTdkX?TRAng5F|b|GZPaRk(a09(td}7n>f3mB(TIl%~FT$ z<|C`-$OIoq({}STRAmtKeo=v8c zK;&*AyY#o6p=DA5w>06e9pP9gfd+0)XrjMCqx8QsX3ZyNrl-3fu8*pjBM%RW3YD`2 z+%u}D<${#Q#_+(YdOwQI0h?-2-VaR%HE`>}RNOG+m)R;kOn<1tbw$crhCrgAfYKI* zk4eQsUyKTTX6DyIUyG#8b4#C_tui$9*cs2fSZ~kU*|oXuY}XZhEprq)#$A*{^$^(N zZgZ~4WTxkuiGxu@MWYQ}<^;QdP!vbV&5cx&JbpwGT;3eQ5<3sq_}KzTbFPunBYF?gm z)h|BY-sfpMmy?e@z_tjC&vfTMpo)RJtp=D!$s4z7-7nv3Yil2zoJ4!=Z7CA}!7}*s zW-T!>vA$~$_&L1~3vRe^X=zERb{Y3bVLkd$Rh7%mt(hWW_(K*DandSAvv6~B1Ar`Y zfGq|zgf##r_4e6jf%=F@tk4DFxMBrRJkTg}^E7;N>95Pg^18j@aGP3eCnbnv-r)6Xqy1C&kPi*jM)x`q?=SOpW^i7P^iv9koZqrmK z-uoO9%Anwr!l}GG@Zug( zK#+g~A~3O8AOoyil-6?<#jUL*z#SzaG4`mDg(MbL=MhoS60lw+Ozg$MIE949#uWSq z2F&IvR=a}NL_z>Z@WTxUur@n6xynMzsMm&R~c_udcTf3*PB90E%RRA@a1L#N^(V&aP{%$SQW9cOeQA<~-l zR`?%ZPk0ZGPK}2X`v043TuyxwrS#-2EG%|N*4;9Ip3bI+2p88Z9;%eS`|c-TVFsL_ zjcZGTS665i6(>)t>)xq=UKGIBu>c1Zp{uRyCeIJoE8e%l|5HE%2iQwTqj zB6i=938rObm|5OZtAhJeJFf8c?-o%_9QhGLq!*g(Y0%Npy#UVc=AwD7X>SPn)%7*7 z`-cGMOaB2C5C8q!>qes3X_+SAj5C} z#Qi}j$7FO59Vm`|R5u4#`CevvUFxhG85sC|$n{DR2prut~6Uh{fT-0li|8u40_+K6-exD0I!077L;XnDh>ua<; zck;CP`Vgw1q%=LfDCa4I^my~ny!QusmXLjfxz8Dz?_KCCDp_`9T3UwLV#KGy8B5|z zcg7;P6s)Kyw9CItRllspwdcy${o*2CI#9C&y(0uqTL>mm3CT&!U%Pu(YMcdES62xO zu+8S|EG5;eRQq!3RHYC;OHN<}dbby{EYujHql6(Kf<8G)6Ooe@H~I$6#q{%)qJi*N zxs)oj^@!)i!YH@->L5IqPmYu4_peu}E3WI_c=Gri56M;3$^BHr;4nV9 zt=bcF{r;b;rIlTtIwL0sN54P(<6^5T#rXI*sjx>9a0r*aJL<{j+mQ;i*TIW6IY!le zWmO$8f$aT>Ry%VehcMsQ)7ONT4ttUF;Xy*umM&g^e&PLG0PJ$AY&B0~*cG1u{myCC2rUOxx+c$B|G*g}+T>+z=XN3X2G+&ezipYL|x_m@W-BYr|QZ}XQlV8BO3!@P31B@^5dQBMvC|ENJo zOYk6bKtgER|MyQ2y;7N0Vx}ZvxTJwo7}fXc>Tu;yfDH3x7fJN#f98Yat>*ol-WmWZ zH|X|o_|E1(f8e_gA7Xrp%+8r@8JS0Hu6(Zf;=7 z+4|tGwt`5ixtB>)=iSqOdQN(tE~~L1M&rrK@NLJfu)h2C9|n^IEN)(&%|g{$ zg^?7UhVv)X*1M`N51du)9hr}(08RIwub-EQJXQ!uOYtMIf#Ca~Pcqb69~xytVFqR% z3F*W34YrG7BRPKxhJQYcBN>V?V@Ke&(ZFr!h(L zcDO5#=HQr+#AOAtBUt36IMbQ^Pq$Jcb{zP*1JaGsy^OhvVDC&95&S=@8AEE~4&wF( zggSKS&)~C?aMA7T7ox0~yP$c>kxcvU`YeU8x}omH~_++!*k$w95 zyzV$U$MWCnD&J>oZV2S!tQYh0_+!q8-MVTUOWx3!j)4o)BYSyp!-=L$KiNLX`V-X^op=@Msc^UjbaD#nDK zS{pgw%~?EyVVpSDJ>`JlRUjp0>i8DY+Xh>iytF9#-9kXp)^&Rh7pp$r<;5o> zGjn@o0Sm#9g(-I5edn@yflM-SoLkMlSguHTN^38KLj1n9-_k$IsNG0f# z^rL0r7_}tf{s+v0>`rR!2_@4RhEl6i#@R#ek(x6`e7Gt&0m{`W$!UTxbwnz>JRP`B zg*ikoUTQp-5C;a1k%2k#AF7neE@F%7UeUiuy==FlRS8BbQsR`yd?Mov^404KBmzmj zj(A>xdCQp@*OoqR`ZHS;JE08}kL^^XhvX~SZnq3Y;^UAssDYXnwk4tyPmYbK<)qPnRc8 zSt4z+l8ne$UMR9qRE>ST;*aLw>S0S8RA{4^g!ZOp!tgn=_HxTNVNjjq7WN(8#l4WB z1xUi*v1p`3-W{5XGl?<1-|)^3?&JK zsE8TbZpjsgKb1f$3fLhdP;jI}zm%*LeKy_ikfg*IFYaL4GYLu*Puw74Q!PsBNIk~v z{%dcWWvbuA%Pwg-F)5}tgQeh28i zOd5=VyFGFR45RVkTQpn z!lEN5U`8A%f+m}(!b<ZNN8$eAB9&)KQMVxNrgxCiBI2HKN1zDnJ6jLo(Q{!a}A1rB~)SOuL_dZzl zuIrd$l5hXm4t8Ur6U*f(_W`iO&n0q;kUWU&XvAM))X@e?G>akA(mRn6hi~xFHDq-$ zOHWXTvgdNF-){CRD?{eO(U5qN@=DTohG7t8hGr8^cc8Tog#{^} z|HMJa8>lG=uQe_{6QTfk?CVvOpLX^$#`i!yvbn@m$|+=`qFv734)>&=%SrqfKJv~y z=3!KmhEhhUK58rNlrgCnK8_^ASR{$g5k^7b1a~H?kQDas5>5ag#1vHjUH80N%`zwq zBIHpSDlPf&=UN<8H_cE=E$`?Ys8|1uC!Fs6SgtE=>(Ey>NtDJGeleIoNsy)sBe8mP z_?9t>)F*pSpEsNtdJlQxS{ULb+x{BgDN#i8#D6Z*;{*|dS)M2*W$_coEd1EjCwYPf zzN=>$N=uX2{S+UYEoJ!i4exo%pqSIGLs~YN!U`)vIS}7`aEc?oBKV9a4rUJQBn#_| zs7bXTQ4POrktF;G2u&2WptybwZ~T?9h@(#=`G0ezqjhDqEmI(ZsNz$`=WLf3TWmc~ z9z!YI>u!8z_gEY&wK|MGvHVhXZoFKo&$JpWxSig3*h$z`=Xv<~DKkvnf3G`~{H<}I z+}pPRtI6y+WPI9nA!rGn%EI>RcJ9+(Ul|^kO&g-m4o4HqY!AZAu64hFwwxGGDrXP_ zoS~tlWVKXV`az7~Ke3e#+&3(EdB3I^*r~`OTkiV5yr5|h{e?Pb2k)pR^B0HBgW{7d zA=UmR^|@jsLF%%|_>(ey-X$Jp7SuTJ+dr&P^QgF^!+|Mt z$Hn+EKhIs$v}5%p3WupuGEy-#$741SSTT=E4`Q>4C`=*dk3>BAm4Tq}P;6r56bTEl zpJ8WUrVLQw>|%xpS^0D(brS z+S1P5wW|KqArLNEav+GFk{AK7`h|&$F#jw`l61fk45kE$`$T*0 zwx5kK_$x)(7G_N6-SVHu`Z%yQ20Zjhja^2ahCbNl}2 zFJVpK@V~FJPOGue)N-GZwZ}tDow$pdY?{YkT8{jiPyRW4Go2^IlkTg0^F#Z?HL=g8 zxvtzYr~T>AH9d_-U*?a7KTitv*{q}97@Fvjv|fG1|I=W<>Zuce$pu^ui997_eHcOi ze)`f@ne?BqFYV7^OW&!C-r-dp=;J#%U!`mOb$$3g-db7}tfFQ`UD&dNUp93Ybyqu8 z8+DIJnfmE#-6;JU96KkyU!SCd$S?uw7`ehKpt(#_3%#bx6JD@MiQ>ZP9<3U=#G3rseqEpvLPm;D17DSM5 z3@2R0GSmVw--}y~tp2r9$*a|@>Do?H+2rPS6>eFg}sPi)WG`X84i|N^Y zUS|xi#QA&wIezhxRY;lG>~zckimt`L1!xrc3{-kXb$Z-?*8NZhJPTyffi=)KbS(tJrQiTDw&H=?#V@ zy=j?PAjEyWBhvoMP?nHZ|5twnV!jJ;bt;{&NA6aL!x|$&JWUb*F;{eyT4S}&vF~jn z`7_gXF1}TZX|Kq<{4|U|b^H_O7WH;=3CUws|2Jym8Zz9xj6bS_BdT-BC(>Q`N$O&@ zZ%Xs@F+Bd=UMGfm92J3RtPe=7O+f=cvyH8;J@|JsMHAELV*7H^Q4Jfy!xka*en(lV zXW0fu*7x{D#pQ}1R?ONRRmt3-nBC9j@5&YVe!hQ>i(I8$D{`yvV8pWL<0cZ-oA)v_ ze>S9}T1vYk{j~h%-KmP*C+jEYp==&&skXXcXK`Jr-qr(fefrcfHBV6d%HL>|y^ByA z31^Hif1(Bc-EdOJUfWLkQAMSkMwe@G9F4lk{Yjwg76QgXh{PxC4uX^S(-V=-UC_Dc zgRwHQ@_o$2)QjI`B66&5R}RYAYx8cXL5jBxt@3ii&4hYqm(GxRF_V?6cl{o?;jm>G_LwRa%MM~{^&t>?NDmH zm&n6)s`*UWro5bS+iYif(hlvLA7|~vW=YR%T2rWdo8QnzrlVyNy&!|GJJ!*@bK1t4 zxuN?TGwC`J?=L;rOzBV9yTAY1H%4FrOj2Ar3mGml{dZ-3(ecv1r zZm>l-oVg4Fm(qo_x3?a7J{`^5An1U+KO7nEzQvo$#-RZe^|0pcZb6X-k5ES2rV!`r zoFq5z)slA;8jcg~H8+MO7$Wr#oR>@`!~rG$$r*+)1cHqUvAh_E%A$ke^98;-|g zSEl|Ij^VLHGw&}M$rV%%i?Rnp;~|pyyx=}M(Ke)*OP}N&@7dMMuTM%O$$64!FD`XPf7claN)3riAlTco|^B{<=0!+ zc5f8voI?1gecR|dh%`MyKs!ZHdSJaU&*omne{~UZz=O<6K~X8&h>Sxk8%HS~fPif0 zMvK7p-;4kGO*fAelpXhf-^0;W`@i0-8Qw<>zzbkUo7Sc&qD7Mk!qQ9$K7FKc0?-qZ zRGC}fiB+Z3wH4Z8R|uo#>Q`^CTl32XyC}CP?^GG<5KXm)*u~~tss{4nf;8DPOan$` zSbCe^R`9?UWvP%Q;x6BmN6tj^7b=DfFVIIA7>A=0DP;w6 z4og5LYhH|#y+Q3$1v>;Qhzo)Z3cEY@vz{~N}A++ z5qTWRktBvM9?no@RwQ7<8Qh(QMTFEfM_5;a=p~2PS|%g;FPh_SpwIFY+S5e?g8o`h z2QQ^SLE=TK-NW1l%a-g^&`drrL(+&MVw4}ONh$$l;*u}ckL}yP^PrMc-4VfXFu5ek z2{gPf?~!bNb96JOj$Ykf+n;TS!#W}pYdC^9y44M6f5O-cNW3UJZ_J?4swgV*NF)?u zo>C+I;I=J1LqZ%CEPuS=J7=!{<|r&c5Cn9O1{!Q_mSfD%LnuMYe=oL|=-f`RfU=z0 zJ8xnWQ@9Ja}Zjp&ptIR6vby3`WNC*EPyfH=T_U}BiTj>b++ zpQa7RNS&r`obe%`ReMaEolg5Vu7U*2ADO9M_gX;d7rSV+YCtADa(A2m)Z%nE5FWVL z;VlRQ_pp~^k5hs~4z^Zzrs}(vI+O`j#+S(qh+@5~PPNZ|{(PqP z8uH#Dnnm+7VwEZsIT35@7XMQ~>GV(}$jsghr@|R;zCB}Zs;>;`&%ve`eP&*9aVVLf z%SL*f`cinHhc!D2HtyKaRto4u`#X#s9fwTkz5qT1W|&YN|5h4_^?TC00fQ-v0+n#= z%O4U@KvAYJIrhCCxQ9W20Yv$7SmEp?|L-V4doKE~7d!uObS%WTP>@42v#{`}R-FyM zVad?mOi(iCNYFV>3$(zh)+aq~)cOs&e{2#C8+{t3^2}6PbKOIk=_$Onj*e#g`FrAw zW$YgD@7MyepuNWkc`OCvxS*?B{f)a#qM$d+F&(_Xe;xmg2!#ibqsg?XlZHp^H3o1X z4jJir(Xod~q`i4-Yip9=LwhG%Hh*Y74siN|_up-ab5JGR-f|~TG3_V8qyz;lJtCYE z?3v}bRTacz!7Vp{A6a2w0YPo8S~K(7?f z;>V93U<5;2+0i9l`dB z)W|YQ9Go0CdIb0OfPuo9r#Guq8)9zwcLEV>;JaehpjKEjiQm>_Pna97L|v&rakoN3 zi5?3A{ZjH*>aF5J1TbaX>F`CBNnJZ18XWs~W}^Es=^TIivaniBRFy~8_$3~{uqEG$ z&;2&#??gdy)Hrl~nSMX9NrS{dTpHxiK3eI%vi(0rPF#;7-8^D?O3sE@9OG41oW^LX z;G`NX==W%GY?k5=P4{u^i6kHuB=l}|3A>=`ddWnE*R?N%XnA4fdILiifw3GM(^DY) z>Fzj-aCKF>m>&=ZV%%)p;G~*@De%~mCG`R0xXD~Z;s#9Rizlpf(Uc#&UTsx28xmFs z+R}o9Nm9iIh3CVmSEThw(${9t&C)uw3J~Ul-q?H31!Mn|8pnbI=V`A(OBY_NJSrld z9)IT98zmqMtnpNCm%w44hl6aX8_R-AN5*BX9+*>d@$&be)M@pcGP4Z`yd?i^6~+6w z?2NgMAR9VP$2jw}e=oGVze^SJNwpyoW6R)b5x=uPhN;!Yg$bbUmzz4KG%=5fE38^m zx0emtNU8usK>^Raccu+q@{SZDYuI#{0MVxp*kK1R!(OLW*teCMh#_w9v881z z?qn7&&Xm-t%DnEl^a(oXwfnTs$J*3OXr;k16{*+R;xth~O&^eH;;ttqknIF$T@DeD zSqc7_HVfz&MEBV zWc*9Pk2Bs5T{1(AFTR5|YFV!QYn&f`XKqE6tOG?*rNWt^Brr9VVl#>2Qakz4y&EAM z7?i%7Xw2FB0wlx&wgKce2V^js<&8tv=l|6LjP|%PeTN4ccP^^3c>U?ri%v09^J!R9 zaJW$VYsIr(lb}BlEDp z#X%5(A(L9hi3fk@9@pqNO9hUle4{lO#Y@r&kGEf6L|^bCkgH0#okKgw(d- zrlYcUd9nK%STlZ84Dyu8l)vBRoDQrH-Zs+VH{xMK-}SuzE^+2$)*A9|J7H?M2mK)hcS-MkDidF_EBd=iT_|d^}#zO`engEgbh%4EPI8GX3?7J4NIbWXDJW7; z@x@4#@aUI_GX~X(>2{(GNt59DacIKWg?aoiS+h> zy$?a9J=pG@DR&G`T9?cL7TLqW6jEM1N)p`^y%?jItU#**&)K1F}oJ@UPD=Uf!3BuP+}>iHgJT6DHzsrotC z!7>9@`bM7!`vH(A4A9fd?K%*G&)_i!apG5CTv?*d37vPBqUNWWp3^z1g=#{YvH_v?l+7w4)Eaqt#+^UberOGp8yH zEGY&NOqhGqw?hGa!xOs5E5$3kDwxsdjVe`94}wVaB5BT%D!7$TiCA)@pc*w?ey@hR%`lo@n&(d@*ucRd0;^`1AaqOX zGWw}ZnJ7n-Z0OL^1*k{S(G~0JxVa#ZsJXWzHSE%fa>eOcq!K9N{NIoR{hT0DVSR+r z)5N$TfC15FSzI%LC6o7Z1O9e)YQYannHAr1Xg7_NLP8tTxY`0gpV?=jSgo92N;f(* zL<^qA=qcWcz6@p)8n2-{0?sxYr{h%kRQ-RQ1^S6SnmD4TvG?5yPh<&oXSROXPCtF+ zwOe*4fXM}6naqNHHWNRdA$8t*BFtsJ5W%U@fg_fjB*NwRrjpeJ@QJ#*9_K-GcpU9QM>q=*{7v2P?<7_f^8FDOMA z*=M955@qOU5C7mIBvZ{w?>0CSme`Q5n>N5pDPl+&4cd)UpvS#6&xCDkev0683HcF% z@$@SULY|0g44UEQg=?bP;e<83*|N@Cs2iMA>d86?KWK z@;S*wyTWjIg~v>gF9s__&#bMDlt6J`sBu^I?0qdu;6<8+d=x_ z>;)<*P|A`dl%el^PTwsp zhLlN9c2U1PlV|>Wz`I>@CyC|{g)Pz~!?;wK3obDHIq*K9a+`9h)64MxI{NU`3*?83 zHKiftqG3QK8#&%ZqiE zsJn-7Unv9>)`RtH($N~%+y(FV=xfrsgVVuq|xEvr)35Ldd1?CqOB}cWBk5;E=F@JlwvTS+J_M^UnNB@ns#qd9mQPvti zQ&meuq|mgpQBCN~?CSUc`jH$z1cHxa{ zXVl5U0XqWK!SR8ZT=&i$gVdm*nHgdpo_s1ZmF=Q}VicE%KnPaA-p%I}mLs#(44x>( zsDj=%WQg25j({d|T2w&EQ-^6(<7#SYMp8mVzLZbuRg7%_q^%<$Tb$|ka&OLW|Cb@x zZHud1r#ZrF#B5`QGDq2jI8!c>E>p=c00r6=Um(NhaK{ehw89@srZ^%1@@g6i@3eaB z`FJHDtND)xpW7Ws-ZLeBa=+S^#1_pTVnHT7C+_^bQ(Q=krb~-B>FRDd&nhhqI00H( zQ?U?5dL??>ZbksTa`f3$Acf&@0v#GAy5q$i2di$An6VlSrpO(Z_p>*th(p@Mgj7^i zw2|M39Jhe@cx*sx6;_0hJc8zL?RHm?+jm{e@3e!C_#h30o+ANp20AqFC(154en2vz zUKs}~Ci+LRv8$15-m<~@?H}l9z6u&DB0&S6weU*qO+$Vn-{^3(M|bRN&4zUQuc*B= z_?NC2YGkcam+a*{XJpT4|etUI22$0`6wCYHwU zN&UaC&_XfDsDEcfXF~FldTzaKMx~Fis1OEp*Y%5&`c!cmb*ZnI78usN9C`OAv#8H> zA$Ds4bnj?-CEA*f%+X>MYwTy~8@}ofDi~()uDK;U5_k;raNEzX-YVM*-yAP0ilj=Q z$d&Sq<5GA=r5}RzeT^|c3&fHS7_NFc3%<^$%x-Lp;j zrU@KkPVgMd$;R&$x9}N6&-v5fL$|!6ZplZBuPz_&LYT@!B{L zLz32Y8|PO+YuLZtwf5Y0)^l0DT=$Lzp}}_BQ)G4)Hwq1Xc44Zo+VNSIr@vu2WjbyW z`vGIrGbMln2#}qcS%RK!FjRF`XD-`yCe97e6O&|G*bS*3-L1{-BcOujd)?q6oO1T2#qipSCB{~LX4iVYb zym`HTjj`m0Ev|7ij~HhkeUECL*mOn~6F=~~ol)+4dLABX4FqBe_lfz6iat!oYPOjm z&#I{by5@^JV~Xvu#aiI|Oj=l4c3*l2*`CKEQ5ea|d_cN6-5%-=dsDtz=Z_?Efz4@I z3<0x?i+$fb%L{zE>QBY~+|{>0DZiw#kunNEOX9XaU;@RHxZ|vm%bE}7c0s}Ma%*bL z+^+f$z+z`aPAi`X*^|f-)_dhH#|Jm7Ak_hz3>cR3roAL3U5!XMmrXRh35g1|F{!2 ztb+hQrO9;EEQ$j#T=+SS?A>HHo>hGH$;6k};8G*r9y`Q!a=AHsu&#<5H9OE=fe9o> zv~ko^O^Kk4fAqP)Md^>@IpTHP+&KdJ)bO#>@l>QAqW34xW+Fw6dm}zhFU`O-G(J?Y zjDw6BQc;{-8ZK|jTHWpESs@i)fM-&w)ih&C$NevXNPqL?Gk}=$Hx=aj904m*SY+8m zq5>3`M!gTwb*?S|btfeo3X?KGOEKMiBzLLcYJ2@vC`l5?P8C!1-{e}=c7-D>-wJR? zN=v~b$vBC)+irHjo83M^$XYEW{?+j!UY!b)HLNb3_wVIXoTlccyEl6ufs0}`I}lCk z`AAvznb~kRVi#~a2Ehz!J)Q*~CbIJ@@&aR0SoOUQO$P>Lw5C_b&v6IiEn~%&7a9VQ zC4}btnI?bvzLHN|U00i)7{!n><~s)~YY>wDr9&G*5KsS)PjQ`LM=BFPTzGJ7QP5oN zf0%ALf}a`^Lcb>D7G$GCpeJ0WoFYafKEKs}RVSbj9c_$>PDQH@V;yhi7IzPEVjK@f zeQpE1uU>l^KEXB+ctX-adNiQ`_P&%0`1HgNcW3`IF+>3#y=YEOp}s&&kv_7<^@*u7 zc7TLZIiX~?SeHH_m7OK*nKFEC53yMZ!(rza896w>TDmiF1gEfl8QIxka9wp4jE?44 z$`KM5Fs(I`!USxHM#~K>LBv2RsbWA^an&tcCEaOTa8I(4%F+;3RqAOaX$(76r*dpaK{RI^4XxwO;)Z z8M`xSKNCG9VcdO#mFvHCLH?(nZ4V<%K$&MhA9%~j15x^kqe{p?S!6PJW7~E$yU*`) zOc+VvYSIizP{DOkO98-Cq-lO>sZw;i!sl(`i$Tq3lgnnl2-xJ=htNo*s!jlH; z?yOh2W^Tu%M8$yK{dQ({RziLm62M-l$w-ydQ#}LJPqXXugU^^k0|P9}X~aS?>>=um z)HK_s1e2G9x2jthWPD@m&Ukz+*5+){;$UQbhfF?kogoGw+YH3Aw{oQz%7+bFdJP4|t z0R%N$@sruw3c0<$POfG4YrAA4d8}vLdA`q-X8cD5H&N%lC zQ1BZnx@$hJc$R4v+I%XdO}Wu%a{edmsc&6X|8iaBdxvMP)Gn2_;d>s-uDb1bT``oe9lwA0HUzpc){yl8i1DgaSud};sz~8~~wz{#r-q1K0d(|EqB4QDq z>R#AX8M`M=yWhRMUmQDm?2zNQn`O{29$VWPoUKl6oe=dTx|E$5f>O3epn2}Ir}QXI zNH10MaJUF%zKN|fIvw6LQj&6ZqABI1L(1SN;7vm;z!S{O#DZrk8!e|0>T(m>`mr2i zSeHLkyFj;+kSZ$ICTR*o0#* zx{UjFG_S=`#tI=~U;_2z5Lcjjz>m^6YV-%|GA3D}P|S*1b;pzt_&SlX2Y()*r|1*g zDtcvDH%Dn;Y01CnGhsefM!YY)T|^bgX>4g3-cZ`~?S=WH&<){u@H{eY1%XIhW){4) zH5wxDjXQ?bK8l2s$7mAArhhbVYLH?QH*^T7B^7ZBJJHZL79!=$R*Hue(1ME6CmQbl zxpoeAUrUe*IUz{Sa1IiNbJSa(&L*(iZ@zu4l>zyG7PyxClU2h!e3^B94IecquV4;T zZV-lu0C*$}${;_&G`rKYJ7Y}yy)mMg_EVS78XEQ!Y9{ZdWn#$rBa-0uNhSGwZ%Ezs zzY`^71~4;$sDP)HsIvUq!H}W!E=q3GAw%PueNe4=cU5@j*?*hD<(atB*#NnWB15lTffRt>vm&pEMaqbU0E0OE6&VdWJ zWUk`LEgKVS$Ix+9+$dHH;#k#?MH{7Mgp4IaosVV?S@kCF6PvxjZgz)(;;sv+=@s`@ z?Gt|OJ*oBV*rG-6%nVLo%|=D7dC5@*Qs*<7zVJEY<$V$mF0ZVCo_jyOZe(klUQxj^ zP+*EdCNdPR@ny4~qH`d%^T`yr0e1&7q9f?MYh6cGol4d$@?~XdW6HcNpFSBoT|n2< z6-qKgEI)0+37ubY0c3$N%#~|#?My@-aO)IJ>Q#bXVS=@ER6G{^nkVqteK&KEIjuTK z9}v6n?dDhugF>XwMr2=xO=z;QCNLwbsMmoc$#MdaE+?PwZ*MQ-~Gn3 zH7?>{{Z+EVf5(yMHJgFMemPxICT!W0`@aN!KByoj^v^2u1UOh~ug{>NqXy7ou60>T(YILp72Ehb1BzKK5fD39OZ3NU z0>DWUp@nMhTj-9OaBh$3n7eO}C$8L{$0oX7pJd5H(gxy8i6*q5-{#9F-aut@=G{7( zBs*RnNS-#D0h7wKjQd4t@z5x>@V-+-7&&<3=^h>U&f~(a>!XAJ9ua1Tvw#sjk-cit z!euUCX^{zNaf7HP5pA;8%^+o3dStcr^}(DW_1A&rl@vzq*KczF4_{{))m9g+>!Je zRCfTf%4dZ*vWR;@3-f&Ts`}h(+$HHhE@l+wgiHMhpA@4bQ2(2DjSILH{v-yjajDK@{|{q*n~VZzcHP>!}uWNe8?{ z&TkGh9iWqty zL>dB2?3}ZJGZX1Ptfuu_VdZw$&}!jx4CFA2Jxv7|hWA5BCg06Jl8OrQEr4o>#oB() z@fMSGZz8SC`|_epN5DCG(MV)uTSahWhQw*-p3KYjc3j{8uSh^*LV}WT;On#fi9L|y z4~S`O`0aYdTv1t(Y{f@HlJj&!(A7P7OAD0`=OXPo<^^<=A0J-&lHicdH@p84zg@t* z$U776FQ21(NC>(l$@RX`?7Wz8`l>j&cZ<1QVj=AP#IiTXpd#{s2)L!ch_qi`GUkf- z!OFh)g)|_%UcdrbTr63piVzAJ#yZbi$RM+)~4~)8eKiBijutMChl&a#s(@|6K#=~+0x0L{j zD+4BZTb9)q9~gPpIY&;KLp$zo*B$AXzfN6nK7&dh*T&I+P&tK4=0f;|IFLW1Exf!L*5%mX^=`%n+adHT|*OajxGnsSgYX>*>B> zkR7b0II#;u!?3-H-hfPfHnJ$Gf%ty zdN!%$0k*26OLBfvHw7-*>t|$jJ4#sO_3cxVRlmHh6WJWb_~;Dm0c!Y2JwBiia-ln_ z!0RWp+`wZ}yW=RGPa?sy**(U?UtWj0AY*7RBS6Wa?@#pfvJNT*R4A5fd|*?p{5Bej zMJb!IC6@1VMI908m)Io|fsdVM6Rz4egE5uAv9nX|Rzb!u4$E}^s@_JQ9LF1Jh=Cdd z#$pzNq5=@1-kdV!tNqu%uLEc!z#2bHl_WU2aLWT_c<*y zM7Tr*lX=_KFIS%~&R+Yz-~?<&O?3gQ+J5u#-?kar?Q*M^{6E&?bbt}|sOwTjlPE|m zn*CQ&dO51D_rK`1=Yy3|f1cfw!?dR(I^k9l1}KwhVC=j!Rq99OyzPm({g#{C)j8CN zg1EWtBc=XgqICFnJBak)HoG`#X_~`-^4Hp$nvt(mGClx5)BCTC$W|mUAIpI~pdTRK z9-lTz1hWQS{1Ci6z#$b0eCL$c5sY?zQlwJrdB9d@Gx4$WLaF^7eTmO~+s2SIiuhHZ z)t9}5MP=8;i+8Tu6K@~3GG8LA{dZSM1=}adyw*qik_3UvAUJe6iajLaOcycYLipbI z-X-7n+Rt3x#qq~pr2b#g*!b#zhcTN=EVp!q=Br!%W!|`I01N%iCQu_G#6kMJm=$Q=llNTAb~ zKqU7(CVn!Bjhfq)DOBi(FBuIR!Ie|jv{l_CnAU$*EHIZ|MJ`4+&l+5Y zwO*tv{80RkpSC*;9yXWsUPaP)OM+-bI87uiUFdYN9y%>Yhy`D+RJ$GKm>c^T9zBgD zj64kaU~UkN&-}XodeL=7{&M=7aDqroh1UyL?!8>a9CWkW)rY>w>$(3nIG#`)M1~hY zV9poAEJoj5H4Hhu@Y{k$u@8|om(QY4Fv~+?*qgU=I`261&-78hPzgG_hsg6&M9YyJpbnYqksHg?(cym)fjJMyv2Es`9BfA>*bEkrGG#0 zj-Pt|>naHigdeEH=AxmY+=L>eqA_ce~D8ceyzm5I!v&| zF(^Bqy5^%=v~PFwzv-mapvm=Ee>^tz^EWk}0=T zk8K>xiI@H$tydUo^%sE>5qV`Z!nnPUA)0U(&RSN*wd(!`<`j9xXn#WU;k!t(;$u`wSZa~6e`PU zjYsnVWF8L^6ho%u|5d((hFeXQ%m479Ebxirb*<}ZKVD&?YJ3Cj^CDRX#-4{VE_@01 zhcR6yk=W0_wd&`2&(xsoMn;xAc_{=$y6lhvEM*0%IY30;ZB8`lqnN*4A@KnPTkkmK z0~IHc*i6JPRop&O?T<@fdUxry1@uU>@N`LPU6KzePBZ@cHt_0~yapp8qDrwHbNQ_Yaq~o7#cTi&@&7(htEU zGuY(M2Lbg9*bUuiJ>*YgB8p?%N(w0!_X}?OhF(`)Yc~`c_~%vPgK#~zm}EwKT`vT$ z=!?klx`j1x8NZ&UUXMOuoxD-nxm``Xs8I zbI?w03d&0hTfnws{&Jt8!a<0ubG*URa`g1l)>U=-#1|P&K&_5UelbZ=+<$PLn60?g zQD*xgG7PTLAz3_`fX3lCT0CVJa5u5Mf>qGZxiO}ZR!C+OHcqAx(Bva$;VnT_brTm5 zDxwNWx5LV8iHm1JDenGZJ#Xyv?KL^|j4YrN7f=quN;U`E;@N`=NdhD>Ndr5S_m`%! z>Jy^!?Q!&ZHFeuMxVEjC3hfEbl+s8j;%qy7#69nZ>FAb(x@Ks?*+7QM^ z-nYV0zg>98?f|c6BmKb9>EKLZLx2P$WYVLf=y1@7X={}qJybEsIAflX!CU9a0H-K6 z{i70^b4aNpL%b#1xQ$`l5DjyQEY5cN9|a@Ye*Gy{&W@J;oA@{6>SZPY1upN8;Yy}y zW#|#0e<+&?)6UD#7m)npzcC>}C*LBt=bK50+D3T1S2sWSJ>3eU7qdVnK!6e(g!`<` z>LpDoq)#qqO^Vs-k$?V(Pl16Yx5gj2ZJ~EO*C1q_Hp3s~22a76y?|Z##%4ANdQb06 zu@yiZ8e3RkNQh1rr6{?;qUXq#AZJk zttN7&=2B|Fs1i(UEHDTTM#biIWVQtXS|G?D7lJ1Y+Ea?tK;9_Hs1puW-5Cf@sB}=& zf~1!^GL11R=$u(sNZ3l?rqWXje^5XZ7lH8DMmGJg=rmr+86Je@<@@K2UdRUML)*5X>sG=e2?G*k^U%G^i!7(waSS$MWJcpf>8;2!c# zUnc!SheY&sfZ|y+hvi*B+k(Tft7P|MFj_gfk`Z`==p4VB>pL|JeZ~}G|1H&NLoUtm+&pPdg=Yq6)ibMRbdF?(e;xv zym8~)2~FNuE;BeF5QDYe(8465jiNk115K~FT+xSa>xg&xc_WxmyZDjw$v>4+{n6}l zf57R;c^;T41(LBMBxb01d;WUt(I;ng1Pt7MzPATR8NR$2Ne)T`H&3lQ50Se$b!$2ZJDJ3ek;x)$=15c+6jp9BJMR%F-m_MhbUoEQWZu+ zX$4y7{}cO|y1AtZP9+bjVxkTzNTkm~@H92metE2D+xSP2_C{e^mbv%mjsl4vhnbFnM{=xsTnjB z^64WfD-g}ueoAg#_I{~pA2=ut+$W+-SJ8OvW6Bh+hZ-#Z;2vv+66kde&K9KLn?b=v zD1_4iy9=GUM5Sd_rBykF$`;Si=V6)pW_BcTImD(NNEA0DF07afJff*O z$=lSAoC|}cMmvR^m>i-DFzUX4t;x4%E3jc&;IC)rY8)7VxoW7kWkXUK63}3S+&g`t z^pthJ^4t1~CgVIqgiav=Thu( zTIL0~{IPSQXmlVpVNQ*0I{=oOQbH*Nz6E zktQnEXJ+WD~c*+xM+WB|25J~5>^3 z*{$4MEs{YCi;G#xR`fK@4|^n^C-&w&!oYF@vyB*FBJ@!WPd&~YC0$)&oE0uURcW)! z(AIKQTtzP)hEcffnQw9Wwkgu44hc8hKNx>lr_>2K05xD8T{0XHJr&mM92dr1Rb zj7ZZ^=y*0V7Sq#@k?wPcMB~F3QEM80E$&Wd6A_RIA0AHkhM&=|02qS0DGBnil*>jc zJUr6_;8nhs42wh@n-+IAVjO?jJt9h^eFDk7tL##2rfMcJ(7a|sU0l}6FI={b9wUAh zz5T+{Th{fGX>(|42I?x$NM!BUnZqjbL3j zlR|nyo$ey8t~9sPa2;0NLwqfhsCBkw;w0XWv9}jmf9%6>iD#s8qS>ccA_4y|j&c&p zl;!q;g~UI$F*h&{Mwf})O;SgGtK@z92F0H+SKi*YOU*yUj4n6Q26=YU0#f|@IdgMBDP+!^BnSt*Wr{#AQ?iMlDwkX zG+gC*T)Y@)3Rl5kMIRYJCTU0?h%1qloI6DIhsppV^sZ) zS`Mhf3Kc^Z;EHP3INxS=s#E&FVT+KdASJAZYERUa>11u{qF6hQFyhGpoyYv}_~_$7d4 zGO{kR;d@s&*$n%i#lZ%4=UC)+#b74p1Q10BxwuX=CIe#DXpK_Dijwxp&jrr$kfjq? zj+ZdT2}`mC(t5+;Gw6L0qEeozxTW4!cC6HW+8FFC0|a}7!G*~pl!; z@ujUPLml)enJH06f4fgI;yXEbouOJ0>{dtj&_toOs`3|K`L3R0E`fV1F7Zuir%v& zcVTixNwqoL+DXN8^|vFbe(eg20(;spOjVwOvi_G~gJD*_S<`6Mcl(+HoMm;!Ppv|K z<;B}RjW|-)ShId@>ypZSAta@&eXMvRD;1w2CM-*=O08E+U~m|3Erc!Qjup|{2oS-A zb!rW^&BBe<*Ze}>VHHaKxJGA3raTm4&-!XZtoR*_7}?G%s;|pI-B~%8+BO14wEh4O ziTH{#Qp3rLE~#)`V2*vR*R`nD7*m&b*0+}9h2v-8fn_UAaSsyeTau#HcDAM4NCQgfQeAMQ35w}kX^ zDUJ5X+U~D24;(fUmvC5FUjFJi+c0)r-$@m%(MA7tT=y#-gFRRKl4@Day>Oy z(|)Y4$edp-5qduycc#wdTdpuwv+3&LdB|z7l4Mk+vh?`sFjd3I*C`S4=~D5+b@8Ny zFjwU?tw$!Ts&x$3;C~a7VZ6fWa92$;wjxjP4X3R<#Mc zr(Sz!$IZ0?w=djPW@zBgHvT74#PNJabM}^he4uP0ZP|@=U*GkyYlR)5{~OvFMqv-{ z#YdZ_-g;iK-ZAV3l}1lq1=QFR=spn(l-)<9#W(vm=Qe{@C{*Qf#Pw43y}zA#m18p* zu>C7pV6<2yQYv;2X7^;_k3)TW3l{HwWTDBI&F?VXxEP_}i`ZV_mOsqd#+&8SWBG8kv)Fa z5Bt%dRy%^em9W?_2gkH2fGK;4GSo62Zl6h>uKEy6IT_|gQ6h2uLTQq^=GnxXA7FGR zq%GcF?DV@%Nx4Q!BA(Yy{rB#-RO98Tl4^zjezl|#F5w)diA-}e|hGWH{)xDWQoClsZ>Z6Nu%K$$KoD+eRGEQE}4m^wrFu{4Kq7kN-659)IbcH_mn zicd!4wo(gZ#NWU%SjfMACt%k?Xmp^DJ0Y7~x-u#uVB3(;xZ=~)G;tX9EKH{i7oFqE zG!$03R`2^EesZZS2~GB35Ll)@!GW-<=oKmu!xV!TkoN^AOEm1|>RfA(IscBGt-2w( zk1enxhJwLDoj=evkiK*Z!dD_m<)12V>aAjjMJnTv-5pxr!q%y3l9rtDqN$(FAuRQi zZP`OWz4DK9a4K4*OH(HpYWZCh`~7NZNwzkZQW#A^!^*_Cr1mR&WL$j-aAB+#An^U^ z>Be9FfYL_NTdQnxkk1f=W#iM$O9@!2W&Y>-sKMrM_$Kp(+87P^_kS*=TAVG2KEj>J zW3f{TU_{}?LhvMGy1y0%WFoY2r9wR$GgBHJP`=I?4?go{LBV$r{0Da5gwYJjaM>&k zQ`tT04;huSv44!;)c8hi&jvx|Y12>uXT<_S=Cmvd$)uCOaF8UTk+>+8>8$%5^I!Qx zM8%ZUnotPpOoPPK;YSsYFB2dvy?ussQCo~2k3Dos=8jm|xp{kgM-ICW;^&fo(u9m< zTbeYi-mRg1)((?u9p++>HvJ?Ugf(K`-N>v9OCf4lRZc&uyEjPspO_#a0Rzxz^_X+W zF?56%FeyNo(G2qgzqJvAL!CQ|N3dZb{>C%!-;{S=@u{s&NlrqTBtINysazpy+|}LbsV&4*kyw!eg@8Fl=KBb~1q;zW>b~G? zG1vEww5c08R^!en-k*(w9e3+v0e5RMFpKbH{(dj7>qGt1Ul5ef?-6yr#^eQ~yjL1~ zy$Pf9yjychhadv!Fis}{l^rg9Cw&>iMbKHaw>i2bJX{8Bv#qCoe^i#(G*hsrM7lrN z>phA3L)W%TFs^a^pC#rYpvEQybc%=_r<0IbrFcuy8S^uMz8Q75e`n(QyyXDDms9=v zIrEb@3@jGMm2%|}mz3zwc0!3j)3AT%cLm@ z>qEQyltR<9*uq?!k;tmZacz=U7tG4XN*RA;+NTKZ5wlY!Sd_Neahhvo5 z*=N7m{G)=^C&pm`lA6X!EDGbDUJM0rGCc*BxELaX*EYtJc*ekLli|NLR=vmYh`v=R zg&j%`QVbMfFn(iJ@Fco)_8R@W6kI+CVwc|sxc;hYT$^Xl#XQF;_uDdtxKBH`w{`2U zTYiSu`dH0eq$yg&ru_mc=vWMCC<^3MNB@d}l}BAN`s*>9x&&;iaPR5wkkRec+UNJHAX7~uHYZ7?5LJjIa(C$vK417y;5j_|C{XCr4 z`k_tI5{A1U+0E3;a@Fn2AHzn&M_(N3BvS?&9>nx{5RvnGm)*N&uq=LPG^hX(L<1?_ zy^s=$A#BT%B6zX9``0CVcD~zqx=&CYFc=rOil)93APNF1YLnrTpyf4n#q~Y3Wm-+j z9=~vEZrK_U#hHN+kC#7Fw`qT0*S?${oxaw6YYIAfd0f$tN5q1Ya=rS*TYzkOUVwYK&5{Z`?cZ(x-{x#dpkR~3UxpAmuSE3|Hl zJdfJ|I+lmF{ST?5nkRuq@zIam*&RAQ9dl@(|8J)k0=D|@lf(ZVE#I%hLr3s`LC60LH_bz&@%;ZAKjc}BZ?FG%7-;&!)s_A4*#AEJ|M^!f!+wF% zApGSPrsZhi|LX-GaAC@svS%G0{E= z`C>qy-91zleR&I*RUn;g_9yDV1_*Tc+WkGL2UfZ_@>t6?P3` znG4#bzH|&8ZG(x?w)LbPWjGob`OX+ATZ8>$ga3z4qy+ z*+B8!cvzy*>H6k>JBbzZc$BI!2p>(^fl%C<*e0~T^{p>DxUWy2f@|z1dB3YfJ_lf&=>f{Wf6kefpTFun9wX4 ziY?x)rvM58a)hh5g${al#pxg{6be%ZQBcS`%xP=QEq{PoOUOkbYG+qG-wzU(EQZxj zrtJgChWpKP_RUb4=x8q<4>$4TeIj<=^f#+|wUl&}7a;gp5Ix)s&+q|ZQe;0NNYrR& zsgV{r$_+DI)D}S=tFU{BxXmi__;94g`sEnUu*>y2S@Y|L}O53h(kkE`{`9jMbo3d zfs6_?6YH>Q2n|d{QMv`PeG^j)ibcWEGez~Hc5>10RUoJ#U{s2N2E3GDb|iN5=+9tjtTZ$u&_d|(B$E>J<3VB& zjhHkd9_dR1sCCp&JZZbaaZ#f1P=D*6U%z_1-zTHc%T4J2mcjwC=x)R>;)V`hD}O>r z9cP}_jl6-Qz+3k-1$kRhc-Q0BJJ^2oF`CthLQ4TtNi&)*idgE3t??Iv&3!^tOYLOj zu4^46@`>O>A&BB=;mL?^*PDU|7MOwjHabLf7`+^Q!8biw5({M%r$_<|3-#zAMOXP8 zRY^HL_S9C~5?4By7P`nRW~rlF`%5x(KGV(q4JTmfPtBwEl&VtQ~9Y}!A zBZt-67QkN~Zl84S&|Uj8DLQgLVU{B8j?d)Y9<9SF6c?#(Iliq)`kV~J%oAu$|-xxX{SorjTG?u`Z*^Gbd0 z{C&P(5SeBs#v)|%{L5-ucqC1)y`55^Yy*O~_>8S%OGZSdi9`s8}ch$bHucARz(ZzhzW6wXJ8`l5>GKhAo z)VLAR4$Sg|$Wn6pn$`>y)N8||-Z2Iwjg35W+~EaPcBOR;?8uVnU@8YY_AEz!l#DpKA$y9BDbV$0|5%h#Lcn3e#Fl7XMk-l5(xsQ^sS( z65JF^bLg2FuHtJoBuRCRL^ZgSq%667w2U2AQS=ubO@Ru9(IW5J2uBz= zbmpfy7yYz6TaIHL|9h$kph35eiJ6(*h&at6(w1KeQ3YnfyRW0C2M<*3EZqFi%5mjw zDjMRWBs@JmlcDT6+7S44f#PIqA_!LnxeiUe@L>>=z0;X-UePdTp@%G1%{rxpq-2sR zB*Buu8Z%Id4I`t@;VVm${V^qZ)^Bu5^pZpVQ60(xp_ov{)RJ4W-|i!+L-^!_oql8Bmvz10I(b`Lfv2N6}aHE)~sI zgHzcm_n#&<{PRm~9>PTK5s)p!3@6z1esUSn40ihqmoagqLlw(#UV?7d1%_*nJFgyd z-5mW}`rNY*NBG_#pks?+qf?4P3ke~y#ovB1{#y8MKjt~|GUb_Z^F?#Lp=sw=_DV)W zL+Ur#l<8PRw{8eV@Ce^s_~gS)+{gTFk-x|JCc*uN(Nreaotm6NS6iokfBEkG0{=YT z1dwmI$(qWQ?@&ch$YHx}`}(Kv3jiaA+CiwmoyHiA}_d`D@NzXU`Obly=u z-U;>Ks0fCh+Sc>jcdFFsN}x`Vzr4K0xw`pp?F$c_=4@+xpy~C*S-fM1Qp_b6GJ>^I zcoWqQ8gjnfnyrYDOx1`Ihrijl)6p~75@2nY-Izwk6#7TFD;~mSe_7J?Z|dpr%PS3n z1XX=s_`Bz8l`FvEpo1Z$J#(xS9L#=S6=qf*-`%8N>=G@N#Dm)S*?frm;LRa-}1}(Z982Ds8mlAUM@m%M`z$gAJhcZ}iAYaQniJL7~B1>^oOH zoSb9zsp-)2bg8A(&(cE0WzbTsA5|$Wdh>&|_L0c{Y#Q}sQG|A}f7xc_?qefT@W+ho zUvk+hK!7j9mM8WfqCn+v&1Gc}>>7Uh&5>W^l3uW8zl9cJwhVxDrfm^-+>kCGC}DPA z)8dWwJ@NA%kJ!d+bgJ@$M&m9W=raFDeDlLHTynL0voa{dv~2@@y8Q2EpS1n1r$vD2ka-t$VAbsJkqe!K z8!OF2ou%(riv>*N0ZSjUFU89RbYJ>(-YZmo=31~$OTBaRc0|Ja*y4G}F*KRPUh5$O z81)#NJCofEQceloeIyMyg?E`X?K^lw?*A|CWWx(wgnL?$z{UrybTNq1$noRZ4pV8CFKum)mPM1L0K?ldGCmy#-Bj~lFX8xK?u(3!{}zWafFn&AWJu|XX=&okV0Mh@ z@={C;3_ETIT!T>fsfOfU)pMa_j#Ut$QUwMKw*Vv2uBKjRz!SHwZm#|QlD*#LA?wRC zSWN(O)~wSjmK`3W|M7m*ZAy)pXm@$)3EO9bE(v1ORQ{1zgl%GMResa@)QKAmR2$|l>UYi0lRflj%7@>nJ*MOLbF zc8K+_+fMIL!LNSngv7M?171vQP#90IHSJ&-R)4^3y9WoF^Z{e4izAsYOt3)=L-r9O_6TBN>z4ZI? zNcwTeu^^lpWhLIQV>q+xnnw6G<;$PBFaEG+Kd*}cR{xOICP&J^XcNmrSGOd16L|1S zu$&EdPQOd=8NaNJsNH{}xR?8+7aX(2YAh)ScTzJ&@oC2tNs0;SJj)KT$vcLr ziv##HXM6{|y^Xjg(}Rsj0UZ{yID>;#7lSF<4{1}cM006Z*V^*Uv(A5aPy+8Zo;IGM zrk+_|Z@peHy6#$nh9c1RL7_Z}+YqU;6&3mT7WJh2v?vNCoRw4H)QKi<(X-L^q(-_j zsANlrpCWf=rXVVY%2C1aVZ*zwd9(1~!A(8~ll zGF+Rb$a*p228O*$$=M4NrMiE}>n)O3yeCgfLvesE90=`1)_xHz{>J z4b1KSDX#2Om%X@vZPS+ReT<*sqISFCspF z6+RWO*%qWFd;YhG-!Lnai%iy$zY@M~X}|Je->+zQ4bE<1cV<#0)*aN9kk$v*$scwF zRpdJK z#PKXdlP<>|GngSv5*c-FC|0CLW8Wy(oBUH#A_lB4UbJo;=$R|>46p+1O^JubQts>} z=euc&s}Cp;!(%L4@Qu@z1kic^jVe6NbiEoHy{tFMrhd-KB697VdH@s>o(}O=UjksC z9veOtX;ofC1>FxZG0i&*5xlV|XF8sfB5pv2 z;@c1_1N_*@=;Uxb9XCdR=A2}x%k4Okg#cH5tFeR-0)l+a&tJ6HQ|w(oPOKgGEb&DMLq`IlKyIo|DM zmV56z_xkg^-%`B^LPX)z(>(645}NnC&cRgG7U0jT_(y!N7nnvk7#zuB1PSt@L%XvQx5D<}nF*f|f3OLMqazd0> zb!HDGlMx&1ZMcsVr`GodGQ0X_J}OV^FGu5sQlnbGoAR6!Zgd((;BsE&Csm{zdA8v+raDc7hSvBP~we#qy5*WGTFMC z-ngi)K6#Ib|427qdniJAcS;C88E-A{Qjth|AN-LRpO|pj9wh7tcs6JY%vfI+&iCI> z19-B|fL$~yUy`u}>|x*o`AfgmNDF?G)0h4J7WN~Dkwl?K?}Kih$f(C=?oSe+C=EJE zo1B3xVwuFe(iu$M?418B)#}4OQ(HUl-QP8{*C}qmgh+q$jUKZCqLIE0Dy&dm%q3yL z;rom@#oyWel@(?~Jwt~i#E=BD>;}9lgU)_d|2_4m^`L(WirI!mHrc7taE;+1oqz}9 zKce@f<|ZtI#o5#&g%hw->`3PB3a#?rB!p=hW0G(#^Q8vkZchg!23?+bfRUBsTI@bw zeORzIAW7Ei=*buITdws%nC<={V`OGoRzFN}GVh7z8k z$^0_mpqP=1ANETZ^o_OFACCd+^!SJolAWl=tIe+xxdMKOg zJtMTMJ`H#Zd6N6bd-Rc<$Kf4Kd_b$ay2n4+5FRZj(R9y-ez=>#T(R3#1*H4enCNq> zi*d)A$x!p-H|&Go{J4w_+sUSBKHmv(P=4fNAJFdlr`gNa??OsT=UC&m$TH}(0ofM- zm@@$WL@x08(+fY~F0S9?sQTlV53sRV^VkZy9;hXf1%$P<@ZFxRPT5tHnK&Dh0l1g_ z(cQRQfgs?ldAc0V`V{^gC=Ad_P#t_AQ6E-%cpet#0nW2u+7k`Mrod zF5=UX$Ri#lMnK2&wV(!VtZ91s5-hj7s6##|h#Z&%Vsbs@>U0l#AG;FI_V35bL=teF z|MW`zC;i;%$5j!!`OjY61TfOH0GwbCkI(k|W48SPEr`Wbz9A{!CGp2WM>gJ{iO1Tk zm&1K;eJ)4n`hvMwy|y_cvp&$a z@gN2rk}5+XoOtQ*`&m4ZVCO~@qip7y7-5C-@6ne{4k#-vsvoAinkz!>!ZdWrD#hGw zN&c$U{`$-`YmW^a2^&yVF}8M&9vP9VPb_C)b@TJjrAFcPx+P7%9G_EhJLfvTRm~>btIU2Nr{zVkc*zUlDverC9057lQyFM{&c_ zre;FHYG?`2?ql=mr}nEg#wcR5d=i}6+Toqhiz~8X!PfU#?|QMRPr1IkJs(l=59PFC zu~g$@V3UilL{uT=mo#e`SnPblqg?Ctq)sCJ$AFCdPu3kFkGPPYLYd2Ga`0d$zht;U znXMeM-_noDV%XljnE#6UkPDyh2X_Lqw+Ye^e6TR z)@Qcx=Sh7F*eEmn0odBUC%*X*^!)o%*eO*BaGyLoGBN&OW!@p(VjIn-Y!e%2Ilvx& zB*`jH>dPu0|UypcqAceUfcn zH5zu#0eq!;KQ2Os?rMG9!vRm}%X#%P+V4|akMD1^`fo^@bPYaFwR%gzZaK;aJq(!2 z*=%B!aZ-6HV+^}H%t1@+xO`=={r(h(W3Ru;S_D3 z%@70-958h@FNVm?yse`%jReOdZ~CrpHSRB4>Y@YumRbTxSlbA|=h!d2_k7oELK&!;tboPtzng0fUtZ4>`qietR;!Jt0HX$QucgO# zprtLXQ}#kvro(*zVy<)o%&zgXm&vnDZyz3~<;jJK93V45ohX1nD+dLT|NIG3ckuEk z@iX(bjPVFPg5cam0EO(RG8#}DW|JES0{DkLya0*(uFvU_REqb1}3hispaJ; z_6jqL`X^S7@XJAzB0Gx4_gA`mn2uO%#iKvqhP}y> zws(}9(}7BBF*SK=zt)f@LmrSG_Kwup#Xr8s6s`zE+fk*?z>pGsrMdASogWbw?cpRh z2bTsZ-&H5~iB)Do}Z2ZRQ z)yR^T*>Q5Cun}r@yr>f|aJ{nu0gN> zw}qRCv;_A*-wR-K4Bh4h2*dzIDb`^%Tx~c8hfc=`9R*<`B&^7w-8;gcLM7F_!K%?h ztx{{b*%1*jeT>HbhjMo5?^chvv%ounaTYBi{g95Nb{sQwn`~gdS8Bx_^}<)TU!rDK ztsB>@m^(X%)5i`IpoJ$OLr1xFX&7i)=Xl*-e)Clswe-H;iv-2{w?vt$h`dg9J(8xW zt6#svEMkgD_A2xH`wTOXAGy5bpi{};0cf!wiO9%yX8>ZWsc9&%4Zim~VdrsJ>F)`9 zoAu?(KHynxzCQ_|NTyOtQO3r`WEqG^Nq2y(MmxX(*amV%1}&~g3^WJ`2o;}1di^%; zjLeB$+)hx%!2bosmX@UlhsPErM*oFI=$P*cJwgHR&YpgNDvClpflU5yI!Z@J$JpPW zbkRj_F5Ro+*bvYg=SD;z$?tOH@6Rl*$~b)@U-ddEfL0_kE&)pQJK*VUpw_+@f(Vf_ z4KKM6n4u~$FI(jwxMS+P+^wE&atwYw4SN2>8}JvKl{7F*A(Mr@-2`{>#-Dlqv>rD0b!Z$jo(eDru5+1n2{D7RB_XTBjyMH*BoK1sX zv0Uif;rl6q%lpoxZGL)&7y)eQ=jUgDHr|Q}vzW2x`nGudpM~>$>%eBWG0zlJ!f`8a zq7-h#0oSoHIVtHl4+nIUm#0B5FOC3^SMOH4nDJTijhHb=Ev3*Zq=rMRIXQ*;6afF& z3F)*Si*&r_iDjaoUbgNgJlIbT(|6W+zF=~U1I-ulDe zySY`7;PkBUIonJ@{#~Qfzo}ee|Bt4(j*9C0{)Z*RA(Rg37-Hz|?imDSK%|jwkZzFf z9=coJbazTfOLw<)gMd8u^Ly5JEf)W9*JbA1bNAk7?^l#))mJvwO5+XgV0w6ZdBww> z5g4qVUYae|a71?%x48oN8Sc2{8NxmZp%?DcZ(uYE@Z>>W@j1Iz7n zdmxaS(>V@r3p(=xLs2T!$d_}2_WmxAFvhgQTs-2h=IwZzZ6zEMj6TTP*GSg!_Y2Q6 zD#H`Ny}7C|xPj%j(_;_a`R(q1Z@xvE7ViO~GaRCW<`R#Q7Pi%>ny>(98!T1tm0o~{ zUqJ!K$)k{C3o<6AQh7OVYKG2NU=#1|CVhzIhFLTq6A`DB&XQ&dIv~$q+#j3!#RE>h zWPs9JK||iG9bHhNCTjv1GW!Qs9GeE7If@{(e^ar)8CC-e%};!veBoT|Fy%inh0k974CcRC?Oa>G7iM`B`X zxw)m|^>f7>!P!%Wb{&DUX_meBa|Vb8cvnskGR+nhxY7y5>5eS{`wzSs$_d~iO;%)N zOP%^arXzigh@xF)Kpw%ph1~1*q)4~&tI6AfJbml90|YRvFDF~QgSaUc#w7qppbJ0< z!5>H6noo3n!j~~ij|T=D7#w_bHl;VJgn`Lp3`P6pA2Qa@Wx$#^26Hzi+WKzswoO*a<)5L0E00X$^JakB zNK;?m(8wslwJjR4=wa6+Bg&yrw`k_=9WZa;7wFb;rHA$I?bU--E6H!vb)c z6zS7N(O$M7Ym@bIl2KLgDJhNEtO*9}diFs9h52hBDD7AJApSO8c4GU5oOPb#VT(6s zWPFL?5fJ!TFlqESK%=q6oP6@_@2I7bjhWg0AqO#NiS2&^6g=3Xzfi;qo_Y-YLbW@> z&mLq|rA0u3E`NDBL|;rP*E%xpI`&KMpC?{~czB#NlY0R)rD2k1#rVuMFDPCvo(+?p z9AWBkwTEilWXDx&_`PLOh(F3M7ubfCmSdy{M4@F6LAqB%O&ucXaL4K!`5T0hk#|HH zkRTyR(5Vlf3n)-6j3t@31Pwhs(^Cw@dg($b4W9>;y*DEb3ia)A1|e5hO2+_&V41zb zHA9w+b=l0pGR;3vnKy$iitFAt#uca5Y2S|0?}_I2)bouRPvZ5pSJY}MgNji;XODv@ z`8*v6g`t=s)j<8j2W6fbYV`c?(Kj3 zhwqz3yNeog3Fu3W+9Cs!`E<^GF|M9}KG>7< z>pzDQ2L(N^v809Tf0FKV=+Z)M=3--VS;Ob>^2k*(#Yc9XO3;^;%`}#FU>#TpANFjC z5qQJ+hX#N3cW+#63RTM-d~NU$g{e+JzpH<2S*@_w$lE(XPsB~_k25q!)FHFVZ<{Pr z+|6H}g<3^z?&dQI1x4PRjnm&_p>f^jU$ZqC$0Fy{*rMm3pF`dvMhO2WkrO{c%+1VK-KyDLw%AHG$^KLki|F}A;3x;HNkdR12BVEhJh6)&~5&btu#=4!3N!e@SL2=~1hxER;##9Q{KVco? zdu%$BXm)F@!KNY~RK~vf9FvN;o#a+k<)kgjg@o`=O)q0|)2pQGHajOPrBr^>2`3?6 zQ7p|=NId^bHmF%DPQ2BR5{vFJh`1aw{TqOyC28LL9KFAaSczRDNw^|DUvsY0>!Kw`5wW21br%A!&y~=_f?Pjuvld24i!8 zml?Mo*S_5WYyQUKHI4a%fh0r@lC!> z+iUI)l%x0W%j0Bi^IiK6>xk3RGE7YkLpUQ2$X21Ymf43HUs6l?wd_J{mIeEYqsdwv ztuv?hIXFc{17;xjO?Hl_PXHDfmne{IZo4%?-X$jGonOlQy5PXhhooSuL{1wn-i5*Q zzcdWR`+`ol7{nX~xfG4=*OMg+ElvXRs36F1Z9|;|-l2alK3U>vuEfYPWs6_!JOkWB zZ-1vxOs6kL{o4B>#VyV^v2%@_(PT@<*LvmPHlR$h2<^x06&%O~@(vLD|95yKYwOvW zA<+K0FqSboJ~j;;oFh}%dHDFo4hEuU%2;%}JQ6R$Edhjz;fMd;?vEQ#8!+Jvq7TMU zprFE;V<;q`1Ttr>zA^2$+>w!=Z>ikB!-sbJQw&Uwmw03LH}(j=RIY721+xIrzt&}h z!3Lsb8ImdNmtA9Ro|ctG8!yLivnEA?rrY@~M%yJgV|rvqNv_eJ6nIkcm??JEh8Eu) z*G#u=Z5hn>Qw{#BSph9@wkA0iW%A*$jbBb}o&jP@_TPN0;tz|2lX0Rdse17^#l^?d z>h=XM|8hlrdYa;R!2mQ-Q+Z$W#?bSW(0o-cG&@;CR7BrsCwaPr1A4Cm4QJ&AtF2>? z*sGwuXDlSeS!iO+c^Gr`J49QejC+@9%S*2Km6vO;wxu^SW#~ z0w%`?N@lT;__rAsC%*FX`~g_;n#U5~;?{a_69%}2mg8CpFMVWE2aq!aDjAhGAyu+Q z1Ra4s-Wzl|U$=MglGZ5yDv7_L^hWesCBDsQ;t~=Y>;4T&-p#ccI@nW2czJr;m{%ad$;fm z6)?;^ih$T1vi+C!%a?C9P#!F;A9D+S8?UaE`1HM=Nq|r6dbSqHg}i)gAs{m)YYfTo zuI%3a*dBOA%nm;+{lt`H8H(hkfL-nDjKF97nCAk^)66Ff0un=T-99^~kkHuAP)bu@ z!;q0LRa5IclJ+mc^+V)ILA*c&a{!93

Yo#*xx#^Iyaijdo-^UC&g$iTj<`IS;pP z*ad}S{%@$ZHe|3>naq$cEz<)~=}qN%&+^!FYHbVsIYA3;XGj1BAX+0aGsW2C8Pw)_ zMyCu11m|V#CxinyO_t|uZ5G?JF2d1=`|*4Se|I}jxE?Pl*Qn>~vgfgeuKn}H2u9A} zx9xEtIP#2miZpmRs~JHlr#dvxO)z$Micb2?+3J8V_vO=tn5zWqg;&U@DTW-DtF=3c zvD=O}mZ9i$9aP{LWc774c{FhtryI&<%ER|WMh^U-?W@v{J|U&SrgQe1v1@G^e^+>g zxv!&aOt^wJH*efyq*5twfsJ#re0MRbfXR!O(c?mBvu-Nm!6I>2`f>7yQbN64=f>~# zrni8m5ma?*oZqpGV&@J|dP9&sSF2Qjgp_hqE$0F2%E@WRNhl;FbfMmbWmY?jO{Zyc zT0*vM)y%y*Rt)HFRW~apSYh;YS5O1*KUXUt1nrmxZ;>45_{4e-xHPJsYK7v67i0*W zUjUUw(ZZnQI;WTqr4P#U0p~}1KkSEy!X|sfn|Id{LPGyu zP$<%UgAu+X_sl$LyM@oQ$6vnJYkD{6BIta8Q&4b}mSrHzLN>xtYkK4gui(-)=j&%^ z8AO@ymoNiOC$0MFP$T{OLsrGpwX(4pN~K?CfuN}95}2nPAv&5}lB1_rB{$RpM#Z@e zr=lqvEoo|s1PYokU8Hx-T7ftuZ8_i&ComiYx#2 z!E53TY)D6SATKUoynRRA5J+Ak? z&g`c6L&UK=mpPFm1`QUBG-?hE{ZO|Ej-YjH5rxCFD~OWe1TeWhGcyODSjQUKvQ-8U zP@$6p#Rw1raYASu$hRNGv(Eqv0cF7XQdk+i7iZl`s!-M;?9BAg#+aKz%ydz(GH?!X z+#GsHLrJt1N#&)nd83|^Qf(_TZGrg2oRnses^At>OEKS5Yx9%|l$XezDT7y6ykts2 z4vA~oF6HVdtXkldD^=GBT)w>&hUy{(JTJw>l9lbvziDGzPb;*BINKgV-V(7#f0^j# zt*F>UuG;jIAXD0L%o&>Iw-F(!YWC!L$E4y{7uZH*GW=iBf;xzDM7<7$6=Jf@A3Fng zlsc&E_P8wZO!iw}$wh#Zh~!HaroNWi=r?NHM)V`A5}3o4ECW>dD)(uB?RXuGa!lOB z!MR05Mm9F64GHqNtjRJ9)#w(intttL0yDBOW7hd1OVq{~2n@5pWG03X}&@W8DRtcD4pH|e}1Xbi6-DHgHm)RvbG#?Ue ze$t3+n-NH}6b@O{y(OJ+v1~}cuMCFbPl0&eTF92P zx-{tZNE6b*ZxJer?a0x;Hkf1c6Hpt3q2qEwxz?CWdDX|r!?!_k`tRre z;1k)9>nIT5v7Sc;v_kXk68aV`VY5UDdtG@zc*izN`4Kt0j@Jtuodug!pC}b7s zafju|pk^+WIKwosCBc~BTCuRe5AsX~vPyEKe5$fcZIT6q8_PscoDC0gZNd62R0xk_ z$_SxFqfCP4cB{~7%dKlX&ZIshZ#W-@TRA*#DOj431#K6G(=)w zQ>0+mB!6#XRCIniFK7S>yuU|F*09G0)Y3&BkDQZUTHMjiv3-A}B^pr1Gue7kV_K_h|y zYN-+~7&E`^8mz$Bg(QTAg~cUAK|VY&h!d-tB2*Bn*Z@qBum>+J`A{N~FvK*{G+6pZ zcA56PxD^PpsBMRS{k=(5#|5l*Kj#saZ)m-{@yv4h`Ex;9wd{@NFfx)Mx$#grjiMW^ z;Q&cr2mBW!zT3P!evlS;aDp&=o4^(fP1t%6La0+5jecP3ZnQ;IgiRC7*B%}oF-Gx7 zSdY|-II&4HW74qkCNL>;Nz)dE*7^j6s}2OHoBaC?0KLF*-)(o%6G1dmj2Lw=fiAin6P<`bQ$C>zrWYXobWg;)S=SCFBTaiki;aRkWU}a^Z*XVSAqR}3_ zk=7?RTkRN0nL$6}%<5Ld5zL|!j97HNOxkqXjVBw;c8q+b=u1dTlI;6*Mbe6ACHL7%q@fnJIK#uFNcF|DR&+@y zikCvMoEVDJs5IQQ);O{b(s`do!2(;L3Kw~HJ^~nhzTkLR9ZnX(Ds#)I??}{FGc~#L zLuNC9+%~BBzIdC)e-9e&(Y7rMjgjhFW$~tq3lxzGBaK75SAsE0B&OSjBIAE1X^VPY z^hl%2;~B}`_#b)7Iz%0LTIWRKFqv)(ilc?c5kalO8fXkyYwFvhaEK~2!nkq~(Y78; zrL{-@eKM(OjXG&wWRQcQDaikrJ*r=}B^MBpe^tclTrxK{@vx9AgVVR;_!=Xa)*&;l z5IwmFr$OXJz9^9N7;~L^Y<4Fv-;l|NK?~$UnQNwdr-^CC2G?KHX$$fa%#T{{ABH(G8m1pT5 zBjnV^55WzOrzVU!p+zWXrrLBB@nxU!t^7dP_>-gMYb2mgsoB^;^qK$HakE~mc7+Oi%Akv0J~e7V4MHwIQ6-4?(RZZr zVkN5jeeSBAu?V0J+sip{r-wuRc}|L5Sc|EYK%OaxpwJ;|pI9-zynN=IoU8)hW{^R# z_CwPCV^BCv82*$BTg!Dsm440w}?db)z-bF5unRfkiIT)a^lkBl|q?v1Z}et9=iStiF=0;){8^$&-*WLb&k1**X;9} za{dr4h5RqpEW20WDU-p{xwRB60t}jajxGZ;SxH)GV)=V13@CY#<}lKM=sVaF)6mip z^;H>KHEWsE)1r05+(Ki=?b9lp+u~axitr;ACUha@yhGG7-4#Y%d&I_vF71+@vLzV# ziY(66)uzD{f5cT}&}c4Z(V|+`^@C+P^g(l&E}RdCPCcSRxQW7+=GXRO)>m#^!>>%c z!?G111+7%Dl8{wa9ImyZb0$SsmL3^2-Dp+G*HSW34>&F3hR`INn(jjWj60SghM#tZ z1|U#gY3=(K8bb3y6Yts#&E;x z>bT@wLWS?t;qYo30$LWmp06$J)Lct($avuer~}{W2^c2p@uIV;sNc?z+IoMH#G~eP z_f7j`U6?e6ZCbm|^_EYLL+SN0EFV9Ry3B(Bj`B`gGQlcHog!e+Pi{%w`(#DC19fgmNLbTBMGc0-%>XgdDnVYP!@*GcaDJkp}dsu95VHI|f`mG-upQEd$fCR+b+uTItBCBYPF;%WW6$JdkT#@SalR$Z6<2fOwoUzwDz{}TN@5_A0Ko$PNOo2Rqd z=05-M+d1-`>DYNg<&~)aAkcxG)<(p35jc3`Ci?GZRpR@@w&}Z6ImlSnL`wlz`x4v!XARB?VI zPHqxY4j=xAR&<`NXs_R`WPL{?(rjcdj&J&?udZt$TM~ zT=jTi{)AnrRVEeCRyEredvbc`^U{)N9cnx`#pqTUUS9n87|ZdTw`e-oc{JuL;jkap zpXK&^;No^ODc~T{CNlQ(kA3AKfEdAE#XZT7WN$tAf4{cQ2!RgIGHCIir%P{rtY z_B)lh`yB4m26a_pJ!c2|uf9zAOLD||?Vp{|_m(jhX)WgdmBX`7x7_Uk2pVw3OMY93 z>tz2rV=LtH|85K1`=36567STToHPrXW#2qKePj%8kbZ2-_@sPS{*oB1^?0P>rKljl zhc9#>-?lESF;O*CPkbiaC9$XDcdf>d(VTy^STI=n-Jnzk6*WWI^(FgkdQ*mLw}i?{g$0f8cht^@2R;hNDlQ8;ZbIm4 z{53p+SDCX+e@A=$!6p&n?4od5A(dLr((T-OJ$46?HofX|=2aN`gJ<=jIFz~7dB<1A zO?I7u)8yZbwsq7vs$;_(FoL8pppM!0JCJFwqCo{s8jROLn;JdI?7tIs@Ah=W*9qamc`AVoOg%qWoE~AEtWO6Zf@e8d{5m%Ph2IM$)2;h z!t9E0S{#dtN$rC2QD5BnG2;(|Xc{K`A**RmbMdwVwU>cy1%Itwsxtm-LF6T(Z8G(mG>{$PwmUsNDejq zBB&HsBgV(B2ccW87Y46r=JS8OH$=Li>lpZAkb^56oX?Wc4As-%%6YqZ_RQv zT~<{vO@hbzf1#nickPd-9s6reo%>DRenJSi{V>>mJ1{`$Pj%XM$!;UhDaT_ZqVCbd z_o^TqJMsCHIIB@xU)-2&iDZAA2hCVlGYBu`#!us5ydGpGGP&;~$>K3=#2s)L0XEw? zr}*7^7sUsnK@WUo%{pd=e>7AsYk1V+B4%E$>sPt#ZeOiSBplSz+Zx*dcx@O)(Twh% zi((hN&5iFhx!G907tB-Ul#m9fgPRY}6PHWzbQTpn0TAf)h%sjtudEU+vLT1qPA_d# z_pr_K-|x(8W;%0g5v*(H#I`RgU1NlU?){G<4fZEzY+YBF*~@Jf9J=bnuSlsPkx{3t zz(cKV^`BLnOh*!um0Xf*ZLWA{L3w)C1wB?+q~BZu-&)?*@wb7A42zsLwHzMe^&2Y) zbLLtRTjuowM?=srjVVX?C(8{@M=1xjx4o5&@R#-z4vHg@tYwjg7mx81xL1nz_DVrG zp~X>cM1^u)aF58Sl~$Lf@sGJOR@PBfOZih3MZV5@5bsy6=2Qtb^`lz{htytr(bVI* z5iFrEc5T-eZ>GhUZ|#;1I!{&`{i^o&{!V=7B-x=4uw=tiuBZ)}`#a1&685&2wy2GU zWfmjUK>XMB6LRD(A%d~G_a>tnuUz(hFk#A{l9%$DKYFoZXM>tI?1Qr`OE2XPH$I{Q z{&HrRuULX~$aUuyEpuEa zBpmqH1cF`D_glTV$(+Qs0QB;-_3TPk*r69&+FT$)mL%9pi<9Rezf9y-H@u8X1=g2g z8+o?;?=`=Ut`_UCEpAE_6~@ow2Z-5tW?u^Pvbjja^L7M(&l5tf6E(N>l z@W>n6c%NHWY$xkw9m93kWs$R^g2{iYXGd_u@wrsywVC2sx(aN)^1trX|Az(0_ed_X za;VWC(BevzEkL|lt^F#zT+*Y3s(ohLE&yU>i0;vb?*?95Xc@t?I=Amwi7HkJgt=PM z*hE~_{+yy5(Qz_iO<4tfQ)@{6dcK0XmR#X^h66~4(4~SHwGgT+Xm z82v4LwKg7ny0T@re(t*6GeOBH5mvK*60;dd#kg+8;oUWUQjufuPr{I6%!n;fo{Y+% z9^H)0*1Ow6`8xn~4(|jYZLRTwjo$};>YMc-NYwYV9qqRH*T_(lsda+nr2Vgdm(tAQ zW=DH?ac^}(g7ji--~Gga&_l~F5SqkK`mrMo6}#lNQlWQ9y-P~-3jh-Ta~>=5k~V2H z8pt1ivN{!;iKsQ2f9byeH$$pz{RI-83S2T5(Mu|m0M;x6{d|?tXZM+7#Z$kYm9KvO z?(7X}Tror%RR79e*mxvT;(L%w9g@Yvbg=8xReu;Q{_K>ckbUlq3!+ zVELNVrFX2Ak=@>f^PRv^PhJs%4T&xT2mBN1BEA=I;cWWX#1#ULR_)bQZTwxjwlJ~< zUUIi@HtA?5$TXT~OJ$4XZjOkRh83!V$I$dEm3fyfwts%-@3AR}#>S~gpDmpO@`Iz) z8yF-i9GZ~Ye%3+n{_oPhsb$Yg)@%_^n%a3!z5%V^Ei@tE?v{8#TPf3GOFgj|0xOM* zgMGpX{#+pePvOK9UpQ=|6Ru7GvuD}c@kV%*KRCT!~`2SQP7 z0~UdY3ocJ=RfXfCA`yk9DrC%8MBBkU8x-c{Vd^>vY2$9K3rVdMdw0P86 zXJLhdq8i*`@u|tj!xJh4E#6LLr_JywEyfD1*m%N}&zCf1w=)_yURA%Yx%*6Oer?qr zZy&cHe}Zj7f~j}25*wE+3Zl!RZv_|Rf!!N5$#4LCZ+WsVtpB&2>n|?kMW}0mZDz6k zU%?5jJ@63N*zrT{w&{@eDeXh~|97qJ|G)DUC&w>5{Jz~_rSh|^&z!d1q1Z;O0c!{R zd2f*9HsbDP2KPIwe~^pnnbHvbJ9~D2_lNykW!t$I->Z-&v2=m6hZEAS2V%dq=MJ*= z`7=M9YWu5{$1l3R4OKrBJWBg@UheifI*JC@8c{R#ICgJ~YaJSIVqYJb7_+bM6B6FD zPgCp<$NJi}r<`^A;b>V7HF*ygng8K_$}B%H&st6jzFl*UUcZiRVj14o?g&Jk*70qd zEnzQPtHc~M@c8)Le*f)yxovQkwqD{W{Yh_daw^^3+Vp&+%hpn^t7Elu&DY!AZ4g)| z3G5}VR4S+DfFPpCo&=*HStjfWs}<)hnqWz7Wh+!|rt&zFZAH{2Be-(FYe>AbQ6cr` zty&K#br32Gr}nD|);uC>F;?Vgh6Z#{H~|fuxqO!CFp(jFmk@NA7cHd|O^9Zz7UZ16 z2vOWkv{Fj2YVRJz2qdg5u2-M>Jiw*0)JGaQi3Z668lg$4_-u=N$&U{w`YC$tH?eCa zGA8pZ>4HNE(CEQaXduX{3qM9sEFp$%ytr;O>0R zUZbG?{Avv$3Wc)n;bU>6$XHxFI@YN~@DjD`cN{#a2xT=+JQ+#Y_XbMMead9EEmQgd z#rkB6x0=Cx>}4WH;HbHyBv;8?af88KBrt_^2b{WB3V&780`D%qF z9zu}|SfVg>aneZKQ(dgD+=q-`Dq;B*a%3p5d{O)7`{jgu+x9R2djrUcBr$p=^MZ15 ztrG<04oT{1lwS`^t3V2gO;FMR<6HhPMT#`6O-; z%!uMW!Sx{vqnr@5t60e&!s~*{schsuQ4)t;Q_M%BRfwGTidQ3mp9mr*${`EEw&fcD zTVwWv6)l>HDHIRIa0)ESkk~GNucC(I%&UYW1A93cz681L8?(D z_DqV-ldrt-Ap=KHe=e6i-XKIcx?37gXUi<82110*;vIBZi^;eu8_*59gB5jby=VuF zp_Z?5#^ItEzVfeG6MnC38^Hhlyqi>Xw=%0r8jhPAe5RP-lI(DY2g>{88%Dfy5r~|< zZwyx^RRCFk!c*r**1`mN^w%^m9jC16EU&GWxvcte36|L~$e3ikE6BZZwE3hNHy002 zgC2k|xu?gS|E3WI$$B7Zw8~}2EpCl`=lcTJZd-Fp`8zgM%RW+G(YHW^ghUtB)>Zd9 zXb#Okwt*6crg(^yOpV0}&#QRFg3B+rK!P1COGBtA(Tx+AYBNN`{Z`ewTHZK%;O;rf z9V3d&qVk~XZqELTn-%w50%>%QWg%<=Wi!kqvsg=LxZEfXeq@`j`hlPbRC@mOJ6<*K z)9~P(%$96oA%qB;V3jbF`}Ca?G`W;e9P?=a3d>}0_dkQ_M?|G6p-(wY_$AO5O`Gs( z;95o#C4(D4o938#BnFnEc{ukL#<*~rLfTog=jKFSdMMu#Nsx0NoJ zhS5*%fXCzGn+&H3Rl!r>a`~eOij!BiNyv{=A0ZT_f$T_sAjQ8IhhqeE(}BdS8b}RE z;H*0}8u)|CjJ0e*+w2Q2k$W5gWoc2zFfstMsz@I6cgsxTQ3pL3r}h4*AfuvW|I`CoPAU{xDA^q8h$B(s234!XU}e+#m8rtII!y4Wrg~ zgz1F-=+JadgB2z`RTcM@7g`stVpQ*{@c}|8FVf4@U&Nz4h3ZeO%qu*L>K_WX%K89< za19)`?p+Bb2>b%-z_xuWU1O{cqcR?#WfsCMR z1#x1dXa=j+3Fq{$(NZPoh8x?E@L^ryY)8U~dKKWvxPC>RMMShuFh#A)p<_E~88Hcw z{+@uGH4wAH63hn~V7TuLor74C(*^eza`g(cc;d-1(QuY77rO*hhZu1wuwP#!^{Lry znm9*|#!TXWacj5U-VS%g0z%V+ZcOEx%GMud=!&djxC$?Tirbud5aK^u`1$FJBs*4( zem0nIpTJPJg32OukkyP10F;AeE{1V!P&R;)ftwrCc0h#bbZC7>MV7I z1m16khFBHB>?c6Io}*(~+t-H$*LQY1#j9KO~XG%0TEIy9Mlrh8koPIZw{b|eKe zll}?GGlk=L#e6l5n#PB$F3m8ZIe2L~PR!S_bqeGo1BMdVKy`LsC#< zf%vwM_e0cS%A^8Lf9(Y!!ssgw=RymV*RB&6LNDNy4hX~1$ScPN&c|`WIW2-};4N;q zW1U#(uUT?3no(S+Qj+X%qOG#1&ugMlCu>u*0~;!9qhAMoo3#^#WU}ZE?kGJ(p^DU6 zRrF&z*7qU@Sv;Q>9dyT1uJ9$MHMd=Q*Utg+9;qXfi;F#%m&|Zj0$9pgK~ajj9Ftp8 z_B--+p!0LckVt5qV%Fzb&v7$mNlo(`{EDSNbMeX)3Lu(uF>}?cb_8#Vj&TifA}2 z+#pGGi zh#=I!>U6k5ytZldPlb1ewjA?kofL+=4AJL>--6K+02zzl+NmJL{8T|06XNoIxL~q8 zkdSG&>Wh+9L9_v?ZNNiK2t72N_Y1Q-Lvh>)-DgExmn48v+ba_*(J$6z)$)kn79O3S zkKgN^{X3C~?m|qCiGE2Fqb06geSt|H5}AW}o}S#iD7lAx*%DWnhBK&48ZQ4I8f*`k zPM`t7FT3&`z!$VUR@2hi1sH8~=dBC%4w%_9LH@m866ARXjKWB{?8&{NyPi1wem>v5 zVB|cm>~ld5>Y?VPiiqMJ^)RkvvpT663+@#ON%bBwl_EVl0EVIsu47b>?Dc4I`g^e+5uQKUMD zvTcZ4qJip^eMNV#6f$Y*RX)@=4xYI#^(t&5P5pSWCE*qBYh2vjOML$VpPV+@N ze;T1Kf?P2jRFw2NhDt)ELSs8dL?U?KBUi0l1>GAv7^wgWTPlK()X=Az5(fz_jee6F zZr&m*^rbys3#)!q_wHS1RhSEgrZb*e1>l+1ryA4#PdKOjF)|9vuDcHHBd9O|TvHq` zdn|FyTV@?1)+RADpe&}j3|7XA2u3E7N!JE+c&-3KkGDj(cJ!|;Hwn+@5FL`kJ`XwX zU=`jQtJjHEK%CHkTmkOg4o}hBE6&e1*Eh~;kgE7X^z8leO9ujc0ZB#wgoH}C|7-(a z5ENHq+Y1SAJM0J5r>c3*xu1#S!lj7ZIPBGnR0PZ;4cwqOp@0s>RRY;w!Tg=YE>W;B&UB?GMe5 zV=*ir5|zQA*DL=KN%QX;$H4Oad47lJ14#j4MbecRGCddcLxDz7T|wWNz=@f=JB~jv zJ&VT_L;jc#P8A$T!LziH2W^j@SmMkDpXgNJ$``y!94LeaRiPHav#CERnqGKAN!;(V z`>p`B1ye5XfSx?xMuWDbe?9u7W9bbczIHZ_V!%R<=%>xH4J^SH7 zh}bSct8}Q6BV`a(XY((%QyS)q-ae6wlWGi}A^lX?P1sU$#!6vnT|P`f^Fw+yr@%;O ziC^ziuN<*`$=d-lzOHC_(8$UtD+iTu-|!`#uyR~n{5xoRVV`QIRxTYN-y4YoD1Ef3 z7he?2+ru${SpKL5BOa%F-ETxm|Js;L!12+xDS-cg*9-_i)SsMPToW)w5kZpBOQH4W zip(PJYw$4LQ6MS=3ren9RnbzT3f1O2sYx$fd{v>^i{~C;Bwkpio|}q^F51s{wlebT z9LJ|))!7w+L-GL+U*HHe+r;roP{d7FN&GyV^mCNTCrwdFj33D(vZ@qOn;ZTqg3jmk z#OWq)9qOP7vZ%ws((k9)+ZG4BWR?RS43P5W10(lUxBx_%(O9kR2sls(gZEu~ITc5B1I!SDZT5E|gOGjyD80KKniZTv+xxSp#qZ$q*;ys$@8h{s!iR+JE# z#%mdXi20T6{)}4kQDrg;ZpQJU&eVvdSJ3U~s48dUsRhytXEaWnhcmmLPnYEE4NCYX zjE~dmFg8{DJo4}D6ALaX=9^f#h8>ga_*mDwt- zo~`6Hak&Ugm&imAq&tO~?jLT9xF-{4b~Lo24=>jyp{29Vgn$<U z?Xf)xIk}0E5he$@XoPLNQeGW&%BSknXr0skyEQ>EIUL0)UTK(Ax)tJ5F-su1C|EAr zW3MDCCdTn zzsN_!Rg+3J(Qr&lN$T>P;P-vw&$cMUAFXYZQ&DnP131cpJ1Ilc^r$EX74vX3@`H-1 zN+K_6q5<4%!T@@9$)`nnzJY!tqRZC|i~>%3EBTQr4QK|?`tQw)sHmO$@qJu_F;u$` z`#I(|HgwrJS=dCMsA_zzp*E&{dXg>2tm6Qo8v&zlv|o>DU~|;m{uRG}aB#4ZZrwP! zIvdTGu2!PL#m6UCqqzeZ3m2&~|Ign$IXQWu)rG};BDiD@mq#h2x%ROtvu^i1 zCLCtj7j(Hqg%N;6gC`-g+DZ6~DgZZn6rkAyqyxtNiL7mfkK$5wizXGiW2LWW_i*cme~_4j$*S` z!NdmMlujq8b^9gf`eH*8PaS@J!~K^36CuO{DiOYZp2wWcvzLDov=w~r$2AICbzCBL z&DjIjqE!?g!5mKmUo>^}H#gr<6;^KUbu`tsJI2t3#$Mc1z1{SH!~%|;e`cBCgzh)H zi7PH=6sVnNc<+MxEtEGf%lXde-P=$b$8x?X$|>ZLkr1}1$T z7hSe7yl#*4blLF-xm4?VMuROiz9ehuYJ+3cvi&aP>~ait1OV9@DdrT}d_*saa=~P7 zU0sG}N6fy5)>E1jMOqZAyO!?ktn|nqx}u%yLxF`Rd#c^tptl7wE6wI)hU|qJ%I;g? zgK24EBe&LeyQghu@*V+6Nv5|FHv~=qfIUgLK&;(^v} z?M|)`>i#sTz;tVq`+K!#NR4B9nFrAQaFHlV=u1Td6h8>;$uo>h+!H#y?2Vj_b0Sw^ z38R0vbiEm1LN1psw_YTyoYrG39nx6UWi+~A&zF-C7^%}abDHs>FIaCLWu7XTgqM#a&2 zO{-S2*K)TuaRuCGYVti$HVM>NZZow|Pxya%=WxDZSRJw~?!eRLYWK4cVn||C&9qCy zmD*RWp|jodCc9WyYx{Tw-O43=5~3+%+Az8uD?W5QO1_=JxahU7Kb|ErV(@%p;IMU2 z20{`zT^l<;2ZaKH1P@m{*SGJ^f$hhfm6fH*YPeC;T>tC9LSkg3;l>x4(M6p(DJ&mk zj0KDaz|iU~=2r8%!c^*OEtaaw^FVBF9ub)u&B95GEeI4(0Z8x{zXP$2qRc!z-Xk3^ zI`LqO-J|3S7VDQeovsK0jQs_#M}7A3@$;OQtCye3UUo+A?y2*!T`K8)E8f$TDp`U( zfJO6Y%#rKw<@vFZs`d}5n9V+C6o7Ug=rMcsqxct-2Hnl47R%0yHiMCbCr2O*l|T2c z9$|}JbMlz$n}4hB?r(`y^u*EpZoD1~~fd=FV{)@ve}yehS!)|Tn{i2OwxI4e=j+>`|`DBx8^*6U_v z*z)(r$S31iUMR5dz%A4p^IcD-|9a-T#>bjgqV`#Oy<-6C*Ec|Ku-ai;USp(;*UF`} zwYB+hfDCxHUd=E69ytd-m3@9sMO9K)5C|{*1rUngi$A7K0F*?94h>_QX$Ba5ljF-4 zv0t!`eMi#eFd*5Wlqv3!uw6y58`I(SFh%T_WK`2#Gp}E;Xp@fs$Ix9qkgL`~JM_0( zo*x0?_=b|fUp#|{;V%o-hCe-*Gwhbe00VC*@Ival>bp?@o=Vp@Z>vom1J+LMPP<;j zPdn}?8||`oZUGgS37=E(M*Fr9&xS2-?`S%^F*B4Rf(LJZrik-8)^#Sw1o=7bCu(XC zatc?*pRzSK#*ghi>rXcZs;oN;^_FzR?7ClF?LuG`y*)B-ehB=rSrZ*^>UtK)6udwq zHaGLQjt@opxwB_T`Lg+wT<|`9nk#zv=>(vmnNN)3yQdQyJVD-Iw|^j~*QB^2_PZR+ zl<=cm#}xdwA*a%LAg{6237li&_yLJx&vy-CY2Om~Gx>wQnZP`04u4=Rg)85OtKnJ}&_l z0!aRxd@kwcIjf^3z&Jr>E)*?lw^J3T)y3k%jGsOV96lhY4Dy| zp0uK$T!3q%P z>tSnJ>3zOi9RzF+Mnc}w%~T|=# z>o2Tr_Df?aekbz_ZEhSz@OY~RX?uI@rZrE@yHzi2x8v1F6}7$ny#-P6@wf8^6D}gI z)pxhcEhlq2%^nk!;#X;H&3D;eILI0r8gcN-J0)wbl!<*nD5A2G{l8h}S5i18&xd;4 zc}*7vVoO9ocQZX2ZGR%$yt*XlHGfR>q!w$n`<|dfLbb;T5n4zn6C#2D^DSc}&D#ly z7v%NFe<-8bLKD9aK-xNUbIk796BPodX5YT0Iw}MCM3y<0(?HV0uJ+e1hO?W?<|7jF z(DegmyW_p-I|{*9vkP|tz|cb`7t<*S9z?WwJQLtQwFc_4D|Ap!&d+}| zH)kw@Gpd=ZT&4Kkyj)HxO&G%OS5jUmg;frYPF~wE1ml05N<9O({>Om$E>ZFLMJb1O zJgi9CVExrVA$zHu2wRs`1AucK0Y`y5sc;6lEE94O9}~c+Ew7ZE(=tcjU{8ZKVeuMWOPma_u+DK%Xrm@BUN8DLI zwe_`MyJ(S8+}+(>io2FzA-KD{ySqD-;tg8dr4Sqn6f32)xD|JO&*z!>{tfR8KQIA8 zPIC6%_rCX9*IGIXycONp^$C7FZGMCm_->b$xL$1gIj;nqLZqsGC(@i+R6ajoplBbt6XA3`}<7YJ{zH_ zT>XvvksBCOvz%si70t~VLdpBbQ_U?cfR6i>XhJeRWk{tn(Kox!Ko?x3 zh`#ppi~-=Bj-&eSj-B1Lj&s-%Fk;F^lX(-uxfcIV3n0>z*ARTos;a8`^|dpoTtr^6 z|z(D|>;AW!7OhzutA&QxBrr#F6KW7`r3$`C|XPtWh6rt0p& z<<;lceT~MvNBO|Tg%)1{e|@(%>FZO-LkX%?vP?{JV}~Jw8tCEi0Vt>We~{`p_wHDW zh=}I)`lbc;MF=VTZKsV^FWUPSE7bf5+e1Z0My}Roi7cgwr^y8Uum=XONN!0F^}WQVN~M>^yr*;2dAet0M+H4 z3sJ>KCM-la=nlU%r}6e6rP#2^>-9z|U4CF6Fpcu^kz&I_FM3pAY-T5$WPoT}Ro&Uj z)iu?;RFQ~aY%k%5y&8aanx%X`3i_1WZ-?Uy%03w{uRwvba77kRSmlL$@32M+D?Bp#b3wuXM_ zzg$T?2~X2iR`sX+fB=ctV5l}&Uw;tZE&ZblpCU-@^$(Xcb9Rm{%2R0dYI!QF>o*L+ zv!soCBjo5&#re?tEcD}mbLMa=ORqXrV`k+jc-9?}py%g8VZo%<>>nf?Q&aQHf>Th1 zlnct&g^*1jpm@2ndEE+`_33}bayz8PlGT(Y8&zaeFcBU4hAA<%RA+GiZ{yzS<-uTs z!Q>eDkD*8#xB5m#n~Qo?xrK$>Ls9y`t-zEsNrbT0?xKJq)jLN;*w*r{*`7}iRi1R$ znsZZ$(FDYXCuwh9#)O}M5|4-Gr%Wyk+?Rk4V`K#BJ-NuRmWCK?^9ouh(m$2F_DTVq z2t82r2KC-`zOh5ac2-DywDbsDRXsIk~j^KJ%qsxkS;RmeC)BZ(K zdHNJDgYACz`wQBv=^wiL!UxiavE?1=JFR2wuQOGg6A;7FhtEkqd?-RJRY>QH%ZL?< z8{dJitW@{dK7;nWJRG4=6O$d6L7}87s!iX+(s5?BBBh(Y_Jr^G8FmLfc0Hvs(vKJ> z-zPNp+zp8bU)*W2)oI(pq8;j2qtoN5&WgZ&>4l;`$p~*T&wjlS3J2W4t4vyDrURuE z(A9)EnKtE3b~g3BVahV>ka2N2ec1f86P#7tp}fQu*2X~xoK=N$(Ur_LH#QF3-3eWy zqoWuW+Sh2iL%J){k51(yDk|t-_ETPBH=fsB&K~<;AH`mVaf#~ApWkfwIBzk<$8Hj# z1Lpk1P)MD8tFDD#>(u5vj(kMxiSbQD>gx^Vv&BirmKIPm0{BNQ$90jJ^D-+1jtXfe zN++C6zKXKuj0D0xBC;{w{>A~IE}pmq3d1)V;`el~nj<5YW@XAjxEY zS!)tOZxd8l0o_|uPs`Bu9bMILqQB#e#g@L7;mYe@%>qL&4oMsw@>f?A95;9lwj(n~ zfjtJSOd>F{|7ofHtcMKX^PCJJc_06Zx_~bZwx;~BPH)XIlQDbS*wG>zVnRt?L{AZX zNA2Gw^5)yYLe+Nyb&aA*@bTtQ6uPRaa|N;7@kW2iUP(xC_eoa*z#mRF>h^Zqog(h) z4j?8WF}Jmi6;eM7szM@^!v-1k$|5l%(SDOD6!u88P%yFBlK%#=Lc*5KT%M3kLMuLP z>gr0IL%k%lsnH|!yB?biJVC$Z6~5DXIeUHbSUQ9PACK&GrhV^(a)oMpyzP(tANe|o z--kua0P+ctUNJE5C;${xX=!c(&O|$~S>Q#9KMUup$$j7eVtZsNyyLSL7q81}_!h4) zuP)~=T^d7Pg9ThVqb)|0HS2%m6<GD^SWoz6ti7W6YEk{jHJ+f`i+>@Y~(BKG>fE zY)}ILU;IO3xJ&S5!GDlY3I7W_$1g^eJynXHQ-_CWK>LIWXpors`Q@26jR9D);yt%X z_V(|Ki&-PHB#cRWL2rv zne_DBYb2`W(mv8@GwLq-T@2Uvw9_!ZygYk#-+YDnj+-|idGUe-STFeIz#DPBK3-nu z!%e2lQaSvS%HY(_`P+Z`5p&+q4G{trwSgckc;I_HV4000k-RF`< zvF4niE}w1tC%V6XxZ7$mD&%oO=29r6RHJR~ZykMq@3*P#VSo5eievWI6TBv``ROLl zo{hC)i?yFsR8*84j+5_m67H|Q+xIuW{TP8AKFU0%aNsuoVJibI=|d-%=;+lHo6St2 z)xr{n=XEv_#p*y(x65Wsip1bZC#v<{F4$OqXQgRtJ3$Vo&hKDAYH4W+*zA+p%obUU zdM(ebFB}n+YrJM!H!GD9yZ!k?oj=VmISH+;(^>j}2owu}x7`~?gsYr6lTW)YFAO0U zj3Gm(&%aN(`S@g8A)^qrPd#l&%@}WfP(BR;U!0FrKkrt#2IjN~s|79O0Y>qWL;IKc z9xbo@f!qD#{ZF(dv|~}Rfo}tDf2(t6Zi{rS3N>X-lSY5k=u|l*91V7to%hD zS9pRka0>)^czywgeh0^g7M7NYadidf9_dLIxQXvv%B#8)=;F>0M*jSHLryMNevzBI zG69eQf%@CZF)$GTBhW-zx!Q&vd7qdAe>xZjCy?Uu8EBf=*n~N>y8!Q)C<;Q!OBmeE zFHdw@T2dnNby+;^={#AaKtBw%*k6dEErN|&R8 zR>S|9;I3C0`UG_1O3oHJL#Q*{;OWbuUAca?Wj|b>hVfX&7S@+b{(UplB;v-!fdBi& z;mQ+VIOq_AW5&qRu1UH~UjaF~*@p9D0}NOrhFD`Tn}pgYOkdx8`-Y%8TWDpyOV(v< z5$uQ2?-G0dSE|xDAd8n(N5FYq8f>uneKMwL)-wU#~b4wl>@mpHT2jlX5EiLK1 zC!SGd|Gu~`V^RXJsYY#=_}7i(Ds5(X`a6`HehdPDi?^7)!w{=13{v?H=RNi0KJUWI zJ?q?p0-zHP^y?+e$++zJpT`s?E#^KgU;Ez zHnC;76(jg0X$GE2$suGOL&xvh~?>;yy`lGvPnmRW))iDIyesenq(QXgh1yik!uPNL5zGq<0^o` z-VAPMvpcRdh9%Fa`*#K8=KcZzyIkEaU18Rl0O@EbN$}TLWfS+qTjVo@lDWC0#1x>5 zvXQcP5A5o`FE6K5i2(&MF)3-;N4E6Yz10r83{t3o)90!NN)05%3IG6jS_y5ARHyCg zdd&OP74iGUIhDXnWfoyKX|wt7ac+ib~d)nS27{^~e_NWabt{bZ=1lt6JAbnHi<`vrh&+62)vSM-G28p9pQew{;|AC9~yW36$|_nsqx&1%JcVr0b9%&461 zR<$R$h#CYZ@W3CTe$mB6kuvtB3;SFwn+b}_#8L@U(#p&t!pAy@7}TmoUGPzsxfvEOZlAo41*m_xx6wUG)FNrCmOBWcVA?|$&>GELO)Z!HWbnDvjo%nKn>y8UUfpV;HF3&jHBv*@C)y`-&aJgJ1h}P2 zrrL#C*=BWvNa+u|Ly4sweZO=?=LAw9%->?F$*YK|?zMVy#+N=E& zQd2*xq`ojI>5Z+a16l;;QYV7}`{QMOH z$duGVOeD-WVx%nU{_f5wz88tKS_ z%_NLUciMxWJ?;dcsS!wj8x}@sM>U#WN0wK*JOoE(jP+=LL(0{7*)+<{5lOCAcJf zf`kpLHLJH1%fpTlRbQC@wTBBYrxIEl0z}yI{riVIqq&-qr-ZMZ5$g z`_`_>VL|oRh08#+D6$=Qde)l530q_-plQQ{fbb0PL9g8)Xa|Z-c(z5GemF(+6H1pcjJvc)eO*HgQitfcJUs0E|L-96_-sY7V8c^$@eC@D| zYelXQ`&_Mr6X6+xJ$IE#C;PN6u?&o6E-U=AJf^ECUBxbPSo$8v$szc>jzOvAg$cFOk zv*~@le_ai@r0Pr-?Z3>(JM9&Dko74e4JvhupnD%4qnMT|t3;-}Tm9&+6j) zFE_Wy&DNTB>2>AEYnTH2cgR0-7vB%qzl$&e#6;u?m1D_jXcrje59N68D=`1Fk= z<@mPD+~C9}Dtv+ZvSXz%Dk>g$Cw>qMl`AoB)@O6CS|w#Onusbf9}09uOp78(9A(gZ z3~8o!1b8%xeAvc++|jogV|7nO^|0!bIq^V-EMC`F!0aHri1qIaW3MDeRR zW#BfJ=C)vRr(Wr;+HvsRxex|gt;3O&Lqt}5{Y;1F=cqAR@UO^rhg;`N5MO(X=~h&> z05UV8rWmU3YfvtiTYm)!Wc6!V9u-P;Bz~s$)s+)6btCL^9ram|PXhr7NrC>xVp0*(*iHFQ4n@V1wKk{EKvrpbV9Cf=IxNeURT8Z{^!vb!5vJ%6 z9nv(rk+UHyCNmzSTjZ7`Db}Icg^Z}WA_ua(6pa-QgTWxLsMG_2zLn>Ye*GhqT2~&n zL_S45^*OLYx|jyGeNrk#nt)LJ@v($1JZ%?>%qJxmYN+C_bcmN* z@BgaSGYII#c7!M3_t6@|OX5Hb#g(B@>MV{4zBVJKH#?%VnF7AP+75%-jBbp2@08JM zv72rNKVgTa)YpN$0v(JC_g7IHzNGrF{>xf>t2rrS2Uiiu$mho29p#DI35C4hdas}6 zvDiNn&nopKTaVn#eImSh5w$pb*tEzR1a^f6+x%Q4NPU^81GlQ94J704lCr6!)=(@Z15q@et+qy6kP+QB zCbGIj7AMWw6_@+xn9?LJp-ml} z!n^e!f81e957o}9`VI~o&}UG_GZe{todQ*SToGlL5#Bthzy8r{Q8tiv5OUd3p#FQA zvVSRAQ1tGZD|}6O<6q&{G7|suz~jp4Qo$Ebe;vYQ#hV6^y}C91U)#3^zrR1eJl}ZV zdr2E%6m$uB&6A?-}!Olpjjz0 zt6t2&(0ZB1(COwU#rZ09?X;T205tUP_vXpZ1@opMousyU-|i!D_eF3nf69|rV9aUE z^N82l=^O7lyE*}p(t3j1B*lk+CpS56N!JgMBi6M#u8$e{Hw+exgQG}F>=%zH(u!<2 z)E~-0vR&}HRFT8rN2rEt#980VX{-HO-^Q~GedO=iPG_Ij?#|`4^^Irtx&gE>0{DbC z)Ywa(u~x=t-e88sqQ+sLjJXq;)ybi7>C#5ZIz*fXV9B9SV=WnJq5M^33qKn12w#gC zFjtLi%0^McDu+|507V-l5+{s+!;*yQK{T0k?=S@B%X>Qd$&lpGxriD+eHncs>HBuO zcGr^I5e3HvzExw6+6$27Hqo3nuY)^CUidke`xE@N>8Ztk2S>nIXoWQHJ7fC>@Jb8B z3hI*I9pnpVN6lvt{UxxH|9FI8fdQiP+}?^VS2(4$wE#|WY&<>jW-qa%0aqp@q4&Vj zulJ3jDESCp;HiADz~8B*QIr)UFR-OI1H$K;G$Cy_b$*4d zrgd@-09swlLxuX{kVzUbGK(fG-2qqih;My7w%Y(a@Jo@aPVO_Rm|W9G$P&wfJ|UT*HeJYJhz<6K&lz}i^UO3hH&Jg@;vdXx8UBZ`V6n$OP(|8QncVhvk( zJFdzuD|R*8@DzmqE{!^4yb-8WDg3svK{eV=@QI&o7vqEY)58Kd&!Bv{Hp#ty3l<+X zWbBf-v)yZC#Y?IT1tQHvsB68QWS=rV4#3^G9(&q$*dLHYoza7dFoYZpx@FFc_>o> z2nmhOIvkO%4CL5Hj4q{3IPj5~+{A8(^F%6ma$t027P{ojQ0X7{?DPy5-7y2{Xgs!c z+{l2Xu_hJvNer{2^F|*{ieV>1y$bH5vRP{8q}+U%G#C{e>H3r3CdBK3B(Iw56zBXx zS<$j~l2E!!t_TZAgu;!cE^V`Q8h?PtzXQLMC#`i&=+b6!l`>xXoaC)f5@|^fGX$(^ zox-e6^KL$vag$-xMNiPynvtKWR4BHNwp1DKKY~mXr4*=ZsHpQO1%Wb4Jba0SnI2TX z?Z*rI)QVdus2~jzw^ghtBuZMSu0>hQWq^cn6VM|<6qxW$owk{(>g+k7B2z4bst^C1 z|F)!(SYQ-ipe9L;9E6lHg%@;kY{@4HAmifV-ZCpyf!cpS7`OgKfVH-q{!a^_AX4O= zO{(#yX0Z&IzwvP}A~jY#^bqH!t)4c}({iI7aU{qWzq z{J#Zy@PnK*7w-Qp)i}Sj=ol_E5S`h6W&tZUCfc}fw?rD^{V!5FKXzOp;QB0*y5cy9 zPkmx6e=D7_rbVV~^eb*}e~{rp#2NmtT8dDeN%y8<=@}oI z(pfhZb`7rzR2HqS>-;Wv=MP&h9Tof>XJM!dDIn#B#Q{Nwt8SrQuqb{8cvbSbWZA^8 zj^IJ|BI0(z$f0jdaLq1Bw+#wVJzSr>o?%Jmri;W4N7W|$d@hvjIF2_#C%5999#!DW zQkSNMFDGB2kCt`84Vd_W690mrlN)C*D@V>Ybpo~BqZ-=-s;O90kBB;3N!TZp=|Bqf zk@(@;mH~)lZax{l7j9f{+!Yu&NHpv29T(Rnio6=|1+!31pcD*3D65C{5+)7Ma=H{y z5ajDb{{AGE`Qof8!$0VKZFt_)BDrqve|Y@1uDNj7YE;v{XalwO_pI|!@Q^oJ13MV4 zUw4TN51~aOh1D7)u5@`DVR)>kd{wqSd^lHkZh67dY{+eaHf+tyE|Xiu;i`qKRNv^Z zliI9P)!kH7Cxtk8@r(M23B>Yh4hz52>y03&uC#JjbKrKkDo}Z(wa>#+E2P&pR^W5| z$FjJgt0(crAnx~^O4~&b>jpHor0V9_d@-BfEhB4cf~n)Vz;pUzZ^Pk-x+XNR+^@~Z z%YE>RuXBLmQ}!c=#D#J|w@r@sza#CP-HD#RB2o~2(cfqhBTKMi+8lSC zt~UF5|E49|##(=lWda`RQc9WsjhwXP0U@|kWPi2`hsRhFRH!|!qw4OalESbZjrrhT zhAjWDjp=lI{%I!ok^I6;^$q+Mh9X27VbfT7H0kt_W2R+z@;c@<$69KWw3e}{O>Df2 z2R~^nRVnM@E|=hRO^ucmeNLBZe?eQdRo0enV!-=dhW;l+3DiTeELQD`PsR-L^nN|D#!K^C%+S;3%$>DTwx3k?;HD4fIiIm+$2|9#wj$ zM>CbLq|~l-)k|X6d#&|Zs$TB(wBH9B6sf)2tJ7QoAmdmG8$J0q?ozsEURGIK&u_6Z{KDF3gH!V8MtYEuS z2vnbOVg2dPZ^qfK7mpFDcaTsW=P)xQMOtj#(nP}kU~CAH59N>XQ?RjO`!-nr9YYh0 z(g672`y!3#@pN4}Ph9@)JglOL1bY+v_!sII(pf}W!7S~L;CAhz`rj3y;t1LM`+*(-9!F59)Ebk;Nqc^ zT`N-Nwte88171wCcF^$OYV|DN>VZ-yGe>>|v!b-Z&=S(&@nUXK); zt3P-?b4i-FjNB6|om&|yoN&tXBfYAT+yW79yZeG?G<*T&**_~7Q@ z3lv-G^cc3CxR?#d13e#$I@VUE7TOkmE32Nb1dB>t_AqFOB6X^A9n+65J|udN)g@S8 z$`^FzxwWUY;H&hpYmY+|dd~V{T!Rp5ue^db8dMXU`$gwC7ES8=vX;A+uD9Fdqe8(J zU>_C1sm0~T>LA5bX)3YPXdg^*Nj2-<$_DHBHh$?N0%xFnccuf73COHipi;oOAwa=f z3wB<|)!`h%2m;yQ@WXVJLB76UAZaY_vJ0@QHE?8O{gizxLR5!b|N4%ow`k){CF_uV zzY(WaB-V;3J^}x=)00MRhY-r&?N4}AA5Q`dg;kZ}ns6Mv4D-fhl%i6X?227djlFmb ze+4$Rq+b>O?2GPbNR%7S+KR01m!JOKeDQH}_h0UxjF?E%-;7v7?guYA32wq_5lJ74 z$fmxOsn*$tdtWzZ#q%d2I}|c^QRt9^uGiv)?sYOOda9aC`G#Z{C;Y&;aQOq5v7Sg4 zG>tf=wX8LaY|_3c+J-xWi@w>Q&zX9x3Hn+-i+p_Q=%2l6vzpX-S#(;Ta$&k&P28(G zERv*+m0#V9yBNXHbqSVS(T)emM4m}fZYe5)(5BS%-j^BSnc)o6tnXmI$6F?IwTdME zEC<`v_27K)ZLrY=QL}Qh&I024*_4A?8zo!e=dtyoRuSW|kF11UZGC9qip5Uym9F>8 zZY7IJMi%DNIiyERkVwx8>(fBYchfBv#bO*=DYl$gm3re_RZ1yfOgK5aI~}1IdTG)+WT%Oqci?;J z;drq~F)oxTmWg39lbtu%CRN{%59gai@MGiXX^@vWh<{DK)_we9|GvF;Bs$BT1WYb> zavwE7#He+S2e<>vV^8649jp z-<+eZ=db*tcnk>sqdRpQA=--?@W@x;P4#E0GXBe}w$q?F)Ow-1EyajmxbJncgSGB% z77coMS3#>nQ%vF@-oDh^&(p^kR*Up8j#Qhs?WFYutJPHJvTryK-@+?3lV{0$U_URW!(=CM!Xyz}Cvj-7JW zk7YoVO$vi#F5XShqRTwh(1=KqAClgjcAg@*Z zgKsQyJoK&?#vY)F0tdETdAUk_2!+DjZf9SUZxJHG~ElezB1@Jui$?p1^-rnp&11KG|Dr zR~h}ObkLGT^Zqz)17Xht&KXDR2ThiXLvUTxKy6J!Q8u;#lXN=Ki=^9K`}?kw1U z&*w^HQb3|{lJfskm1ZpY3E-dC@oVmHCw??O=JD8?v=}bhKRJD`^Y0h}>1)LK+zPua zlqhd7G$FRIce!+0cV#!9HtO_tbrc|!2C-$w4bc?u0m|=>$|4~iNHE#R9e9y>#Nt8p zcg680FE7}zNLyT> zm5v7b)RQ#@A1k!a=sb#u3T!lOcT^AdT{hRb`Q0j4@=Gze?+?YcBTjxd+oUPf_1diYMSV_t>-{f zmxl70OBO{*B+ISOnCB)YeLnBO)xoArCc56(%+oWoVhHEJGdoPJ;DB;PHB}idJnz7c zfl>b8-$6xZD}JUdtdhoHPw!fjl?Q1!`Q_^_ZEHuzK0}dbyf#bJTt1UKZg^6VM;%fP z9gHYbyY&;U>rbLOuiDk@{f;^~K{sD)`GgfjCNKwwCQHtErGXL>b0mtCeIp$ByXNq` zJKU_6WwZW3Cu22u3t@&+@LgHfMx;kXqhjVeCLL+94H+tKkzrZzqnk)nv(uSr^S67$}1>q90J6f5fKrNYi&ip ze;Y>vf?q|JESh(9k^%jVY!jnUBAU|ltk337|mYZdt z@whu%bKEB}U5-fEL?W?}E}W63&(|_P40wF^hCPuHNo%G112jp#j03hMgj^l}&lSU*JFo zs$_XjbKhW^3n1;X*P_;M=73(t+}=I@pJ>~{%6COz`>fAVI|vE85KHvZO&`GgE-yNn zfThS>6NxXjGqP*b?h69p*e6wmXPLr;-rzXo5dr>9%go{v3jfD0)F(WKdEa@)AM_l? zT?0dgV{LVqO?|8h7X!8l+|GsiY&-60)#i4Nj^2E_lER5+JybWdUTAP((r82!#O8O0 zR4VsmOK1Wg8e`PfD5=g6HNn*VT;HyKAl9g6V+0i#{m~^0W7fqvaC-}#L8R0Qk zr2P@;rgNZm9TBItEw6B={P`PC&B{Bc#Da3M3Lrt4{5_>VZlYUX^3o@-*f~wr&BD-Y zu{bpp-nt*kL~uOi2IyLH(_<|x*^VhG3uY3P3u3Av|yq0Qki9@3%++xzSH8>8OU zn|-+t6Lp4k@>3&|88(BtaLLwUj>+cT94*@p!5O_Tyeb}zDk4KXQtyJ{eswsOdN*~H zoKho$w2~qc#ge?@U%qgV;%8+=2HfE=y>#WysjNxDyEV$dl(fHQwQYBO@T5TURH`(O zgv4anvhm-#h_@({^xvs-QSA7`7}JO*M&Pw@m$}S{>Dl_=Exz47BQR^%e$c{8m?RSq zj3q1%NiKQWR(Se{**_b%#R$x#SiX2U=!QbC6cUfC8bI1zvJnf7VChEfH}TNU8MT%0 zhk+D(WCY?AnLR+qnwjvl8MT*}moI7lO9&_RJ-kgHA2x&g^X4OtgLG{YQ%?4vJ=yDW z>y{XOBg2qhcxH(-T0$fCkger$jHB9E+PAmDUYkNhTq3fc$IIaxvv-DQV%}4jI$FLn z36G2CD_<}z+=Dh^S80%M{rjc>Fi3RKN;R7*r)0TT6SV?%2rmmo{KC)AHOm_T(RMcF z%byrFV6x!I$?Fh+<@sn_%=I|^i?)bf|1xvybp{@VgVaTp+?{k zXfUbL11q}`s&Md?6A; z!yiM0v(s?5vyDWLpv_dadg$t2>GML@d)wgpaK&66s#eg}SXxz(w@Un;@J+kLN53rgR;4)za(#*nZnN!FaT4OIhsyJV9u{CBrH*59K4y;61%?2;N#~@HJIZ4 z@FD3mpq$sv{T?2WIiC;P&Y8)Ipr9lHS^^@w@{2+OsgDcwfp-pW3GZbhaV&Z50O8=- zhZN6=D!`?y4Q6;=q0P)jzbjT?*r7#=Ok+R+0rm|r^V~`*;HS?Rw**5V@w{(CFM?FJ zft5)_P2A)Y^;&qN>F2M_jmlDg{P+Ycg?&!mmH1!r?tjP9VL_=t?Ri(6Y6%iwl2z46 zZsro49vFBdPdbssquVVvy>dsSklZuCcatbOslN{lt2hqVZbdD5OcZ7IQs!e^OY!Qca%Yk>WkBvS$gaaLis5D zk%PlyXP(}A&zgBV$M2$sasPK?*tvrRU=C_*3JL8?>YbX+X4aV~{NRz@8HMEi@23io z&;%q$(`6|~w5qCUGQyg)c}P?ke)N@Y47iO@+~MXCfc-fm z67@c|yv(ixP+i=q@5PFP4;K(8Xlg4v45_XRq!bCG3r#$loX`7PI0x@tLnJCP>YIIzae4U!_%Xb52dtEt0rI0C(QB+6fnNyw;)|w zSnW&x3ysi@R{_F>fuLx=ivZ zr|y4;(Qd|9KN2gM<>V1$=ydPfvRi*4u|-LF)ncn=WEfGC+kp^WGCLUCAa+ zHO*7LsY83WKkzk%jZO6<8~#d%8*SbIt)Rr@Ai~>D-vgkU4iY;b#_jPs!w7!bDslb$ zi&(rlL?Y+|DUeA=m8E!b#oIqP6LW(jAFV1P0~k$Bo+mcSYN!FFIaZ!(J_f14N0w~v z3VOWkb<7WA8YPdNlSsC1Vdibh%Js`7fxaq;aDaW`{H9dKP%Pv|sEo{4&1>U!dN6^!K(ca`i z$WQw#6?{LB?cQkx%8TvHBPIc65bG+Tt0hh_N4ZeYAw2H_kTTz%_G^f52b3S@km2bS zU`SeGeKvtY$eD6+)3oq3SMnn4L^y>npp zYMT}Ab8l~qA6QV3*K|7k<`)z-p|38x~SljV|Gu&D*7iH{hF+nVckZ{C_aG*``}xzLn58A_AyDyK zpOf-lZc}S}V0M#KiW)|8!+G=(p`60p2oV@;;Qa3ddoULN_TY=o`0xzB&cDnmJmt`2 zX;^ejN8n$v{@0Bc>}mF+Mzgqt(_R$^2UZinqiAjIpU!LZo3=>(a*Xy7yxbHk8ibUjA_i^nT5FXY9OpIC7bpO(5jHj{zzk zr3`#rBm3Z;`7I_T)p(kSha5eQ(fHcp58WB1U84REGyD z#oL^Y7~iP`zPh~RD_4x2tYf<0Zwj}$tWPwXJdx#anpC#>k*^~Z_}vasjez2ky`}+r zyfhv#OOFAyN0*4Gkk2^|E$uhQ^}dYg$|Z1Yj((wushu5a6jhco?NjJ?Z79WgTETHS zR-r^de#z@qm8WNmmLbQ*Qmf{J|3fYjX+?8y61vUoMRUnhtjp_QyRhFA(H0;GZ)vcw zy+hmDTKmqhS!AIQ_c`^g_X%Bl?jDd_ZGKzdYe-7DvnTON{3y{}QVO+bX}?aL8R+z= zIyhdLx%VIh>{DM$8KW|@M@Gb8p?fM9D#FHr2Y@x`iKqYhws_}9jm4Cz>L1j>$$nq# zcb-0Vd&8m%2jFGp*|tVFyx2FN588%h5Nab;NjzAHgi39!*sx2jL^lB!SU)N^Unf$cBeYFZFe?~sfGEU$(cB1MU*Fpd>?!Yk^j~M zQEgf3+~UDW0GKT7KWE$VdUsA*8a5zMmPVoQHD!FfJ>4^TJqnrr@dFRDrM>y6G{*OE zLF4?;p@Ex+M_Qnuw9bkA`8fz+B=AZ70Yk{`0sdZm`+-*6sH^K+R#)GmL;KA*W)2z>KifCGBj6T-N@Fl~Ut@2x^%1spGhz z&Z-p9tO1Q*^4fvLP<+<&O=%Rd9T{yYq6BX0C0jA{E*t=Qp^`ejiT-V_{r&uWZbd_T z!D=3JZCoS6_V-esyH#{f&3Lx{bJAIw@1C^|mC&*xpim?t?S_rr(Sc?Duy%Ee0RCY* zLEdr8KbnS+a&7SD^tUR%$Nlc@oE+b~^IpIiZ?GmZRIS=+==NeEjVp)WCfA=z1P8cYG&l?~`9M7AgN^lm|03#K+M&dtx&i>+AB8 zNCWJgowuPT&n*3c2Rg6@;JCma1s_b|ef!g^U^8MTt&A16iepxM`q5(`qsSH7mb%#s9wzdxQ5A&#A{Cf-=qFZHUDLs^Q?qM zc6`7^gks{yv_U)1DvYN0Zp*7eR)P+|k!5FJI3Ayt0W-$SOR#)&%(+;KlRniZHBef%I>O!u(05A zJYWuqa}-Eunlu#i$qu;;c_Ouj;XhKWNtZUt5@nquNU`jcMY$jJdq$D3`7}0qW@Rr~ z2Wq6LKW0uKy*!27aU^&|kBVP6UN+C%VRhBM@2e8J{Y`Hi_*dum2ai115(NQ)yXWl< zRg#&dWn?AW@y~0j0s+997l8gc`Fi6*Oipa}T(1Tu|BJepupcmUsvoNIVw^Bkf7*^o zs7aKr6rjz5pSX0q+FRf#FlmwU0TzeLxYFjuia;s|Vj=i%7Jah=irX4ZzMMI?CKfCmObuN*t)yk=Q0HbAx0GfUMX<}=g9%(PZ!gSjKB1;SV&@_P z3Sd)r_mFWiKNRmjmXi}srmtMGJ4X6`fzrQWsw5N*ATKX30}4H*!jMxHqvJsiTot2t zG6Tu8fK29}466*$i$A_Tg}YBANZKw2T?Z9>+dmM2%$kg5VPR3>;4&y@1xUD!t{)+@0u+6UhmB8P%C8hWN5m+qBHa2qrZyk zw?dHo*4UWLC2`L_DR!UvPJq^AER>raIBgt)LA8((PNG6MATyj;HIno|M`!1Zcqg(Q z4peFbPl18(LzCZ3l6S$;pLG!O`T6)}w>{7w?z?WTAEJZKxP$|KvxdSZBx^NUV5qXr zG=u3{Ou$|0o-nsOljKC7I1XeMi_C;2qlwG_KAYWLxSg$&%&V8_4Woy}<+9_|cu=aM zF;9*4`0)amDTVS%tBx3howI#`N5E?*r^>N$)q3DD@&U?7;GzDxy^4W;D+{=exhz!r zfa2P)*;z^{_{0z8W&e)V&zYGS6~;thVJhmVq;O!D-;fxYD)jYqqsSBp%HXc3Ni*pq zwvooe4fzRlSko}cTGMjeqmu@JTi{DpmwQ60v47o&RSLtjBTN$Zw@sJ0O&|t$LfzNeK5A)Sc)~=YH!t+dVw(+D?x!u1z_SCh5bAJ# z!b<-A4;guR7Yzc%iZ-OfT)TEI4l)D!=p#ka1$3IF`18c)%D#26l?po>Q@^OfBefM2 z^-8}Lj28QOouUD%%rO;pUP(cjK%Or@agiwbW)tyKQ-M<~b1J9FHb4UtJz8q}Qg1Wy zUXPPoQc}6LL8a8l(*6_fq;8m5`fa#yRH0Q5cY$V=sb|xOu|u zlD>ea^QO^=ys17XetggSswBY7Wnuj(19$~3T9|hq|MeU4&90}*pq$fWS zaHF*KTEa|9OOF#e$u&Lw2Z1qMci@gyErm*6p0STtiUK$lNOq5Woa2gbEI4#KcFG5r zVc=`Nvb8wPoad>rdd(&Ai~s~T0R^X-qhrW$sqebDUqWr9euNy;{=uJ@_)O|q=BMWb z>?sa-d`3S$#hRD)-FQOIN`IqAZ`*{ywokc;*o_2AwXqS497I36v%Z7K~<$dh{0 zdD%3Y%ffKcB1;*xrMPUcQWBP-HK^{ob=*vxp4B7jiKi)cUKn7SHqc^b=M&7$*JDjIG&1Kg`KE`Ko|dtDoPRP^+Zp{h z>7TRkrhVe?HojrAqm`RkLZSal3exiyF<@@o`*kVZm$XhF?G`~#IgmwOUjB9N(z8|P zUosObx9)f)!=5O)Mf~V!;dm>he%|yCq8%NN?QWa=If3p}FuYlyWykx;DGT6ABmg{# zvwN&(#LnxElY~hk;>CtY>Ds=zaypDrjdh`qfCux+=i|u(L6zzR)G)26t1EZwoHpMA z>^G86eOvccM!M%_XSJ?HfZR+@gAg};B)6w0oLZ&V>}si%NioB5VfsGIYU5aII# zb=7@EPoY_@+r&FVHm5ztrHBaYR=<1S>oF4RUH1au1nB9-!y`QE2j|j&V4z38ijW@w zytZ@-R>A?hV*Tz3k;5dMM(txaVfU-`*Eo#D)mHcITnCf5>?-ht%7s zpQk_GM}Gf0k=g1Sf9i9qYRRC2G|hwF&g@ z-LT8#&mQ^jnGG;n-%f7azg$}r2kiguPWBPy`FPtYN=M6NGfPWS8v`7`1`Dr#-o3Zv zW#I&qm>-^M-`$A}gBngJYPEp3!$x9ZEVAA|-WVxVb~*2*dQNL<65v%;%@XlQ(QJ_} z)HDNXvOhVP%;{1NH%pU2!I7*WLF;srp|iz&^{JIPwGW&gx98kU8^RMid5UOOx${-9 zqs5lYKboOUfche zY-9W3HX3NE)?3^Y0!yALOK!1;j3nmxaf7!fUya-6=~|wse%v^TbK+#B^h@xe?*Y1r z9E)sIOE%b#ieUx^3>FtV+b>?K_o1ph&i*JB;RzElXuGp>aT#>bo1B{B27|#z%N^0- z;jaP@N4sQ1vb!%h@}_S}b#flYh-~-wtlZpk0T{$$zA};0py^YF7&2i|NOJ7Q*o-_Tt(o(-qOzi*vW547J}j~;9Tale?6~j zyjBFhbJG$aIqn^80rF>l56Pm@reTobTatp3@L=E zBvhHEzNJHZr^MOE*<<5l76up=`FLZK98*)azT4CCLV;Vv8_!Qz`+Iv^kxUZ(H;q7d z4Lv3X15Zx5K+}%>Wp2=JG`X;USmarGSTb+AV~TqTU>fY5OW+w8U^<)Cw7%nKV zM16#fTNt(ar=!Hpo@5WA^lPb~6n9iQX|L9nB#hb@rnTu){(@JRrMw66L-jG~ai!y( zY`3B(10!>CBmmd|fQ7N9Nrj6W&N*mo z6^6}_`T0x0JXuifg2%ye+|cOqt*|h(Q=%In!CWu3+uySo@@-&1T|D`}KVJ!2xpX%fGwVCnZ(7C(gbXmN^gb;Y7IOYHM`YGnpti z@fhpujdZZiBT5q|iiU%04bylO+oqw-8qvj+0PW#;7?0CiEWx4oT|s$^9H(-I(>?cuk$j1rZq< zl>8L0rt8N8@^5!X|19xPdQ>_(I$$XM`|h%gvWL4txmbG2zELO137A}b>M%~uQyEOL zB2k3K!&}B@ez(qf=t}3y>iA#%ETLs;mx@2-dTI`u$bFpdk~<)O^+R)Mn{}kf#^kGJ z=UGRwE7{>cD1$tb!j``WnM;5KGQ~bN`Og@&JDv%kOhg60XhwB*NMsVuoP@1P^W@Aq91HEI^NoO|J;tO2;MIQyFvv zCcZrv?FTMS7I_~o^xk!|sz!LAc|8mlW3nkKqsX8;|lr z0|rW#2?M`caa*>TbNqZIxjMW*%LneGZi&?!L7#~#TA??1UU%ETiy6kNrIZ6F*q`xLbN)7MJLM?AR`|P>6Jn9vHJ|Zmjgzm* zfaBm&1cEND@SVAjSOy!ZVdXd~Y~G$92z7>7#MJU&1V~b=j*juF$&!i?SeclZTxLOk zksvCXbpVhw>w3F-tFJp1+*OCT5i|x4K-*iN)tg^1QObpD2 zm|p-WtCX)qVeRB!MTd_Xx#76d&;p*=9OFM7E_n5P^~}1p7K3U~5Y4EEzoaQp-tL;? zIe|odj*)*}i>DA~3gv927)r`zFcMqr9g}^dXd2?}-Q_UU7y&-1fYXu^xnbA9r;Z5# z(2Ibskw-u=te%fAvrWK zp2oowxq#=a*K3W|A>QetkbLwrTo+Gs zv4(>|iZe25zLl0(17CZ4tq7{(8juU%{`@y=Oih1AJnd75z2z@eo=pNsgZK>FEqTq& z&1GDJZl_|^8Jqm1v1LIoUJ0M#NZ0&WENE^f`bJw6E7yC+3Ks^R%sw|2D1CAu^Szeu z26GfKG4Wd^#kRHoSjWIU7WLLjUoOLdYI!2-sOnIsd%s!$34w*6rKz=a$#JWdv(cb3 zqh|i_GOD4iO1VR)cn!j)Da6fP^F2^>IFO}{eYAr87w^)QST)pPNe5VhT*-?wsM!j? z!ouY8C&tDwfNPliL=Nz@+}v;`FMx-+j1i`(L_Wv>(R?R`FzStqB*o9eK5VUzT(kX) zIP~QHV~%ng1#X0y6*JHP2C2G%n`sNLPX4?(=S-PqNE3Xa^a}jOKAT>P#lg;@(SYD3 zN6>fXvLrn_{fasJWbN2q~^ww>` z>rAX#b6G!S+P;ysza)v4d0kKu8s(b0lc=dfm{lIm%lp~nPzo+=Q*8ZSTBDl(D>Oz( z5jEt6yl{c9Qb#e>4(p5%jT$bmQ~U_SxW~Del!8RZpYUR_=31mtJE z*TYSnF1dyl3Tv`{=gw>S)ucf=gP;GZj5_&P=YtAH1%F4DSSsN%?haBBNbGZ?drCq5 zS`!|2vEF5{v?Rfa@kpJc1>)g{Vr(~>at3x#}Q?EfkQBw;Sb0cvR?}BZTQ5+Evl+|dNSmb^60_v z`!q2cWe@Uw>ZvfVVpo(<^<~~V+)uvc0o;@@Q>Q=j z-9z)kh%Hcr0MA80m&mmNHLIpV(xLe|c}(|32WxqBJZ?2{Qf4I~0*ZYw#gG>Ga;5H= zv#ml;Srb@$qS)xT!m7Xq=>H^d(YW8=3bVe+GQ*cD+4#a zZ;tMD{U0vpIo*+s%TFDwZ0{@elIoZh#;qIe-?x?nKxF z)@N`{4r;yIz>VP}*(F07aWxt=A8@2(9AcTxeMKPAhrWFpmX{UtKXSTy3QIj{SQTm6 z4KtL}lVOU&O-ao6PKs}X%d+2Tkm;8FarYs5n`*j_z4!N+CE2SKduHqoQv@PY?-bCO zq}e|}4alj-Y_rU3BB8{C7cWBNzt_EIE-c%jEc~!@qW#8ko=VYtSV~8qMcIM%=Zt1O z=~ty_xgF6mB4XHql*VQq!o)}pG3_Ucp+5@83wisPa|bc3arSVZjL$EVhbt$Ou*H~M&fs` z9QFv+(%142fK)Vk8gsQ#(Ax}kY zsfaWbycVvHq%AnamOJa;$X`pAB;Y$0I+A6->!QyrwCZSh@7;7V)1%KRXfpKW#GZOV zcwk#-q)9oSzp@70;)}w9(__63Rl*@68y$(vz(!c`a?0xd&XJNb1{IRi_>i3lAH}P1 zzipv+N~ZGu-DCb}>8JA-^V|6&8(8b}NSP7zt)6!`%Z|pppJI|}I(@Rvm}b%29Tx+M zwqNKA(m^tdv0lhBIt_|+NOjCE88!lXpOb(x)iR}>$rl3i-Ik+EYWNLlIF@gzeW#5Q z%)0E7VxwTOqpcPuy7Pfk(8u79@>X?HkAjqu3ghfhE5dCf>9Kbkb##P|Eyr^D^p6=i zLFUWK!`64N&OienI59^hk}9S~%bA=Rme^CTM~4yL$Kru6tcVzZRRvk56k8;+NIPqu zc2DTd_xFt1DTp)-MdYVoqL@b0;F6S2Vw2TXJjgSk>ZFvUR_agIuOiti$;t_|OMm@j zBF3D#nH?ex=4yaCxFC3``at;e03y^D+BJCCf`^czjzN~uF$ z;gWF*V*_6&6nkY*l2;PLxMr4-j@e!qw)aVc`|$wEOX*-7?_&1FfH%u1_ed7;-eHX` zkKY>0A>VUWlUD|ZC5BDS;+kF56Dn<7040qJkCRR>+O z&?UPTHYTn@3{flXH-UwPh2-Sb0%0{syrUit3GL+b*0N_X9U&ZdbiTFyYcVVO0@S}BNsd+fFDg~d2^ad7OHA!jqzL1? zG8E?O*zt+Vs3x!h+Nj?Ld2=oIsg-U7zX=8r3IK?pn7 zj_rww^QIel@qvvMiHL5e(%M=}dV@!=X0b8H3Oc@%>>(TR%Wu&RB;XKVL^IX8UwKG6 zT&O-dh6$BDN-s^_F;U2B+GmJH7m}Vtyic+9V4LS>YOjz+LvfhY@2 zo!n%1H0iSPI}VeUdZ*OO8O4~9*8K*#6g{aNkqW(XpPg!c62o#6pR3ymzv}r{3o-3z zNqA~u@6gJwR+;!uU;MuopfqtWK6dY8vl?v&Lbx-lL+w#@`Qi7A3j;6xc?%sqf6Rd^ zra6r+P3?D0N9CGjWs^D@VD!+pw_|fw#+AyVxm_toBBM^vodS%Xz(!f*;Kq=_Jw{V2`gkjz% z(ua?6mVl2RRb}TL(Rz}JzHW&Qvwrysx#044OsDt4g&l0U1Ig4=t%^VW#f}J&_m{F1FGj?!Nz$a4Xl+M8D~IxWir6f&jU}?d zC@^P}H}x%7G~0R!65dL~;2<^~*$K99jLW}K=8!^-{L^rXE`#5wIMataL90S4P2I{e=Az)4KI|37 zOQwpAq)lyAQ#&+b0rm&gAkCJIs1P@R2)cn7Mm9Y+GaOGbF7w$X;z+9(w`!hWn&ObH zHtjY1bw;G%0#+=4{IDBnHye|17cRIB5^NkU8>{|GkX9JH;}E#!C&e83ktB^jZ&&HY z%x<}CFt{be2-#xQ^G&fP*1%Q)tKfR_Ftn5N1rovY=+mgDL#&u+&GtBEu8Qn{bZSe; z+eq?6n~%;5A-?%}z|Bafz+%^EprWQ$HPrL15eNn^H)iDgjR0A_-^v1wzn7zn0dv;%QC-|qYE3CwqmfoV9#@LY}-nfs!ihXJR81>uB#S;gu+{s{X*bEI)nzH zMgmMLj$$O0I?>$9@0F@()6nJ^(x_ND<+zEgC#H=I%I=brytNfN7v5DzAL0W00|kw$ z7Jx!7d+4)zv&FmMN<>AWgFQx|ye$lA`Ej|3pKb{B*?>H;?P)st$nFdBAx(VY8Cwk8 z*aPacDT-4GVkG3mVrCY_FljocJ0+{M^mH@Ri_=%t;~uIh4uD=>IN%QS=P$X^4T>jC zDY+;Q_BJj^fa4oT*ERJNGrGs&y)9_QfDH%5B7S>pTm^@TN9n!QD2}Fi9Y&ax(#n?^ z`kkW|kE505xb%Ksa$PU>1UBv&+_68nw_lJo{-TBnxkMT<(M0`H8^JWiAjOoUt8Vx6 zCZgg2${7(LssRHF%j05Pkc;b{;5Mu+FpY}8f#JLrO9hB&FBeH{PJqH z0B5|PB*l6X?6EK1c5^yy#jt==kc5GOQR8)}W3<39TE|M{(_A0eAQTk2Y9NV3a$v5! z{TYfz;~qk7dVeL=bkdp3j=13QuU#gO7A&<#PD3qCTfjgqS6ss0dDD+|I_+`KrIWxYuH&`k9ha2K|acBeUm z@Pl*1vOnsh=Qk*q+J5&&*IRGILZC_MwHP*sS~u`BDYM`h_=M3Jkc8H*%mOP!l`dQL zMJ!ESn?#_@cec4h)a*=_=(S3)yD$IQ(_yDry@PEhDK^D35#p-faGp7*j{7JZlJ)q@ zy6Ez-xjY?F$!N$;3X!yKK;YgF)8rHyv4y?BHG&^xc;JvFSt79K^nXA4zeI6%AAOJJ zY~B0s$Ciw2s;T$?Ui~H{{6zu`{^~=Knf{*VVQU7&p%L*^SEkk%zUrj zhdunD)mvX^!M&q}S9dJ99{W{DJU<9)HsjgqjA;Cp8$sAA~pr|me* ze`-U|_wSmsV!3WJj=~td5Un(+6pzz zI55<3niR0U<*ibVtNL2yxMUtW{a-yl2n6=i+HvxQY0~;0u#Z z6X%sOW=p4<&?F57P*24tbc>W0<>?8LTpCWkk&w3)C5@UXA*)ZEJv*O|gJwP_e7Cho zWfU}Ar%k(I7*fS|(l;j5XleMw@~JMFq$oZvmdS2MYos>IpI~rGfx|IKs@2`CBxEYMR6O*h2Jkk zt3$Qd=L?JC$j9Vhjjpvx-$QpqPgs<&qS5ViCKAN>w;Bc?`^h4sjjYa*l9}s;zAwKE zEY_UMswS62NK5XuR~%E)Yg{T-*++41H^}Q*uK#nf(fdX(yBQ1vZ(JW%%W_AH;G2#B z@Q+TgBHVPzx=zJ;{e+L};X!*^aDh2@zoe-VS;iybB!%tRJ<4DV^W)@uZlWLa#`B6_ zMR%%2JK0c63REO~YR!UPjYvK4W_JCA(v57?`G05mW4H42fO|TXzM0_i`Dw>`@5t;# zeuC)!!I-<^DDI9Hvt0|qAiOoReI-Q=Y8tP2a^{#>(ofkr_cr>tuI~WTyj!vFxL${+ za@ZHX3CR7Ch5a@eVhDy@hp=#(G*SCBIhiSa(pTx>>aYYG$piK7;hU6sqonoqv>UROY84+WDZJc_WsQ|t zUBXk~{i6r`c)c;BH7Y8Z9ZJH3C@e0!v*-nt-u-W5tJIHrsXI?qL#BIsgy@%cKh3*Fr8!h4Lr_sU-hoGsp z8raWecf3@^5A)yFPY_cjf3p*flrx+WH0$&GmaN-VD)u%a2lJc3As$B{=14GvqfLk)`=G>kVNqSwmX zWA(k{WEmEiGns8QY)Ci--Wo9!vQON*zVw7D`JygV_AuOeOAS+T7CR+R8aRy`!8`^B z(G5Ou>V&a@YC|Brsdhnk6Sq2A+WV=);K`#Qh*c!ON$ z9Qw@(p7wp0C;INrb@OP#iq)o4Lpi6j?Y|Z0)zVo#8igE!zH?Qn>kgyY9O*)x~u_m+Kfl zidLT_;jtgG+*c^4u4wOhm|t%DG|stP`k55{;xt?@96YwtQ|2m{SOCPHG|d;*!ocnk z-rubHua#_tP;qPL zg#_{xa;d0Kc&ZhV_Z2wXWjF*xT6zr4WO?8|b{bXXzuGugJE@C7i>Vl~j6y(d2yijO z-e$HK)!cQgo**KX>3mQ_o>+0MTMjyk$^$K>L$0|xiL$rYZR_;4|3Gq++YWR`y!vY) zpFrWJs$b%D{dEcIiI4iqe(QZD$Srq|+ObI|AaJQ@pYDIr>R1Po6;Jvw?}_ngz%$E_ zvMS~1=bsQRt2vskgW?iAkHB1mr3Ia<`ir}rkpb6r{!w0QS;@wo{WNoeol;t!pHUX0 zxtL$G+xZ2LV+-$%Q4-B70lhW-6q-U{(giL0 z%m~DaaWk8}weewsRn1!^3NHp(9ev6sACxeRK!kAx*Fie`0+s!q<`&N&U z#}A1w&YYy(;s3~Bhb9fC;lAHQ#WQ^HlaLYg0PFW9Yw8zQ~*Tq#~>@1P*r zhMs)d6C2ciV;c*_&BxS4`(C12`6rKDDl1H=>fP5ly3@H(?C;d&%p7JBc6 z3Oah+;3?!phpD2EgXH=Awz0z=qknISlk}Vfh8g)wl{~_rTX_#8CNwr2YI$gzHWgr?WD?d0M#h@OwS}q=rt8ukmFl z2!b;(5)Dk))0YndgI{K^z=&srdJ<-u@UrQqen1NT>QBxP>o*W(7yp15QBpNDo#SK} z6{FYnrKk?3B}Wb5@CarVdr}C9UY|+<#ayfIB6#roCg13};cKGXhnYoV$Z(tv)y1&$|FW0R zNTLlds%{>5@W-2UOX%4Yj^b7t0@0fd-K3*#fy_r!Dl5qLm_~6C7NoxG8>GP&YkkfR zWgM59D6)4HK%H=0d5$FfA4)i~G!Sjo#Hp*f7toun;naC6i&(_-rf8694au;w~n<$Dk+&?sw&+!@PZd01CMi?MIXJ_dDvIiVnA6}8P* z^ok+)Ay1u@);8Ar`};33>@qZ~=TLf4SY82{?Sm{*rqy-=h7}t%IZL;~NwCcp%A7-N zIT|~1y6|jjdPNmLqYx@Gu>C_C`y;18aY1dPx7Birl<8}mm+#EbSvZy^p-2mupJO^Z zje$Vzcuia+3A+sMzmeL3?a9LMk(iGN%Ea~T(u%I)xj((8q~qVwXo@fwDtt!)_~bcp z1MxN_iufAU_w>MsOAaY8Tj-63(w47;8*W~KmMVViFpt5eLgWNr9ewYG_zbAq!zhN^ zmM(sziD1wRCrA00GhHFWR|7-MTpO0lx zRw5>XS>@FK3%kp#eIp4asdZpg>@b1SCrkY(Xau+8Z{NosRWcbn^V(J%R0H<>ztQ^t z^sCiDK~gB8AEp*cW}Ufyi=u_*tvPSCNpzm%Yq=Vw3PtOuWiplA3(e$FGs8t64u#rdQR9Gi@F_l#PP!x|lF zDlXMgmGP4swrBA9Y!+}H9&T-TYz16aKjU^N6rLK%=IFly4!zYm@ELpA^U;Hk0Cmi6*zKy@z*Gb}Q5q_D{*jObY8G4yv~qPgF}B_49(&f;wvefgJf(-T-q-Q z0b|ZX57z^NtxSjUAepPaff2PM=h?ww^>1HFtbi>Vgbi83ZuqPaeaWjnk=|`o4N@3O z9J`{zEU|nGu|=h926M(*DD$;s3g<{oh5bU@tHZr4`DY)Su>Z6`h z&{8vW1#WA34t{O-_o|Nfqjw~mJon22q#eTU8!tI%0lAoG8Xh3Phl73UVY}HkRkX7i z^uRE?8z)~LRui3~i_sO$cRs*FsN=cVcrV?SGI zW`=M*0>TE1%II*J~jHHgP-uVVrr6d zz;>5#_v21->fYfYyz~B#3>-V$=@Tjc3^T2Lvyj_45}pm?kHeg{#db43w_i=}iMTt= zP-dD~+^LYx97=BNrsZFu24?g_fa(WO9Ez8?-Tk#Q4!pHmJ{B0aPVDfzc3tT3(R8^{ zQOo&#bB0GQ>P;@+vKnwLezfF)-iak$Vzodda@`*TO1RM zSib9}XlQP=a9;kjv2zRNgIUDH=scZFdA`i7UU_QspC)EH_TjN|6# znfTSBNS|>D7`NAd1bZPq(wlwIH&dgK9C-LE{K-KAu|ph0w3|SjvI|cmrn0cUV~ z6W9k&?rRlK8Po^%GGmFkN~%9SR-eXoUadGTHzWW#m~{;eVc0Ww$(5)1=5z2k%K0@- zSlbLVf!^|4^OuYhck2iIK?phho0X4{0?M0yUi}C)Eh83eMkYu8Gq7w9Ab9Zi*ZnOF z&44fNcxV4cX-g{lP#bnEObl|v{rv-N(gz23OK5v2K?Y=~%q$PJMzu@X6hTv&IQk{b zI5?p2UBC|idvu|mJZjG_u9gkc?aIls4TM7Cor^fNBUfI*Pd9S01z82D6hh^qfzzuM z7q`uyFP%GYt>-Z@&wi-~jsf%x#n~`jlYsPq`wcVOk6%BjhuY*mk^t~2Qah+I&#e)L zoQ*=FAwurJM@XL!!|SV#UO-zoMbeq?3IMS(^_Acxj{)Mui9C{$p*$p2#jfPRu;oIl zFgXP_w!vgeeWM?Fw$KvQaUYGICX(y{q@3P|Bhc%0U-az4c>?Jb_hiYzH&o_;9pW;8 zP+kbZvbOzcM49V+buuTfn9%e*2^2Xc(ytNqNt}Arz3v0dcV6iUSdy^iIOOEN?C)1z zTvk65BqqYsGBUR27K~{WX`39E`qCr${DFY!?w%eoNUMM&If82#wK`tX)V7_p3EfW( z?4}eU-v^ZXSsOQ`zrPTn-0x6jT*Tj^YW)a#OD;g84tz8DyL^(Ov2a#|$$qU6xizL( zI_2%~fzHm$qp>=qumLwDcoCzp_XCRZ_^Seh9aAs|xuW=~UPi9P^NLF?H=oR=FiIj! z0Y&Uf$=o~C-e@kd$+(~!M5qwGDqhSms=Y+c31=I#Ftoq$72tgYtlUBaSD8&XvQ9aE zPc~Vig2Q8D>|9+BxHc0pd}3mK4-f1cck_Y(D2(o(RI!RpI;r!!?!dun|7Ea4zK@R^ zs-CPThWBn6zLHXyMXDG*w6I?`@cfrn`|0_lU6X;>>CaF=M4On1Cw9F$DHQl1biL|< z^)JR3Fowe#7mQ&;33QhF1F3+znwXMuYvXApC=@$ndRk)!v~!XBEC#fBAAVCk(YTR& z99A~FpKrH4%y5ZMgkEn<{_P_UIzM?9A7{3n9Q?Cc-*ql*pQB7DuVANVkY%y~xYy|o#d4fG$mHofRoG(}gRA|Ny+a(4eT?JW z!NeCz<^Md`{Y-q4b>?iDlG99kBIGalbmE2kiNS*N72cCwG+hoAZ(sKW&4M=u0 zdwzQSNBePZe!1A<2k4do(PVY!9U;I|JX&o@1g@Kaz6TVrIe~Xf zC?Ji+0WWY;(w-Q+Zyy$uOJdV|cL^*dkupF&G>qyoe#N;fw)-h?-i6o-@ZjXjt8a?% zJ9k`q&toq0UR}<$JVI8MS{z;jno07-psz5d!J!NCZ1}3zb@tJsFCUqJqp7!b4&C50 zrVZl&`Ze-%*$Bp4G^tIEUZ9am)-v@$Y3T1f8N0(j0_zXWv~LsC9(fr zUtie3f&kqvQt;p%=A-|CR_-@r7eFE|Q#rrs0wfR@6;1L8fyT52eMs8gRTcDI8W~i+ zT3@8yWX6dwSB1G ztR1Ax*C~Gq1yEVxxewbUJ>2gOc{N>H?2ZqjYNH*nfT14PyiisZB^WL=pJ0em$1Y3O zdj=cyy@(aO8PN^GETuOi=H=s)$>?7V92_JDOO64MO1wmvZKB&?cJtZh;0e66ILF-E zIqF!@$;{FdW#bxvWPSN~Ij1Y^=NwYGBH%Gv>Gu(stKBX-HBZeN+BiPoQ?*$MK3`Kk z%TwOnAc~z%72kHpe874f8!W`{7rC0 zkzFunwEedzmb$fRL`c@-Eh=&(bb(mj`!!5|y-?NHgQLN4baNY>tm=Vu7Hk~5G8E}}o1?I?nd9!s- zdA;t(_4tU$J|XA^rW$ms&ap*TpaFP8;LeL|7dLPBsHG)+@1wW05;LI&3RTUr96?#JU7rkO3T7A7<4h$GaX< zpG5_oHlnyA*4ljV8Z&`63jwO<#C-WUzyMJ7Qrkm3FM7GLfy$mFJn=-=(}@#z-6)aXD2oGAW1rdwx&RPfW^GX5~K z4O3Uw8tB@|}ZU zxLHa*KLp(p{k`NzkqJI*bzJ_DK=r(R53o3sawVS$pKlzx{(%Q=5aopd%*Eux>}YZvL;Pvy6-KefqWn$`S&?N-o_EA}!qw3sTbE zDP7XiUD8q_-3`)6EYjVvba&pDzyI^R*$=#7&)ti2;yW|PaP+~lwt%!Mx1vEL*>tmS z)t%(C{d}hoFx#5fuXN(~ko}A|`tcmB^mJ#xD%&~t$GP?59ImAuemkZA_+D&Za*VI2 zs6jD#?nGkx*{R@1YrGXl7!Jmfknm#o&63{(zlld*v71s&Wu@>culE|7{%VuCzJZfB zdIIgmq>td!@1>6yVfQzF9jDv?NvX)-$!BlHAhMhBa~ zAe8s6oc{Wpc{Y6Y$>-m*JMe-NA2mK=00D#g(?s?&@BQ_mc}@qZF}h*P$a)t-M1-98 zBkNQA^ON;6ag5-drSD1L^YHjO_G^WkG&#!h0FqCZ9FtNo&&SYTo=k=7}I-4vj89?ay<5N3*a)L zF}AbIqLhku=qGloHXmg!y-@J2$azdbs5$EgpF$Zm!cAEzjdPZ)9M^Z)>+R;dgdUKe zV*^7moF=Z)Jq`;r8n^uK8!wYT-(EFzh*>-O|7`0id_%eDd`*1d?mexwaq^`L5E!ZeWPrgF46k;b*#>J z7x+brS~Ks+fl;TkkCY&*fA{0`)Y13(`kA0k`*-%kAJU111+ir651v*J6MlDI-p}_d z#!hDtw?#)HAflnRk$N~fe#Ds{;i6R}hM(#`nD!}VZ_Q=5iGG*JFAjanJCAQ>j<$^wmwp_6_mWO_@k2m{1VQk#$wFd?+Yy^7QXQgDY3ZxW|m%0hu+s`P< z5iHV#kjr6aK6(mUus=%+CEfN%J~lQp3*Sw%jE3+I+BWz^KJT6DudY0{2pO4~VUMcX zELX=N3pon4`Lsnw#c(v*#kL$brS}#{2wpdhRz3fISy)tvvd4LKu+-iDc<+7@H)bOa<)zg6G% z^QGgeNgJs3hi~in{nuJL+Q6YhY}2`OCsMnSubl5~8&+Qnc2jnzHg6s_T(b*sju1Dj z{Q3L0atWV`TB{y%q#$b zKtEg~!OZB>yt?EA)kxGi+g`&XurmO}=V;~~51z zXn4;f&dHqG9}n#TkJ;jOXzH}iWXMlFO0~MmLvq}H&jL8M?cyTep0;bD7ZklF!01+r zRTmYxyfaN9Ej|H3uAc*O-o8{?cBbS`>W4vI&mB4yq!@uatw?`7fZTEq47e^Y3#KDj zzLF0`Du>9IYo&fR87gF+w07|%6tL0m2rJ6+3mu5XAIn zuG*4O;F3h}^fxUiFZTB}0CnWZ>lQ;V+ozQi%OB88&E9T;XKi1kIVJ*pO1|N>Zsgf! z7aSt)=y*82fWVu0DvBZKbOovDM-)Fl%$x?{`7U<8j85&SfiUPA_V0)gG#dlL%&FuJ?G1 zY5>OV!CK!F%p!6=A}C?^^9n?X95o(_*gel8dLK;tJe2rdRsf*9&|QMXA*fee0RPAEX0h4E4vni# zM_OF23;Go>LS(Bm<6veK3D@(EHkOLUp0t*h$_X}mEWAXI!5HHn8v=lfj@W0<4Q^&i zPLNxl=S`KVDfsZk@M^mV0+}#NOk2vLZdqv(i6WdlvFd+ zFmU+Y4z19Ghi%hMXO0e;bOq(8j64}NZf_n4^lqwN6&3&bHho5@ZGnVMPlX^yKUu47 zJ$bGGAm~!kva%$tJA(9^oPyz5UeN&M4^RYw8N5Jq9N4(7?lzpYZMZ2S#iDMW45^Jr zk|ApF@k{$dFYCz-C9V7Y<%~PPf^Kp@LXc9-_)Xa9MJu!#c&!A4VA%jpOaR}w3OC51 ziMUXdUd9ZnBuc9&h{I;ccFYcbS#(a;z-zplLCHx#UFHKqrP50N-_-Di($kI7T$MHQ zLj4G!QqsdRc)Qc>+j~QcMjiGh?+;e|Vts|S7n{x}tyC{OeFPs?#Q;Kb=YB;;XEZUt z`$1Jdugji~da}k`$MFmM_FLRc*MB%5$I~wATDF3b02cqXO4VP+36f)k;3y zOvo;RM!TPvHQcW0KVTKe)qWOW(QWPlaFA6oM3FLa(C8q=CNE{}JeS{19C%^(C|mIx zNi%wqAPM~Bzy5_2N2?i>ir7zA$4?m4oY~J^cx*!VypHi-zkV31gc)V#k@gGf#9{Tw zM2>&Y0UKpfqKmHcm>swK02AL??&~Q3u#>RN7NG2-msGgPRvY>C9FOI1>aX#`OD$d9 zjlq76+s@}Z{S5b;x30&_e}JT@`)rV*#qAi_D+;)ezFhaCTRZ@(vazu8#03C?F}*XU zgva*Xiq#l01bvcSTSoF?1jDEGBz_`FU|GadZIM1b^-o&4WO?q|4GUWf4M41h&bP&eoUnU6G|~}6N5iyXO%^?#7{|WQS%h(>0!Wg`?>P>*`)Mzp z`(AMc$CS+(tT+J((%>Rhulh72*-f-0i`6I;II5Wnpv4A}U6{otE(becX!-B zr+(FH+wMiZ<^ySI=>i)-v9Jper?qXh54m9Y>gqGn9NnMoJGw{peZ%yhkAw<%7XT7* z+_3f+tZ};rfYJv9F{-U+d;14M?x{_;#2@buYBW=RBzDgyPEEc0_u#G$7XX6~yzAhW zMdg}+*A)Z+b#MNY@Ohnr;8{L#OD$K97Z!oJVD}G*X)Sq7g>|?^5W`~e@1_}o&e3UR z2{D4r!}Hq6aH>Ak_r@r4dbSUM+jP2G)XMTa+t0V`OBzZEOGvaU3ayJKV~V38koiuL zPa(r`=NO=dno%&b@3h%z{11g$lyyflvW+3g;}h+qM$Umt&1tCFg)bLhsAkQnuCAe} zr)6m97^m1E)iSZQ*VWQ`H^2WdU-8IL(RM|cR)xQB0fSWmaFn9ajJ1Cb!+qxl<%;BE zPxixH_Qs2ihxxJNOZWXc?%576?ghBn?xm+RIm#Dd@F(}@N6dd$4hWF?9v*=F^&A7p zBZ}0*f2uLiQJ*`M-I^U8C5)m7Ql_${UPD4mX1s{df?|=VqX2f&W2&+=7|^i{|Ai`N zPfcj@qw+OA{U14MICO4rkS^~&V19Iu+}-7MJy;ycMUJjCAN7rV2k~76MOm`$-dwRh zz6a_jKh@U$R0t%M^p|+=nqgDJEz#fv8Mzit|te+1pBQG#=T>$DTM^vS1 zx3nD$vu)<244}8urvB0SxNrbIQixla%5Gz+q>4;Bear9T0+!W6ip4Wt`y!!1Fy^nZU zpASsSeZ7Ns)3o$F4&NyHxQFZCCg~#m=N-slZSIwW$Q_4?Cus? zB_O6HU+3AneqQxEk$c`*n6!QayeAycCIPVZ`M4Y_VB?g4#DgS~y;hqUP;4yQpF{n= zDTkZY{K4zkp&kbExDS4J{eE5TfylR~D~|%xU3l$xn;?Ft&>mWtt)@aA`$(Wv^l4tl zlQqEJHT~ypD8V1^C-8QQ2ryYH&dyWx*Uq{S^!?8EnV2fh@cd3wcAx`Nq`GTKDf%1T z6Qn2WN`8F+e)B(NyZr=P|8{UcL&yyX?{0XfWCN}01{qm9`Z^IqZ}&9X2N5wLYopn| z-*x%j&Tcl805kpyki{f2oW0NS+IxXN!{cy5w%0GTCiHaGVZKnF32^zpSAtKcDg^!n z%cb1r2|cL>C|A`_ueYg^I<3b^-7a6ZO9?65E>gyf?R~lF5V|7*hTj_<)(}R8oFrq6HE$7ND%wW1sI zj>}Q0JDZDhm>5VVBmaYW!|7IqK(F8Z(ladP$yG=y8e;0=5^SD*PhaD_0QgUSp{E7E z7X`eP&txeTI$M5EK)WbsM^ugZ==oyJ==ri&5s%9rP$MIO_u~2W709KyKUC2IVHOo@ z#|0{;(3i-k`A=DXM@0t<&t#Wu zmJJr7GZPsLN#K1+mXUtryM)H}JNt19O-I-6{05%=f_Wh0 zCB07}I&-CE$ZHDX*vmU4QNy6FSLD-Lks}rrWw~MsybOjmA<)5opG3k06O-w;z?gQe z5g^Yzq2YaMfptloLCF?Wd?1T5m#~dl zIpaDr*ZMH_klkGZ?J`cmhZC{Hv+;R=6mc>90os+sNE+9JGVKv&D5Pis8&S2F-|F1l z5{4Z|(Li1bdL^j5EPh4J8J(!1@10c~ztPZsAA_QkwTFdFG2omGT6Vt%k3K&zlkhz8 zOoix2M&PHQCYbZQH9>d}?#jZPp5AopQO#s(>XD?~CflZN z?r4c(&MZPtC8PR%ga%mLbm8Ums}A6Zt@~!*+MZuD`!p|MsH#r%I1UdEqSk3A`5;f@HCJ-``)L7DQs_i9a?Okrw{r>2jA#1)54=i62W)a4xG>gIH4RM z@}0|OHO5cPZ7h}<&~kNvcf1e4apu*mUB*8Yj9FARH;2~&Tp~9E`M&jaY-i^hlQctH z+o;NxKnQwxHr zYt_FR6!MM?t0hE`>h_p~Kn0`gNA2^}SWc&j?Ad2*pkWk(?ajh!<-2v908gWo zf-lw+C;O8pR*qzqBl?2NKAFAhILcAeAJZU1d~?z022( zjMkICmgD-g(XN?kz48nkXxH zFCoNnUUf9}D|A1vEq0rJQOE zoLyuT3h1&{@jSh}BJ)vWd}Qct^FD=hRM9vAWH}SNfA=o|{L`dWorq0C%Nuf_f5Y^? z990C%0obncp7AGF;auDC3rC1*wpFzf2(Ypg6A(`a67qL^=swS8^v=!;m9Uaoh9o{| zf9&`i9rB^~U1VgxCS^7v`zAlEV$Fw=S5G@Wty5q^1iG|KB#Oa5>I#4CGqEx|KE#cV z?blksxU}^23cw+1djXz4A(<_3O+A~5T~`2WPZMrc+d{lIMJNjTqD+G-Hw;q*^!E2B zi}no*;wt|@;E=C&4G~xf#_yY#NB~j}X`~1_cq?3E49ziA>@He{En-od0R*yoV+P-T znGO5!YkJl%XAroL&X;@>BOd>QW)*Kkmh4ghZ5yZxsDMvb0~f+J@C(4&)?XIwjpBxsIQ$~dH@uZqnB=Ic*?*RNtZ&|yu<km^m`QMI?mi$7F=VJCe6&mX2?pe~P^cBw@}PD$jWWGL zQ|Z5c05mi-fVA_#Nv#>@crfd@&QrJ&!|Qzmg2|M=%a{3HqJA6zzj=XBjPPsA61Ut} zUV_f`a48f60ikU7ON%ryv}7tZYeBMN;!lmnEjwd@c*$S$`>?^`QF|%ILwLc9G776p z)IQB$NqmMmKhD^oLvbXiGZH5EfEfE} zF;S|zu~wK>5df}#9X+8$Du7BiOi)5!W_ul+2Z;!qm-Vjg@~UBt4?zpz+w>BqUsmfl z9Xm$x+ApYaE0~lqJ~%=WOkNu@1DJiFc51||Rx-7iCqR^HFHQayx`{1M6S}abEwfRII{cgL%P{uIJWxd5)E+dNp|-`x#_X?17?pES!F!i?KLTQ1 zi}n%Wvi=wpo-(p6GX-O*Ms-UsbJW76s}mI~fQLrIDL7CE4X;y=Xu9Q{&txepVOB~k z`d&M4TRS~Ga!j_{|D_q|bsdJ;ZUEB8vC%%OZ<4IIg+vChv?g<;MSvtIW{VVGqR_#}5Y3Vjv z!Jylg8zzQ7Dnd5$oCt2w2YCJ45b`9?w7O6B8%ZXD(V0LqVphS#VSGNyAK8fQVRR^3 zvc~7cAK0>%;#q9eavWdqa}lJzQ|;u4tCf%KUOV(b)2)DZ-iZm9j3B*nps7|!0n0KR z<2`l)HVR#mb!jc%4ipJmJ#ELnl)66L6r%!#GH7V(Xyrj95*a?dM>E9#oBF*=d#Hd> zW6a}Q85_D|aZXAP&n|(vHM0sh*G0Nc-O$A}4RE}7kNEV|j*FwzMZ0%A-oS>@v#tv7 zC2a;IEwf5X$#^qC#>5&>u1q8)UDECaPEhPH%pUNK^eL&<)AIs_W@c5>)$?cdb=qQn zWtsi>Z+2)ya@4L!9vx+ybn+IC6Yv8?MZc>QbA#3sgA3k)!*}O+*L~%SQep{*x}c$X z)eq=nFJ9n5WW+_(Fo~~+MZRxcxrWR&*=BUyyqy>+Tv^>(?qr}dglJM7>dBYk0=Oj= zzMQ!XLl2K&HV^=HGe$38$>W;JSvtI{4Mz}OhXfg-P;<)34M`Ux8``4o&Mb*ntRU0R z)*BO*ln@sZssa|L`HDI%2gE%JBYlG_x(mIPE_p09mHxboxcX&qyc%^tA~MupGKBTDDG-_3Ad)+#Fst{rB(^#d*7GVK zEHh4dL`(NBr_Ri!AQ;hVih&RGXFLeV&>avM@_AIiw-RR@WSx;4NQX;5-a_LEr8<_n zQ-|fsoQjoN7O2B1=9dIP62{Gv4KoGVcdt6KN>rm>?K2r-83j|0Fad3+sDC26n}_Yy z5ERUOzK?EA)hqF*+_7;7Z?Y-kY}ebGdzhxlHibCEn(F=1rJo5)h;%C8iv1$4@{aZ_ zqkrq0uaM;0qoHiUH@a|5>oSjGTg^dg%GcynTe3kl(Y```CO}~-b83nc*c>DS$qS4H ze306A>jH!9EH#^@_j?0yYUu*dmtZD^M;h`5_~94h0AZX&Ss)U$DiKpFzeCr728^)1 zzPoLF0~`>&?k;f!YbW-@VVo%d+>=(#ZWP|b4o}psldM>w+@}W7gSy{aCdU&<73+|P z;RLXC@n~vUQ^rxrWQ5YcFRkM{n5_#{FA1LZk4e)mj-x_p(*v#+wF36tV!v<8MK1PNFpBU&lRm5lqeN7n zXYsc=ntGON8I<9Jh|al8&YJlv`9&exWs1hX2KQu%UJzR(#^x8F9!pu5jtoSK$jAtB zh}Y5Ig^|mkZ~c^Q*(W~!;gqDuN>f81D_6@xo-b@P#wU&{Q#bva2X1MXr`WMlL|U{X zJh6ZM+DuRcoSV-L-@U|nkB5^?A&ezKoe!NI#`+{nZTzx!u@lh>;Q&Q8)-;U3_SY z=#z25#71TxMZOKju?EIWQzp?UJR%STQBU`Z)jzdXVUUBTJ^rM>L&y-L8%+hZju2sh ztybCQ_s!{uZ<>R}SKG`2$*4w{L>U5IGey5DKk<;&_3^;(g+Q;zt5mptkkSSjZVG%pzrS@OWA9r5mVV~fm=x!NB{etx z@?9LNS_MTx2=a|i*cymMw`ET$IJ0mBKNKQvKtwI80hnDc>z4@%`S+ z>VMG}fQ4$j_#07c>zs=Nw?Iq?e)hE6TXj67gKv=`#*jJsk^>(RboQ6qy^rG@-B3Av z=i*M9cymMHZ4m(|43$bI*`tuX;y0gD#p4>|)$osttZBm_c0q52HR5vcOg;`IRUefb z+vE|}eV58V@IcI1@cNO`nJ|GcP?@j6+=VQuA@M{k%axzxLWMoF6tN&cM2G=w5J!Pj zY7P}suzCZ%uQITGja@tGyFuX;fllsxY|riPD9W(j<5i5ddoS^-Tl_6Rn?)rTzMIcH zsZRt|@{Y)`>C)qj?{xs(Loo$dDnO zq7k3@-qN^);RER_SLcKN%oOnz51d+{GauKk=G=Dw(Y1_fF6tpFg}Cos8xdBzZwiq> zKW#UKX2(PH#9kGHU2b{TsqICGQMV&y=v3GUtPX{y5f`xTdi`Iezgc5o60}5VcAUQI zcKqy?4a3?Fii1UpbmhXJI<$?r2_C0V_2$ z1&=O|RXO#i4V6vq9y#zY4ZN0G{MrXD?{Txlw|mO8Nm?7SZV7X5nSoxG8GM=E9H!Q@ zRtah*Ld9zx^g2&(`hQ0u2{3It*(Fpu>*VHDp1EyvYX8tOmgI^kdc64ck3&Ns3_kVl zk0X*8jdSHPSfZhE$2ORnBxS{yW=%3s(SEPX8t>F4J$8(pt$uD68ftH=YSi!-@hl{A zeZa^MQSWXdh;Dvuv9M%`p=5o($=T{pS){DTQUm+)QA=qrey(4-f7{!MR`MQC(e~n| z_CH*FFI*1U<0{Z@SymW7+L1|Q8U!#KbQvtm&3;w%l4IkZ3`dPiH$%;E;C;&u;-(mL z+R#gHx`1lht8)F#w~t!Ivxyu|lj{U2fW<;4!q=8Pb;6uEW~={9>(*Y*qu0}@RH2LR z@N~1e{2=m;E*WUh*_d{H)yuPVA;BH#zs_aAv^2oy0l)KNBuXvAlt~{w91*sW(L4-| zn$_Va<}qQx9Ln?vGHfJp2y}8wC???CokPz!d8^7j;}$KVc<*wlUv##9)wMPqwVN)& zejTxo%4aXR2W~OBJ2W+SZ-uNBx?Q0^I3r7a*5K+l12j0nxC7Wj!><(l@c=<(lsQ2}6oADYx z?QWgiSs&J;9>Y#uqjlYg9GnSv%ZBzP6F|$F)A4c}{mZuO(|s`*NdYsztSX47B`~8Z z6E>U=RYQsHTX{jW^(Ho}l20q*wx!2a>$6eTTB8o{9vu^0?7?*IwMQBcqG-1LaGyCdhI31)h~vELWW-NRLL5w-)hJ8j1|<6paaCNNeP#R{ zosZv80zFted4rriuJGXnQ7~i%45v}G0RcP-@&PA7s^PEH)%&=r&r54gNirf9cF{7k zm0^f$D(!fB$eo@6yy%MStoWc0XU9jc`+Gpdi|8RrdThFRi&^-*W;01Nn8LcXuiyk8 z+&|6;<1L5Ck}&5N^7tZpaxyxNoH&sDMYd+%p)JLpMC^N4uT?#yoRF7>95dRdpQE*5 zv81S@+iwodJv6^94sig{O2KYD!<~rg%v%pD#(W? z2_IN>E?rdT@WC_QD7Ez?H5SLzP|my+f8 zrjsr`U^GbXFBOMy!UzfGqZ&KyLUc$vfHNl|KX)jA>-=c@k15Inm z&vj!}0cEU{Y5O2AK{juXnk;&pZaC8s-$%1P*qe@(p8_)i+^bUIdD{u)ze|wqD|hD{ zDm~2>Q2pQaap16s@!E6!$dJehLCZQ0?)-5?H~jIVDpi&HR{4c@@%b-(t&99~`_o8|52lxZ`y&$IjIGle9JO-py-6ElpP5*wnw39E z>kjH{4UN?v$e^n89VbHbSI+?#vvW6|nVB6wS8#Z5NEkk(z7w>|Z)hTX-Q))I=bX_h zIe-7kn2(3A-sGE+E-_wr7_;k;c`K{ErE2A^7a#d~##><*~JI#Mai>Nx zkEW6NU+oXXME2!{2uc7J9KsbWZ;}5ZHz00Y>~f$lA1-ONmQIh^tLJ{c)xWX0RDPBR z=lcAVkgb3cN`Ywjn?C5=M2#=>%Z6`tFRbGRhtkh@3QY3T?qp@whoZHvZ`AE66BM16CYGEP&)rq8?M4W&-wzDh635#>Ln0_12V9YtQFhie=x z&g1WBCLSJtoEM=pJi`eiq(_35wuW@TU+@ z@7atY4=s)Qy&%NT>D?1neucZny}%VCye>%*hfXjUML{ZG%6=^M-zO?y6aFR$Bg}_d zFvnp>zT{0!U+2r7;djk*&Q@D?+&J5SAAPyq*L7<%<}Uxt&-?8aa}cEJIk72I4+9?K zQ4aOIyxYlq-C9Phrh%msmiH}hr^IPr%|6fiaRjok*W}gqa5viJxO;bk-rhn^Nu419 zvZv%PZK&j|;YHlbJP6!(ZPIj9#BoRN9) zxDnIT`55uzoA-0m=@QK>SRAH<3tfBo88|jli+{0!bj|TEdP9rLR^E)r!Ai5%tpZBP8EMBwt>mL@Ydgd&*Y3=v%F%#B-#i&`71RY#Z<%H zl8V>QU30UtvuGZCI=ffHo5Jb>BM*+rRhA}3gJ&Ar^UcP-B{ro{IGQE*J{6$|{IL@L zEVSgiAby<=@ zzedc02&v-o^N&N~+>e&ly)20CLDOimlAD>_VIxyPuiEq;6L+lWrW z@0qH{TA+vV5CCt*Ngi&aE_h-6MuSBkNCJk3VK}rXeNoG_9kBtUX*Ps*?=UI}p~kW9 zy~Wr8wJYX;w$oQ`+Y?5OiZsoa=%i`f+E#;DK((Y85rGGL8$?Q(D9I39)%}Fc7F&3$ zZ&m$enF3os441AP~#M^!-`?r#3GEi=p{wKfKOKE)X$sE4-- z_Fza!b7Lpxe7qfESF+`Z{;-IO6Kv$1<1owg(i%(DC{jYs-vyWVZTzC!e};hSWD<{b zdo2{hxF(WJ8Q?_8vvS5ks~hhj_0W;Kw8 zYOHNBIm;|mUPVFBBbXen!Qj0^S!l>Lv=^ka{iZ;~Y4@mo~ zXZT#xycvkpNDL|Es}L?=w*#vA1I5pG`C5@sYV>$ttDP%V*<7j-NN#)maYY#zxKd@g zpsu#8V1oIBUfsYtlm&QUCtr4vpgCKcp1MKCDzJII^{g*_C#T1%MNT=~J70?&KdPG^ z^^=|6Xc5t=QSC!!bp7dWGHbv(rtCY{n%lnLG${VbABy%qUe>XazdYo(|81k_@cb`s z7juB2{}9l$cH~LSkd`|_4|y4C*m%PW0e$nL=le_d(jUx&tR+PLP1XcA(z%H;`6OBk zRx;8r|g)`vy3vkV6y z-ShaNHE$H8CX+erV8R4~L@?-Iw&?ROTE*;~M<*9>wk(ri+(Ie77f%~RYCzRsI|EMf zjFL?+{*EcaS#zI5Q@W#TYt6BhZ(y53j=B?njT=4C>rDv}^&rk7Dnyizw7Cz(0f9rh zpUPXv#DfHH>#_&!?bnz~0VAb|2=@ zlye!hzGVOJDq=yhEKtSEDH?e8*I>Ye-8VqeZ1KVD=hckg4OOvvOQ3Ua_Dr-Eq(K}^*oRr$A1pZa>g z6Qw!n+P_{YI16;h%l5DLMA*I-aTM!i~Ak$bNO zf0LyeYcI-WabmuyyEuK8?XX3p(%{^ko77x-VoT6vfL$4FdiTIo3o~ literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/packet_layers.png b/doc/src_intro/img/packet_layers.png new file mode 100644 index 0000000000000000000000000000000000000000..acc512ffc9c11074c10da433a5e162c8c1268714 GIT binary patch literal 5941 zcmc)ORZtsjmk00w#UW7KLvV+_!HN`X2`v=Y;##aYA$ai?r#QvkiWYZ*Tai#G?p8Fo zZ@+J5cXnoF_T9bMi$~^MojF&(^Z%@>3?;;)!2f-W>Tp`n;2=}7&2r%w48-W zg~bISTdb$`+u!t zt#B2EGr_cu@6LTcfiE%Fzlk=w9dm2@wZ}waW$gSCj%d>_wdN6GxrSbC0~Lf2_<4+t z$SKD?hm=!#q#cm?C`?;>KoZ}vJkZ|p81*Cw55W+U^y=0~3=6;h<0#$|-Z)O?4n|b? zm#;1W3db;fG3$Lo82fiyBDq5Ve}Nd(UsCwOS1@@RngLIdP(yu~C1be}D^hy1dy1iyb4HAi#dh4B;(@=m?Op0S$WWrU_8!bH(=u`H~ zY@Btl@J9*yLMxc2^<*d$?G7s2$cD1lm9CNmECL!xZ04oTs;;fV>BTsh_Thpk#UmRTgn2wcas|gg9vJA-aen+Y z1+E0OK0Ik1r~gtfQp8S|8seJG+9=)l)i5@zC9=Al`Q%@~z?5 zXjc!Cjjk{5O4k^WJkhL{6E=4dtteZb1LaCExRy5FO2u??DkuLyu}jS>+2z!-r^A)S z1I5c-&$;ltO46@zX!D}<&6Z({O2x*#pKQ67&%Jh>t$~^Mip^vWJnb2|zm-lok_d&E z(Y*SW<{l~6Ut7INA>X%P%Q2OS3+9Gm_6GmTm#dtioL`oO?^7}Pl68{C7X_}Fb^@sO zJQ&4FNmKPZ%x+mJE0S_ABuBUK3V$lA&(L?)mL-njlPYkZ4ns&Ex@naT8^_lSYt_QsB)QiOR1HFjaU=y;|$z~`4go$Hq5;38pVx^?3Iz47r@&4cP%$`6Y<4Lyl^+p)c)a?g zaa&l_6-Y;6ZO=FF#|%;>>ZWE7CX?*lHV%Hf+|_G-+y#R_10KRU+**33eVX*MxW>eh z^&>4^1nQUt8zZth9gynb^J^sD2W!Dg{8+Vgc z|M;2_L;L*L!#A5J5_E`<+M5QJA`6R(_6E-AzCZbdS@yfA$&`LJTlORyzQ+(ti==w> z*u1MN4kcMryE&m@P}G`0Xdt@U$&)gJzI}E&x>sE?kkuhFO2?EM3;gJhz#ugVBW(R9 z%`iKpr)Oz}VO2#Tt`&~0%S%jw_Bq1T3hK1(SzrHVb9nJaQ*9}y-m;wrKR>Y7Hq?N& ziB5X|ulc6eREF&zwr#;cPisxpQ`P z7QVjtxt*n_ullO^p6#{*H6KENLhCZ({M;IJ`@Wqf&m#N7j8kOT zWn6;cet+ugJB!AQBnAK;!!}7u3&-^ye?LStfia%)e2*HyuB=sXmY>Tgl-cm&fts8h zSQNgesdkcoaMh6V>p-+J$}5Qe(Rq{2@%lh~@+ZXK1}_$I*xQdwyBKi{H2waYSiVKs zmzs1ciBvJUTC%oPSSx+3n_nl|{db=_1chRpL8Dsz1&*!9c(;Jf24EMR?&b%WV=3ul z>#RB2qJ!m+&(Y2GQ@kjBXo!*{2t{sjcvQlYK{>~j6XD^us`#g>^&J(P zidq@P%GfhZT51k;jWx!Wkjg}lgY_oYt+EroDA}OZ_|)q4$CMXlTykOc2=*ho{&>k9 za*>O@HUc?Sj2f%aRdRh6$#-9$lRi=>XQlNTH_yFRHt5|#VBWz{ppn#jW_QW-Sw6b= zI^8b=|+!0xkxM1_6LbKmZZ%7p=WIw+7juU8g&YW+3 zP-K;9=5gocH!!fhHe+{nQ(?N`4P}n(jnN`EFTv%aTgC?+hVD0y`%!)0!#AG<_kmD+ zov6xHAGGpEJSM2LwfVrExP)WaZ4jd;_T4rZUMZQ~SzMB>kCV5Jh>gxx3?hFmaOe(a zt2(Y4d|h?OV&U1n#sV)75^sB`COh|tb~NfLl*8Q66+XWHxka!$U0&QF{Dpf&M`r}# zc4s%Qhf+CMi>Q;NmJ~>6HJlkfU>h>r)lRv53vWag*`>~mc<-)H=Zo3M0I)tjz%4VU!g>AAMO) zMGBJIiPx|^gCRGLr&NYh_r$r)3R{lh5}r7JgPZ@vY3Q3aN_`x#ZS7Dy<^1M9boyxb zzp?AzlP*Dp0|%&yF}V1E>oyLbk5b_yYvoz7=6ZMApDD?#trXcd)7Hr!x%(&EWm80? zR_9IL4v_q5^KTknb1y?sWUMdMQKX9Pfq1(_MYlsnVwM|+-$g;$05KHBt}5#dxvM@D zY~b3+xC_O^hnbz)eCoCDT{&9~kh+j*fMib7Mt{jEle@p6ASfoYFlJ*GkL{Xz`1lxu zTOKJj@~Vj37{q+xLv+{eJ>Fp~PD91Llba?tRG)isPKXN<_!RIoKv&RX!1A$%5dK0U zp^D@KW$eu;Ns_&Uobb~3y<1|rL;OB{XQ$m2o$@;$5H+FLMC}I(?*`2YU0dm)m?|If zba!bC(71SK*|W1lbb1Hwg{_gNx=r-a^VyczR1<_QL|ru*PHIF^zXKTt8oFN5O56y( z)Lof;rdx$+uYIijQU3TP$XYXDDFLGjE^aU`WA0cbo}=YW<$?|86mpjjudP1HYbt-S z*Mr#j{KXMbLG|pn77B$r*&*vqC{8Ni>qDU|**_dn{A9nAcBv0p`P5FZGZWZ)#1%i! zlsML+on;gK;3O3LA@M&~=5xl@8R z-bCY?NWoo-*Cs=@+67_HV5rlcUKsOje9^AB3wg;HUURX5o&Q0BDwY;8g^)QuNI7d5 zx@?h~1n-gV^i?CUcM7gktaqt4m0o=n#jp$@QZ5iQ8BYl~Ywf`6SI0=J3tKs@+96S* z!<~|sT^19#)`Rc3UTKAN3KOI8%wa#3WbDM@J^UETS;a)l789Hd?LI3q%@?5?4fxNc zO)vf*pzXKnY?q$aTb<7%7UdtOV-!`exGThB0W+W6=T!0%OZe`~Df;F}-Jw15$|HJ1 zx!tl?I7A$~zW;}2(}I!KV5{BbU}EdC%BQ;U%4II~C`EfBiML{8Dv-jpAA8}6H!^-# zX?Pu4wb9NyaN+ue?tv72Ld!V_*kZFdJ4N8D+s^ro*{wcK482@_3_9ElrKu`GKn0My z2fl>5Gr9iOvG3UEPE<#>7yUBmLe9P3YsP@X>S{bq(QPdKJgvHo;X#9vlh>jSPoeuC z(*`R%8m6rJAi?@2H`Pdh3X!VYt6>t!VE3@PsnvZZI840w;~=S9rb+u3G)x}(aY~h3 zbPr&d%(cLSVIwydmLP|h685FMoCRJ_MP5}Ehly~YGB%!x!xQKG)eSa6I4G7N{bqj0<9qVMTIUixMH;b7 zvN>kV^57o1Iz@^+)Iv!jB86YVfE~rwSV(UFZyTcb&lNrNj(I)sGKcx0$~iaKq-(zT zGw-gU3JO4TR3yjT{(Zs^AbG-KA90Vlqe}kpV2G0EBS(i{Lkj%u@2?LL$N}Bb z6i%|t7L1>Li070L2XTU2}d1t#Ju`upfIz|{K&DUXvr@N_RBYj=ACG3jHh@GXu(d1eiT4S@Zgd?shkEnOv z&fBn{?f!uHbm+(eSr@5Lx*^YC$TD(n6`x2Bo)x74)h$~rYx%Xr%Dh++&Fp;WTzy%O z!&qel$dQvrsjf@%7~ViO`GUzX+m`BvzkBtmkD|aQjNcFOcny@kRtxnk0sjrk0sji+ zS-de-BBnXHWa493P|*Xe+OCh`Ox?oLh+pEK1}h49n00L%85dA*hy@!>53+Yxf^92bU#*91C@-BW$yv$qFRZQq~U=`_|nbQd(Cvwbgoj3SH1D| z>&s?V4ePDKdxWsN{zO`n&4wcd{U3J)oYKG+N)Wrf8-KTW@I-|i)q&W#rIM1qGLK>3 z#RzIn(^(9^!{GVPZ?uZ%8WFx|E5Y9)OyZty5%ITX<&}mQ_o{>;^ia3lksnO=43BLj z4EQeK7f*FFf&5aktHwrJP84;knePj!w0d(WwsP!^4TqCU#ndvQ&9=*P7i^s^JBF-` zxR2)gUAISc*6C?Nun_DJ^Zv(YzCD_uzz<<6OV6X(y~nv7_NTq6L$k3gM$-`7^$K3! zgqha`02OCl;kXz`UmuR)2=vYOt?~{&u)@_eJ8*UKhtUK+s zn>Q`P;Y0%X)R>v`ucYnVvyt>$9->gs+KaSf!Noj=0@x z!%M7M?Scu%PS5?fcLM0Mlg}L?rb;R+=QdBDjP5}dCYn`7C3+99&hKL5e)Lw(9G@E^ z8ZV>esUkpSTz%>o>cH+j^Vp-{l87$bu&MW5d6@Rs+~1#3wgX+RUsPoU73i;CGsJom z|71ltZkrCq9K*dEo3kgo{!<@2)o!rpdXUsem^zb4{OmF`dejZS5$_kNG?~glcj2ME z^09LbJ+swD>d+37Z`m2; z*lo3)o!F{vk!xuga*ejJ`}jmWw0M$x_vxumx{lvok#1~j)x4p!h_h)>?@xgCmAJY5 zzFznLI`ILo%Rm0zc^tm7f;j#!3Y-gG9~n>g_!xuY#Xreu@!XI6CLyxOcC_zj)9~4q zSM(SkahJD79S(9%iBN-Ato!_~8uHNiF4B~<><;m}={E^b?1uoM#n0~){_@wbU5#LL z2!x8}JqpK62rUwUOCu~E3J2o%quU{#@tdKPc{1+TdUi<(6 literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/packet_layers_full.png b/doc/src_intro/img/packet_layers_full.png new file mode 100644 index 0000000000000000000000000000000000000000..6ff501b98406509a95e2aa5cefceec3b0bd2de6f GIT binary patch literal 10547 zcmbuFWl&r}xTYZl*8~Yp2rh%e;O_43Zi5E~m%#!70t9#0AR$iwdsEQ5(gj0Oh>hbbp3sSXGC2KX9Vpdh{0Hl>u- zuMMh;te!g@99HkY0-wZ$MFI!+5l&80OcR`WwCV-M)4J(AJ2|8^NWc+C`zDG){T4+Q zI1~Eb2URxFSjrd&Q3{8PUP|f`ADsX%ER>ct4^g#HIw~kq^W6j-YABW(W!ur?^Fk23 zx|Kx2Q`Y#!sUW|Az)g0V`$=Y2+A4i{c{vJYD2});s*UH~dT`cCzHzZ~-YZfa3G4B_zu+!;h+=F|hn=eHWZ zzphGI8HES@x2+mR^_73>-Q}{bRR8u<@u@H7|1Cj2yF=BG-u{h^SC#2vIBaDmxhNz9 zfv2>PuGf{bD7CCa%r6AxG z2dVx>ili+%X?WiKHa#RF&^i3tS@Qn5b;+Axynspf=QZ2BB34uLzMR6eMzb2-{o4l( zHRRGSnb79%Qt#;0GU9Cd*OzwTXTbTMm8N^)iKPK#wi;WEzKvObin2bS&?o*09zTz= zBRz>Jb?C}^%*8YJ3a@*7xS(FrDU#|S_Xy}F!ek80`C@rA5${BMxUUrddCe)IE>JaGEVOV2sQ zivJ*zga!l3tgG?#W||dfuGf*YtCy8DLlC%^JW86Ui5eXFhcIJs@r@j1hduJGE3z-` z4`}xFBDJH*M|@Zf5KTV*r?RK;Y^u6 za&`9-&v5F_v!@FA?U5@M)`HBOmTEMNYM_%~u0reiVm;^lm~_yjUgFLsr0=^S`hGJ0 zK(B3!G|CyrAGxs?cCSppd>e1MbG|@yRLjmcZDr23mQHQ%X|wgS7^AAnb0Ie&{ub!^ zCHvA3W+$lZXnxh7xWcsv+pMGltPoUQFVWFj$UsyAuGl)SI%S z$|{o;ZNON0+Q!(x@qMj`FYXRqo$P=~a>j1mDA7yQTc~l9WoU{_&J5!0=My&4W?RQ(@T`6GEJ(nvZr$VbVX*N?{SX^we492O(ERP4Rjav!R#4vRn z{%uhb!OgOb@EV?*@!}m{J3<_7b7W3vG*xPLXl4RNA$`_pay&P$!1enQvln^H%}c2|)~$mXtPOO}(N!}iZIOhy zxeKt>05+xL%8gZBERLEyrrUO@YRvngVXATtqkIovM{?;yjd+-CN4rY zs73W+|E6*!Q65udrxKxjU9%4Uy4F<_`+C60MrKwUvh`B=wEkE(FYHW zeJTqOid~Wr*f=nine7w?o1jo#%2O4GhMx9co_R2OMcM&!*2}y_top19?GF+NTHcKl zWR<;di9Jn~_i#9}66Ry@)I{HxpCt)|349E)|E=N2zv(`O)Ye~7Ej*CQa-F$yie8(x z{rP13yzxxs{PC}AE888Pv5&>4wqc`9$BpShW;If{Nh3KS@c#k_8g5H(1rw@~Fi91fwIM>K!R-+FV@t`4P z?#34Tb?t_Hq!QNGv+fxxlN)E2GLMTYw@!#J>$JCxOyJ|yfluD(bKhH%+WuC%c2?_m&Nk;v`dRdPr&D9}LDHCamV za>@MR%^A&!fgvXQGD#W-s3HlT&b2=Nz=4&A$s%#>alBVeq_)Y_@g!>86dqCu=twrm z#A$O#Le93cR-EbnX2`T}!7g;b64Rmx1K+=V<5+VgMFJ1QQ<_WK_bXcNE;}(Emp%Xu zO}hG6F`$@bCnfY^H|ST!GVPRwTQ&!LmJF3U_^ zWZgE8F1(BBrQYd*ZhZST9V5cYNsnYwblGfz9jPDGX-G}KePqX#3)hdv*36U%MT;+s z0~|Vf++zABlWSpOk3L}4-?O!wY&i~}XQ+rdbLFxxqzy;}yR#w_WWat=du)KX$Rpb& zZ!gTHDkvK@F8z<_rARcy7I}#OoYKzgJ@sKf{&-{QX7)sBm~F3rI`mR?Iqeu#)$>aa za{91EqWzrSQ%@IzezYCXt1yej?mkmOD#yjD{Y$>;;m6-U)W`if^jktMjiZ4_31VVu z=M?4P;V^JJNbsFW70f=?T}Cd}NK9>Hv4EGS_%qCanTS34#i?16k$43ev%r8n%ze90 zi+R;1LLn9=5>{8jn(G6G!EC!QMx84c!0fj@3|vAlG}Zo|;T-{JFoPQ#!o!MDZ(qGA zn&j?@&dz{!Fk!o3PW{MR2dwUCK(jNJDrv3;;MRjyQ3Q@bbZcy)8pCiIJKk=h>KI`e zDB41|zO$NI{cGprv9oGsXWQ=a-HtMYLXWj@^T-3zKF_ev2s|23j<6HrULyWqr+0+=-pdkHv{f0!5I<1ZKaCHZ`?iZrVgND(>v>@h16 zwsuLXam%UOef(p^jt|KzhbtTjuznOK!f{>4!z);mZC*Lr)K|y5YDPTXaVXQf0|MYG z#H-46c%=S-7P(!x@a9yz?<9p)Pqp@Dty9ErO2+8p4}Oi@6h{Ith?jjeI_NvCVUf&78!xcTpCVL+PCh-D?E@M@b0n5sDKdb;gToo2HCB!o zc6}e?BC1Jk1%GpRO%mN-WsimWbVneV8hq=qsVy)viWSJc80m zz!vjk^xOjb>&rf95Bi7#5os1robdLjNbAwNH1TT8wUCl13ZUA(pR3FC|4AjxN08J< zI^2;LHtBD+_E6(Ncq=8oTp~ttaavAH2i^kgwopiSU>nhPHH>%7lFNquC9UGlFYfGicq8TlU^bA{Ps+2er;F% zYKtFdn_xva_V(+4`f9G03r4EaZ3N&JU0z4I*E4T~z7aC{=<>d(nw5}~p@1HJM2 z{o!=Ie5L)J4F5Nx`Y%-3{(HJ@9NAiouw@5&6)nNusiMHY?<+zi>b@|8OWp;J1bp#E zj^087!_zN(uT~N@g;P36nn@H03TcCoQPT;rZP+9f?q0lD%Pv(*9^Xal8?{(6IV$KM zqIq6R%gWJi1rsLXlX*tTcb^qJW}}(r%I~D;{@muX&qTNBJN|CiSbnzKQ&Yvi33IX` zdC|`_P}xpoU~wb{rqyuTHMe(|K5yx&;r&_)3H<0ISS!fisLeKlxXl`V)iAMow((^yO&v4NnL1XO^xMna&b;aB)w3Gp`;uu1eG<>Edhaizt-JpB(>S*jv-wF5_*supf>L~>c_ zjrLeI*~PV1VpLS{ePRk{$E>sB5isn?)eBmbkdCJ^)JA2ma5ZVhOjfjYnHE|J`oNa$ zXYM1&rMVCMTJ;;@5csPAasWY1b7xM|X}5TuBK-IT!Axz2Xg2*Gb6>SljBKChxHom9 zp0Ck^$anLkU4jO{7eC``f?SigU(@Wzr8&GIHHrKJ|W6W)uID2y0Hbj?Vuod*~x2$b5V6%Ed#P<_ZIT&!#5m-+9j;uKx zM910W??mLjP1>WDC^t0fPI`Mx*iIqkV%Ou_TEC5!)nY{VBcX+_;je?C3QulJ!xt|o zO6S3-wrv2`P6j|g&dmt|ZJN9Nt|sc5Kbt|pd3C>J9+1nMv;cWmxj-bLf60?vg_YlU zLCKRTOV`DcSwrzixKdpB)UM=-hL1c7gBd-gEr2j29v)!nZt)sB9v*0@U5{P7X{oDu zl>(X4KHKWXIiHapz8e?{`eH64X)H8Xd+KtZGy98 zt@E^5tH@*Wfk@T%1B|H9uHkf)T;v{EJ8%Bci+9PDbR2t%!*>nrGvhkKrvu>DUfcf~ z*A_w?7>q#D0o!TvaB?ykzozxKU9J(IGt}*^)lElJ>*(x8_@+y+e-)gbWjex5cnn_# zH0|?j%7%yfW0O4uJ4;2r5YrZmA+tuVp$7^h=FB1B5uWkewuh=+_~m%CjG=HJV>jCDw1R=5kO)KYR?#dVe0<4Z-+lBaOp4}88^flW z+7z}Krb09D{*HN?YKwu<&Nbyrb8_h1A_A*dM4__3zY>sfvO%_9{zCnaIx8Lfg zO0837x0P*@*Q8Hi;^ENcJymUFV3pWU1WnhGjXQQ+!)A;xp6f?%;$X*i6XDeqlz~#N z!zZn3?{`MbOYkhrF8*AGv9d5r-F*m)`ST@Yt)BR^VRQ?Hl$_X(dKxhcU#lfdl!ycl zfn~N_zkTl##vEXVDnsrQBqmXmotV1RBk{}!bNw?wBC; zm4ZdSm^dDA?nh%2YOOrsQf4E#*?CZeO;1AP?(RM z1bKRFjsRE91YCA%WpQ~m&mCK3^@PF>tnorJAH0B3Mz0TzCQzYvqwae9?)OUa`~M>F z{J#%#@Zv)hx|GuT;TS&ivP)*h(oann_fDjw%TQh?S}>=}82v8=6RSmMS`TRidHwfg zQRD(7xC{(?yXjx8#YdsK&G&G%L{2l<YlGg*o!=^g(!_j*y+54u5)kyl>geDhm5K4 z7Km+~aK={}HOCobXA$unqN?9GTdr<%_Sy|=bQrL$A_&$FTeQd|gQTGyz|S6wajqO6 zykt&0PM$@tC`J@ibYvpD1Eo)v{w$5Em2yLN1!`z!50gGc^Lv%`lCN~`e{T6A?~*H> zam?k#-;=B))12p;pC65Bm!>@9IGbn;@^_(+W!Yx@vMW@fTYHS7GlRy3LEanm3aKcA zOF;@K%O1o<+H5^CZ_RzVGVu=rw%vXUIUOt8PAlm2yZ4&>Dj z2YZj9Blj^KZe%+99$3XP4y>fIpZMK`DjG8-&M@;&)|0`8(7_Nyk%U7-a)AON9$K5< ziWvO{iIOA7m4s$2snWYGE=W_~U#THZ7k`Bs&6 zuvt7@5^djb^m0&}&{agHp!<_1S(3DDagV{L{-$4T@bBE&iC)`2o2wImkhhp-NkWP+ zI;<}<2;X}CylT>|3*C^%u1wN382Z0uK!Vp z$ceV6(}uDW%jpRV-BbLh5HF)BBH?3D>oDH&N#u~DCi3d+83!-J&H z_T&d+sWsfYYEy}F8Xko8jAdne3q0h#4iJ0Gj2rhf6*<@ttH7Pp^tdG5(#Gmf?klpf zIxk-_cUF?cHoIpecC6&} z{e3y#Xx-!bjniL#dp&ZuPPOLUj#Vo%pjzu~Vh`0F+=Mbtv}Lhc;niF?DOEG>=#qNA z%L({#`g6D>3oK;(<6ia3k6xjQXFG|=`FuP2=*vq!)0Hplr~bF}*WgA9#Y6!I@J(8~ z;^H$MV~{!$^xD7FbMKR}zwbo5!HwXOnpj(+ilUmOt|RhJZ;;J0%S`LN5YtVede1oD zK@cPFtYeVBBk3&U$#s5FtzL`7P`R3BGnuvP4ug=}i4NUn3|2vQw*BOmVqPepVM^TV zY}JL13x0@L)_WMuwg>TVc;7K5`QYi8A>*|i-@R|0TW zSCw&VEk6KcYPhBGuE3jU->f<`G}wq3_I^KOi~>kfp&hE040;p;J5!m;&% ze^b&k_^Yzv05Tw@>y2ED1^LF}a;kBfGY%WK;tqz!(N5fk>7<@r^X?lPju+n&C}v#{ zYvf#Q4Q&u|)KzCM`$b{J(Ftsh2XuQe-68|KI*hv9PlO2u4Qh&4>JLE-eUVvW5bcW5 zh7tIe4<(b+v!ZR28bs@$zt0*u;%Q3-sXR@@xqYTHd6OjU^e?SWY{V0`n1qh#Q?YLd z*@*G*3=ACMNE)pLfuDi|1iBXkE{^lKHvg`Lsj1l1xGczukJ}_s%Ih)S%@w-w6~P_t zqT^`1n{Imds4h~TsjqSy|I0Ue_MnAtdo7Ly|EEv!t0vcOOut_hbz0M}4Z?ftYsUvS zTpe?nTf zj&SjocJ8lkOVjd5?p**)l5o-A#JGyq4$KadeLyHh?YMBz{4~h0y}~hfI7;$zMoG!w zaA>`C{sfzfy@&NrOfCwtVEQ2T&9w$P8j`R%s#?$$6CXKtay|-6v_&% zIiDx360$S21>R5@mwQI06$o$1=6l!XYq_mD)5y@e0-q%rPJ&xN&kiXVXi*6-s@z

N$NTCu^1Yp0I$S z8|e!}rjS4UY!3;A47#;#fJI+_bQgtk-rgOn_fZ|^^tVWlsR?Lod03sfR`3mk zRS=5vi6=o}O^Er9+Rqc716$0J_*cclx^&(u?&*coh|aP*&JB=WdEMCK=E=SIdyyGu zj^VaH!siStp=~(C3>AvTkjp_dw?>pHaheTP`e~EZFdoiek%lViizQWBJacrS5^Xk6 zcf4j$q74|vnl})|OW44$blWVHYi-zPcMY5%ZCj29FC+f}KyqV+k%@;%6I(EjJ%BOL% zuKChGqAaB)T`3U+9rHB%tFFw!3n_()elc;#pLdq4#@TNmHnzsX5546HU`xPD)@K|g z>-Uoajk&EWiSdiZDlZnu=-cEwQ`IF+*0uvOFC+>Y=mAUge{?5(t~QPqJb=Is? z`kj_}VI?}94V=s3m8v0f1csugndS`JquQ9>i%(c~ZuqOxzKwN)gF{*T=LN7~>@^Nk z6ezXz13#gS<&sC};@(=$Uhe_T4pdw&yl(xlTRDi*MUFR%anSg4l6!@du2%pdzf@gL zDFzKrJj9VxX}LC|d%`NF9PP2Kk00ZkEZYEfS|-VdOpXF*JlwxI8BHn3pdGU7<<7f1 zDHk=&Ep;+*+u|5*lJS- zL`4gSy2k|sSci|nJy4{3U8QP*+Jk)6e%l4fQyU zd_+%7Vz}Hk44fXWv%fVJ7D`$k)k7QzS_}0W-o14!$ z#R;Iaxh1~v*i}PEB(8-BX=)j~n~N#2vrI6(B98X9@N>;R31*{v8J1c`UapKkAzs91 z1BWT8UZ=ItN0yI>8Rzw=C>XhRZ3#YZ$f`A7HIToB$g~fN33&d`P&B!Rq(4G|Y84JC zj$t6VXrr#NH57)yLO~phpZPt?YI3{*-=P}t7@B*J?-k|*Wn$bnDi^X64z#(+{R!u^ zWc*f+9APHW?gxW@9DQL*Fj`zs+Qw-ov8UnMe0tk@#23*^uz78+N2DNDeY)7yn`||Y zdear$^=UZ4>5V^q$l7dOwHNF9ANDPW^+@PYN|BZP<-uk>9cd~T=PJkeYg8j=MZ8{s zOmbSq@*#*6xW8|!wSArX#wn|umP3h=cDm;vU6EFEHgqq~igCX!>B3>4)ql1y-#qvE z@79R(6^X`!l9}(ys#jSdZC|3>N#v5czXzd$j2)jpEv3UU;#azyRB~+0q&C-amTEq(EXAFss+5+hDauWexGBIAW~T6ztTdT(8xKKUB!DiC zvuDti`JW^v+LL2jMh|*Gj5xFDX4vBISm!uR#F*l1msMNz{5|Nf-MQG8H*X6ve|m=y zH=s4>0NGi&?$;!%Zm#==*MkzLR}Vs(zYZ&qcn3~Wl-|Sy3e}r{a~1*lV4Ggw!>78B zzTN5;TUCLv5@O3g4VjaRtRIkrP(8!MOR=_ZxJ{b1v@SXhH>}f-UtU`NH#Yq6e_%t* zf7noZaL`IrYf#gj*aC6x$%!CQaF^eMI^(X=tDPr#n7$q17)Nz?p>)#566xeyw=egJ^~ zdSZwRy2NJI5Bz?Khq-|sn7d&c$Z@?rJ63JDc!hruTbNj`H>wklNjN(fL1_}^RwIRt zbp2~1ah!JY)`u6pV^uWY0l2SpC=ZZ9#QVVCPBE70kVlUgLpPqv+~9>?toV^irlE_W zX6xxjWtKXhYQE;k5~*<}I`&?(70aSjI>z49-g3yWf76N3?Kyps36Y$5mp z7P8T6{Zq4Im!87C;kbL$3t_m|5DLih_g~P)LFK&7TyMYD3K86v7&F_zKtl}{xBbjm zWlBokH{TRTj#cN#l&OT=8LG$mA^t-Emh8505QO1yWfolo8Bvz@KBA9?%@eV)eLD5k zX=Huvo3++$Xs?$K>~ zj89C@0Cy0WztFhHwnh;!d_|#i@pOhU#bt179Y^tmP%+`~EI@k18@q#SmnP&aD74SJ zomr7g%;fyJf52EQrlT`B272ah$Pa9+w((6A{sq#dbYNlL)MaMg=B<1nn^HRUAzUcw z>KisSAoC2s2#~%wS*hg3u+uTyV@V}MVHhxz;96f&DZNY{7{Uwek9ukl~7TV|?o?6n_aFYV^$uTmd$clsgnM(sTYGslJER^FC?0+8D+)@!H>^7Z ztI4(D_bf7@E;NBRGzM!Wg@-R?y`$vySFFsdX!1T^cMh*^Bvz}@h{(0h_g7Eb6UrS^ltI8wOaiYBfj|)ExULK7fd1wKS(4|a!_7!|m*qos&@SaZ~ zU=TB2W%kaHlb?IpMM01R1*2PVX)^yh1TYH zk-(9Ru98j;6W6X>SK1ubP$p59V9DsU?R3lF*L;-YMtk`BDWXyDjN*4UH->pAYri+C z`F7-nR^sMfS+DT~*uKgW_A}*hMPo^z$r~KBt6~4?$<^)QZjO#%CwaB zI<$#GEm91XsHxerU*{EUSTetHVf3o;nMXGT2->MT>nZgD*G5tteh7fP{mf|aTO=Y@ zO6aiRmnbTH6*3S?s_Kozz&iU?pyBFQRpBQ3yp$|PZeO;nZ1}5pC}T9;yx%bPt)MzR z+5Y#pvBnLu&wT?NA_L2cD#l9dJex>JmnKNO|&m%poM zz22)vl_*hbMOF7?$ijzLWmtm1$-@@3S)#JS5qBg|%cZB!cu_;_4cTpn9nRccd* z4yu38Se^zPicqOJIYp{j79^b>!Dj})kQBhqD)tQPSuMU6$!NN0)ektRzZBM-XoC6O zHLn>@)QDf+DAd)dD$BZw2UuFw6qw6|o|N5ow=REYc+M3j)f7KF@u(>~s+35RDx}k< z6wk{7wCun-P8zfhnPlrNjTvtAwXZFNi!9xpHCuk~&%)J`)o$djJ-oDcFE@BR`cqWg zPEu#f$JiA}pv4bYpAu?VTNMPM>ApOlimrGK)$Fz~tQECZu^hy;7%LQ*E!3^V9KiZO zz0%vBiu(_DC`H`?JLuGBfHRHa-?G{TqVbJbU8L_1I2i!mp~&N4v%_$@a7X0pyUCMp9Tc5^yrV7f8*!mIVJA+^g;B4kLS*go=IicEF{27!NhpejHD5~n zz*E<=6TDw#d2Mt3zOGN6zRF5gVDFd~TgcY^P^OpCl`v{%#j_4$d`(tb1Fc8OPeRyx0B^Xdp5&%2gmtFx<_psII&L)|VClEd>Z zZQuOX%(nytod|nY2^*@;8%dUZ`Gql7UreIryzxEe5QF;c+n!06q+9p=Iyr#8_IR7p zJ;OU4+sx2HNrzEl1x%mOon+Ea>=XCq5Sj33Cd=hzulDWcy}i0XbR4bxm^r#I2Ha3W zU!D97yZNJd9t8&XpNTBL+E5s1>@d+kQ2r}?#65Sm_^11j9L@jnO+U}i2_lIk+>vH( zeRoIs{hRCs?11hFelOQ`w;t;QMB{N!NJaL~@M{-ELr9j<*uFrsg;;ae?vGl~{XF#W z0S{*A)RohS%5@gMP>x-mO?GX&Nm!e3o+`V0FtY?M-#K3ASP}3kIPr4Fs=Pk3$i;f+ zJ!9o5<}j51#=76k1pLv&+3W;eiwwRFe!8(GXCb=G;QwcZf;AK{tLM*zzHpXj)#AsS zIDM=u#P++=%q^FRJ4I&%q&Kw$(Ccw5eq^LiNJxmXi~kimD`#=dYCwAT$H`vIIqjVy z1NUX^>odC~pUHAj)BrO!Bq7W#)~#Go2as}S8QVztRVg{Z&)LH@wfuv zNrSShEWzv)F>Hp1b8sG^;|75i z^~Sud^P8aEQX7S7zY+!$qvF*I&w>;5ql3#sTO9(Nf1oZFp2~G|p73 zpgHp6jumL z<^}jAm{9&nJ;Uys?e&y|$DHdiSzCHx5(`9lD-_ovBa%MEpVaw)$de*X&RK(tQj=Bv zVsBH?PsnA`=IyHhmuUn${9i6YPe`n;W?Es)VhMEf2(K{1$l-0tz`C@u{3c|4or}F= z1VU05PIC>+uHz*Gs}yhcfo4_ugFWH3^0#I*k=kM!SkS@yWbw|1V#1rCYj(Tij&A4! zsZ<}`&xDlEz6yjtf}XQk$JuuCeq_NMg7w?qhcZ#L2X`HXuM{1wTwu9&UIa0!e1GMX zE#EU+#Dyqb8j6hrFZJFL0`x%m5gJc81RuZfGBx@DKi+B6&d=>kr{s(Om4~0(*4oPQ zK3#2SpZ43c+2cL!XhORxUk+OuD!y`J;bHS`_wgV`t$b1v>`#xHohmv^o0Y_`%s_YswM!)y0NkiFj zA*Ons&=S)wLYOq`D_^FCb{n+qj&UUB`R*yP2+c)d`&^n^2VXmOm=txvTj1yBd8fjU zt{J_NzrLtu1Xf(P`nc4TllE&s%vD7{dP4C6_<;#BI20=!2Yj=3(P5G=4j4@{IMCGt`Hpt!QSki-w~zs|C%R%+e}J}b z+x^>5CCK2Hsq*6S!dbbVwSIdf9X58T(|W@G8ervF_wGcui| zOZ%idDb@htjb2gZd-{BiK(cS#SlI{C*SD$F?7lp-ES4OtuQ<7hP35}t+yY{9%roGE8+0&Rl&QR zw@>lG%ozz`6A(L<)DnRa1(e$A8}P@s*Q3ImZ`n1-nln1pK!vi%RZ>|rg&ry`cXs-I z5q6e~V?6eg5yeiaHRnLjy6Z1GY{VZ@F2&c<6D+qX&gWJ6oAAvZ_&RYVf zyXJk7v?S*2L393B&!QMj#;f6+3@Ei$??oITS7a+PwDR7T0|dMOsPXXe^|s$2kXn-t}EUji4Hj4 zKJxdvwuMbq0EiIwz+xe4(Eg1Cbi)@|5Vg3eSaSC^t7Px=D|EErJ>O7-Hhrr8_(D-; zxqk;!me4E{KNnGZLTUulf`%^EdapS_GN#wMq+=9|A5`ejLkaU(C;yV} zMd8+7`L@yOcf}WtHP%k7i%B%8>K(U^F7xu-%RX*4Qa0K>)V8Qi z)16`Bv1OV~Wt1e$my9{A!-QTW@4%iM=RI#Y^&`fg&B^2z){g&cK>5?whVA|!QSo=c zY`X)61&n`ZO7ASXa}g-CVvr_>RSLa?d_%eO@wpjX8d}lx`DMvXiBGosLkCI~7ozm# z4=_|mm*z?}mNaoK7TPaB2jk&dIXN({c7Vf}WnUb? z7RvPUi9VdbZRpeF(`{smKeQ*%{(j7UcO_o(&UogF7O+OB_`5{JrCg=qV6+_|1CwI7 z+JbdaYhzUT^{o$R-}V5#g1$@x?H9j%#FO=y0Ff(}AacWgu&iQ(&`UFL7B+{DT)S_W zd%?#6itUqosS|_+`FN4;k{;Pe?yptLXFFvbSn5}t%2cAtrZSF5bv|t5_VOeV{FWU9 z8QF5SYOhM<(ch|1*X~uDDgfwsnSa$`j>OWO+Ry>l$A`>{eMij;Kr*ea;l=)+_aeQ0?*WQZ(Nc-}GyqMi-HK#na z{Gp_rfFBc;4auk6B(6+<47+L`xt^YH^bIcAG8@T#HfjMP0U&}xMb^8+>&TPH63L?5 zj{PB2yA1`D$kw$@SUS3UHWyI29$0Ot(+^Mi8|x?M;cgXVc5|n31|QeY_L%@G`ZRc; z01OoD+1^kqe7VOkfFy2=jpIG+@1KY?#t&{FD}9BE{D>D+9cT-uBBsNCkQ8QlJT4Y_ z@?eJ(YTwnIrY>;#@cbZq9_{^{bMS5AORO7t!%v;Anqz(krNlwa@>TbvuhN_|SY{hg zEQ)97N4|Lk{TDv(?Wg(sQa$fbrxicLhGS$+PhkReeR543=~41Pxp9A=nQFRemnUOq zR%?IDuv!95mf0xhg;)K~O%=|tV$I;Y_%k&0gBS;~@U6&I>-~1(qDH`}^wA^l_GY#V z;mv^T3FF@7zF5#wT)9`ks5A_%e_ePPP04TsrF<>0$-1Z}xp;H&5P4~gwD$~Nu|Jd| zdNH9U*uk7$C~2F6q~sT9ZfA~(733cRBl|`(c@WO-AznmN&Vvr|`?shiPhn@gLIGol zHuKn5zRiq`;%TEvReg1VXQC(~ii_6 zCphWi+PP7oH$i)N>2Tx*UBW^h+9-{wsVLYP3S;TjTcv=8S`P>*euI5~g&B!Rjc+|) zEwbN^O)jLbNsd}7-E%&)Qeky?la>J!E1TMWj^Qs%P0!xXvYL5C4VpQ*X+Zy$ahWsj zG?E2+R=b>Ye_gmOnJmzGNgF7v5yl5tttmXXz^V*pcX_AR*tero7-cY02uY2ur<91O z$)O0Zlvq49uHR`>9CeKpE#ouM__il62SS|jxXv*x=;l%FXY`xOT(V;zur&mVxXCBp^2NOpG;0E@- z0g#V%^ZG?ZiHwICxZSzzsg^dBMy0G@hT`t3-IGmgM(QsJ{OH7ft6FWRTl<^-;Y_rc zVCPjvxCPwGUtBl?H3K=J#*597RxDpJwi~E0&EjdX;pdca@u%qNV?Ogp>3p8dfGqSH z#yGqE>IXJOPMn82`^cOeno(cMt{!KJPTYs*;2uLHYyH}(>kIS!$8PW9KBBgk`OypJ zA|J6a?sKL0+j;5bL16x49wfw5naj~Kcz&E74GG`Qq!zVQa{+U~*`1#KzKa{$@vXPZ zToKv{Q!BRp5ZypQ?k#%m_Yt7`&S_dA4d>Alw6fS_Y{J=v^}#Apa5W;al{y|w>^T}a zY2I|FI+S-3h&^Uh6NNP$p6baP^(&0EHE^#iT|99rh1ic3J7BO7RK`jLh zLD$Rc`Vk7dJ)CTcC6*S;ULz{5C-xYff4#o^8fI>ly>pn(IYcm^7YV6(Co=b3{&+w> zw!>d{Jd;&PAoFEeu$F>koJIdwrKM>X*0H>?}&E1Li>NA}9pim3CvcAiNw2~p`hgX^j-O}91_qHV-! z<;B~tOe#SO$Z2lgECnl_;v$iuWQdZ;M7s$uzH>WHOH_x+pDf+sKRAr&wmiQo+%Z=> z`PMfSq|jx&-?k~L>S%ru>u~#M zG$pVJY$18$FP6?*jZsB#JD>X0B)+|*uiq*#MG+XPcg}eQG*J!3W-^Mt`k9Y82}7btYtuTRtZNUS2gqx~)eWrZA2zu7vOl`m z9#e%5*xm8lMxBGe7YE$ni+g#-SITV0mn)LGK#O<0D4j~@6OLE*%p`Y_!n8eaa{Z@7 z(BDCM2T;s|s<8;>42|vG>0~5v5yS205s!{9dk?G*OXuGTbip3ts3!acU}NU3o7=zA zDI&e2W1>ELx9YsbO9{36wtj6`Ap(5na4k&#m9 zv_x_bdAZKF(j3khJzYX*)E?U;aHyIsKd%TL9!9lh?g8>XgK8?}8b^-NNO>}`q+53l z(LVXU^leGF6AVe zT8JLj7-#Q!55!UxlRJoVwHR+UCq9qfRQt|6aLngN>4e+dLILbAILK-|DzF;Fjivop zYjbc{BXE^KQp*0U2dzOuEPCBiJ3WYHx$_hwQxpdGET~!{x+#Y*Ym6Pv|8;6i6a)?P zoj$l%Eo*j6J9tXd^NS+sp%U-gveaSL#zq>QweDUI2fBg`Y^U_c;5AkX2-ra1S z|Nf)@Gd;1E`w(#yMj5btV#F8nhZdLY_q>g6P&$0hhD=!(jI6~1Y+dSZ;oH67yLR*m zxF|I1EnrBMh&^Nbhm(bsRTQTxhqS|BmRTKu<0=-Evneo3efMM%^Vi@^7G_# z5ey6paJH_z2-mpp;)$q*X9NJ2jIW`nM zwG4p_MGvKYkQO)7yJ=`?+7~?J5#ogwN(MN2W&=#`|19WLY7GKHhA9ttF5lrZSwGan zji@XK&CoWN?1T)oeE4y6tu4H~bKWO*3cuiSrds{1sK5DnH1OB0O^r$YDpjl-UH619 z>bK&8{zOSu zYh1e)sJOwWD&ugG6DEkfkTVT(=98znwYRcgn8i!%jV|7kPy!A0rR@K&yd~6JBEr2D zDavhYesM5Jf4vL0>50Djd)aSaU%kD6oDf^6SJ>PtG+iL=z*9lU;)xT%{Z+^1W6Dv7 zqr2mV!O|?=Z52%z`zM{wf%Ag^SZX=TQSJy)8Dz}P=WGh+F%7cV$oDJwA6GLEY!$K-BL}BZ$M&<3}OtinB(0RSf@@SFn#cKT1oeY%_ zCUC@NI#A5Fj`jRhnRW6yBUK z=@7DX8WmZ4TMN6B9+PJH!d)EN@yaec)U!;w8;UHoCN%tuV0d_X-d4U^v?GS z|MVwxRz{Ef{v+!);PHgpie0hqnMR3*>+!WE|E>K<8~!3CKcV9~hrf^DYTYVapnJ?F zWZ~%Bsebk`wo7s%l^6j<-&GPNt@|9jd-WU-lnn>gI8eo?UwTY&Uq)2gAc z<|W@>;REuo_IJUI22Rbyc%<=EexZe?rN^e>O=t4xHQWa)kl?fH*j z6mN9X-rf^>5y7-hmT6nNPanfLI9f9sTZ3zjh9`7B59=IcG`HChJ9RW;!%d!{A}!&` zW#FmjS`}-&jwDSx?drzMAf1P6bzM-u%~QKIisDwOs^B&PIS%Rzx6?kv%|{*0(z{`H z8%M_5!h`Is4o!#xBj~}L50d2De1JTMUi`us_|M|1WPjn0KlMCGk_Xqq#H)qblM~7L z%uaa2NPEb(&Y;%`x~VfAvV1X9S1&k zdQo=mYmVb{mBu4Oz5e?p1RJW(2PuoEh|TAZ^9;bfdA*}O`8&w2X5^qn$M9l5t=r<6 ziq0Ra{IFBjnN{Z?ZdD5K8`ZXdQhc^Csc zgDkIO(o2mS6vc#9zR{$zRt}3+Z#v;k#VNun2--lZ^S8qi=4&4~A<@Iv@)J_zxV5sc zimL;FVOJ|MPt7zj!%GNXJJ++ZO;9|+q>}YWi9R=v#>8x-3PeD>afte2m@x11oD5J$ zHo>6h1s3qQ1!XU~5EHK8w+xl78~Z+a@5PnGJqK%Kc=;xSD0TbZBr9%C>%($g<}>Kx zb%IO!_(!RDe<39bO`7!b2nB%m6Cq+xck98ScjZMlb-OX=_xQ;T9eoQ}tGZn6tl>$< z%3_?U4yw=S7vn6`u8~-sCq)w)^p%+M@|9XPzD1IEy);RxUTVd`Y}*5m-`v%8%RX8QtHt7umn zM`M6^;`PFl{_z~N@Uk4$6~uAyz%XplS|-3}RVEuaU{w)lQkQi_^NSRv?Tl*lHv<(H z=PHs>dw31=k=Vs+-t+FRFfNjoZ+qdHddT0uv*hIT42+{1eEK-6j|k)!qjZt#TcBR( z|69N+hkh6hLfKFXVf0mfezqu&4*b@mcka$}=e-jk)Y;X}6niIsix7uYC_nqJ5A z5pW`C{Fe{Dk{3&Zf^`6Ur#n>qp5+)}yc5!Bpu6JsJghHrtcm2ybI~`eI{?QXNJvm^ za_QZoFl5SH?&?>p`Q zJ=x@D{G4}FkxxKS2Aks#B3CtDzv60Y%1^@10FJsB87+YlUH`jNo`(mbZ10ZQ|LuxK z9~1oFzKF*<4?v;cAx0mHn3D{1>MeSjePtN4yM`U?1+k z84Oz2b|LrKr;2teT?US)g4*I$5E#jDNEKp#?AN%?+r-sp40XoE?F=LX(A*El;K{>p zv(1v)75g>D45U||mac<@rrZ2TSRC{qMkVQB9U5i4=@v$VCj;w+Ts+mX)EW*p7(go; zIlAxF7<<#ta85w50u8lpPGxEk?F5nX%6tvApBQK~LkD>w^6^+Pa0R5=dqZ@3`nwX0 z?RJO9UVkhP+;zH4Kcs$`yY0&U6}M>F6UPmqwEuGf7B}y+U^U)8YN67>b74zzzq?KA z$5El$-2G#O>-g%@rnYcCZ{Yi4f^3Dx&9!%4b~-ru#J8Qe1B6{X(lr;X;XcwT%y$+1 zzJqe={d(s`yjEvyL2CW!X4Y*-Jh0YneXziBMZ<6nwmRjTJb#h6evy8Ek@JRh(2Z>l z7DSMHDDWF;9J>T^4%d(H0y9{2^6R{|_}~uEUu_M3{#8w}92haUKv2FMh%y}sC>NrH zB#UMW;QOVo+T9XZAdYAMi!{70?Boh5C=1+6>_cG)5Kj0i^se40t3Q7uOk~joA&;?b z{G5@9bYQNE_nG=Z)IBY7mCC9sx>oS?Om^mMmO`-xH^7;cTqRAQ{u-xy+hZosgaxc^ zpa5FpwOJ`e;-IpHs8@(a&2*dRrFY)Q?maXfelq`qyr5ib+W%pX<0+~!aN?rBoW$DK zNZlXqA1e#;i5*uF!gIDoOx&mZ18=tRpYWzN$>Ft`$R$s#Y{>J2@F+X23{K{kQLOl9 zkmarA9!Fk?EWr&@s8kBHC>`dWGF*aYPnF0;(?K}BR*xrD_-@|lc5(S`zSC-aAY}=Y zt)sPMd%?udci|TH%Qbbq^QfS$Kp95;e#;5-L&U1yEh|HC6JliE#>#$g6s2#;U8UhC(%v0}d z`aH<1xcUgvPh@^~4gf$jd@-DyX`)CMRhAn&o7wmEW7#rF8bU-N{*zo&E}mZF`_lvA zoI?0{)DZ|hK&svg=0pEFV*)>AeRk(Hu+ga`u(YF5SuR`UeB=HK10I&`i`Dslyqq$a zMwC73Kg3WjMxmRxD}J=B?j(Oe#)Rkf*1q8aQ1JGJ1XuSmJ3X-y%BB&G`$AO0`vOO* zB&&gPAzU4zmkYPB61}m@OS_)ap~t(|NyyOG(h5Ot9WC#fHx`K-9mJ-jr(Vm)x;7JTr&UH ed36VH#8nQtVTLqkotNZ51bJy?sY(gs@BafeG^EA= literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/rs16_msop_dual_return.png b/doc/src_intro/img/rs16_msop_dual_return.png new file mode 100644 index 0000000000000000000000000000000000000000..36ef680dbb55c4d3840394c55af158d34675c156 GIT binary patch literal 36497 zcmdqJby$@D+AsPb3Kk$LT?&dKCEcMYC?cRJ9ZJ`b!qA`?NQ!i$fJ%4Aph!pz(%mpf zch|Y+x7Ip)opsjx?)SWV?|%;0<>jRV%roET`@Qc^-OqbvMLCkww5JgSA-R9=&SL~Q zhK4^kPZGiZOh!B`g1=7L+|#f}5YnIcKLlayq;v>!3Aumg))S}L`5|ZZCmV;v%Ud~1 zH%7CleXskR9*=(O+?3Ku$+qZlw~Zgg(@{3Gnc?bLT-)3@uwXv*G2B6geT!efUhn2r zTM{*8@{8w`BcocE$R@R`pBqyfM@I22^{j1+H;ateW6?PGs&_#qH2loWmzd$}sZBnb z*ayBET+|22;Vbo|pBVlHis!a+ckbLtX69JLzx?ENEd#t7>`TqLIP9^vP&P}9|89+! zb-i1IX8h4*^Jnn?jv7<)+`S-(>Nm8Bf0z13g^WJO<=tPu-p*F1?1@;=)_>_ua!Od> z5+0LNqTv$m-1spb2*2ar-T(Xwf7T2$T(Z0C?CjiI=3tRx#>mKc^6c3=0}c21%?5iF zCD;wVc_O2Wi-BI%(m!kKn6F>I7gc3DA=|vOETfI_V0ixgxq8X7mtDJ$2OPdKN%(SO z_Rqf~Ww<@^`gn6BPg1*ErEXB6Mb9x>5~2}L%y$Rv3McZ^)YKBEne+U#B${vDd_pe` zFR!kaWiCYVndG=`SzV-}N^;-Z{4-oB#!nkiyMT-iSYv8my*cwpUEQaoM7Y`G=z!Lp z$YF}gx99+F$F=)+0mybfr`69~|U* z9(ib&JCanoZ2nYHl6X3y7g$2=Tkc%kSsVi4DTQBvTMeFmZUaABmW!)#Z$Ax zCCpLa(cZMw%H9%&Wh|@wEG0UG(UabFbN<#ym3v#My$Od-*~PxTzLR8R^{=?AzCD@b z(kwV>FS&otn~3BUys2a)A91D2#t-6r6SW)1TTp6?ZE{StXZQ0m_omUM5y31i@Dwc~eV^T*uK~MK0#Es7myUcOA6~16&boq1H zv{17-PK+ulDoUQtg35tHBhQNbyVQsWooF2CuV24>0s~dC{!>#^W0}RnKO!d$_Ye1$ z5JU)#_MQ{5n>@K#GC^7)WkFdNz~DD+6}QvW&`|w0!Q*j1gQOdEzSK6-5-nJ(WnJ}N zNY|4AHBeNGjT6hYY5PoDoSydF)HFcKdlo(`&lN5~N|v`|?^M%k2bL-fHsB+giQCH= zUVF<`?dH9@4-ZMlrC}1p$Is6@A|m3KQOgVy@)JGtDvVw2m~=}1y{cq7h!}1$Q;U1`>X)$f=*P9ml~Sqze~e8eu5j0x_CBAbgte#4cnEDKvB=|f5t6&1@pRJzqw z?t9A-Qb#o9j!ShrYtt*U?AfDLdy9k!hep{&dtCD^L&GaBoAd7lEV?hTv!B6O4*6DB zOC!?iP2uvM9UUDSgXCR2_&aeu!|1`hv<7)dOpM=$59jbd9w&yb+sij5K)AF^ykK28 z^m31(hn=r|3<(L2j}P3S6HJ8C7%62PpC_r(6rE>KPikmvG-m1|8lJ8G(&J!vY$`(c zF}Cx`G@Retv){d)uJDkzN^Q|w4VJtlASBj@P3YtA|Fb05fB?xK_GF?HvikY^lgvuH zANTm5wxoNEVw8-GZ^<47&+U7gpUCJ=@8)Ki#23PC@aeo>lSZ zCz*H4P*Mz*54H>jdvnz*T?Al9zoBf2VLxGrDPO7!W|3Rof@_D8X*0fU>%I5u0XN29 zr`+-R`kyu@$A13gl$7V|kvx$*xR`tQ?s+MGt(ou3|I{(Fyl>x%uL|2L7!M}{T(kTh z{&$2Xa1S-U^qD1HDrK>grtk}n5wbppR2|^xDzwHJzff{&B1jev7p<*_3P0hsHr+Y_ zYpHm!LVV}AkoBOnheuVL(dyb-u5%M5BK=h{4nZU(C4Kw?P9Rgy13rId&d@A8jhtg* zB1@dl7+usUw{p#+K=6wlq3d!Aw%PW6eruY0UP(^QIqAL>D~p{!6G66z`_2kcyeG({ z_H%d-a4j*v=QfH9(b>we=7pO112h*pJ`swd7teBYbDw44Jucm6;y&Je5VbWTT2o|w z<b5HTN1%(x`wvVQ$@ zQc~{xTsAvJa(sNe{BvEWgR-_QnLFL}e6S0@B_<-sC=T~!aOomB`OEe77j8#2WWo-! z7h(IKL4J?y8d)gd7YEMs)Y%byskr(eLVy4DDfLqQH+F1UX|QVSZ=`DlzkmOZG*;;* zSLocoe+o&g3LYoCUT!I3_(yqia5 zkbC#8Zx_^3uhAN=lDtKg_Tj|zIVG?PS^V3x~Ixl^FtOX80D{Xucme6 z89m5QucGIS7OHQF5n7qG$fgm$KqOtNaNU?Pr!M*H*NMU&y?TQn2}iBx#0YJGESuGh z_%;sD(JMD^p1XYcvT-q=S}mW)RD#JGuB9#4Kn|(?@-Sw(MQCI+-gPl`{gTgR3aPKf zM>|Rxdc|4onCCTb36Q!Vrl3|_t6J5#VSONj)9SBl)=i)G3v-E4J`I9^A4MWBTvNQX z(A{Hy_NYk@L7;uqg>!11JAeLFgq{ZtiiJ556BvYqJc3p**ONUlQEJbwBglmbb;dQ*81MZ)Ud>7l{F-=gB$Q63|Sw-B!cA?v!Jbk*nU-yVf^KR1;+b>@tU-Ss1v zNV_SMkJ-AFz9XJT3_4{mzJG=O7au1`g4m2t-k(%0{i)|c`Mb$CqV|1*IH3CZS5gy1WEg6E-#SKc+{@)t9oo7uT{8_y6)Nl8t`=OhSPz1GdH z2kdNfNq_?OH?@QdzgOOa=&7Z(Iisc=z~J*k&XQ`EE zJjw_NiK<&#NB~azn062`h`#t%Kq|9$|NF)qwXn@4WOR+YsyayO&+kQ^f*gU zB9xH5ttGkD-rUBX-=Utr98FEH-)46s8-X?w+FGIehTEAH&ewQg11Xno#W%MTClK+C z^^QOGJvvSY0YXqegPf0c$l^VA&5RB|T$VXUMdt^_)t_4AJZuoP(=QF`gC?4;K0rbb zu6l1S49I-#7%QDlsE1~8v$NUg;YPMau@&`hHDSq%73Q~OOo6RZN7^EM#U`zc`!D9s zxaa5PE!SpBk#7##w~htNG2+qP@~8~i<&|K$bF{R+TP7{H=QD}fkZyrS{=@hdhZ@s}N6mDF6wC@?kI`=`3>rm=A~KIAMm zBL`dTWV-ZH9`pyqXRH747=$|ZWb4(hPBmGREr+=b;~d?^2ekWA7C zs*~G#n_Q#!DFHLJFxjMA(6oL7d=wYAq<(vqbsUNvHLu}GU5}X*d6dlU+rKxu(R*Q3 zZ4@;9O8ai^_{OcjJo^1Q7gt?+cIDgLiMp{KJCJ+3t?#$L>f=WUy;KE;*l04cs z(?L!{lPdm3Cu>}z0{67)?OPv9B^Ft$du^ut_XO;eNXWY~=jScAcXntF(#|H%M_5Qp zOQ%Q~87<}&C3cwyhlCL7>5a&HW~HaW;h3D7x-2Z*JDM<-_8y?)bLE}BO3#Bc60VyW zUAyL=D@xcrosx?dyz==x z=0ir64t8^MSn>z~!6j>ESFN6Al{gdz^hF@$={YE5`oS(ClGeT0O@x$55*D!hMAOoz zbapc{v)<(nCG{#dk^Ul-AC;b4u41v$9U~~n!R7*1gVZA&T5kbCk8iQa*{n|9e@cbk z8n!2!?a2-*A}7BmFQ2xykRa}GnsIT_X=w-@{NaQ0jD?lYx5ef7zr>1b2J`V^upIwR zu=vll1fO5rJe#YVS$-ZL2=QEtRUz`(lGO*2n_AZJ(q^v$XttDW5wn{5gY&X3-xvz^Qwas7cY*k)HBuR8r1*J(h>W!;eu3;e)r~a z+qNkwFCVBNd-LW^B){2tJn!)FISK#AA|ylw%+G1Dbow`tCqP%?z?uFGl?&lo6RcN? zICNTzPy;tn{rrG40i0mbpSy-d#O&$-N!I-UDMM4!ccMNh2_R~ugsUKaJK8eMw}h<{ znaA&RXKJm~Qt3%&_e=n~26kPCR~F8nf1K{o8^Ug6)#6^?R{A*0Yr|7+;9#3eHZoGj z;^<(>^Mu#Mix)wYf&zC%P*9bKl>T~3N{Vr&!OrSbp3{nc`o^u1tKmX;DmzQVw{7UJ@gj0e9wq}%Di9A0H+K5^p2 zc}7MqVA$ynOlNa9)Uz7GRZ9`zKaFTHk5HYv@SrAz8D zg?x@F+7@M8Dww3X@og&(>+<;1tDBoy>!LSqoE~xCVi2?%GDkdNwhDlzJ`O~c81Xq-b+~JR$8T(Gr|=>doI>Q;%6P3h#zR6iOZ)vTZ=%a0 zB7LT=_6s8zrh~n$Y)218MN-)y#(>b!i~iI+$5g&3Km+Uv+kth%Zy#2rczSV|yUgzZ8>|(q(AD7Q!NYBKi$2I~~^%H1O#u#Fg z@zc(PI3ph_*mTIC(ZsY1!CEd1fj!#SkfBg8$c@6goe(dC#Gc}-w zw0MvOHc;4|Fh3IOU#v$zP}qd6P+g=*u^0g1@gP$pwX5^klK2fM&ACr7_%m<|V#0 zXwS_2xo0j#DM4~|GDPXd+B*_DR_@C6k3K$7_wTpHOH2WE3G2=W!O5&AD-O;k^?|=? zhWh2j#YNcxb-&EjA~ZHIKG&xKJ>q^XQ?u}6Y%F~Uiu3tgu68i{l#YWA&M-bY`Ual~ zHuTRQ)19$*Olc?+RM8-@HrrbC%9=xhm+F@o|NRlV>Ry{+`fI=fyp3KL(D*} zv2eC5V@IrCwH|HYEH)S=mN?&Ox^rZ8u)qHyJp8R}04)JBK0f{-E>345PXMKt10boNsJUoATvYC)X>yav9&%=tgtY5lDJ{zuZZfI(%0dySt)iF(_V-xwEsU>v$`0-1CrbR?V zsQHY~=H=&Gi%q$J?14y|nttQWH0$`%fW^w1nXxG*NRp7J@?$=G6O)bO#l5Mf2=a>; z4fFKOReMCl^y^@^;02j*E*;;xNXY4-4UzmdN51O$sXclr6Hn9H5k~!67tRw6nL*wVzfzOM~aI4zpQ0<;*-h zDD8X6jI zmRIsUvd3k)(W}`*nawNQS{cf!)#);?1a=p4O-Z&VOD8xs_AJs{=_&*QYa5hQq#Ex1 z4NfYcL@aWF$o29^?N9d7(hj-h@8ozKxV)I{JO$DlqD=XCM-&7SKveI$($(0TGIT3x z@87?VG+GIwhROu0w#UyH9e%v}AhBmIY{SXLWqd9hQ>Uiq{^rdYD%t~oAVVNqC_jFz zUl7NV4@V_>1$gW4oaZuk?%o}PcF~(}Lbh17XT_3`Y;TiN!JgF=+pJY+o)W8rG-A)M zFAVfN(=x$Vz$?~qifXB?nwgYF#quJ=a5%=xGFJXpA*{R8Gxzu1XoPJNkqUEJ62lb>s7fK^(rXt{z!n(W9tuU|@8(zeCj10ULT{eLWN^+ICSD6xLtK z_d}9l4NWs2Uu9*LjrTlszOSGV3S{(#Q20P}<|ct!V+E^o0w|(T6jPw`=eh4W{%UQFC|@jl zFgQ49*q3M2O?EpYCYOCmbEu5tfI&wMUt=t+1a96-Y7=fg;)Q*kUP+T%P;e105j0x9 z^vc4?>1o)i7pkhNh^D7;IPg|ZGBT1nTTGznFI&qsX>ihr-7b1tqCd?13aTKS+UolH z`tgm<(4=|7tVm~_T$8%y!bO^<0W)8*JPBN;ZgY4E**7LWN6xxc#}eWjf3uMO#fth5 z;L?BY68*!+`o|9kQ17tU&<1?r+PjVSnvB!3Ua#f6xb>JRK(?mhsc+x;ErJb$x~$sX zQ^LC8fE@n6x>Eo8e*fOm@@b+#gO{XU?#P*?U8=t9P zTYlG%at!ub-NDvKkV%3&C9Jju5pJO!uoDdYka@YVC6RTaKWtU- z=c7%6K-&S^Q2)D;_BuDii&f%E_eQAj*MK+yuf~Al%(5Dl9CM~gU?~G>HFlDOB%9oHyP}CoPS?Di(fHYWR4p^C) z0XPLSO1StaehmS6M58W{A-y0@)FBPtN_DS4dZ28nYHxC(cmz5;s2VG)s~-u8Nh4!T ztT(X({WNMqErTeUf%tqQ%Oy*aR1^_2F33U)hr+tajh@`|N(!(oWTnUj#7Q{A`bt_u}Jqa}yp{nmtvY7C8vX>F?$4w@+X^ftC7YN;XiOUc^uvNXUI@Pj@n zh}q-LMhl{R!O29BJI9$kwlC|tt=ttqSnmKaT-mBRBOMjCq`)HUFYV;yl(G>o?wr@} zJn2NERxDv`$x!$!@k`Xe4QqsTy5mUrA0LQsbkJbHjH~HbbyAR|FTRy2RpWaZkOLJQ zW_LCnzoQNhw=hW{x8h;Ox{Cye;T=zRhv{UpnVcud@h)Luzp9gyFf&*dkyuXE6uB=L&s`M?rj%UF-9@3SY0b+go(NHXRB zM;5>(KVIS@1;sBw(pO~Oo((>Af%V?w#~;B{_Va0gR?3AK!cJpm<^^s?a0!oL;r&V{ z0>!Qf3#%7d_Sp?skdwzLUISqj7>Rm1>b=kWV5ti5Z+75&=Pz7f0TqWTQ`N#QzEb4& zaCf8n9jh4C5dVj$);?ax*RbCn5`BT|oZ=jhj8dDr4*SjDR)Ddd;i>_-!$0;LPLe91W8(ZoG zhGt$iZy1Q(*_<@p^P=TN7gR8C8b~vU#PE$U`cEwgS7yBQeXiLATQ%2is&SxOCk6%g zr}eY*Pk)^N+Eqal$%7zTUX$T3sh3UcabmPz!9^|lUeV?Ef0u3bVZ{yU6ZmKXP5pl< zMetv&*S|1-sSS4mzm}cH*0i6v@4hYf^`GAN|8Tp2^Os0z(i#tn8WGTfa~CccEG>Qr zxM|Y!qe6#_PwkpoQx_X{&|ztq!EU=JO{x)QESQuSUj-@dz8m+^4^QNZjvO~fZL9aMFFle^qrAHh~-cj1>D}+NFIaV zm9A)i1~E#&tAg_>Yv0Up4sk-t;aI;+CT=e<^8o*t@3om z`j5@1IH6~8%{o!h^?9iyZGmoX=xuZT@2^fo@|lqG^6~;e27G7QyPq(}}Z8 zlJpE>jz7T?Q#LyU!L$v;8$9K}6DNtSL2oXdvQfZvK0!fhq&e@%m}K4D#2-I?yxeD! za9LE87VPS6Xml&^hXpt}H0*k?mI(e*rGdb#Y+;TV5F4-;*5`W2Am@O1!9p7x>~5%+ z+Fd0gp-ooc7P9E(D6kr$g_BaepiLpM{#yn}xBU*```p;{rjq33JHNVu?E`~?vO|~P zSZg02D&>m0#!f<{*{!CK3(B@bHZ^05WgVhoY#2{qJzSfswd~wmL z+eH7tX5)Z5wvLz5HY*mhwXH3$9t(#DIu}ng# zR?f4RkNe0N#i=1v^F8H3MCgv^;ab8<9i26DU95HhsOQwh)Z$`viUTA=SXfz!zyN;( zTpb|%IeL13VkWn9h)s_U`Z7EF1GA->8Rvmj+@FDBZeSH-Gc)g@=S~3D5^(Fus>gpK zqS$NGfWMwWu0XxeoZ^+YcT4|U&C=V$V3@+Tk$driKi+NiKE1F_b;iQCu#_me#`-p1 z?j$1ou?V_0>gni{;3lbjlEdb>p|3N-<%jWZo>69b|-g@6Vj0~Q5`?pHn) z*WtHd$`dlVEx&x)GoxT0QYx^lZbg?R9G-4BIZ-a78{TDJxD9m(uUDJ7fMm1+m~sqG zW@7<}`o};4aoS(0CkP!vAdqwlNGw}#T6UpkW?K)K7Eu3AAo!3M_ynb>L*SYS0_?L< zu#wA~PS*r)CjOm2=VeAm#@IX15Ef6*nu@eW@ezX`e&@-Pi+Gh6+=x+V#e!=W9#g3` z&>@LSYY{h~wXenYr9?;bUUrrT0NW5x{hQ!Rb%Y$Tx2PeD{oq+jfqjk~chx2ekI>i%;pu?_+pKu)^ zg?VfF;QyOVH^NDs#mNZ%VBC{N@n*ZwQ<1-Gs+g6GN=V>F4>?4Xl$QR=GisV$4&hQ! zqbYAx7u*!CwTFv_CmH@a81lN*8E|c##TJ-%yoCV0G6yIo~8C zB*eLzGh{^a_0c}2a`roEXJ>cr+_`6kO@4(_jeB0~{{Cul<4GV z!?U%P@AtfRc?^2=IjrAROyh%-J{&dw8==oXJd8G%n)C6)Br1aheq9?@8A#Ii2+rGpYUD;*e{qhKU}u`i_4+oHmV=yXkSj zvO=c81h*-3ny-m*oZiFM_Pi37{1t^v`<&!zgSITv?i-7xQo>vhcyUo0(`p_01t2{? zaMru1aw6Qk`0Ql!5S+N1;BVj^0BG7WVDjgfcilkn>7Rc9xw~rScfc0Ln?GRGJS?Ih zuYib<(`KK^T%w5)SU7J%&$^x6)6*vykjiCZtSuH8ZZCpE(FH~eRX3w*+jvc|MUNsx z1}aL#JP*ZPHfG;|Vypk_3-HvvQ@fBEvGrR7kqCtzwmjfQZxsg!Qgov919yR^1FVX4uQX7#mAsUzCgL7*_-@3T%;j zIMeJ8$^Px{jdktVorM)9_) zW2m@w{lQBy0K7uYZ+Z^2hk&B&*-!5nZ-X9Kb2cw}(sIGS1!Z7{4L3gfjeFXzsF^Nj zsYEcmIJGKWz`DB1U@*4gWf{{%VGA9UY-bL&wp?xhoBU!XW8xyV)@1lUzchqfd&li| zR*eWQfio@8Zv|bsJwt=<{=G&E1i~Qc_-t*_5Ui|re3ty3$nW1BUfiiug zNfN+TJGk&WJJShw?-*_`kA3{`;o0W?-eS2Dq`y(*Dkq^Xw<_x+owfXt)E2`{p}SkGvzFSb9Qy4TVFPbU4v}x0|_>%C%PN7eu^4s zC-3^VFf46i`(g#N>^P`+;$m`nP#t_|@Hi2KjI4uf3REJh+}zyd_4PYPhX?rJ8N_E2 znA+Rhe}8+#f=Fv?(}QOaHdRqsNq*siH^^OVb8LFuo%@jadqbtdxA+%Gjo;Gx55@R_CBF|U|-}|7tS?dY6-+6 z!4`GH+I~+rW;3vH*kG{JO^#*)8(&;$FW6Q0$gb!`RGDE%_U%)rP7xq@glRc9HI=eI zKRrzhEUf|y`C?G3K14*kgPuLKnf$)ExOg=mgYir;3TTl6_=P-!57tP?2&tw!#a2TK zo5gN@zke$mX?77jPaApKRZy99Q^-Wi*fJv^MPz{4;6a4#6^CFU<*kYS*ou|~S5&_k zvmEtA9ZsyB8jY)9xNKs8qGvOC5Ru9*$hin?9?wMPM=+T7^`;1J(0ULE+3}PH;u$_x zZ0RRJ0DOD}!k(j$pURa#g2sIkfwegf)__HUC6p_IP@Q_~zPzi5bb43xkad8pikV!_ z)LubhKhAP)%gPK}*g~zWhMm%e&0SdMa5pQuG<~Wiw#%NQc&8%|&&$BW^M+Nw-l6Nd zAmFyQP~2z{r}!?fsotnSGjsLw;&3G$ur0j5<&{?-%k*TU>rc;N*lgo!O zf?-uuCU8gZDJco{M)-n`i%*%jZFH$2jfy7O8u@ke9`9bi9)$yocmW^@Ss-EK;CQY0 zRp$Qv_ic_2-=AQMn&IB6hz#5?kaib|$Tu3EY8o)t)`~6`aaXe#_HwT;N!{6`h0R&+ zRv!3KBxve}NH|@2RO|2g=wYAC9=Nd)dg0%`U5^6&?<|AplUJ`^83GGsW?qGt95C z)@i?gulE3k0_Gz>0tUs40oOgylapcJpQoc^hdmSuoyHepAsO1G?WUN!cN`b`uYw79 zo{5PYI93Q~lt~Nh@(&(_+z(;B5C3z*3%E_g`b@_|H>_kLsqZ`r3Um(Ex%fN zBma()N;A{2I{Zwfe$#}=D>)_U<;YXU6v1HhfaI{exhV@s+3Dav?mE7h`IIuLG}ph!=x zYw?xoe#5h!C~Vi%Qvt09^|nv5B85h^C(2?!t)Q@WPfPW2fuY4$X|#BUqt+Ja*(|EJ zBeU``oDdj)3I4QJMMWk$6ndvdL2OJ69UPy(bb#fJjZFR#b&Q0B1aLAlM^_W&nAo}T zO0AFfC|;t@D0>mLW;&ZnTb*Eb<3(R*zUcuGmF~?Wt!sY)D}nzbwujHXLOy}$fiDt6 zWhdgzhv<>zHYTd&F{Wu$k60d!y}jWu_DyM--~;=q!%=aLU%oq{*X-@mvtHw|TwGka zsU$!)V&r&Gyw@nt1&&4GzMxO^QN?TNT-j-TylM`-;pu;^*rYnguSob=l~NkIjtY+d zMndNwc=JD)NBW14L*|Me1>ggor}VvhC-wF9=ZE6t8}}$7-Ud6J8Wj^47XSh&SP+RI z<2rQ8OjrBsoLO^}XdV=}X)^ujTJ2vb%O0mNSYk^Ed<-v{>$=Qb#rwA~HGwxvVWcMa z+4omve**hnh%zvG?%S>}4$(pWSEyh0&N42>`g2JMHRf3qKo?GejH=*J7F*ZUAV5E3O9EgW^lL?2a;rleInMXK#2jv9Q)V`4`u|U$n3VliBYXBGke2X{E+Ql(Q~|xe#Bm|I zy$&24&CKp@om?M4We@uSI$XpHPTw9SnGb$7Y6`y$Ry6`F#S1?>AR$p%HAV9Y8A=4SMN zC*HcJs3_Q9l?GczUJM7C*ZeLf_5Z)Jy2D-v_}&htALlPRo7iRulcfpNLU%R!(zWxpEx&fM2yt7{6N02ZZ@T zG;URtg@q9E;WE0qjL^-AD|PkEG_0+yr%XIOkK~(ZV?6(1iiHu2vns~=SPhj$&0Fu} zefspNu^^4`2Od@4-vju58TKvwRk+78gTq-i`3Dr{@|$QGYIhjXvrXIm6PhbeSzzF? zuI8yL$=wO$ue0bM4(3I_jtwZZO^&rFQ_z{V>=@^Qa6RCl8W0BAA7b2gcu$``{TqUD zA#=ix^VImbsAX>s0jM+T`NkyptWWxS_CC)fIg9Kiaq$Y-CO98V5NFwk&3AWNokmo)js7}Wb$Vq(yaYMj`to!i*Kz*KP&i@AMajtQVgtHi7 z{|5NfKH*10M%>m&AljX%;0oH$GWer6vK>Sj8o8Jvz@u(_R|1kbenJ5j1!-iI%i1QG zdr>A2${8xffhGoAra-WJpKZ?fHSR;`T-C)lMPKg*iLx)n4FOfQ43AD)rHF*8`251+0PEYd3=>i)ZQN&^tMtGv9A zY57er4HR2PK*FVTF01@!OUpyJFUEFNJ`J$tQo!0dPeE}NbVgqH-50QQ%*-F7qtn(G z;1Y@}i@`p<1rb|rU`TkK4T|xX?Y+IG#xVAPO|3hI&{)o2yoeX-cp?1>gpa?!O54^p z7h*|gyyTDIx)lDKpwG%|n7Ny2qK-G~m(z6aAWz^FZqnFN;qMufLDi?zT+u;;wMHX{ z^x`hZUeznyO!w(DFKqbr>t%7V5JaVjAvD=-*XU?(k8&Z@hXV!*aEr@!5;KhG0#`du zM1=3e(0gH^(JMx)@BSl$11?U^yP&b{@9&426?r5yI-Z?04XCgPvDc|UKd{SsSSLM% z)7H^_nqT;WUTw#&l;G-DrKn1UnOcQd+D^l+^dvJ)}g zV}?iZ*G15EH|Fp|;dU1tGzZPN^?vS{u-KL+VMa--ITgI~6Z^?K5Fy+Fn+M;YRK$)r5Jr)V27BEPrG2-}Pi9IoNQU&~QzQlwx)M zeZJ#C&SweSmu}%6w0<^SQbelzLZxcT9ke=?Xx~3La$|V8b@t8#)vz?YdBgsk%JRa+ zcVDb4JqLERnh!5d$5RuJ1lroHZOJ{F)pZg?1O(6O_);axYWu+9=_d^H6>^T&)Y&m#wxBYyqrz5XCHtv@9*e{#4wfb5N#-C0u zDDlucs9NG1BXY^9`8Yqd2sXn*O&jBSK!kXW*QEY-a%EYLzja;YfS9Xw*EPjxzwCu~ zUDKIb;w^&Da&5zLAArUg$IJbik+NBvvZre2JY$PyHAc>QaQomU z7uJpZu=4yUBlYXg?&Y5_y2zi6k}3z5!TtTwk#sU%y-43VjOFdhJti+}1rECix0e-D zdOcUp!)ALNEGl7d;{WHx?ecHy~zBw`-GkQ|EB!V$auy>%{_&y&lJswMkSA&xvgAm$h{OX5s@ONLSPi!1+0o?hJv4aXt{ z&xtQ5Dh06^IVQsihRMu*%H1Dx%S#^D*5ACj-djRx<>9gXei7Mn*$6&Z;h1zk;(SF! za<}GdLj9D6^(X$dV@P$m4u8d>X~5@$@-fOMWbqGUYJ|S<+00$OuvE0rX1eRwC^+PH zkZ~x9_cla2ccRM2J1ZM>R!I`lFb%<>EpCQLQaAf1W2QV zmGj6ERnOsG*e_Hko#3+ksj_BSj~s*RNE)yqBfYhTp8jzyjU~%^kLIpe@pmCeiin{JkmJ{s zUdz?gmDsMIJdL*UHu1apTEXcUEw?q?3%%{yEw7k_4Xj6)Ui8M2?X^)H(Fk_MW^IKt zraRwK*PGm6tdIF@sh?EM1}cWU)6*u!;rNiNUf+crNG2^+W?O!)BYCLjN&NC)sXkzx zf6`i=q*XS6y!Xf>eIpL;SL}m0y>ODab^hDeBv3ZG_^U5IUFIuJD~K=rH%t6uvbmW( z$_}!%o#gI(-YI9I)2_>YAT*e}z9-*7dnMquck-j7x#^!@Lle@oMt%!w9hLNr7J23A z^9nobr%a_6ZN2xsmCk)5!PY`}!+FYNYxG=!M)5(BLwS$2S6wScbD;=dbPI)>2`TW} z&lA`GCGCgn>0q3&?Xe*7)svtYXfCuCnkfao6e*{~Ex0u1YhpYqHFkLHr+?<6L?Xb0 zv$I9tKq#p=RU&C-(C;`BK?Q=aleXpQ>rul^O?(836ri8+7qL)S8gGvZxkBFJcx6xV2t z6m}pBZODhiHB`i%v3Ed);~EdXJF9=BSaVRsO{(ggGRZ4R7ZpRd9TlUe#~yV#SJg}P zrT%;^ed+bdyTr$+PhLJpsbLru-Xez*puIX{QFq6?uFCr)pG*0a-J5|TU(yAI4s4_` ztHgDSCda7b%DDunYV!8m$IZ-MemHTA;Ny!=tWP&8J%2w9k-y=f$oVxqq;<}DRs4S3 zNb2s>;SF|A)yHE(B}Ioq05gsz?ytM=-w(Q`_;MnH#r0j)qKku7Q`YWeT6+FQCQke` zS3JM*$nWINmab@AkP++=pBJxV{u+H_7{mSba2&akQan6rC%0O}+mHXhaOY}Z<47tUEuL^~#ahj)!aPt`f(vE@aGlc}-GBayK*;JMx_vL8X>DZXg*5t;<20kH*!^T-)EFt7?H4?5VALpHmUmP?YVZY-h zdLpoQK%{b$sCSUY+J*3YUu<05nT^7QwU!~sIPsWwUI(g7fPiC?3xYQ2k2R8z9X@89 z-`69wPzZB+Ep^sF%Hc65<#J@9`1lSulK5#wnA~Zzs)sPtDG0VC5A-aZO2K~br?$zC zDGxf8DYlnyD>uIotLsW=x#%xc`Et|}i^aa#?cbaUGRjnCcU&BN5A#(b+E)Cu5TNcd z+K+)p*Fct>Swe#0uW4>A?gXp;f>U?z-i6$Ycbn-?@R1SZno|57m=A-HwX&+}TONbD zYE%C48ZxOT4)h5AX$-)?KwoEu!9wtdpSmAq!Av?>Dv))Ucz-Rv8hGt|y>^Q$XgT;N z7U5+{d~`b}=l9e$meFaHfI2|7m?>7%_G^ANT{^>rnTZk|AyzCMb@sTP3EigZh*)Tk zgWOBYtS>^NN4VilqF31>Jw<^%MJ1#2HXYVYlXK45ddv`Z06txJLvLPquiBjNoSvM_p+sX6sfhStX%lcD4m)e5RSO_GJ z`Y@gth)`&kC_{ky)9&`G6K5t1dvq_52k-8>yblZvhv`SZzl>Cf=Ay-xAY$DJ(T{n( z>FMdF0<(@MEn-4KYLwi%mPeXq6?}NQ4tMlxJzf%sl5i~=ghxv7!eeEeVOOVQW@Zk| z*>yicSqsD!T4osge~qg&;~4Ml3#nrsLaTO^lyCHvW~Ms~(zvG2Wp2h|D`tkG(zCMS z7sV2&{@~0RFT6Be^c!aG&#(<%q(h?>6UEYLIzoDi+Sdxw1r|Eg78O`8AeVR_?|iL< z!LvJ%+ykxSrU{n5v%C8k0v^*N9i4#5NkgO>^luw@tjV4;$OjG0%|Ag5S?DnkQ=4(p z(P6m3&W?}V=bNG20T;G8lv1bH%ht1Y7+)z~cL>Pxw(OK9F zwfN^ZfHpm$hS{Zn6`5bzDE(ZNuNn|m=hPn+5NBY$ap2Y`u3Y)DT1ZWlk)uV%J%G3@ zzdiEV%>0bV(2AT%!XZ`%rqqzc)YSX7mM>lu9IU~3jXDSAUJt~6WHdBrqGMugVYZQL zi65NjTu(+Ss%e|7^a%k00mKVT%f1muZ5U#QAG^s^5Y>PvZ`WaAt-h_3MPZ+1k>>?ScAWP9?zIBX2rJoeoD3X!=2ttu z46iwsaH-XIw71{1?7jI8fAk@C-qRZoVCi;oiS}`&DQ}1Z3r5+Way&p1h{NFNrv>CiC<2H^5D)eRdQ7 z+>7K-pKifpwXTYZY2lv_#>UM}g{*E4ST{jQG6H{~{i_nw&U%LuXi0Y$%jUSiaftx8 zgPoCz9G^FX;I1~j=@mXc6_^~nVVtj#mXVT0^sTH+6CTQQ1#F*-2(LliSq&KVuZe_| zr!qX(feY?l2&7Hb@u8SKZV%Ck7P|kdz4MN0YTerXQfyl(8w(;;!M2qmN)JT^!~$Xi zq^l@M4M+(cLizC_&bjyd zJML+^)SuQ@9_Tk_S0)`feE5`_**6PgdwJHe_pIK4nE)Fy zIqiNyK|le{*Y;^bMvvr+PS!Zb)XR>NB6BOrAV2SZZJrwT#qd;TWm-|uf;SIR8`fvk z^!7SD1}$)DMgj+0l3oLo*`!l-F8kn-BhgV&jfMUv;Z`d@mt7Y}PQY1NB|bFT8d(wK zuPZMSt*om02{x+?^;#x9DMl?R*Ilm7!VxPL?LE+6MYVJrbgd)rlxO5(TrA6oi5PKJ z+}iFgPdhApo|Lhd;D%Mj>F{K!Xa<-lz__%oNr3$#b9!EZ>rg6bJ=Axh+k=F?KLc+b z>VwWKa0*7nmoVg{wZ|~%?y23r$I&pmc z{YKjfZpQO&7ND7AR`UOIqUrBEx$rCnCEdLkz5%`n4@7m+~%;52E(J>?VjP@l`?s} zm}X(f5e#mc=xuypGx5>X+_BG!?!VSr%jq*b_+?^-3SD}k;?}c5Z9#i$me3cH31U6G z7V;cr8y6B7|GQtlJx_U`kRXPlxzHJeePMi(j;l~5fQ0}}sJg)>Sd+qGZFpu*umw{5 zja84!3)G7Hbrz_`fXN(!csGJZ(IU09Y@Auyrb?q_jll*M2N6hPoAN3C_i z!8x`^;GZBpPsN!WJ&NWRoQea~4#Ntbv=MSxW?kU@lZp1kTIe4fGc~<7?9o*Z(o)Ik z>t@ux4|MrEkipso+A7vQg01;nJ5N>JUtbYEm?C zO-}A}&qHw9qX|jxt3v0!v?jivgxm#Aci#6Cy%L!*izYie2j{Bas9vu0 z`zF4kva`S6`USx)*?lncA4|igdE>RhuK!x6CJ2f*5 z^;_i=)n$)yW=zpzgRsQFQDB-yv1VNE60BxPAL9&)Nxo zJq&AIM$HWZWqPF=mQ@BFo)LiUTYzpsS@~G-B~qXDc^kMnW{K^L8F{-$97ALE&P=`X z-x$bu8H@MUI-L+XEhgmcn5y*tYyCH`$0Oz-6@R%0{!L`>$&+{6>SA^6V`E~j!G0AQ z41Vu>_wT2WNE^V5**|*pE&%^CU9dF^b`@yao;=BiKr8g&oPZRh_5kGbYg>?87pIR= z6=Kn~G(~x+vQe@*iNoo2GZ~V)Jp*%8V!4d-kNp+>#qgl7p+@=TQGim zRQ#_Nj0gykiNey75(%jll)_{*YN5GU7tUtx#d7dk!oCXIxs(JG406ej-tTj()i+pRx8aPwr3$O}iU#JlIUQ<)AXqA0#DF8ptyoPhx zEwypcSfxZd2iped&e>g}s8JaqvSJ%Y#9gybOHfo3>4J=oUO#|v;qK}j#(Bcw!4qJ1 zg|TiqIB0^QmQ!qCzxxp=;gkRt>?&yZ9`ZCd*VMCc&(^y?!4}}==4KPC4fOnr%*?l; z!QIuHpsLgosXLoe(KmkYgrmGTdRgQUV;0dW;Wh9eXAk%$`7E5ftw=-y!w0=i+~7Jn zMi2hN^d-Ol`q;%P-Gy1B$ft?P9A6b;mSKu|eLjBpa0|$&3UJbF154%!TU)qeQ5Xq4 z%%32|vmLgCuhrEX;UKZ@%KMFg?A(rsSa!(7BpykpBENdBOk!eC*M_-91l(N zgTU#u1N8ygTLf*iV1{jBxdAyo^7H_;yoHxH`x9?~6NzIyehs;}(&nxn_-#=(-@~gsU_Izny;W;uxx0 z>+I!N%Cd1P!q?!Pgqz_z>KczfO{N7Gk#f#<;TIR>71cL7aj+E!4jef5E^Luhax)QY zCtaDA0d}N7Z(D$Lfjfb?w=0X5U3uS{pW$z4VBjVy-2mJ zg^JwrMx*k@HW}_qp%B zDG4;mOoVD~mRn&%>xLEcDj`JVU4hGk71o1@26E=%S%fNW@U??+x2JJ zxgH7P@0J#yl*0#%*}Xu+!2hTn>W|Rgpmp1|K?Tf`UnnWzy2V2p+!?Xy^1L!y*nGBU zRa@^;_4(5epwM{mkHTY3XxHG~h?Cs*ufNE5?GI7azOXh;NMc>L(=o);rf(HPS$NT) z>!3nXNrvf=i^lrVob|NJyiMJ$`S^)zE(uY{{FwdoFhc*;t(0&*XU~|(t+_6bgD2iM zb$Q3B;S^&lCdN;#+=#PFZQY4U`S{J;BOk99N9?=nqNV)OhTWebG^mpv_?8stX{}%@ zG5LC1`iY-g_HT29?^+K(+NVsq;*J&f)6wC!(3X$u^Ql+j6>HUJA_TDkUS5W;M(!uI z&;+FXuefM&{d1`GYU6$liJ=S4_&@!DzsdZ~EyZ5uCr@4hNA@O2R06Bu^%C5g4i8ilY-uw}P)W zj;frauYK~)V%?UwV8iISt6k~!7UJ{$nNywkygU(9UW1W*7?9sqpxnd1T-5jRQ9(BT zD1X)lh)Es#P36WI|E6;7CZUuw0-mq{Wday&T3@C=*$=f`INyQ+k(-Ps_cops=bP?x zE&Xd5ndL^uqSS<_it}2KPVP--{M5||wlRT&BpO=U+~4Qq_c@6~+T#l)5tNYAezZDP zLL(g9eD;to4dCfmw`P#>OD_{w{%%5!Kp-Za!9o%-Y-8+3^~9VUuavwzm8M3EEHePj z)_}>%E5Grgvdqq%85LYGi?4xjMgt&n=MuNep!5nP!Q5_Kg}gugSbvFTSF`z_-TA zX)s_wV2N)`MvnkDH0Fmc4N_oy@gn6{j|?luV(+v1r0$~cb`s6Ky~<=N)xT3^;&(5= zfkhj|Rb4$a@PMnGIC(Pl)vLo$TS3!d?!?D$labka_Yfp^$wOW-gi3&&?<1HT`@3`? z&LFX zBz}%kL93M%3%1M?-ALvSCE7}Aq~2wzCQvRp?tX+Iw{L&KeoE5t+6rY9G)7s&tMe&b z(a6u@;?c0%0d~WOz?m;{r#Zf^D*F2MeGU#=q2b_GEX5=pruFsq9)oHX*s2}_g9T~= zq7?QS7+h-$g0G;txlnLpDngF?>rniHw39aa?pymR`>Uu4W~LxJy=#eh7H9_x#^Iux z%BIAT_dBXxtb6=kXO0{jlI*TLY#*MQlitO>n-;oq3oHgm_4n`3)m1e$8|M98UFGCN zqUZWxoj|WMI-Q;m(RJ~-gtD@-I^DSFXfJg}%?KQ(k$0%M6g#{fvcF;DU)SY=A=(v( za4IwvSETymItRIDQc#^{gK8X+7;Wus54q2v_U)6EMr@wY0KQf+AjdpE^Woq#aE{NvciTwk=<` zZXI-Yo|<$rAl(Ro;Ab6xWEwTqzr3^js z<>V zlJ`Bx0*A^xz*q3g#pmqYvEx(~2A=)&qe+XAw|RLxVsX^-yWgM7ewvj#xiEQ;bwh2T$FK=S&!M_;%F@!Z9Zw#-Gd%23U+ACH<|%v| zXtN5?hg;x>LhSqnP;uu}6AkpAzk2mahX|mCHwpVMQirbsE{;U3Os%w36%i&tEwQdS zX>KB7rSL#N^!7>qQ&{1jKKTs9!4t8>9hNNl)elt$jj_Vb_>n;|GMPGMEyeA+lsjPU z)><;J`R*k!aWk<~HLsdmYhFz*LSWl2k7i5xx~y?hP5kox`&Bqv;!LGW-F3dR9~<32sGB#al`; z9uT}Nhr&H9@7ie!-xD8Bno>(~+PKM;qTfbp8(9&0gn3~j`jfDjd}c63aHAJOgK zSMcmfUEwy4Ll=JkOP>~A)*7^&IJ)8Q6a@dd7VU54L+YD# z$&pR=BFd5@1x+lovE5^No227Vg245Dne^eWj+f z*rIyvah*oD3d%J181q)#2=69d z>^_L5K!az$jXXrr3l7$XX#|+ren;I>SXo9OM)3@wjN26zC%f*gwfG^Z9;&*Dg^VRO z=S%FAL1Pdoa~!K6hgk0bf1a0Gz zbJ?$RR=#KD@4>qaT{|&$%$hwozAT^WmY-L&=0j!3Otvf3O45uTq4|}qMU$*jL+Rip zpg&;4LIeCq+ds}H+^~WrcGuaGC8iJtepd+yR3bhUCKDmmn9USB3hFfRmW zQjIe@^h60ts*x2j2V?+@mk`8z6Zp5ONG1d5}wWd2ZrJ z3mmS&;=Awoap6y&KJ9Y&EDDX_AZ}|Ur|;CBPEcFh<>d6i!Hec9`VLr{P7XkwX#4i< z=w^jRBm*l~8S=TNaM78+>MS1{c?^Otayc6SoA5T?(?%zLF6Bq%qwl4s<7I1xa{%AG z9plOPvi;9A7=Be2Y^W4=%PDwk%|^4WQYQ;&&*8m&J&jnPnH5c?{t#i^zDD4OhT6bk zQ`7rzb8|le2)9L15e!mBTkqZk$Blv=MNUQrf-&zvDWI+@7&2-AyEWhpH7m-<0MU34 zU|DtR;;#>3n#cziLJ>$~a1*SSl$58%NrO)N2Rh73fAb%0Wx9qc4CREc6k49!RHH2NB`-%U#^7yVKY_ZiHXeG)$W8E(j`A6RReX|>+YrIhS++kohTJQ^ zdfLUhjNCOGo1e$WtVcCii2v`!KpWm#zs}E(&@@d5mVkdYDqx(<)|9vIMojl2YU=;#b3bc^WlnZD9M4f9RPz37Tz#3$+H!fR&BI83{8 z!G^p?2f{C6CLgO*=1NY(C5XYH$WmBZ+SYhBq_Yep)2LLqU+ao>VB8H{SkPaYIU0wBETy~=Mu+iDS-4AvR$s=w73juV4jVJt}myNj3@rOdxInpw`D$V&vH~7pk zO`5AJ8sUtl38U}^ve(ONPr&5hKxYw09=qT^d8^bC>{z4>w{3%3ksAZTnMu^ZO0lj6 z!8ur|PNK=me<{(Hdh}txHBJkU%7X`G-dGEUXz(xN1IAmZrIvXc6LJNbe5DNdT5G{Q zD!QNnn2H`!=lm{QNS(8hm+bm_JRm?5s^Tbxg%E8&;lUrEjcuvrZG!l_l}L3%!z;f^ zD{Rp<;80`%l(7q*Sch7Rh`iYwX7|KU*G!sc7sq`_Es(bK2Jk*%VN-h`&*VU=#ly7=fW$pW1-Vi0`ry^89W#wbAFF@q2m#dQ z2tYAtfBEp?!{-6|M zWk7{aMMT&b0~Ii|%}b!phv;29*ixIDz>2EXHb!nS>)58%1uoVvi3ht0pv?jc zsH8kThJ_o(+$#Tdv7pBe5bhMKklbFJUv6(O@-CWvX{0SbQoF$@f$pHJqOu8YTQtcE zTm`*e1RHYNl%lMvni}Lu9j#FmV1f#U4sRKa#)j&qL0}-pojjm=HL^M2>?tSKz`(#o zEY{G~HFIuv)?h|PtYl!uhGt1DypA}|bEOs=$53ToV%ArU!IlEwwQ?>6vUWPKU6NOh zi!BeDlwb)n@}8ZsWHx0vZA5r^t}sCerZKd9AJsJ& zI9PzGYLBC_`1a=7)5Lv5HNWF{l0v+U^RdFKAY@p`h@XUMOP zIw-B&)YzmP8n=A1FkD-OrX+WEE>TM=sOx_yG(9zv8zVXJEy}cufRh- zFyJ8r1kB}xV(a(zJ$qjB=6TUPZsHastf`B4q$1ID+_ULp7)uAl#cea0+``eoNTV`R z`0g^p4G3bEy%_mb*1f4e(?++vyx6*2RxkbRw`8FdbA9Cy&3R!hopY*4OY+fq-PzGH z1^o!aGsA9kk695f=P-?w`JX;ZYf163r_Zn%%SUFUi^8#VH||U+FSgfZ{jSYA8x&&$ zMTOFut``OqTCX%HBFJ5q-Hp!_ykLMDg~V-Si-oBNd{mBcv!bC!dyfe&eQwux5rSd-+cvxi#Yk536;Xbcml4 z>`!xB#ZRC4{GLjVZw+#h-HNq}V6yLc%(kjrBwFrrKKToUm~cF4vWnaB(T3ZU%nPGp zv1eRQh=phj9C}PT9$7rcmH)iqUQCu3%$}K@YYjE5?+NyE?96$1UvnAHa9EADP5{U5ADL6e0Jl+P>X{nHX$wV-~Pg38#m{+jqP;I-fpjh z59O_wn=93{F7THup6L|gHuG{9wVrMD+cj`hxv_9?)R$we6^rAI2a00*;#8wIOrFXt zOHSy^KHnerv-E|%Uue9m_U7|9w;9s)P7wUi^+Af-?5O*qH>8ovy1FG9kA9l}#*xLy zZ0lDiQJG&yE>3#~`4oxhPPN-fRzA9)aNSn;xO(02mP{G$Q%)S0^)(i2snD9ym&^UN zM*<(j2$yC(xkgA7A2!*Bla)V z-l)3NTsF9hcMVH#X7?N)8`!B2U`cevHnzi__@ZOxzv@zirg zLxbAoKU0GFk&RnrR`PTLl~@l?T@D?4H*)_-+R?EnT9$o&4xOn@n+2mH;d551O%C@olIs+On?%9OvUJK8GkTWkz zHood<57|uXmg)vmT0~DY@15ZLd43l3!3zQ~q?x{5f5x1wpq(WNE2mTjGNw5UUekyuYnj{%x~^z9_FmKv?*=N$OOm`{XrVNlxVa(m8>j>Xdlt z2d^8S^09rBqDFBdT}>N;sbwp9Un8z;B2Fwvv^;4-$GvG1k$v7u~O^JkSW|>=1ACl#1iD4t^{S`z*Shweva4` zWF5MiAklmyd1@HjlS-W^e+WxlO^oGuY;1X1dn-5byWHEiP5MPWVx0m~Ldc7$ign04 zp|-mt9k~e##r6-Ab@&(*-l|GfwKJ{58&>FvrlsC2X>S+ivTMBjI=E){LMMcuaJlk@ zUe1K7PV|CGG5AJr8lp_Cbu)v>FRosE^WUxGyt3jw;V*r-)^^J^p4DrKyLTe(yQZGio%E8(Igzs~xMe%?&V;5LjxLz}pDa$*O6Ua) zUH0>D+dqCIYCo)l+(c%M2h%Q8v1+}Ds29>W-Bb|u+M`j$W9>QKbZhd>eUmaVdA_;0$Q_CX>&5x!sOBqMrgnaMNZ2L8!^}rXZ zLcHUaIfN`y*go#-m>T;&K5qU~EBLv*r03l~2XhGK#&X@hPb%GW=0`526PGqN7|nan z$_jSjq;!@1)pe@o3?nOGEyz$AL>!#4T1dU-`NZCkiUQD<22rWgV!XO54TB%LmgB2fD`dKrd8YrSNu+X-=v`yw`VThb638`NweT~V!)v<;#7Ku%IL#0i5{TXpW zxdKz7E9Qh!&4L6OjK~C5Q|o`=ivPeB|A8z17F_W+dXwHk_V&+^TaY%IUtkFh!w28L zp925N9WZk|(g`jAw+WC+AJ5-`u6PBsb|Fa){F}QWm1Blfr9Jr=9Fia4_z$0MExCr8 zooi_8Aryg7#7T&X`p#e+0Y3&zle5;>hpf|7m;lK1uS&w0qX`E*OQu#!C)!mO*H|a$@1wXwf1-^p9 z0x*YlApXMn^L4s#{&gITHGcy`p)zgAA~4&n1Q@NGc5}Vvr@=o+V|3kUfCj9Y7_c*{ zzOh9$lVcag_D(EY+>Ev^m4zl$r2c4Kdefwnf~WsfG%L@BE-nGQNLD5a=yBgfcy0=qaR_yim7el71_h?b}W# z@4?Z?kS*pCIt;P9NoX7;B)K1+on{nsxSHf=zqd6P9DRcmW2We@8UBov!G8Z8s>^=6 zynR)+KGX~hh}|>a-T#el17!fTA`b>E4Qp0iT~uwY8Naxy(TFBI?^hsQ1092b7Lg4M zmO?Ud_uZ+9p=N31R&sJ2j1wkS8XFlc@#yQ~0&%eniL~2ont(%77y0&8%s3@tp{k+3 z1hR*8$hPlhDlMCFCVy#+WB(F50Uq*gT3{j1>;i%dtROId1EQ#(;_;OW8_jEBy zNOXB?R?YvhdS)$Y0=^4~%$1l|IC|m278q01bU`X9H9cK+%a)~J^D_g*-1^&! ztYaxCpd$0D6A%o*X`MLnYe9BG<>8pz0KKI^VF8{p5UtX5n;dufPwu$rPD;pc?zlj5 zo{d{;5QUWEgvG{#ljbAzxXPV#cf<~5zI^#{z^l=dO%;Hz;byd=%K=D~hmec0PGcu` zceseo=>pyW3)i{bk0cbvI_BP%Wa);y3|8{*sUHRyYOvby!qPL4n@OSRp8 zqqj%Qq?~hu5AoW`ppK*Z8)Z&spSw2q21XFnDRvoN49@SZ%T^;tvLeZD_2$yj&ZwB2 zmOh-tmB15(REo%@|Dh`WLsk5Ts`y7##eQ08u{y;xfDmYezK3`QWqccniHTXfSJkzy zrPmo0+`q}NCM*nDt@mKwp?jA$tk4#Du8-#W078AF>Xz`zALfyLf;j2{yPYvO2k16J z9#QLf9UwOCFkRywgn^PE+VBEQFg%LM|F?=mwbuW4;t&TrOdE`&Dgjs#h0245-!Dhi z*9ce%*noMDfcgJ8(;{O5yj);fr$Z>tQovcZpq%A{&J+rjugSv6=(RUzT*7g-rat|D zcev%Ts~-N}O2jLMe^(;n(!tncma#5QXL>s@$dLbHU;q}(a$rHxxnXg5BE}g5)}$J6 z<>h31^$*zU+9?a22Qz2_+HR%m`Nu5Rb2PUPe+gzh?@mIcPE%t!jb;xXc@*U+?SRYh zqMKVe2(7gQ_UA`?9%}mRKuKkA1%MB}1t43UM|J@4EJ9%FGO%A>eT`teM~ES@x-fGD z39ENC(;fnEQ{?h+#UV!{BmU{hp*Wb$%~XuOabrL9tDqUBRdCe25XFSwjr}Ez`$G5w zY>tyxQSbOfVP5dOdp%rtuJv!0g0|;Wz|_#oFzB+O7@TkU6YMst&ki|riGGkk2OUZn zS0eQ;izthmU1lXG5=o#tPk!XVW->=)?O z!5{YG2@cFPN0T&{BJk&%N(|lncs{)R+&(KSt9W}f76ed?0Xu2%5<`!H+bR^=J*ugl z`cLt=9%BOQWMuv)@)Sc%z##rLJT9>8AJNIN;9eQMn>?!z2cPZWptQkPtjE4sa2pDL zc?-S^3=XE`9d9~q?3hZmEc%_N;FKo}erTfY{S%FA;AL0*8;x6J!^G!#=rlLhg9E7o z8p`e9d^wkExsHab{cp1rx$bc@z)i4?9kaxv7sv(~8_Y~b_5*-#7vP2gI{ZrCXkf8k z**=yp0-r{$a*VtTdXmGR8nPo(;1-=|buH*^A`=a}u0=+oiTKEwU83+N5epnJTyycs zFK4Dh4j3BFOvEJxe6#4IhB-or0l)WvL@)3~L-@D0jLZE3ul*eZf~1z$)jv9B%S@PM z{s0a{6N)Yw>Zf#od5}+g=_o=LKJEyD@3y4cN+?IiC1Os*@LGl3`}J6D_S^HbgeTa}i-t z`}ug{)qDJAKS@e&)aJ9R|H+u*w=^#DS;A(s5FUpPDr4?z{F>TDrQv2!W%)VEbOF!jnFSz56-o_6$UHAjlzuqx$&$XTtv%%RrpV literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/rs16_msop_single_return.png b/doc/src_intro/img/rs16_msop_single_return.png new file mode 100644 index 0000000000000000000000000000000000000000..152dae0500ca6ebee76e5def514733bb941796a7 GIT binary patch literal 35964 zcmcG01z1(>w(bNJix2~(6$1fjX#tgz5)|oD=`QKC0EvZ2w}=SR-6<(49g9xsl90S( z`tQB(KKq<|?|IHWhv(<{T`X8@t~tMNjJL*oC;w1_@HE9~1VIQTABa9i5L|osW;=-w zKbZ=XEr9=>vV5RwgCIn;=r>LX6A>kXTt*~C?>%vdUL1DRcrtx>VzoW1X$IFYbodrW5V85Vy16Y=&at7RyO>&`MP8&50{OcLhjIGb}_3~!h2%! zcke#)Tv;KW(x`gItsfr28MnPKy-?S(5p5G2(e6m3-5$+pC@Oka6uwf%^jC1sl8}%D zZe|r-rK6*JOhRgpKEe2H0^{xN{Xk4*2%aVRdeT<_o~66Ut};}s0tMT9=g!S#<{ zDef}7ozF*#KIW)CIv72AwlUM{guUa(9G&A{*>eJYInhwxx&G`yZY>)Lc<`C-)-t@f z_meku)aZNr{O8{LnbrUGkBOa$JsK}g&&)i>7MO*^Zmh1}y?YlKeB+g{Ms443q^tMK zpBNb$9v-JX>k?`K(7byiXXoQI^+KW_hO3P=#0#1Yb-rYQA3nVD4P&{N(D704!AYlIKXF)D zGqJm|g3hF+_ABC#9+51UEU>(o>pV{3Uq9i7ti~PfpEyIxB6{y0&hzKb*%lH4TAYZD zn@f*&PS`CEz1v#C>h%AJFIvbbT@<`V7gjrgX(TEuE6dWEeQ4UBg@gPkceda8{rlNy zg=>-B5=Dvqg6C|kbK9aehL4YL=U{uZ<1*V>O@8}=!JU#9bFVzBt9dtP<9MBZ-Mn+> z4x8PgiXRQvX=JqukND|AEuWpTG2yv-yx5Wso4Q;e1JhNoeZ;O5h7f5Q! zi50!XiombE>Vyf!A8)PVpjML=PT56jxFry)Pn?J+_d^bg|f% zl=<7DoY1{Ww}Y|q@s|Mx?c&?Z!)t44sv)QEDeQ$f&wowIa%!c})z$r&mGvWS`!21? z61`&i)_m#%K1(F%hU~X`e@gb*-1Z-d(qyUWao#dD0ebHis~Q?kxbFUXL_>_;3=jNYK1Tx+29 zQcA6h=CgSp7#RO6+wPHa;PnMklKqYH?T=k^@595r8yg=?x2Tw#vy3>-QWMC@)Q;D9 z;UMPA%T9eZQ;j4;j zp-aCjlnh}cn&0+xl3bkU!=xHb z`{B2t%Q=|BmLefKqfP?-0vllNaer;cy zY_M7$D$ZfIpMUbzY-uombz{3>kjsS4aP_H1xl{gNwp)U>p>jXIAl(OnJMPF9$0tExQm7e3lQZ_pO~s9r)e|8*U8;OkQa1fr&< zx9k@CUoxu~-WUDYVYoW(Mf-d+lIv%G_EmJNJ*&ZYaBz6K)j&HL>%3h3?d_Sh1&c}? z^g!7R+Nh8!30l`T$Ip;n(&(i!k_f;>&@G;4+|%@QG*vnC`TEp%UWcD&&z(DGx!BLX zI9f@2u)A3!z^Pw#pk(z#MaA35qWo=Z6wg&5AsUGQ8Zl#I#={TqJ(RT^rwcYo$;c*$ z-S_ck+hRm4E!n=vL|Cg^*~8kKo}FopR5Yf%ZTNmYH!d!&dLpC!HL;SD3%m!SN2_VS zFrw+`22}y^5cj8GXb;gAaD?l7;lhQRwB=Eqnf$+h|Gp$(cZ+C$?Szl7@A%A&C(o$M z`2fM)n_Ekx0dhjWk0Cz_%+y^toVlf>rP+^CGgtRkDih!c9|*b>4Ib1sH=l8Lp1!y^ zTuSDC(5#(hvTgo3DQU9xtHRn35n>!9^cuYm)PWfSzcS)5 zx!D)O$<+fJ)&4!KtysT+hGy3CH?Sf<%8gd2RJsX%tEpkPu04rVwFC%#`yv~~_OuEq zI~+7YOXN8TKMyajLy>N3`ynXgtZzI$C$x`t!$v6OS+pw%J}!!1q@|@z$n3bFmag>s z=dX~;1K9y{BO`_kjbdD6^{ax!oObquQm0Ku7Z(?qd4uF40o(Zt75fuspy`dxvFli_ zj@@(l)gj?9HSUETMVe|Ze$vC3`y2YL!MHiwuG`~{fme6-1Xeymb>+3%FB&SV4i^bjMOAjvdd+%Ie45i*POz(ii;HT5faK^DIVbj`~V@Mq-7^ zJ1gWfwFIYUr3$3ng0;DnO&gL6mK*{W3CdG~?cN za^lB)NgVHvbH6WYxlvCzH9bwPaf6kWSiQjfID)=9BA@h-x>i&I&%-)b{MoZBN|{=O zh_}E0ad|r>%k2!!!r_6_2#@(t)k0<^W@6&G3zxfFzC9_~g$u~dy=1JK(7_@ntQwtf zZ%#Q(yrU1EwHPUT*V);L-7QtV`7mEC{rdsIJL5hgYW^1fE$p^< zS;RcUmRiulXGO-smay!WV^vaO%8GrN+6~Y!aQ0cfdehbMZaTNSW3%xn{PF2H zP39$gaO1#SjWkn~alE){X zES|q~>Ey@71+k{Ri)3VY$UNmuA&;B@<~`y|9*c{n4$jV3d3eY+7yA0Jg;Pp_PlgAC zZOovfqwUhBUC8(I=g(4Rw)5RDqoOEb1BNW&-d#)oMs?GfSZ2w<+bbz)eS`YqY3zDH z=-$?nubl86L2+^MpN5}jq=0V9t`V26F{iGsu8?omyT9g|_LSVVR-D{~aB*?jp6xrh za2pVzXy)GQ6MxED9?xjnFLqA(tqPO;L8;6jZ{ri~LnM43*B44)i;PcBzJ|*u%qkDSb|{z`ZE`~yZ(MINRLtdZ)pqakrIFET9^ z?mGr5$B;6sJ*``xHXKPKH;1dtlO)^ae1pJaojpEWrHbMMbThOPCdIk!7JMT@Zd3R_ z9(r;oLDj8B5?~vk5}9R#6d!~ArqOo&*2wYY(iMEfbfk=Y)ODMBx$@{xis#i&g*8{F zmAIo?&&>s<14>@Y%gEF2_Z-t8&|goYje@0|i^IGA4 zEv$&u`JsJu8d1sBCoC`@_WAhna@krvrQvx}&rWsPV#OzJN=Xx%X7~f%tZuMJg zWhyIM^_((uv*8g&otjXenCCF!x}`twq)8 z;*HsMJj7{h(a5fH-jJy*c75UW@X*i?#@kOE598eq5JcEw;1#WMW_?z?2vfSqs2jAJ zPgC-Tn{3lf?bo!+oh|}s6K}v!uhl^ZB%_zbMWT5f&+#b=O|S}|`KebIQ1`C!HX!iD z&spD;l@L9#Mu1VP6TYnXMcJSz-P!$_fHY+|;(C1gL`NlHM^I@xiYYH#E-6!u?`N!( zUfWrl>@Trps!+{27M7bMqt@FGfP<6syteD+MUNZ-c{uUOc_C!3)5l+DW@cK;_RB?a z$LHl;=*!ToISjr4o9$VD)-$9@sPmS4jC2@t4U}QD+32hXGpM+vTBepPW2glf`$An0 zf6s>ae6zN-aIIB;^5n_VK>5&+#`I*1pC7?AMZS-|`}!#sjUo?NLZ<|swnPJB1+6SJ zsAk&Zh(}NNMG(?*6D%(;_m|qUvS^ig!^t-tE+Ev>(z>KLZW{OXAjM|An*loHUC}JJ z11IEeoRBM{rd(f=94#E;6?*y;&(hTsG)wJ5dgCpGzgN0Z1GqenxNL6r?EvJkLTmZK zW}mnFy5!XCtPb?v2UP6$e^W%Rvknju5s6#AT^TR6n)FRk1(*DX^D`^jGwUI2^o!7Ti*Y@ap{f& z8;#S>v*~)@$%cT*Y9UuPXj6%!Q1P-|ey?Nk$`U6wt;Wa4cUE5$pQWPmOFDOM^`}n2 zmCKhAxPD))bzbouq;wkIPFBvOq2Mw1qsJ$zt=e(;1EBV{8z?g?wZ2-&%b(>R-ZigW zrz@dz-FufAK&<7y#C2!A@hZT^Z&6)ep4B!6?ripHug%fNU51y2x0irF@+6}443v~~ zuv*szXvt*%EG*T5G*dMsGyV!4w#)nFna8&&2p&HuVlo#xi>w( zvZ6gFry5a`#%!3crfXnO)6kIA8Mly$*239-H=*NcbGtBQnRJ-_L2h0V;mk(1t?6L>PkNhIOe7Ea`6eY6hh}W$uHteRN+jbmEYQ= zi!ICu+1S|VQh#!=yO3$v@##3lZ9@+^p@R!SS`O7?_9RM$u7H7F^E}_N{XDv z4)-2ay1C|^IwJzqJl*1G>Z`)4rG0}Jt&2xdQIV9k4O}d*zCZc|AGt{1&>EZ$_`3N2 z&JoQ;&gj+c=v#^-tP^4EqVnF0$HqHQ?!wkM}I? z?F)ZjI(_;ysso_R@7c3w@H2^r4^c5^wNsikUNYzgKuYulK+AaPxG|$z#w^{J>$+zr z6M6fT^VTB3lZ_a|eET*`^ct|pEX(ox!NI{}&=L%>1-+B^Ks@=hNwn;3*+29<7 zOImTbYZ4q9I`Ok3!Q0QTwk3j-Z1=C9zI7+%?y<{-(S!^I!6+?zwdI2kT4|h zszk2?!EV13i}I9|V^nDdV94fAV!j|!Wo5|^<{4d;l$2B=_hK&?I-$W}W3nvJtH0!@ z$)If0r?+VT!i;K^aN4X-;oiu|NC*wcQ)AG_8la!aWJCuA1!dc>Xr=l?)84(r_7nk} z8$6q~DSW}EH`k<(MFu!?u72w)@r3NAt);pVJ^|zU=1}IEaCRNoWrv4wz9bUa`IwZO zutT=6^$0{f32=~|ot?`!Zs3F3qeSUjUi5e-f9>ms1j|H?R?V>N(T**l3W1?nmvpuK z`@q6hYlwvrMD&<+7>n5B$AA;g0WWBUShwC?-aoeX`}AV!7QEe*c&esJ&J%RH05hb)>U*XZat^;_Pr zu39EqxVV(bMDsp!G);52)!EsZ4AARMQ(f=Z3HT0_e`+w_L@EwGk5rQJ-mkfU_oE|WUQyc^_;$~*$VTrf*)Xa<&oL!Vmh4kiHj0zcH3(}*7TnERT^Pbn8 zwz9Y9>2FXo4Jm|={>x8HwBqQ{*=Qgq5xNKElF2Fc_GupthLw~Bj_Vu2!51QgTuVg7 z#hX$TQ&W}<%>G(vHtTNVZ^=GG>s{Yy7xwjTgr^5{1Yu`qZ)|Exu~W6#3o{w55ahR8^afrz4%%2X z2#uRt(sFVrbz19Iki!80P6+EG%XEMPxeIVXDNQ9luP}^p4|K!Z{e2N%`7Ek_wQx}oMsk^Wf~t0B zZ!s6RLS=Q|cuRM5F@vKs&>=>~)8)?F_{gvMo-=cEbNJe?Ipu9KJZzy7EbJ`5*M4ga z0tVM&CZ>e~g^bzu zxD&{+6DOG3xj+w6RaL#oz)&5*X>ge?WRQv9atuM`J&g(%a@&PoE`AoS)TL-@_DNW} zS3r{a{{6eRj}J$G-@sQci>k5~ffqkLfR0{HS;^(&W+&3cBz zaClrCkkXjy!?wHW#kjo()Mo9Ir8P0d&ELOQgQVI490}2jQ?Q@!KDD;C7S3rv1m|4& zYo&O?*F2p|3l=^=l*Zv^4zRP*uU z$5Ax`X<`Y!-CLQGa^!oC1eKss?eR4}Ark!dNd@M|4|%{-I<1jhO&lh@Y4`5m$MwkZ zl~vC-ehXVg%}6^(_Y}%zHyxaup3ikA?rdQ#vY}_ZUU>uxI8b@eq6oKabpKRmU?JQT z+@{b)Pomukx=pp~_OQWN%nPE7VEa1Th!2iXA477_+#OJT1q*p@X+Z{Rvdwz$+>4O< zv>xL}c3*>SpcFD?G*eV2EV;Q9{(4>>+0@(|1a<8+BKhFK`^v-3%ym$|8=;ei_)>~B zRY>2sbxY<`LW15{)ytfx)wnp9*I5cjZGeTvP(uvs=rAfYP{lkTDhsT#Fjj=5AB!9 z$u}K;PlsI>64Jsaxb#s&#oVM|5N%>M>q0g&esJBS;W|zgj=BYvmE9=@SEsJERTi4M z{=wzi67tf=89nLEoueK3wk|xug)>Sg%7LTT?6Y2_r%xL6C6Shrl7IXdS6f>?v|{OgsEF# z4@+3Y%LsQg%QmQQ$=@Px!W#JqJn?k4xN;gl#E)&=g-IR z@Cm9$%AMB^_f~X3)C-}p7%u5C#(s*-R;mX!(z6%MRUp=@5Jb=t)7Jvh8Kx9}##G|D zN8pTFA?V$w&YTGXvfp8x4>;f|pz}z{W;a+nozUY+NQxadzPO-NoQ8~yOx;Yqt%+p4 zK)=4OuFfegx4t0S|Eg}PoGd4sfmZ3`kzL*mCev5)oT2k`f)2Ek_Dv*~?5Ywdn>IVhO7)#fz%BdqKCs*FCs-vz; z&DB~J?bupIjW=6l^0aMh`bpieMdbn7S*ERYb+3Uq>(|mE(-Or)Y&Muz?SX?Q4>~&( zs;jqd5m=OOlA`p(aYKI}hz<&NX4+!Z=hoze4|Ma*aH@Jzl>6jY<~JWet0n-l^$k;*IeDWaUj^vOK*;$axgS5 zjun~0T2v~=V)ISHkoUreJ0h^0WWp~)Exs7@kRH54R zY$q{xa?c~7)heI5f%=LL$>x-)RH-1kecFbM^3@QJDD07^hMSsFLI;8f?f$$vRAhyx z@I|H??61`o_oLF@LR%2oQ9Bb(Qv;NiNAmI>u=k&XyMvEyT;s?vcW&wDH~w(X%)D9U zOUuv;40nSgRUsi4`c79jvbGVKX)u}X?d?JQU~0ceN{Wj>@ji*Hf`vt_MjdNK)rR59)z|sB&h-wNfRcYyF zAuBQfS;Y+v4HGwG?>OcRa$A@ArDAC~3owzoPt9ivnkYRw>~?7-q9*TPu$~mw_|eYh z0<8@>$SMG#XJ{{@W`kx{4c#wf3w24*-8Fi2Xpj21HD1ILp!g$qle!dlM<`tb;20#q z9W4^ao+cy|Tj)(^H|f2VxB@8neQ2nDmVc89=VVHIM3j{+)?^^(I%mN-X-+mhtv>M) zB)m9+$_QOZ0&TIJV^a*9HHH!~3D)j==nfHZazN8aFx#3r>8Q@6LsGoNXT!l=fG#(ZoSvi`rQ@)p*Eh2~5@f{r$0VtG%RA&%wpIz;*rl-suMe^9i11vPOmU64(>n?~4DNhcu_iC{?HRJ?z*7p-OK)IPlrv++%xe8K{VCSD6Jrh~2qQQxCjVM3^$hJp zfo5zLo6iesUGE-*XPdAG7b*FMQQ)t3aoAz>Pw)Ez z7eo8!H~x{F_|LuY{~>nqFMnKHGlD1Y`*%U$^y&Lgo&=YBiEw|5);zOeC)lD9qrt44 z#B0+B4tm+{e5yV(r~9FcOcZyk_|=jaFo6O3t%2v|g>rT(e*jP@stR!*%H_y=GF>_;cUG zj+(MRN&3`VhJ%X!MMsBw*@hi-rq}{PRPJhKtu$SV=cktDD6}2%u;sAVGmdSpcasoU zUmG4zeFy&SQ&30I@sPIq?y2%mZiyoh~yox2EX45I1h6yxHv1`2Grl0GI|gd6}NR!C2>o zQmC%^LK)72?s8N2oiP6cjNQ~^sR)_9n3!09xib$wA;p{0l?uvKrSz2U3RELA!;*sT z;IK7dUY$ZJ$KxFglP1pn%nY z2!kMC6agouUfr%dqDCyiTllp+O!@BJJH!JtXdU<+m167bU_d0@(KZJ?*RUt$;DVH6IgcwZHVYnCurPwP;4KP~MRdeY%| zd!6xO-d~SU7R2CT!W`??P|jvQ>dJ#AYmB;Xq*i)i9xT}m^sg9t303&wh)0?&M_E(^ zg7qyXDyrqWsW=BLJaOv}bEtIrodX=M8CnTM6IjbuU!f|m)F_#j!#$9PZvm_p$oZ^4Ly;DnJNlUr&{X^Gd`LrP*}Bh=`_VzuBq%3ROLTNVjX!`u z1JKFm0vVY!(EICGu2lbA(8zxNwy3l;>Q`+4hw^pq;M{mWv1q2*mC7S6wE|Oyfq{V= z<*dEBE5#ZhK*W6bK-ZNd7X}DKHQzYo`-(sFfDLWd?Tr-2FyYw;5n%zdvvKaEe~PoD zhDNlb#ru$MyZQ{aFfo}uYO{bptbMm-_|@?kI{6S&_eTAEG#TU#l+&3Gqrvg-u^j|OOK0(w+8A34zgUntp#2?tczg}C96CY4;TGj3CxU6yn>tmF)JAU~WCt;7s*%MNE>z4L>ua!b)K%LQF?;X{WXHW5?7a>cgVFj^^%Acs zhB+}Y5%4?_xWWF962x(Cmc|}OD)yEI(zGjSU&!; zmZuGXJ^Xx8LXoM^>Njm_UhgqE?E)tO80}R)zJcrJ)jYKq*YQ#Q{Sl2CNlAUv2@v#z zIEoHLinwUJIIZ8dFku?n+uN_hp}kLKpxWG7&Z--R%m(|jZ^shXPk4aqlctt0#jxy= zW1<%8x}{nMg`#MqP2iD=ii(j}Rnf=|BfZP>+M3S^zf5Up*7p{b_V@Dr zTY8Nkz}>)~h^N!-9tXbs#AJYQ!90JAq%21vK25V(&Ba-3MYQlW2I%FhF<0!) zGu77BDLPfag58-*ibG|z>0*OeNBl>R9-%_3N6wkcoE#hwL1H|vzL~9*%C*CL^X5qg z1_s2#q%Y$c0J6e-T0ZMz$osgsOw)u#9m|7-w1@wo&;DDA=M`)+Saim=G^m+p2XYM( zK)3_CR0aBBwn0115NyF46(aK!rycR`0)e&yS!H_dCEkf2smiRcSNzp_VA=l0#e@}C ztUb|C^4HK~2}@nJ&l8~?WiD4~4;A;jbOo8}kf05Lb4fzN=e(8n>t}}u(g@c+F)!~4 zD5ms?Zj}elI@lEG5085+4izhai<}71WE~*!cMxB$-MOOyD|Q;Cn;^AFnwq9{Ltvse zLz4+4Ym{i9Kt=aEbXAl(L)t?gL}}fYaCQ!}!P{Te3o`($J`@!Nh3`6mn-Gu(BW@dg zpyIW>8_8|P2!Wa~SR#`8`d?oB{BaNR7rGF;and$0Hcs)Q7El7vNQZ!c_V9*WtcHL^ z4o!YcAp>8gW~q`zJ?KTs*0$Zz|AtX3rLN?9>kP@qZz5;Yz_eg#@LxGsZ^pL@qs982%F zWkjY6DeiRP)M1HZL&ZHvG5JwVe||tY_N%RyXIo>Ap|Y@zkMlBd+q~_=r2*ctWh1}V@}v*@d70p4#%lW#q=szd?lK&Gb0$nEpG|@PV9UTvohIafO6*rKAeue@ z{^2?r5`_-_J~Hw&0#HK?0Fjv>fiHxkK0!?8#->?!G6|$Jgo66YLHu^vXyqaGUzn)# zb=aLtV%Kdv3kE?|YwKZL24&NLA}4-#m<``ddYsw@@Ms~f@06A;EfKkHZQO-s6>q;P zB++qjoI7>ulpf^^o0=2g^nui&GB>%rY`*YJr6oE$qKk)*j~qUKzV3tmd=s)S4`X~( zbM+yBtCB}#!Wo*&q)(8{I&0mcE}TC@$Y$ee{DEf-GSCJG(Prk@ydoxM<~m~GeGm9- zN=`!8t{nsVTbX_Yrc_6YBGa3m0ifuSC*`TZlTZ_Q=@v1U27JD<}#eUHWLv?O3G3=XNv+2vfn9_ z5BRjY%5WN*qZ_O*Qa9HjuB`)SW}DufC_%raw!Rg6l7=;hv7SLBA3o&nw*Y+H2{9pn zXn~OGnH$JWx_0dvq`UtkqeO4u?+^D1+UzGgr*qRlUGLW8J%E|YJ*KS@4T=N&79`j<6X^|Zy+sUfW-~ee5G9s& zQLsUl55Hdrqkh$bWTC|>aGsOfwgM|)ps-uil&w+gVD34SC)+-B5u#?uojZP`!B}W- zq7o7{U0vsig?27?c6H$(|K1*X9159R@h49%IBhSdrzN?l>MW75XjB1x|54%U9DT>} z90=itK-{5InY<`Np9ArM9X{eTh{PwS4Rj_mnuZQBwcXKXA=%mJgw*^%gSuUr_fMTZjf?#8h8Cu$6ZaPv z7R~@iyCVeL1e7XYZ~~%*-46={WXsCSL*gKn%gAh!d@xjOgLr_>%fRD+QV~#CxcNuc z^l++aM0PxSSib0C1$K*%++AunQCR1;UF4cu@uqr)p)|Jt%(vX) zC~&{cbC>sVTPTZyx~baG@ngq6nqdq23oW!0XIVjF1MNG{e0cCDKWZ+cu>y!yqG4J% zGrrnxzv~z$O&~{%per8g1eeJGa0`e~P*sZgk|IdDlF51zw2MUQ>d?%tUgOBzbnVha zzP{T!cQyIKY690cSn%B4)Xf8Z;^tyIE#>jJ&{`rS*- z141V@+UjuBK~O`TFP|M^_VwRJ|zTT@Mq z(V}e46I6&sASHT$l^z$GYpP~Fed+Cu#+T8}X*5z+44H`s9GskqfMg~nC$BE_Wrl&S ziK??de;ShWT7JBxl64np1Zu$ospdeiHI06Je7O&%%7?HpdQk8)!SMc`qu14bB>ad31aylVAsDsV3LxR4awGNkb<8a^8jf3ed>FVzy7mZ4Uto3u$T33 z(Q!2mgpy;g&JGsE->9%=DKjeZz+)=C(hi6FP>J6lZTmdPUc5Ajr!a@vD|QhCx0L(v^Jw%2OtQ z1*GrZCk^oh0G6$4^;Ce)S2s2|=Vk(Yz;r?tO%D&`!o`d6ppb**&=huog2G->@)U5t zv4w@yI|d7VUri5mS7Yg zJAV8MBV*G@&DYN^rq$KehJ6_^)fFINJ&=|biQ%_}sgf`?ig=r+^%-v+OKJ3%DZ+C% zl0zm?j1?~A%5OeY^b%G&Dwu;1!N0q`LLBqZ3pi&2&=!@fr}xYV8g%(%h$id(ML_#O zM>Jl$iXDTP!Ce^laXZ*lj>4D#%~C0{yaEf&a(~APm2)8JaUUcXvl306l;&a(vs(Ib zF_8d;%rr5vJXI~}t&cbj+IsZ@qRkGoP5&DZ7;sH-fNI%5sZ2rALp8C{!z~`)UOi?{ zYr7sloXu$sjN?KQ=x6#Faqx&W>Im)QJ{E1Y&!7$djzqx`3s2w8D(&V z`KkCGV>7`EzMz$0KU-K^bD$nSprc5^FM7?PSNQoU{#g}U+*Aq5j@D$?x$DXorZch& zrn*POf=%P&*sW_2RrzQ!S`iXUeCpIakghBigl%SI!2drDF(ov^ z>5PSef|R|O5mt<<{HR>Pkojo5XiO>EL|X)lA@yeE#X%nJK2+!4f+L0w|05eodGP%C^Ll{&oEnB9)EdE|=dq<=^s9!prl*1rD#R?u#7r^gYCs7Whwe5ZFe%7dL4cH?X=V*3mJ6mYaKP) zevFUwA3j~-GjC$AqOloLbM)L zKilsbh5C&y7l<@CfTbQ78%u<&Zf>FjF%(?J#}My#@9rrnh2}&T7V-f5{s9t!p5Syd zg-NC5I4+0|ULajhLi4$K^Cl{5WJ8)VVX_>a<2E1iu6_;i4^S0v3R6|@w)$OODHI|_@nL^OmI9+g?%LTEbW}jDxTziRCFJLtCP5q2f#gzS zYir%_joC+PYHCKRAmB|K2n$zAHB%T110h77LS(p!kVdE8?;aR4{+L3Sfw3`wl_}@H z^%tdbBppGeLiq#;(xsyx%#GU$TKeT_rELnt>StIcAMk~x`j@>NjO+U{Wj5c>ytLvC ztB$>aFkhgPil?yhs^0QRKFWFcy{J+dvsu%w2^Pr10-&n{?!zeP{(D^ypiTm4DdK%r zu)v3G+6DWItgeE{jGoH<^=4Kja_!${jenVG$*Rr0ncB2>2WEGe)$$MzDY6I(%0e{5 zay5K|ACxWtENegmKY`ALcmQTa`(Rq%Q)aGKKm&N8vl?A~IJVOoZHgQC8YWuGQz;Qx zj+J#YzQ;2ys)7yHQSKL;fIqE5l4Ts^yCxf$Z>w=X+@PJ#ewZXO(9oclrU zQb1etWDxsOF$K;lj*Q9mugQ73tVPkR_Y_ z{5RP{bJIEgP*?RC&5E-0nfye@D2~5vdP6xES71JXKmexr6^OKjK#Hsx>gP31P6hrKKf!|*%7Hlg_m-Am zIBql?0#aQQ2*t-dP!ryIriJ_zF>x4p294l>-}twJQ;T7#cOzJuT zPJ2ilflJ``UqpQ7Mk92+ag&}L+y)gJD$AD|tQD-GFmM&}|4i&KG*3;jA#D|Do5-a{j!;|_V{$WQ=9!&ePl-%V z+$dsHZlScyaMXM_y3egwoT9;QBhiHY;Kv-X((>C56U_D0;bGt4Xz1qZY8Aw*pRKJI zj6Aw^u!wDKC4}jZKgJI@4Nr`DZkt1Z0dh}~L!;!~*JcMDmO`gAf?yNOXtZ5~O<)0= zz$c>g`3SsjTX24BW-&T|4YOMR@#OXY7f$McVQXx1$I#Z$MtbCAu~I97#2q@~#O+6z zmv#iUhDToAuw!ZI$ybeJ0+w0LC6B))fZJ!()RqqfZXL(I;<9Y=Y zIE?8E?^^4Qv}K}Ap;@EnyL`s(Od&&apicHRotcGbziEK+8#@2jJT|YaRZ?q-Uv9#Q z$yz+kM>~6vc$l6c{9MUPLr=5l*_?a$%u@4ssaqXL8WZ1`&YN**!1Bnj@Lq0D*`il+Ys|L$?VXPDTwd_B%zQ2l!s~i!6 z*ArWwzi3HJa6hPUbZm0zGSJA0UREI4w5()LmeMhId-x+!hDK&o7^n(^-MSpdquLep0nWBe`xcH#-MU#b!w>7-UDqnul>#~y1haDK=Kp?0R_=^$>!y{x|_w}?|w;6%DXJz!ad>d5fw+vG3toNgP~FC zjmVv18oFb1dgPf|V5#}V4A;sFv9eL|)j_Z2)l`ro0T)eKII4$@#Y_YwQx;mp$Vn** z;y5DqqV<)5qCmS#%9VTg_arA})nvO0M_Ko(TL~S7)9VtqN5ng5_r^#r5P096{PNO% z!SWc9)SLRQGXrNT-VBw!#Fz8GKbG}qbz$T@d?1O#Q2$l`IRa$Ww3C2&_PWTV<_SLE zSv=%+tk&v+HSsHPOzxpG>iHj|XI+-E7`bayZCk{1Qgm#L1o6OkC--bA)T(Y3mWwQl zr8N55D5>Q^DM2g}7N=aW{E2Qy)YfBE(CTLY+8K_da)Rxu%eP(kTn$(`WP9Yj_fN3T%`udUUr zQp1VmO^UldK5(8+@@Q*ch!Z{m$3Im2+14;O^Rnyuv7(-IU(fc3FSj1!XSD3~r4ts# z&;25XOBPhLHL5#hrlGL4X6$^Z+Omu z2b*L?fuTMNmHQe-e|DdVrO!kL+qC@B)}M`a|}$v7WbRNd`%-)GQe-9I-Q zM~>4@dgW&SCMBH0 z`RWKSzIC>v+go6j{}4!oH0~KOXE1AnuuR2q?q0%;k9k=LJRkoMd-8VNriB9+F}u<5 z$g}a}?bXR2S`}}kb4T9Fl@eK6oK@*f?y62V7o57rTDz%T@X>tq(2(sW$@0s4hKJ)+ zJE9~0a1Q)l#bC!NvB!m|pKqFrOwPUS{B&OI3%}ui)DaRpNu2_J@L4~FW%&*T_bZ7S@xMHhN9k5Re+xmP zlY8*>k9%hnJ+ZQ%s6F*(stcwb@`d|83-jU6EUJYUE-{;<7t?+-2RMWJz3tTgMpFf-PoK?$bBQ7^02#x~|HuJ*z8a-V^f2d1~eJ zow;JLb_cmTmep~RN@#H6WzfOT=0Hb*O0?-S+bGhD6wgPEez_%qsr%p;k!iyb8Wqpi z3U{6O=M(+kDa1Tps2c{o0!`CEBCdDq3n3$IA0*gi=i@>`-h!BV9MaF(YmK)IGPnC5 zapJc$N03K(I`+{>I0i&GE@jU;w?vx+T+ozN{67lYs~A|2qOS(z^v7Cu-|7Rif+)?k7?> z=aAA2qcd;_12p7#J+r0(eoW6t3dWNi@mhwIsF-bLOewco25M4F@ZQJ9VnB|a1WQ~T zyc1yc?1n!s!w3B2esuUZ>*xwy@5l@Pzne$fU`_lnkHFk*`+Ufxly(<{S5G2pG!WjFaAe`&=v*|5Xi{mzgtI@@YMap~=;xjtY%8Ms z59}qO!gQ@6S(vziyv&0K4-j{xL$x=4CV)au?~ z@M}7JF)^!m(()D!%si6xA8wFvww^pC`JlZ{)V-^i(<#C*DK}h$p3@B5Rj`rJP-H)J z1J78d)40=EJTXC3C+{`o$D4G6iKm|Q%pN{V@qG2E?dx>6wSzD%F%5C@hM=OhLr>wl z?8Ucg_FD#%1^rmQ@-6)SA#w{Ryy}7In3yx0`Ac14dLa3tH@g4_j9=wc0@UlN2y#K$X+Bc01rb5uR9EDfnMVvaK8?qw%jm@nC-M_Oh79{C7wV6 z)|;X&6%rX4DG&N8_|z~AgNE}`Dl5^n!bq88V|#l841{Luw^Hn}D{p9(+A+g)fj<~+ zIxuhpY~7NtqP&5|nLs?DV@V)MX=rY7q29Q`VQ`?U-eaT9m=dqLZ@{y>XPao+c3A0h zRO%ezPGxan`O7hrw*2(Td}bD2fuWt!9_yLvHT1g^{!P?CK|yiM1M(&#Jv~yuRKRq6 zpr{xEerF>{1lL(vp%Ba52qK{5mH}f9>Mke-LBD>z*egCmdh0zf?B6gDBqpj0r2Rus zP{QsGsDab1Jfjy#0!vExQ5FWVr@uyvKv1^jUm@qzZ-hCqMeW(y*=9%}J!uu-;ZcSq zzogCNZ?6xxAOik1{;NMVvw{(*Y!K>WqACu=kwf9AUN~vC@uw`Mf5{E?@9|s9%jNMG zqY`lLRQU{NfWp2&2wP~IkHP9#*p~OicE$3PV{LkRdTLzvHgJbET3zYRwz_txi$-y= zbUIG9wVirlz@<~NKB(jrZI}PWb+;wvyDlywD$ZCrD4^GLL03-?B+=8r@)|%=KoA&d zNY2O*hk0iNfjHDRhypFm)CQ#M|<16)tj*zjcDbB!X7g^#UmcM>J z+QVYdQDtaVb-xGOmU>dd4sy26+&3CoDi#<)!y|h!+Ypv-fEwrx=VU^;ayO)*Z-6{M zCf{_?*e@w&pr3EcE;BAO@Bdp6`K)Z{5Ud zuW{~x>CqJ$xS13FYaA$J_?FvCjb`puq`r0ICbAnH^|~C@&$B;*=24Rk6MMwq zP-VLxfDHW{f|ij75_iACS`Vp*eU7d7(3u76vUs@PuC$GRuhdF?F?|Tzx4{3t{ACrl zGCxi7OvO*L(&48@u;aV(m*&H8VyKmNj|+q2=S#*K3i><)GjoUpjiV?Ui7qSC5EZT1 znK*+Q+>l*s2G99(MTM3)hKd3I^*uB)w7IzncbvEZHUJ0Q!-s*Dl?=%-?qTG!Uyg?R zkw}A(KLz)S2#VsdXu>1Da~ZT&2ul)`a0x{AaSv5JwitZ@wX3f>yYnlZJ}XWPLlKU^BNe7 z)RGc4xVI4BTwi7!0_T-Vwa7BQCcJ^xT?3z(<`#^3{Fy1DasBmZkJXKTvXzoCnBQbT zMfCR4qU_{W3@mL$9;Gf-SsmsP`Rb8*r#&al($X&>B_&Qp_I6qyBU9(7lV?VLZ7JGl zSH#o3j}a>>2CT_{f%0ACm(;W6w@b~vOkDJ7RpZmbXBo#ZW zdW#et`tbH1s&G}0jEbszp4}f%8fh;r?F)6ltJ&qZtJ*D6BSXXYFdcXkvuS5zFez)0 zPU-8=I}lY*M=h|Io2?WjK)JR2pxJh*Es}I?X{ODymHPOu)leV&+-~{i4-;%uYfSr* zceX4{aO`d^Ev)?(bl&7k>FGc=lE8<=o^Nf77TpOK11hO^@Q|uX7X@GU!J1373Jk-Q;`3$pWxeAzH^O`gFQn%c1s-3WC>g)sclH z#Jp$LQ@Z}CC#veU%PvLx=FziVJANb-5Q-p+#w@oHh=a`)#P*q*&Z599OU%r^zG;Vk z!$Z7~Zdh++ya;qf30`CHCHG-r_LP-x>Hqwe$g$->_vz~CE!Al7q;+=M;JpjOF-inj za#XfSn1jwNgYQRVMHQc1|F0{vfzn2Z*=1o{N61oR?#VtU8MC~_BASDje0KpYPIjzW z*$^F}&O*9T7?_Jp_2u6rNKe7$5#2l}u{|Y(qQp3ENwZC)m;}C)2 zwl?(9jpoED&%RY!S4ZD##?)$TIQT@LDCt2vx@I;US3qSbDp8yd zY3xEI>0rU{*4`po0HFkwvO#cnEDYIZ*O)br;)HG!YL$CWpUy_!S#e)$;b8?a;&j(5 z5xD*6(RAo#V7UDSjt~7LlSiXGgcXPZ;|_#;gb3E*tVxk_QS3$GZ2=W;ZJw_>i46eV z6~SV9cc+x#qcLq#h3vx=Mcfh;RYSw9pQ&oRtdx4W70kR7P*7 z%>#I8V7j}XkgyXB%@HKG5gCQF^opxHaCNOPNHPIt0a9}ZBA&(@fZG3h;zX(s1RF@Y z#HWo9exI)oHn;w^D8~yyznYpxLvQpJ;s~_xw{HXOxu6z33~|np4|lh6lM%LYwBr7b zgtq9Ys5RInxyjdy)zi=cqRVvhvP1eA5zzh$F|x);%jpe1BTf+#x7>7@#=EW7iYG2Y z>EtLDtm4kSpYm&abhQH8&X?xcWh0SMg7rU9GhWltE2BLjF)@(GZT}&Q9?9FXB$9VG zBS^{CQ*Q9v|Lt zlf+gbhA?;!7oI|{wr28rgIsK9W<1YIF9 zXB23M?t)DKKV1l=vu0LP*~6a4M=cHhI9Ts-pAQW~=#fKo)Qua{TG(A9ko&BsJhxLyjQL(M7DO~#Ap;URwvf2E6}+RUIFYxp z1=gVLjE)N#C~RkXG<~nV_Bu4o_fG73!dRp0ojh*9e9&zhBCrtQKiQMyH2=iC@RiF0eoU4 zTjlz7fS;YZfu7GIkoJWpi`RTt?&hwC4XQaYq zNlh%o&vKJR7OMn6WH;6qsO{<*9kag^r}_a|1ZZ+CwVt3)9h7N}Noi$#@_yC~bBD5o zkC2t%dg#;y`g$*>gR)_yi+z`?efH?ljaGrz{R+x$(%;}>SiWr8X7p;G;k>wv>WtKb zqL*LLV@`u$TfEO`sTu5w*yrkWCYt`D*qvX7z;qQtweeO z;ncr&rqu}=Ty(B=L!JvP zJ)OliYKhj5i^Nyg8k;(rCEHRN&-NP_hzysN3F*2h=1#6|h-%8SVZT+@osyb1jX|rZ z=eEt7r`6n0_l!n+gBXzqj~?xKte=<|<(!a`@}bA20eKa(tnKaHcpAY)(y)4=eP(7j z{^sJ6h7XtLY%qYdMA56SKRMk@&M)uH5>R=TBYgnj#@uw{TmiJ5O73u3BwI7iaXQy2FoyArmDFvP?8@ zq$Tn>+HG4*7np@Fj~May8GV_wWy|PiZd>R?NwW4>mrR?HRoEQT%%?_A{IYi&sCB(7ZkkRjQ~LWdw=gzZvAMxC%M~W}UC*&Tr65Ou1dYmy zg#hUhq>waK7zK=U3YTFIStx((VnPbG_5xUN^vs6;D03B(p&4fp0~m4V>*<{Z$DNpZO&@ZI-usJfn#crOw*zxI`r?EzRW)ji#7?cKL7N=BQpseu?+#)>gwjA5}@O zFH3nhuyj9(ZZocRm`sG=!jnsBPYxP(A#^uO60{=(bp&m4iePwpDI;j zW~2lA@xK8vxl$1ALy)&hMrI2fH5a!nL#E>lii-0`EL>@%eg(v3InvjP^8qPYasrF; zzN+dBYEB3RP+~41bjbKPmibxuq&EBcX+f?Zrf6GJ8%B>DhAA-x3CniPc@jj$2hsdn zPLC$H))K$%m$X-ZhhOs5n8)kHr*&t!R~uWiy?SO%aStH?rhkYxQ+!%pn~x0RgC#xl zJ-4r`g!b#OqRtL{y~g8AwbGiyqfJ1a`1;5d zn7dv>pbJ{5F7@b@m>36bYQd==pe2(bK}bPCFkKoTQ&(3iR@0l7^R+DsZW;rFl>pIB zbl1x9IC#@PuU>uP{}jPIvCBJ2O)XpfVMo$;tkSs}#hEm}r`y5!fs5KbH%C!>MtXd1 z^*hbkT}Jks9odsl9%9)@PM(xf42bfjvaQL>ffA>vjZ}U4xHTH#OpglYwn{7Zt`&1A zOE&EPx|@z>4mz*-=oKZf3II)(UK(Om)NpGuL1xxggXtJ?1niW`Wd<6jLVmIyB zxpNXlK}l(KXh>)%&0kVnTqwB6Vj?RpP7qDdHWwFp&=s|<(JK(T#4Tri{J6Nx&20=| z5hVaHTYYoOJ`vxr7t0HSx^!h$?E zEI4SfhR0q4`62w{%FUZU3oTeTH?2-aT3Sy}k4u-(_RA?8rn$85*|BTaHTbN5UbikB zX!TB@-B^tpKj&=S0{QDt@Jn5Zj$TVL%c`oY>5H57-Q3bOh8tWelFhUQmLMyR6rFmS z&piGp0u2bv-CM@@+I%+1J$LIhZ^49&pediTxFt9blQN2{2j@?JCpH|H5#-45unK83 zW%v4EIo$%L>fkP zFp*TAW3CC3Q-SQcb}go&6uv^q+=KGo=n?9E+4VPPe3uDq|Whl`J1!rwl_v@|c@b&a&0?GHc9^PXIgo>Z+gSnYdz zjgm-s)6OS8oP`dBWfDIy>)Cd@C;N?M99_0-*$0?d!pa$=p%wqSI9vs5-Xlq=895!@ zVZDu4$?FW()y1vh3T8EBIV7%8>b;O#N58k%MqkI)Dea`*25W{~5zWoj;)@k>0 z@9lc25jmYQ;$Wqi*SPP=c=xOJhMrgKJB3&EyTwOy>|gOVerXZwHL7~nMJl*=(Lo!x z?A6ylmjC$i<9B|l+MBux^-5^Db((`(4fb#IMo0ECFAbl3Ke5-QsKm+F_hColqP*{+ zM$7)8`gu|MZ8XQ9rQ(0@+gk*^CVh)@ud1pd5o+jvPR4{zW;S>Yb)LmeMqliW7)LUl z0JvOXrZa0yq40e{nW>OBRkNVJAsW@jn&~xV6b3ECOqmL!ZVBLZPESVj-J~R8qUYqd zO7R825Elxq&j~>HaVICIA@;!jBPoV`2-CF$-ZIkT=-+kXagaH-%S@McVXg7O1H0P> zUayR8q2}`>jEs#r$cwc^XoF#j#Sg><_PU3jm{ts6LRMzJkb2_m?hqy`i+gC5qDYY< zdyiv)ZNoWRruxb5?u>||>rJzuT3um|`~<@c2MH3j1Ds6PzyR#dJkamM4Bdt+k&zeV zEQ=qCF`>dn>SOhjE|QB0U{SN06$?xHMJa7b*pmuZ#`>Jn=5xYE>dO7vYV2)_^eic+ zw6qwpj1srT%h|an-&;#2*pjotPk6dXCb9b6RSQf?%U(37jY;`%Tz)DJ^8m0T@g&Tp`2Zz?z*Q zCzI+9>X0|he%08t@rwdb3^v=+#lVbZ!jwQ8nXlnum2QOHOc)ye%GMM2K7b_LreeY^ zQ|~oLj2fI4h3K5IWOus$UsPq|YSkC5ZER3r3BWjUDJm)$bxy))6KqK55RkSM00_$I z68H_eOH4||Da3b%HO3NP3<<%9`g3kMcoz3e`55>(R`EsNL>CA2s@v8r?8_l1altFM zCvnOx6K*{_9G56Wx`a@p6~Ql^F8jENS(q%vlx}2bEGJ)h{ITk?NPvLMW9Obdp@l(5MJ6ix^Qu*spjnL{h>^2ACu8*N72gf083I>#RAYfZ;o<_9eHA}F(#5XHf5Mlz z&#}O&X|gXShL*8~ZL$-sW$xOOzWF$#&Mc(SKG8Mw%En|{#V)PcUG-5-((Gj0^jW#N zB4x~~c5DUqv19p?Ou9{R)xW?3GjBQC+ph&odKw5Y?4~`@_liQY5qk0$ntU(HvTh~!gf%@d9_0qPf~3O;ao zcT66a0w>sPY!U=q+LYUL`XaK!4rFuJI)ZEXhK&1Kz6hkRf_7-eu-3{LUUPj#5+*fc@p#_dnqj0;!1WDr{PE404=Kr1lfG43WSOYP!LMF zU!$GGQ}#CHLVI&EId60Z30P$M`)$QiBVe!YU70y5c(DB0+I`J<M{l)%D9I_^p41O(bWq;x}|-j1Cab4VQuQ&Y%Q_;h3r=o}m=mZz=lW zn-XM8Wf|Y5yBF_uii2rl$J!rnxb^ID6y3dQzu4NYVbj|s&jdF6TIgCgp(;CWZ@(4M9pf9G ze#+4f>e*^CBxr}qx&Cxjo#P07QJA*$M-v+gnH#{pBzUO-n4-QM@bUe-|?r}C% zw{T=+7H^))pxxWs(Vfx!jm(wqasF#G=Rd1weq144(NXYJme=0sckTR*?eYSY=AOsJ z8R`k?u@YZzWlPj)x_VSx@ZB7nG0RhGnuH0(6l#i-gJ|$sBV4x z_T#>powYRO?7*hLZ2LL`DJdKAey!P~QahiFEKEukQOs2@{6FJ%@Be1c&P#iCx9_U| zwvYLxMcR^eEw1k-w8nbBnDP}?IQsw4Y-D6|sJSZIKkTJ{RPcn2%IW?}sn)5s?X2A7 ziQ5J5h`zDvLn&C=CxU~k{lzA@)raCsqKq9Z%h-&R^fvQ&^7j&b--GA9@6I$FE{yoF zR@!K&N6KMDEUw1Ux$lj2Mms`TwtQN1`D9E$vX9r-pWf*QS6WUg2y-7_?4PB7`sEFk zhLN(W!@Ht8)DH1kVq4CfWi`j~*Ut>IG@07c`d`GjY+{J zeN};PIl4x|dlXGyc8I6nxTG;9|7QPzL3Vh+IrY+!?9HEReN$#=T6~ms?3+6#vu1&K zx#V*cHUCAGG=nx@)`V7iQQOa70wxJg%^)flp)6+ugM#?HK#P#w|Ny-gBmnp4d=?Y*rAX8JAB)3i=aqq-!(u1iTNrdzb#Qi>*ADH9E6+W%|lK{c4`9 z@!A_{JU6>!)ib9Ct#8y0YspMhDm@-e{ZS`gr|8aXSwY6!}=ch{T@SFeGS{aL9jE4OT z$G#ekwSQga@k&KdXJ+J?H5raeR+}j6yo9Lka^NJI_>F6~PBMx$L$nWRogE)CyW3f> zJi@x3yw`VJW5r;uh+~5pCDO7~LoPR4kQ*cK__+z48=D_>bCI1Qfl39l2%los+i-|{P* zExzb+6(0qjH@)uJs&9;9&u-WRc`KDCn03yq!$ES}R&^-5Q zA?0~SxW364|7hiDgS<_+$J4{kPs`>_VVM;T7hLlzeA@L1bFaEmB=Y!$t=35ORcFxA?uVun8V9m ztm8cSBQavLo2TkA@(MmPcmLWOb4tE+NO-`RQRWhR@6+>SxjY>;{)F{}P*+)ZAvba} zCE!|SjEaJls&JM6c}A#xfxqIdf>4*h!+6DYQs{;z6wDrr*dLqsW`;EI(&E zp*Q)X(+0FX7v!tb#n!Y8c7wX%I?P@G2IFbw(e_L=s4;i5(I6pH@M-&&pS*j+-aS^RR@b?uTzalgs>OvLL8t{5zOaT&pGhqSrgW9-50 zWMT5?FU)ZI%8PJj@_2=|oR9Gn7sQ)y&Xy3JzWK<^E3?i^mPTMPA6)iOiQ0Pjut#sf zS&!9gr*0Q3GjF`<`$dW&r1Ri&OCxLIWTmnVXIJsenLWe03@Ih${? z^@DHaWSn8#8;fq7}bi|`L^KYrwR#;?!z|Kt{2QlC5#Fo#jjN}j4y7_cWsv%9WGa&h*k z)mZF=Q6T$+^GM@_VZfQ*W(jCywwOjVn}tWa^&W3nHP-7dVWFFRQrK)5`-53~&imG! z$A=z`Or%O?_-j6n7mX0|YnN>k3FB`X>Y*t!Z-mqpcMC@tZ*?jei!MBh6DGT*Sf!z< zR_ioDvAWF+GzR?_mw6u5O&TAVsC(V~!W+whM%$<1Y5rPl>oK2(O5upLVqaC}hxp_a z8sdWLtUuLBWuN-+A<;^1d~!*Mk<@0YkLEB#AQE?o=)U$$`hiOy?rFP^m;1YBUi8-? zmWfmIs6WqOpWo2J&)Ymna~6J!wBD)CS@Xy?_(|e-Q5xCg;mkOVjPXeru%s6s>n$I1 zYO*?YZFl2Ptx-=?uCboBlE`ioW=z-qsB8#kzXjaE!TS%-1kASQZ_jjmNCGpLN^_Id zc@34Exr=M*wugI@;_VCDV|cy(38`s*c9M~qG)=~XnC~h%_5VmE_x};*HR9_+MUUCd z%n*TOo1bSLVK*=eH?>|!J_tkfd|~C<6DF*ip6m8%v&`*hW-@MuR3CPnm>wQ07sbIbuv^>dZs&Lhcb`!2C4)Bhi z{9)mj9G4|x;K1vr)c|(0U0xfRmZmhRPPHPQA=m=g?S|~(N&Jpj{&ZN5K}X(Dr>=wC zhy&@{?^su0(8y?9?jLBEWb=2lYaYtpgknb|gs!+coghz4mu#P}8^UD{o(MMQaX1o^KMvB>43mWi<6N@sXbC4qLFovj3*+<8AdSneY&dSPI5n-J=$(sHRSo}tonXd z8XIzTjyKlDhA=H0+Xw5#&0VZ=I%Z9=a&dQGSH+;|n1y3vVQq@#RE*2*aH7LE0US*2 zqCcij$~v`dgj}SROi*BBz=tzy8>B{!AN*fEh1z|z#DSV?%clp{PPG`(z{y@zb&KpmXUKjaEn9+P`xEY_cOCpF^TN79CRI)0A7RsRg1vjZ8(ft1X5(-IFOiI$n z1xc8YgoFgV!L7(sl)(idEp4&k<`Il_JArf!WctzUZbDbhEH_2Q5#%XvA#Db$fyB`3 zP&-$bfUjHYnD-S5V-OZQTwR}G&K%ZsKzR3|(x~(-zah67V=<0QsA+4PVFJQ^n^Cy9nJ}`>k%znDDn8Ko65=wrsbn9iG1gbO!LoR!XV;Sq9MywD6$6RrMu}S?29*cj z7TXZfIdsXP(VEsW6`ocPirF+hwGwztAfVsl9mA#VtK9oCm$&hDR3cqx%3Vl@f{&*a zZ>`ck$DERt7Aa@KWDn6e9r9FM!j##I9*x=b{y&t=?ZlZl11Qu2SgHr4bDXzk{2%cq zCCy^j*r?l98(RPFSI}=Rk0_m7Ek4c1 z9D-|pUc0S&21J3}xAp6%J@CwEXL}d`C+wj%VFHpAQS<=>xnMTlX&`B4WmV-4UM>;J ztz(w$wai?i=zG|-(Mf^org0-OuwP8%Tv<}_lmk{e<<7+Zkwp&%F@ywaV&w>YD=sER zRAMBFj-y6$6#p4UyZUtq-Zv7FN`SPCvfaCOO>r7_8$-1I0?J~)*FY}-j0jVwtj*V9 z`WPD; z)#f%)gnnZ_8MHkNTB4cYnJCAHvqe*ko}_wkEHLBb((jqdL~#a<8zykUAp`l#ToOT# zC2Lb>SJzQY<+6}ncm(M}`_0VOgQF$NH4IL;460OM2~w=D;6^8+S&|crX(sZ-OrU|G z<3CDDt^@6`Ut^v0iGK~LxgjzszM1*Ifz;-U{xhc5e!|BX`)xmROm<-Q_>_Q8pFX_; z0WVRkfpo2p^G}8gyxmhYkUl+3- zIyVE?0W2x?3v9F2QhO(#v`LDi-j4LHWG*Q69Y1$rqx<~Udak>DcKwU5J}y?3_4TU} z>Jtv-B~IoA7Sk5MG;c8#o62TTOpRLQ7AdbFtHcR~v9h9}0Z?_3Uqf|{v60csBO6pr z+Ti!GNcna1=F=dJ<16Lz>Kp1jDi3xQOUJlz<5GSt0V4SLbK6e4lzs|Dh`(dYFS=#t za@8wNn0jZ&G5ZI#p0|Zg`l^yt1fxZ?`V4M*kBv+FfVPF*oJEVyBk{${#}B}>uS!%X zqCMFkJmGKw`8t(?3l@I@SxIdY^X3r+a5YQwW>gP#?pRS&nUS)fMpyT4%iEUidmSOM zq~3?t+7>b@jaz&`j)MPEKDy2`pO9r*C8FA!H%%p6*sOP>5;{Mct{b#7*KmPP( zeqI3>{@W0Zz^U}=-MhizQtBHe$U(fwMAQo`Jh}ko0~sKRXy{u~#}=xcBK8I=CH=rZ zWo6d=?;1&{kgo0-uwsW1@kc5%t&x_=2zIw9AVeramW_j>xHs@mOb-hKV*gNV{hzY3 z5G!u8@M4t!aFWk$(%seCpjjo7Gm;7pgV%Aj*fO=LwwBLx%T6Ajx$3)z!C1V2)IU$A z7`wRFY+Itv^KqdfshjvY;2(I2xXeBzL>C-aAfj;!vSKel+R7U}mWwe)-^kBD%0a!M z5o8dxg5Vf1KlU6NQVvwJ7O;&zOi0+|kvU+8dzi#xgFxeu!R#<(N;bxbCH;OxY$bv< zmy?yv1?sA&bor)1!Bc6f>go$RZJF&++5c6HHu)dKXlBiibu!i0Q@_=L2zzv9UXcvEfyC*Cw!apfwU*j#Hcjy07Qup@0_FiJNJ8*ptSiYF zMoc_DnyefbgtBMDVE}3?sk67_0Na)8W|B!);J zc=o$^t<$xMO!WhGSeIW`ULJw`|3{HjyeBfnB41yu_Z<|Cz|mfGq(D6VM!sBQ8TRge zgyFw|bUoVLsro}*V?mvVB2+MskD++VwU+rg}`ufC)qk>5{(8!Ug zNubnrLegAurNb?O*RZ^Od&5G}~d-p7o@ZZ*U%mnOPq55td zes^q1QIYDcuFetI#V8a+XQk&C+{?^d2)nc%Xw`<_Y1Jjy+8SfBS?bs)XW)pTbodcA z4NAa^7i4}YNkT*ScY8a7`A-hq^^sFk|Js3DKVa}b?!f&o%D0hz-bHZSxCK8{RUOHf zfrA7Z;SNCQvbn0IGhIEL;seNzT67R`&P4gs61l(%|>bYODk77>R zQ_P+MJ6=!rp+a2w-DW5Z8+_>_>;5x4uHA&O0y>g^S2g;Lv83*$rdIHWfCeB`^rRHO zFK}IQ<$;~#`X^$@CMChe>b=a2@}6QE)2*hinY^FRO?ihHC%b1&q0uWi8x@DQIx>3% ze{)H)k4~~T$e%e)xq0tWX&6Y4ay}LjZv#3KFtK63ZrXI}T0{hHW-_`1VY3w&fT-&H z@eD+AZ_y4Hnah3)mW4kTT8f|6toaSvnPnhvCvDV!VzeAdc*K`a@}qsQ`ksK}&$H#^ zR5CsQ14i$Am~8ok2s2X7k!lrYBx0S#rv|BPYIzr|e0%aU0Cnv|ur}m)J79B=G0oCN zfb|i`MAo&hl|J$1{Zb<9Lx`+r$AgIbNl9g&M`%DYKGWM{u3}W{bPCp^%eb7?F4FzR zvq<$wY+>5t9Xdzhm)pN@--p&LAI`ZMr0||Ex|t`4bo)wg+E{imP8>~ROJ zAy;Hd0zIX>Qg)H|GD-nA$#*VTQv5icI+VZ~*oVx#qqAuv;+f)MS&h0uesAUA@JaG W#q-Y47ugj2w`1#`ElHcqPyH`YP*Vp0 literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/safe_range.png b/doc/src_intro/img/safe_range.png new file mode 100644 index 0000000000000000000000000000000000000000..8950f219d8fab600a0b49e1922dd9de2dd8097b0 GIT binary patch literal 5158 zcmb`LXD}RI+s26?YO;tDB}hUf(R-AQ=usltY7xRB2zK?l35i~_qO*S`dhcC=VD&EQ zT9yr~t;LG^%Dm5q_ro*K%scaZIA_i|bI+N%?{nt9ese|W>8jIF-=QWUA)(XMP|+tL zA+5ezLvB!9&6PfUe>YTa8m8_fB=p^X2kFyNpq0RSeI zN7ZUfU`o^ON(u&sKHF46tA>UhpE%EBbSMgIwC-~0zAKB|T}apL5$j=9QBiU3e>FjO z3jiphB~J|x|CJW3eRZaz#K+59pU=$*0GJ!ZM}&u$3G}I`bWbzc^76iQq80-HswDsW z;g0~ep*HE*{S^ZPQv}G9jscJ`w<05_2#cwz&;}n#x5$uw;0auuKU2V~l{aMzzl7D& zfzZ?CnFvw*Pt8`suaU3I9SOJuvB_adeKc3Yj#^MI6Qn(-ws%Fw>1U{$@TUBeOtx%e$4!A#Od8jG8VO| zdq;Cw7M$B8Wa@DKJ+I820~r*R%IMn7_oj+RbnU`jjKK3)?P7#%|IJ;X>aMQ0$lDe8 z!L}CwPo?0CPQS+r9}Z2;)z}(O9y17o=nP!HXtupulK*lA1%I<#HQz$`Zq6>FB;?OR zn`@pPOM7A^Ekvt66T7z4t{DK^Vv4&i2ExzPXa>|;(O1y=eTj=>6?qrrNYeNVkEefl%9VLzL6(%q* zb0~iFA0AjetpLTdpn?h11_H-t#@#z6!;xeKL6`z=_@@0-!Q!D{-^shj>yh>;7i*6c zbr*Vn|EQ=Iy5yL%U>~XS6yR_W&3Ks{)QN~wR39JXI{Wj3pH=Qm-}vItRr@6!?@_3_ zMl=c;Iw>DqRhW+b=Y5BNlT6M*@3r!86@-(D4s>(6pXgp3C)LpB=n=K!BI`a&(a4~Q zG!dV^zysVR_iIxmG3>U@RX!ub!W~xTUB>tCdwd(&-qzqmWeO>`-(SV>?U0qG?SoFv z!Sa{H1z_r_6Fnud;FYvk&cj3wK!Qq&@)j@!)*neNCM#H4De^p1R3ff|Y;tV{_yCF= zDKSa6tL)sowH}?TgL5xrXBk=gOf%cWlUn53j+_@5^0D1QXjIb5tTf`X&5!>qdYdA= zgI(L}8}rRE0#1}~pqyn`;#z;Za7{D#X0!A#cuF272|f0jgQ52yJ2;SNLNYOmyWfl#*lLpv()CWJ_9($vhF21kKwSS_B?NeZvARwx1;V$9;$i-SFX)Z$XUr{%%$f0W1?Wh)(cT?=ek zoSEh#NY6*sLV6W389VO>BpBTVGnAmmhqQ>gv_Iz)DY7tWsvsxK#7Rz)bE;%W-7JZ( ztzFhAD~kXNB}Dpgd1VMyxo`4=ftXEZTif&{7JIB~v6y$^I97J*`ffJ&CZ|-;fEnn= z{&|V`>qS?O}YzPubxtHOM-0Y{u;~bUSJc`duc=ax~pia2=v_T5qwm>)Ug)+}!6Df7vcu zpCpiCV)aaHxT`uTUP3In&_BIqXz{C3pb$n{=WHsRyY(k4#c*?!xsVn*pS^-lXsXlE z!o=yg%&Dlt71a%pJckW}f0i_3=^vm6W2@f53?=Um%n1PqV^)=F~!Hly)l z>m{>lbIg9%0(eWKHIli&XCR>Iy7x+zx80t}6epk$yxY$Y3JGi=XTR{{udlyssJ0O5x`yv)sGw5y(3uJKM z1$n&I%1}m9fr{Y27y{q_IY{t6uhuRnJM=`l?|ED7;tV}56wg5(7Y~NBodZ|)boyRru6N&CRtwcd*I0A?9*V%hl zLX>4{bz>iK-!r(xv|pU$?H!hP%}U5g50!Qj)x5E;| zO|CwZ$odhpHvIBi`dH^sH%Ia4r4aY}&Cdz1D&KD;*%*2H~`6jx!A8bl|1zagz5ttm~D0*j#*7_oRpn?EUHE ztvApuJ&C3xMM|KJ*!L#?OvJ~t4~QuXXw%~nPOJI-qA%QxvTz^8dQvyP3WamJeZbw@ z#uGZXikN>|Z@DrUa`ccb&0hb$w}Us*2mNJBqnzK6oZAkazuV-WG&(NHR5YNX{w-y; z%_{fX&VBfl=F%xJn;pZefB2U{p=L&hc@tuM%Wo>K;4}k&Aorh<)W~>eB;aVtW9hCh zzqF!E2%==&fNG0p*WYq`5e{)8I5t19udnfq4$q)Ck*j_oy5)Zf;o}NS^?i96oAQS; zqVUg4D%rpcyv4+2khVLvs6oLgbInEtBcT^>^g;;u)H<`XiLGG5(l}2#W&ioZ(c73kI#zWjIz=z zKYJ0S*P_M#@5m>T;f!kNAQ z6VW1sxVM(VTzyNhqVnBk@58uCM>W&=#4cg2FFuC1sW*?F;w>Y0^23vN8)NHsApRCX0xZ=DAv^KSWx-G zMuX)tNSFS*>{JJ(La_8D?pXGh+0)M3c#%{(4&e2Rm`U-pP$3;GpPNEI@b` zNlcHT46+-K5$#PH79$W_bX@v1CN_wxgZc6{7Bmzojp<7wrwcu-@b`B7)6$?g)Vuu{ z(G3K>6fC240)tsg-72j&O-fTwmzF#S zYKptS?WGh@W0N@fX=f;#P3(|ZL`-ukY*%mr=vw28-q&!SDcu^M2Mrk7MY9@QDB?Nq zwbW=Y`+Ypg4(-uc#;r)5+8s$^8`vF}QjhaeE027@EvmzBo9__-0Z7lZ<&q(2k+13M_^(QDDUAt?h6o{L0L)KHRpSL{f!JFwy&&0Xd`~g(P5p-=P z)}A-qd&cq)WhWIX6o*!?O+rH%?%YwG$Um&?E3nS>5Rd$7FeBMTMDA1*{sZ-&`qdtbDF zx%m{&Wj6%6PZ02-toy+lGSAAL;>F2m0zVK|1UisNQ!?vdwiCC+rUZ|BylZk3&6eib z79nTn_wk^zAO;u->MYRV21x6+2ddJKK3+{k{H{IpJyDR4p<}CaYt^Wm=xscP{$J|6_2Gx-fk^pY zs0sxZvNbCDJm=1>O(N)qi!O(vhL_L1JD-efv-Gme$f4c=eI-%p?z``?3BEERrKQSw zgU3mHxnYn%4WnAkRztt&?;BkFlG1AZz%12%EhXbcC`iouyN@yExZLeus9Az}4-tB! zFdk}+HaN!2mUn+zhgY3HRy1So9y)Is|3#!!t7|9-#m$bTN~!5;r4Pra=|6th=lHSp z4KseThEa1VL#JzC|6FT;~QxZoB-o2_{y7is4QkVBN*_f1eP zyi-cvwhW`ocz4rAJ0~6Kt|JcmC@;ac;ic?m6FPvRuM(<>AD#ziG*a*K<*nqfPug_8 zaVgrc3!gM=z6bxX8A|T{P@yD0-P+$tYWLd=a0&Yh(ne;O_w-@k{ePl{I(k>eABm=_u1fiHtKk0u@m($@ literal 0 HcmV?d00001 diff --git a/doc/src_intro/img/split_angle.png b/doc/src_intro/img/split_angle.png new file mode 100644 index 0000000000000000000000000000000000000000..ad69e3c41f242bd412fce89fe9a6bbf5ae85eebe GIT binary patch literal 6448 zcmZX3byQSe)HaGphayOKNGn|e(lEr2E@7mRZWwA5M(J*bP`V^U8bl<9?r^A~Lu%*& zhT$9Ef4;TecddKxS?jKQ_C9Cdv!Ceq8@L+Gh)=7WPn*8A^%kj_U&kAp+AuA%(KFfjLU85CkTy9_%SAF)f(dT5sIYWI;p zNx}5#L#ICw3O(iea3ZHF{VF+gi%D~rs*7$l0jhod`MJ`HQ`k5}vN^Brg0}i%M@BlkMnZN*T6glLOt>Hv>KvU(OOtr&90_cnfKx6S zYnkWf`Y6uMjAvmQwOebu4})_0oJ-bSMM`Ebax2`6Yc$lVRv=^V3LEcWPTyA#D-^a$ zdSL+25#k+~xo`%f{OJ(|-EOQFm(O_t``+Vh8FD`&))&>~>;Qu|I&V1p(l62q+ z^V<_M%kX)}6Ow{gH%fX9Dil0^d=bf+*wfyP<1)YCigOrlg@J-zL>b<`Vv&t{;$>aj z8#&!oAU}26?bl+7a)J6D$eJq~Tj9ZTi0I7Eae5(-Dd?G$4Ws0fo$oKfcgTy&j&(PQ zCK^eDWd#jCT*n`zX~q&sKx4o)Tovc$`Znn)^P8bB1pS<9(A|^-1 zZ2PL^%hy&bgdr5lk&j*q%jKp)JXL!?J(*CmZ@zQcw~#EXV8PC(sWf+J!9n(!cRwdA zDVusct5;q2+00Q_GatRy&kW?2nN8SJ2MZl1CRt$=TGp+vR~a?BNWS z3o4Kglzryn3{!P`o^k>~l(ZG~Bf~V^ALW9z;+#X7Ry47AEojmg3=ba7&jvOJOj4XAFEvY_`dJV06@AbYqFc?5A1g)ZESjQ zvnBjEQdLP5SOYr4eoVTq!R|o(%OQ};Hiyzg#*sUTlC|Ug!`-PM#xk<5L09YRIoptW zR$^ukU8Xh=iGf;QYagl&ZexE~Lm7g;V|_*>)z!)q53Qj+paw&$JQtA60@XGrCNeLo z-fuP$Dz#jFo~feC@TGF3x452fzJ&+ADCnMa&d(8fBh9qSs`EUo$_Tl&&5pHY{j})z z1a-I(?eiViELbuHI9LTdR<@WQDQYh9*~og6m;aLT;hu6%yrj{;WrB7aG$z|g7YP_5 zIO=3=G>K2#k9WYdI+M#E$ZM-QGbEzf@^BDm1^$t-&=(bAo-Q%INv^~?lo(fSym4?7 z-UoSvSoDwXJI1%k8?KVYYw=={1W{U>$@^?A{&jTm#xTHs4Dv!Bd6P%@Vl&eNGtc-M zu<+q0gLKsaqTP13(>zRh@CWX zgJrw6-GKNYVxce-En^Kz;nlfkV&qzJDEQH2$w=BECJA9huX^5DRsQ@#V;UHdto+wj z-e&g{IL(+hV~0zo0i{4*=5+Ee`$8h!X?yNR82I8n?je1=fi6C@pTuqe?v%eW40bH; zD^=NvyLdRd%p(;AZ80cMheZ7VuW_bx-FqsZ8p74Lk)}+2wOx`U`F+{GBL-9#W(*?@ zM)XUca$JA0t^vREK#gP)8s1$>9<{hf3h+?E*nSSw@Rl`DoOa%VRk+P1BoIA<#}*EA)2HN_%;B1F?DIKdvEX z9uRdst>)zuWTSh$Vjst}s%9R?%-I-}klyThpha9(Y5p>2G3V#wylkq-AFh&Ck=?F+ zz^!h|d9^21KUcFfM7@zc67cOOx`AhU{-&j8XZ*exL)j^iR2$U*zT11qp&vOn(?B2%X;R<1?+S?CpA zK`sH8xmT`R*;6xQB0kNY%NO6<%#hPQ=O2`q-_J(rJ20b!hS~S9$XJI7AX%Y<#BpZ> zl>x#yfqCw!q#Z%>$B33N%tfA@?l%zPWG{zdi0HedL&s-%{-C&%zkIIKD&z|}mMo>R zn2&)j7fjZTmz(*^5tFV|YQs6b?94}0J_srPqcC}sr3;MLN$;tw9{gR)CT80}C^mW; zK}luI3gIz9Z+x;Z)T2=j#lUR*>-2laK>$}-GeOOOPF{B+lNc1jjY>d~fK|)pzToMn z@p$HFx+)dX4994R(u*gR@ZnE71gs?cy`gvEy{{2}Wxh>&Z@*67D-g7rG=^f*284&mKNYgayYu5CKwI3|}Z_wyPK4l2Pj(iV#{0JO_@%JZToFc&=!w+)bYf zNxbnt2{W!QZ+>fPuozaI&ewZ)w(=CuffdrIA0pcWd^CzSOaods1ywH=@yHAV08RhU zx<>@2>B!TrP?40(Fd2C=h?~UMNkL!}-Vu1T{Sk6wDV;B55cqDnHA@Y#6p^7EcK7Zv zuk1;pj?KHIlwSJn%|r z0L;)p%PciHMp(dDp_GJ`|4&2|Ve?DYCE{b$tKvubU%&i$RLanFBpJKZgPTN|2YRj1 z=CGNphXSS;^7R2b2XBT_L+W=`tU~re6Dm>&Y9&>VsF>2P)SJtUJZ#p=ptLm91E~Qz zNo4Nr12$A4bw%NfpbH#=Pg4JQXdPC@9ZA(2 zuU@L_BjD%orG2L_O)riK6rKnK<03Zo&WTg38!^q+`cmGlznrO7UqM{df=}j;#r1=4 zwa_GwHwQOp8UL7Bjcn!(z~t|Y@-YDC;G}}J^r{!rM*>|Gb%AiQzt9WWfbnOUS;5C~ z=UjZXXj3e%8Kgc01*!6vX;z}%EqCiMv(x!0j{!C3l8t2P+CHk4y&j0k8H)r|KgONg zePrY2srbhn`Jh2$rT45x?RqwT@DX2aU45#W7s3(H+JLsiw4s3L;9DFk%R9Btesr|7 zyy+?7%fS^btD&4ZqMJr<;nxK1k>JCcw@r*Zn-#5;gycu)>f+7QzZRn%$O5*63^8`x zBO1ovog2S3m?(bZN+dd5XA~Vs8;1;TjBsZlPjp`YJdrqCiXm^Amne`uyndIZ#kH_P z^z8ti+cR++rr{h6R3LZ|b-9RV97|PgyufrAomrM#>cDOqMk%Km zEiI=JwU+AiwVUNRropDMi4?&`_vbRPHaf(O)B|(!h6%GA8b>aJkZNt=;$$ziibN!+ z@S|9u(jrl%446AKU8T?=yWddFn$YCj+1NtplDPE?ECKlAW8z-bvGVJ;2QiOy6--HR z zE+W(gYahQ)&_x5ct6-5|e#M9fa{`*vY)0-rmMrR~2CTaLTrrA28ITBR+97$oMNq19 zX?rKq017+_(iDb3Lw;H0?fTY++J8YbhY6Yx^(!)q>>_P$;Nr~`?eyK6` zsl=~c8#I^SeDe83y4CkA^grM>$M@eR+NLmY+5^bl0lzCT3=x>rw0zWT>z&X*{(zwSp%j3OkxHPHH-X~hNG%_d7f4B4CG=7l$(MlGi zB-;IRXjsmnUo1ML>sZvIdTI0)jOw%B)*w8m;-1JAGf05~B0vlebn2Z-a(62lqB?!Z zG>TMTami8Otw1;sz3hpIH%W|-2@ayOLz;Po$|k^g9JI}n`{Tw3yv|5~`W%}f6GX8=>k#gs+!QQyl?du82T=1;OgugUmW zH|+MbfVwkp6k!68*jhc@>lWf7slO-mwvi z3f5NQ+rP|PZ;Do0_AbFQp?Goto0*aPxe`RuSnSuN_bWERxQSnK=s=e7 z$r4EcD5R^UGC!4b_H6;RN9?GEs{&Ulw#*o>vF#JxV>oN{adb>Y*2*VEPAPT!vC9;g z2ztd~>xfqt)vlwwzP>y<6^m=nABr=Mafdqn5bfBrW1Gd0L=##Y82>B+cxf(^fz7mW z7jCF)XubDtgrCCbq0a_S6a}Os_I8e!hJ9twW*{n@Vh&~BcADtJ5)S2e_2yFM|84E+ z=jt@~fF)~l)f)>$KaOf}s#cv`p09dZwPMXmFB5f9gkxzr&xwB3aWyu2pZh**tQ{*i z{{|YG=_n7)$U`oFaLROl1CFT`dUH@JE z1{&!a23N6pSqW#yl_%k77H8bES(0_l^1k@y&cVy^E8{}_fJ5_8s1YqcxrLP2Bgq<} zp21j}qZFrlW*+>^b(^_EGX^IMMs_vc`L-sC7Qi^mJJNPZxDI}(W&{3uqx^0zk--{# zk6OYL(iwcGu7bw*{D*5#ySGgh zca1xrVaP1qo8n8G_)b7P*e`(Xe3{^yg^0J0hx4I;x`JTFf#9YtouJg2!@Y^E3`9fd ziCF|xHhcC$Kw*(;M9A##A}P%xklRDzeYNY?;c;acti1i4b;phbpG8{qm%t8h9&?^g zqI;zP_75ISMIKb0u1koh%CwQRdo|mNTI_l^t8tR%wLZ)Hdg%9;<|5gb9lc|L0n}LX zcqvLp5T{m)Yh%Ft`K+IEQz}Y=GvAQIcEYOtkpN;gsaFksLzBOG^-CJl1t$;f zpX=kR{AWBJ)l>tgzEF2Pu+tEGT$DZYMjr*PTwFUgt$Yb!_Y2L{Gq#dqB9iK{?P0Kt zncnk9-CmusbJURs`vBbZ5_|hE^CWvF9amEy1Lr{NvASh;nF(25kH05i zH3h5pv}`)vloxN=OWQW6h?m9dtU6g!Z8_4rHEL)`*tzgd%!!G(`G#XN%UqoJ-j4_O zM4#8R-Jor=Q^d4k|510CTrugtrw)#f*G(sA7I7kJ8EZmHz@KnjgYpNS@+N1S`KSSEOFegA&jjwF+s;^#wuDY_i+#*2>E=^dR8wXem6_8_yo zfo^^7g-Q=wLiN8F4SNy#6M~u3xyi>Fh7)qxF7uMM(dQ5k|AN)?Y&s_BYcldrqQ8AO z4=(xbi~EyPD7xiMj=Cp)mVfJ&bB6kcv>Z`Pt8%|&)5+-sl^jrqWs@*L({;3M`R;H0 zyE^@+_X$~1u zgr^4e$mvm7PT4sc{8C(*pPA{NSwrwg zTeacSjvO2^=(+_5YA34(w3Wm18(X4SFd4}k3W=B;m>-V0G%$8x@lUkBSZ+(jugnnu*g$+)T}7E6(z`zLZhaX z*2+_IbsEM78kpT!np<){T{*lAGmR?(c=HLbJ=#cEOn7#>{@g+%hH$O6E9b!f`G=#J z^~xaXu(s@+&(v0EKQ8QgpLZSO`AzQm<4ek?0{4C!D%sF^j(!eRY!D)^PZXGHYnQau zKL`;YkG@kd{em?O(4h?baO1!zBmnR4Hn1NVrRffpD88(ulng4$mM}irhT($jO8d_K zRQv9=wfb)wu0=MP#Q-FBkds%DGz_zecnz@DEviW{FO~(m@cDoJ=CXa&FqJJHlqCAl z!BOWqhD?pPYE1hx6w3jwB@(=c(_zkZ=AdI}sOuQ-JI^0EW!qXwZBnm$-}jKe6ShDF zExwWi7JM244C0EY{zCx^lIR=(V{Gn@Iqo+g{~G|k>vzHmeVhNI*8N2WV8P<-av>C( z@oZe8A3(J1S-DU5Q((AQ(DS?1X>bLQ&5{Z%`D(LW>FV~3o3z>er|T1q3>X;V+c_hJ zW6_3y_-{`xPfx4$2#c)c>XJh2%D{ppw`u($&BbU?KY8q0W;PFpa@+k$T!VK7wxht* zce{-zmzxY~DXzuUy7kLc3{ACp2ue3UR&a-M-;rD<5p)3&3y7WmyU(k^pc5mSo;*_(}4CzcS?~uhJ_yqmv4>~RE zwR_HGPNG^pcczA_%?`F3&%)M7T!1f>f18nt5h0=9c!TroUwB;5U({|_Ei>&=o^0Y5wJl>2LmS+= zZV;B+jYwhY{~FJt5^~oK-BM7Ra@DQn5uJd&FDPv?78NvIs-Q(Nhd~f;a*;(@~z&W|Tle=<5n@#Eh!{T&o>p(rz zJ3djIN>*y+PTrco*C#Pg9*g2fzso}z;_2o)TF19RxzyUcGQw6ne*%>#q^(?RkE|a# zpRni6*z)rWrZjklePy7}g~E;az58)kCQ}?{Q+_`xq4OoFm=xr>ltW(D$!G!CBHW@F z+B^>p)tAB=k2yMQ|Cs+P=KVNe`O$>1E=p@oK;EQUx3R*O+;TrsGlpt;_lauCa~?o? z%|$wJnoX~H!K8P|`=X%G)%LtM@bWOxMdjAjzm+O;-15-yIDIKLZ1zMw>FLFOWy+&u z(WhO4rDf7-!p+mZ$tTTok$QP6itqYX6Ca$zyB1b=$l0 z`Ai30G6Y??Q0C6^1-f52x^ax2AegN_DOrCuNdboC<&F+yFuT6Cd2`#7pXSZA?yISZ zqkEBqZO;9*2Xm!%So<6tE+~pm9CtYiwQ+yMD`D!^A0KkpX}=CfaPiq5%_Ip94X5wj zozh;37_am#`(|dg%`2{u9?st_QfR}V9+#q6@|1f-zei9}OEs_Q5(9aAeg9XSFYR2% z1q$VKkdG_wf6+$C`Of}z2J-THUNiLM{esJf-K=61GLLzu+u`$4cN8r&-u%C+s-Y4; zf2Uion*6Nx-Gzy7W-alXR$ zr%4i`z7byu2sP^2v=dqjCMiGG*x}{0^Q?oxy`OB&*5n=CZM9jLNt#vH^?m_4aViqd zsv7m40oGXpC9H~AO=x0iaYIsmrx$B-b)M}?fpYKKy}biHdA$^5+x_^g4sXb{QuE!a zZWeD?pXwoRa+Cie)Wus}Qw-&$6-qmH=epS9-}xnF#71zrUwdqlE()yN?EZeZHM&;; zJulnHigBt7lPH{ZrN1?AUJOsz?)V6LkLFEA(F@_SiC9-NOtj zPGmwQX?InM2H#0~1#-1%>){k?6F&!#ZTo+$ zl|pj6{O!2hv)P3#zKk2at;;V};Xlfqn6kGxw$@`@hjR~XSt89048q(VV+i!UapWF8 zq85tx9%(K)wY0WO4(Bpb#kZ-5+i_rgPN=!e$E*jl%dKm|*jDwt%JIvU=sZl%%CTLJ z*I3WxR`#$+^aXodblLvzq;L_PE6(|VH)Kt+vQ-p}F1>PGe2Ull_>sIp#BaD{@m&vj80b?{8-9gm2x2rK+% z)x$T*R|U^0xk9~j>J&w-{+=YP(3w~_U**p3bp}zTJ+zj!WmciU6k7?b@~TA?ykoip zY>@B)b#$S@?AtwW=earbj~F#8ulXcF=AreAw?$;jGhiNhO&wF1?>^|L70BsWR`kCb zFjD+&UjWX(?#)WpeOm%4@-TImFVE&FKARKMl|hq>jeF@*apfmy;oC|5`n?5<*)am#d{w3hPl@%4 zs}rfNKFE%)PXMl}mv5}x*wr>QeU~f5EYwmKCPK?O1H?t{DRf3RB)C@up610o6f2IR z?>g4r#f1Acgjqa=BK?Bc18mz*Ct|z%`eM_uUV!V0ir_MuG-4%l*8FF35y}fgmI7~y z-!;b%Ugvd>1&!ZIOx&nH+-Qo4=OO_(6=qHf<%vMhiXr%Qz_x4#<>ttkj}q(mU-S&< zvfR~vcO(Dp{fqi!rV`Ud4{!Mx=wSOJ(#9%#F>hTaWc@pj+SA=={$JDJ%e|8v7vW-( z*IMc<`hyy)j+%@&R`qL$*n3nCOPuC9yVon1S!+&#BCf>R`Zni-m|qs|yt&`Da{&Md znsY?(j{E*Y;P>HoV~$npw)9`7Y`}v%V|0w3XIEZb5|qQtmXy4!J8USX zaKh45#?B%?LmSd3Yu{3$r`TV&UY#H&B;$EPiPX^0kNq3Bk|HO87fWl-*%f_cdJk%# zrP|hiuVd@q9>=CUG_5#I9dktwV0VS>7fDV;RD$aNxvG7~0^!zj8K{Ko2#KOhqAcaf zML{wGj%NfY-zE&5#BO_-cB>c2P<>iqNvQ5ylyJUE?5^9ojzDOxb^O*D>97SNKe zIR-Z$!$WHW<-!a~D2?Zh=6$bJYncDrNRSA{ZB8^^blXCcHrFNmc|v@9mU{zYTLQ~J zifZ$as2{G7Kk6(!M$=FZFLggi^FLc_iQC%83>@p5=UBED>BsQuOj!>G+9#PrVFO8^{oS(g@9mu6f2shKTPUu>!Kn5`Jvr@r?T2bZIBb@ zIP#}TEB(8YP7r#ap{1E!v1z*$T#}t<@$U-KHRUI6wg{Br{YdQ2{LIA&?YP>^oG9v~ z#H~N~0&_{0N1vw`QjJPub!BkBcU=Oe?$HaJ3la?vGHXXzx>S*N)BacY`@jG~KOsTO z!RUpT>0_+k`%$qeUW#K;5#Cm>HanP@92pHnweHN-NL)k_u5LK?*ickDz5K$SBr17XrxSK}LR!zN8&Sxc|SrOE+we`DP zh7|uMP~Oj(ldj`gOLtq;gFhQdw0%YWHCL}+jz@xGz-c?54<$vp3*;8}ud1i}Jsb z_w-~=fx$_eIlQSe{y#qJBax~fT7m-@H`r>~;Y?*OKD3n4+=!I6G(a&&VJCo9jAm1* ztTfR> ze_&Z;f(BLZYJSOtnA0xo34{KPIl>}}Hl>Y>2BT*Rv?K++KdNWHae@k1(lCuVn!3(V zm;H2vneGUy?Pc37jVSz^F-n+80IQN%*<$*HT++KzQ<(BVafo2i zv8DGYD{Mx-5n<;{bJ#JXDJ>^s@g|j5&T$UEI%aRHqq+S~wKkqLA{0oWOdvD^Aow^Q zq#!F4g0QoPG5pkkMd(c!F1UOHOVUV*OEB4;-DkDLeyyfs01Ws2W+gK6d--@Y4a@hR zYni^GN&4>u82QU~W81>g|x5k%M9x2TzYT_T`pfV5MdF4#p_^6<0o#p(WD_=TB z*3TK%zyeJUc>E6?SmCCI;{_;AK1n^Bi%T}14vsZcOX^tm0B99G(D+PklEu+CNSCF8 z{RZR$QxjYmF^Az1;8FVG%Oe$ehYG6`@@hx4Q6;Hk?2qK!Bc&n8788LW4w%ZhS#Ry5 zMpkgiLarEmoM4p~ImGObNWV7~N~hvcY@2>{>VT$M+amg0whxd6&U+1OT<(2Dy8Xgb zZzV;0L8-Pu4z21~(TnpkNuptvY@jDnZ1Q1)H&0u%5@3AxL@NTaN_TG?Ov2UdS{BzO z+~5kHSa}rt4!yKv`V1~oxMi^yjHN5_VaG|<)J*j)Xe(@wkFP**E>f+Q=OdmTWF%jw z#l{8KHq$xTk7C?vzB5q9)*fd1v0R=G-|v_Z?r?3~VKdPM@7CPMjzDT{YigSHAi%kw zLt7rOAx^k3>ZA_)k?@;jicO95^|w%LNDeZ^Lj~EwEz9_Pphx8<%7HtW$|(uMh+^X? zF;!Iom8ZE(>&7QE|U?L=noQ<~0wpbh@DdG2Ww5r!WaKlDQJJzlqx~qxU>Q>Zhh~N;;R(9aWFS#)KUDdZgc|WCj5E$*vsoafnV5J z-v~pO`qbiPcLFhM1)+cbi{Y4f5P=)_ZVGl}Gjz3kLJQ`svbRz2tiSDd2uV)H-;)oH zm@;@O-^3mAg__b9s9a#At954k#siS(DvOO-%@I7r&t8R+or&3jPz2+7YeV_Dr9W&uy7=XPz$N2S zg4iFUDxUKRmgB!0KL!2U>DsejA4hIiDR<^yDSw`iS+2eS?4P`yoW3U1lj^@r$o2Av z4pCYVJc=ZFmWeLDG&-Ai!oPNlg%Fzkw@>GKOCaB9{>tACvU%~Ycp5V_r@{Qbp7hzX zIdxmF$3A*2`A`|_!4eEW^mLzqV_g&sI)^$uhS1gj$}O9q++cQP&ti7mBbQz5F+_@A z@Y6t*w6$doyE8fqhwvL0{|@(AvCgH^x6_D7d$Hr@MiZ+}5<4&QeT+)za=8e+J3r^G zP0?nPm!P)LEJz|4E$?7|8cLmcbtu;`$Kz5PdgxiPWl))^ zPtKE1kTL=xnyPW||0Vi~2lMe>ID5uD|H@REIC8PVpsd*yE2+{~FmYDcQfWmf`2*PQ zmG?B;{v{A_G{|&)5#oJ!oqdo*ipIDhZR@uLdkg?KbubVh6AzleFD>cr#|(h&J*DBR zHqI4tR`OTNeI8yrtPQKfP%SIzmL>@I)`1@Gd`<4_*#=u)f7gwFIg)U)mw0~T&v)^q zXhkS_p+6{^Gp*CEvZvfuo0zj?$Rs<|O_$;n4Y8atH27V4;K}lJ+;|63s$Dq9k|rXM zj&h)+G~4Cn>CLbNLh?2 z2ubPNq}QI(X9ro)F0uyyY<%unbr};g3%bb)S0^D5P<2@O$0@}HJ>8I$g}*O2nqu{K z{>ZDx&2*1Zni(5d4SEvHm&>o6<<i;pwS5vIG=BNQD7Gvu1hlLOa@K*B-nJIOkQzW7FJ!rLJNK!V(cdjvAKa zz;>9_vs@m^OWR40h2_D!zSeYX*v{mt`j-nZbEYSfL+(P(dz-ECweSYFd&o*1g8GH; z(v#$ToaHlYusd|W{pSGI4X$8cEn{APz@k0L`GasqmTnqrd1I9T>iAmuZDEuNZ0NU8 z@nXjWoPapL0BCH7ux)?Evz|52EzTNLc6Bpb(o}jaD{p>(8pS@I>X+w$VA{J{^PJDM z3|lJ>=BAIF+=lom12UD#JbobvDx#J}nMSN^ACt=0psa`qzv$v&xsP3|5BbGD)ysse zz;&f2OFBF!@e!ulfc!6u(YWcyA)&ml-iK{Z5|cN3TVSj#*{`s@S+l-S4&8=XQyTS0DAHS277W zv-SxV^9-A7mR1Ch9SN-mctvr1?Il2@yZW(viEEHQIdBu0Fo+-`ItPke+z}*HTx5ft zsy~P#z_vr<^Bpb)+0f2>+NErj(o;1sMZT-3u|r{A6>6skG>nhKE{%|B0M#0B~dU>t#KQ zYmph&;a#ggx}5U5oO)a;#$2i~9_c~9{R6x@f#C!xw0k6;g`nFKK+bgbP(9B{op8J7 z6TPHJV+q~(8g}JP*1l?NWW^1vJBE*t-(6>2c zc;!UAQ?z8fS4>G+waD$m>eHL-jnVHVPry+&er%Vy{lZRZ0l&Yy^B{?b`x4vtQ`I(2 z+^3$Ol{yi#TJZeR!-tP$2bP6105|0HymM9a&aIQSH`FpRu#BR;$!_cnQZ?^>^1Vl_ z)c_I)!6Sml4Ur2#c@{Wb{?EWH@QI1Ls*}GYla0mpve3mjbPsm7A^wiL^DZgq!!ub- zbbEEu*q}(`jCjIe^^Lm}5oOHdwJ^QwcPSjUhKtl|tZC6e?qj?CU!aM5crBwZGu=fD zn@N@B#c4LH{$SYO%*e_w?3@Z%X)!krOPX2>I<4XQ_i5F;sFJ~CR%d2re$93&x8y)s zldiw(&QeyCX6Ych;rs$pl+VSbP`xWHQiwWOE4F0S_DywMpY)AGscDF-)>6Ef7C`vj zpxaMx`Xrkn<`ZjNs1Y{kTTO|v(JKC&Z1|7T*+H-H-30DQ0G$xW3 zI@ill&?e7;pHEh7>hf(nTJ%xMdm$M(Qe}i4W#UdZ9bcP_6m<1ivbLZvjMKtTC);(HB9;^vx6Y2!7*c*_~J-s=qsDyXNfDGJ|gJNYaRRzC$<9gLCd zP0RpGZuzr+OKtv!0OMtlr`l#%ChGk&qcCD(^-n|+ivCGSd0&3??1>Tfqia!TSCnk`W%$=tMXpZtHpE;H_-cF;JuOmshglcY3+Qhjy{k z>T+NB94)M_Oq1FKM&>nI%xA3Ijc!Yao_L0MP;k3ZI9q8%_Pm}$oOtKH-{aEHtaCFP z^5$)Bu54mLLbj+0^ktDQc@f&Im^0t*$y?B8i{iJN?OhCTOSwyGpxz!Uw|b=(ho2F8 zA9SvpQiG=>I|mI%c=_d?zAeISN2)WP#H56T=j|1nd@Qd$?|GRTzg{sbY6~SBG{5(# zBsDlyYSRVA&icOj6SDn{+i2O(&_`_piBrjDETSlFdHKN}295FbW>{uzHR2WLZyLs! zUoT~=%CxI=w9@z&$#Dm5PHaIst5{+6fr67*2wA3a-Mm7qN6|Vd7o6YJRrGzp)?wt8 zi-a;otyZrb3e}I3XhjWasBdn{wQ8uCX6IFTqtv^DlO$qf&l@@L`R`7d5VX7q$KfMH z()3i3?*1ZW5U}m*zG&5!`OPNjYx~E9nk9nRGQ}f|*xF~*IzL$){kut*Kp!6uz4O2| zMG8Xessi#8J7N_(11h~K7@aQ?U&F5m!69#=>i@3hrx%su1tic0OilOT{5+8PO07FR~PIcBfd&msGO9zzFZ=|AVv8(?9!KS;h>GK=Dn2d)l! zLM{bpVuX{D)r>sIq@&4F*T^zjrq0~ifJ)@yG0S@;RkxD3)mDteeJ`^1;O*ZujgD7K z4Z@Se)$1mDaP^>)c)T?78+@%@g|-kV=rO8oG*B2Od$Lh?gg#!ocf(XMz3k2~4{5TR z5YY==?l)@0i_v$_vz8Ha1hl)WC=StI(*nf5%o=uR6^$e;8seuTRZZsTY@%qW-s`}IkGCVtC&fQl6n$CxfGaQ-d4zb!?5s4B#vs+|TGVnqh$lY`x* zxz^ODOE%K>^9wx2UTVQ>!t_+L4EfnFL9O(0&6PS~7>O~rZn00&7(W$7)dqdxx=gYY zSc-d)cLAKW#Cupq3AF4Jfb@Ts;TnfSOs&fx=jPQdGlc*OBh>Y~tVj0zV&BswIlMnH?8 z{5j_7DNBY<&xPVDO;h3~x95UaE+lQczmC|3mmu!Tv+kNz0jOJ6NhaPHV!M zy5Ha#2{FkVPhM#t+SBqi6*FenY>=@*b@r z_P>Nfcp%49;_n20q-D4}ifGRFzFe z-3S&_5`qdXc3f8Q$2^gYe2xA6yZjjz<9(B37K}Ct_lQO3Rt&PZ8=C?pS0R{Q)2UUo zReK}Pxv=g~FNzlbRA9-YsA(GrUZ%!f&DPoH7TN|3%@K3)9%GI&R)(|hMXESiJ9H4Q zOIfgw<2gfJT_$Lw7z;;|00vFL?F!T2hK_WoorF_%Hd$1L8qcHRMgQv7k*I@SJL9dix`Eu>5EZ$#Tc2?1`^XO?@zqQ~shs z;)iOn{XW}eKD$|^;+LUCk~%u}KHBy}dg*EtTgG;9uzxv|0jo@8-+8|vaB}Rvt@(Wt zoOf$jXzy7?{+OY&A?Tm)jS71Dcevp)ClP*rU{ft%_9z^2H)~@6P?r zTnpWxd`C{?QG_&A2ouG;E*A(+j1blg>O$~2i^~oP5MgkvvcqjGntUearS_a1qP@`Hc|^59r( z5!K&|bMB?77XNAS2^ZI+Hp_L7M7}g0;1*(>f6}fwS5Vh@FQP--io}x%_D%X#5|Gz1 zV|Wj9C6%o5e11ux?}}R<${@I4^{JPU>-d`-cp4L1J3Hfpo}2y1y2@Whxnem62#3|l zH|l=IBL}yn^Kdz1a8YY92Ok4BSFLc>IKeV2%1)eR_uRS7u&!%~(C}2DWR5<&Z?A61 zK|h~g`bS0ReyST!wjg)`=#YkfTPuJS@$aQr5>v2?%OLEpFqQxBKojyRTxJS+v$coTH#z@NjWw9|ke zeZ3tX6B$VG$P@s8EdL-f(acepww+3J2b@(9oq5`8e^m}}y_(xbr?~9|-cug%(&6W{ zJk^NsOo1Qp(eQ(aN-z&|l~n!cvC1g`ud3)W5!?3r z>Tvp4+0MI_C|&&5AP&GA-9Wuy0N_oI_DDgnW5goGWL(HB{FUsAul7PZg&T1F;^C?i zOXvSI&-wS$Br}$A)$wz1lkMG~!d)F;=k*SQa>dr9&Wo&NTu){tV!h*{xm*(szV8N) z;2=ytr`^Tl-Fq2xz)Hogw@el&G?AfO?P|J1&GC1ZrvV>;sOayE%*dk6+Qo|Tk*vG~ z=1|1|kwSg$X>nU>Lt=SmxqBE22cq*Q$DAPryfX0o=Q2u{@h{EfrG|Yi7Ji(dH57>&Ys!_bCDP_?dz4s@;2^|d#?A^*4 zgN1V4hHUU!1q6=beWuFDLRD`sII5#m*rxRg8~w{9gj!9|DuHh>?bhdN|FrTUJ|d=c zl&nM2Esf!1MbPSt(JYW#Rj<*0K_ugW`s>0DyQw1dO=}#LieNdw@UC!}?*o$As|(UWO?}sJs#9aPwfJ*#d3o^=tHD~FSysed4t-TW^XUiVlOK9y4pbv{nIRFIMElpv2W5-zo>4aP z6IPCv3g}}oToWDc?^~zGfOUt^?KUl~?E-R@mKUC?3Y&`Hjwq1mEGL?7r~D_^9NQ9oCDY>O75 ze$#}jBVYFzzmJWwa;^Q$cJ@Y)eN`CTs@LXO-@cD93DQM&bs8-cFQRY&=SHE z8kgD@1~3&lQ7dizd;6@>dYE}slxy{(%&uiQFNkQz6@~(770X0;VtX$h>PRa|c%m7K z^fg;MJpr8M$GSWwV(%%;1V2)$AWgSeiGHx&*fe*L1X*U;uHZ*veKna#gjjt z2Hgn$)zZce*tzvvbj=>6lJ5YrntN*Xi$9hmT4%4~CuTLA<5-#q(nKsjY-W!(m!MGi zYy(G6wpRMbj{o6RbLc16u-Icji!6|^onpkh202vdLOW3ut}C?gh}3L`M@gh#K<52w ztlD8y#9rvtn}F+QIqq6GOWo4Avs4c)oR089j=L5gy_F=cF|(&zo3oLL<_ppTSL>7r z@7u||%OL>M#6sKJ%@>fWt;Z0mT0q>ov-t0P6l{Q3vUKv%L1wEX-$1kEayl2TEiB9W zSLGZ&5Q2kYSvqxn6t-iF_Wd6fn@Z!)L?@jNW_g0UWZ7}hOtJ}N)c~2Y_~Xx=|2Hs& X=fu!Bf^W0gF`FLHSf}=(Q_Q~rrXKbA literal 0 HcmV?d00001 diff --git a/doc/src_intro/rs_driver_intro.md b/doc/src_intro/rs_driver_intro.md new file mode 100644 index 00000000..8353a444 --- /dev/null +++ b/doc/src_intro/rs_driver_intro.md @@ -0,0 +1,1523 @@ +# rs_driver 源代码解析 + +## 1 基本概念 + +### 1.1 机械式激光雷达、MEMS激光雷达 + +rs_driver支持RoboSense的两种雷达: ++ 机械式激光雷达。如RS16/RS32/RSBP/RSHELIOS/RS80/RS128。机械式激光雷达有控制激光发射角度的旋转部件,有360°扫描视场。 ++ MEMS激光雷达。如RSM1。MEMS激光雷达是单轴、谐振式的MEMS扫描镜,其水平扫描角度可达120°。 + +### 1.2 线/通道 Channel + +线(或通道)是机械式雷达的概念,指的是雷达垂直方向上扫描的角度数。 ++ 比如,RS16是16线雷达,也就是16个通道; RSBP是32线雷达,RS128是128线雷达。 + +MEMS雷达淡化了通道概念。 + +### 1.3 MSOP/DIFOP + +RoboSense雷达与电脑主机的通信协议有三种。 ++ MSOP (Main data Stream Ouput Protocol)。 激光雷达将扫描出来的距离、角度、反射率等信息封装成MSOP Packet,输出给电脑主机。 ++ DIFOP (Device Information Output Protocol)。激光雷达将自身的配置信息,以及当前的状态封装成DIFOP Packet,输出给电脑主机。 ++ UCWP (User Configuration Write Protocol)。用户可以修改激光雷达的某些配置参数。 + +rs_driver处理前两类,也就是处理MSOP Packet和DIFOP Packet。 + +一般来说,激光雷达与电脑主机通过以太网连接,使用UDP协议。MSOP/DIFOP的格式,不同的雷达可能有较大差异。 + +### 1.4 点云帧 + ++ 机械式雷达持续旋转,输出点。扫描一圈360°得到的所有点,构成一帧点云。 + + 使用者可以指定一个角度。rs_driver,按照这个角度来分割MSOP Pacekt序列,得到点云。 + ++ 对于MEMS雷达,雷达自己确定点云帧的开始点和结束点。 + + 一帧点云包含固定数目(比如N)的MSOP Packet。雷达对MSOP Packet从 1 到 N 编号,并一直循环。 + +## 2 rs_driver的组件 + +rs_driver主要由三部分组成: Input、Decoder、LidarDriverImpl。 + +![components](./img/components.png) + ++ Input部分负责从Socket、或PCAP文件等源,获取MSOP/DIFOP Packet。Input类一般有自己的接收线程。 ++ Decoder部分负责解析MSOP/DIFOP Packet,得到点云。Decoder没有自己的线程,它运行在LiarDriverImpl的Packet处理线程中。 ++ LidarDrvierImpl将Input和Decoder组合到一起。它从Input得到Packet,根据Packet的类型将它派发到Decoder。得到点云后,通过用户的回调函数传递给用户。 + + LidarDriverImpl提供Packet队列。Input收到MSOP/DIFOP Packet后,调用LidarDriverImpl的回调函数。回调函数根据Packet的类型,将它保存到MSOP Packet Queue或DIFOP Packet Queue。 + + LidarDriverImpl提供MSOP/DIFOP Packet处理线程。在MSOP处理线程中,从MSOP Packet Queue得到MSOP Packet,派发给Decoder;在DIFOP处理线程中,从DIFOP Packet Queue得到DIFOP Packet,派发给Decoder。 + + Decoder解析完一帧点云时,通知LidarDriverImpl。后者再将点云传递给用户。 + +## 3 Packet接收 + +Input部分负责接收MSOP/DIFOP Packet,包括: ++ Input, ++ Input的派生类,如InputSock、InputPcap、InputRaw ++ Input的工厂类 InputFactory + +![input classes](./img/classes_input.png) + +### 3.1 Input + +Input定义接收MSOP/DIFOP Packet的接口。 ++ 成员`input_param_`是用户配置参数RSInputParam,其中包括从哪个port接收Packet等信息。 ++ Input自己不分配接收Packet的缓存。 + + Input的使用者调用Input::regRecvCallback(),提供两个回调函数cb_get和cb_put, 它们分别保存在成员变量`cb_get_`和`cb_put_`中。 + + Input的派生类调用`cb_get_`可以得到空闲的缓存;在缓存中填充好Packet后,可以调用`cb_put_`将它返回。 + ++ Input有自己的线程`recv_thread_`。 + + Input的派生类启动这个线程读取Packet。 + +![Input](./img/class_input.png) + +### 3.2 InputSock + +InputSockt类从UDP Socket接收MSOP/DIFOP Packet。雷达将MSOP/DIFOP Packet发送到这个Socket上。 + +![InputSock](./img/class_input_sock.png) + ++ 一般情况下,雷达将MSOP/DIFOP Packet发送到不同的目的Port,所以InputSock创建两个Socket来分别接收它们。 + + 成员变量`fds_[2]`保存这两个Socket的描述符。`fds_[0]`是MSOP socket, `fds_[1]`是DIFOP socket。但也可以配置雷达将MSOP/DIFOP Packet发到同一个Port,这时一个Socket就够了,`fds_[1]`就是为无效值`-1`。 + + MSOP/DIFOP对应的Port值可以在RSInputParam中设置,分别对应于`RSInputParam::msop_port`和`RSInputParam::difop_port`。 ++ 一般情况下,MSOP/DIFOP Packet直接构建在UDP协议上。但在某些客户的场景下(如车联网),MSOP/DIFOP Packet可能构建在客户的协议上,客户协议再构建在UDP协议。这时,InputSock派发MSOP/DIFOP Packet之前,会先丢弃`USER_LAYER`的部分。成员变量`sock_offset_`保存了`USER_LAYER`部分的字节数。 + + `USER_LAYER`部分的字节数可以在RSInputParam中设置,对应于`RSInputParam::user_layer_bytes`。 ++ 有的场景下,客户的协议会在MSOP/DIFOP Packet尾部附加额外的字节。这时,InputSock派发MSOP/DIFOP Packet之前,会先丢弃`TAIL_LAYER`的部分。成员变量`sock_tail_`保存了`TAIL_LAYER`部分的字节数。 + + `TAIL_LAYER`部分的字节数可以在RSInputParam中设置,对应于`RSInputParam::tail_layer_bytes`。 + +![layers of packet](./img/packet_layers.png) + +#### 3.2.1 InputSock::createSocket() + +createSocket()用于创建UDP Socket。 ++ 调用setsockopt(), 设置选项`SO_REUSEADDR` ++ 调用bind()将socket绑定到指定的(IP, PORT)组上 ++ 如果雷达是组播模式,则将指定IP加入该组播组。 ++ 调用fcntl()设置O_NONBLOCK选项,以异步模式接收MSOP/DIFOP Packet + +该Socket的配置参数可以在RSInputParam中设置。根据设置的不同,createSocket()支持如下几种模式。 + +| msop_port/difop_port | host_address | group_address | | +|:-----------:|:----------------------:|:-----------------:|:-------------| +| 6699/7788 | 0.0.0.0 | 0.0.0.0 | 雷达的目的地址可以为广播地址、或电脑主机地址 | +| 6699/7788 | 192.168.1.201 | 0.0.0.0 | 雷达的目的地址可以为电脑主机地址 | +| 6699/7788 | 192.168.1.201 | 239.255.0.1 | 雷达的目的地址可以为组播地址、或电脑主机地址 | + +#### 3.2.2 InputSock::init() + +init() 调用createSocket(),创建两个Socket,分别接收MSOP Packet和DIFOP Packet。 + +#### 3.2.3 InputSock::start() + +start() 开始接收MSOP/DIFOP Packet。 ++ 启动接收线程,线程函数为InputSock::recvPacket() ++ 调用higherThreadPriority(),提升接收线程的优先级。 + +#### 3.2.4 InputSock::recvPacket() + +recvPacket() 接收MSOP/DIFOP Packet。 +在while循环中, ++ 调用FD_ZERO()初始化本地变量`rfds`,调用FD_SET()将`fds_[2]`中的两个fd加入`rfds`。当然,如果MSOP/DIFOP Packet共用一个socket, 无效的`fds_[1]`就不必加入了。 ++ 调用select()在`rfds`上等待Packet, 超时值设置为`0.5`秒。 +如果select()的返回值提示`rfds`上有信号,调用FD_ISSET()检查是`fds_[]`中的哪一个fd可读。对这个fd, ++ 调用回调函数`cb_get_`, 得到大小为`MAX_PKT_LEN`的缓存。`MAX_PKT_LEN` = `1500`,对当前Robosense雷达来说,够大了。 ++ 调用recvfrom()接收Packet,保存到这个缓存中 ++ 调用回调函数`cb_put_`,将Packet派发给InputSock的使用者。 + + 注意在派发之前,调用Buffer::setData()设置了MSOP Packet在Buffer的中偏移量及长度,以便剥除`USER_LAYER`和`TAIL_LAYER`(如果有的话)。 + +#### 3.2.5 InputSock::higherThreadPrioty() + +higherThreadPrioty()用于设置接收线程的优先级。 ++ 调用pthread_getschedparam(),pthread_setschedparam(),给线程重新设置更高的优先级。 + +缺省情况,higherThreadPriorty()的功能是不启用的。要启用这个特性,要在编译时使用`-DENABLE_HIGH_PRIORITY_THREAD`选项。 + +``` +cmake -DENABLE_HIGH_PRIORITY_THREAD=TRUE . +``` + +### 3.3 InputPcap + +InputPcap解析PCAP文件得到MSOP/DIFOP Packet。使用第三方工具,如WireShark,可以将雷达数据保存到PCAP文件中。 + +![InputSock](./img/class_input_pcap.png) + ++ InputPcap基于第三方的libpcap库,使用它可以遍历PCAP文件,依次得到所有UDP Packet。 + + 成员变量`pcap_`变量保存Pcap文件指针,`pcap_t`定义来自libpcap库。 + ++ 与InputSock一样,在有的客户场景下,InputPcap也需要处理`USER_LAYER`和`TAIL_LAYER`的情况。InputPcap的成员`pcap_offset_`和`pcap_tail_`分别保存`USER_LAYER`和`TAIL_LAYER`的字节数。 ++ 但也有不同的地方。InputSock从Socket接收的Packet只有UDP数据部分,而InputPcap从PCAP文件得到的Packet不同,它包括所有Packet的所有层。`pcap_offset_`除了`USER_LAYER`的长度之外,还要加上其他所有层。 + + 对于一般的以太网包,`pcap_offset_`需要加上其他层的长度,也就是 `14`(ETHERNET) + `20`(IP) + `8`(UDP) = `42` 字节。 + + 如果还有VLAN层,`pcap_offset_`还需要加上 `4` 字节。 + +![layers of packet](./img/packet_layers_full.png) + ++ PCAP库可能包括非UDP库的Packet。为了校验是否MSOP/DIFOP Packet,需要使用libpcap库的过滤器,也就是`bpf_program`,它由pcap_compile()生成。成员`msop_filter_`和`difop_filter_`分别是MSOP Packet和DIFOP Packet的过滤器。 + + MSOP/DIFOP Packet都是UDP Packet,所以给pcap_compile()指定选项`udp`。 + + 如果是基于VLAN的,则需要指定选项`vlan` + + 如果在一个PCAP文件中包含多个雷达的Packet,则还需要指定选项 `udp dst port`,以便只提取其中一个雷达的Packet。 + + +用户配置参数RSInputParam中指定选项`udp dst port`。有如下几种情况。 + +| msop_port | difop_port | 说明 | +|:-----------:|:-------------:|:-------------| +| 0 | 0 | 如果PCAP文件中只包含一个雷达的Packet | +| 6699 | 7788 | 如果PCAP文件中包含多个雷达的Packet,则可以只提取指定雷达的Packet(该雷达MSOP/DIFOP端口不同) | +| 6699 | 6699/0 | 如果PCAP文件中包含多个雷达的Packet,则可以只提取指定雷达的Packet(该雷达DIFOP/DIFOP端口相同) | + +#### 3.3.1 InputPcap::init() + +init()打开PCAP文件,构造PCAP过滤器。 ++ 调用pcap_open_offline()打开PCAP文件,保存在成员变量`pcap_`中。 ++ 调用pcap_compile()构造MSOP/DIFOP Packet的PCAP过滤器。 + + 如果它们使用不同端口,则需要两个过滤器,分别保存在`mosp_filter_`和`difop_filter_`中。 + + 如果使用同一端口,那么`difop_filter_`就不需要了。 + +#### 3.3.2 InputPcap::start() + +start()开始解析PCAP文件。 ++ 调用std::thread(),创建并启动PCAP解析线程,线程的函数为recvPacket()。 + +#### 3.3.3 InputPcap::recvPacket() + +recvPacket()解析PCAP文件。 +在循环中, ++ 调用pcap_next_ex()得到文件中的下一个Packet。 + +如果pcap_next_ex()还能读出Packet, ++ 本地变量`header`指向Packet的头信息,变量`pkt_data`指向Packet的数据。 ++ 调用pcap_offline_filter(),使用PCAP过滤器校验Packet(检查端口、协议等是否匹配)。 + +如果是MSOP Packet, + + 调用`cb_get_`得到大小为`MAX_PKT_LEN`的缓存。`MAX_PKT_LEN` = `1500`,对当前的RoboSense雷达来说,够大了。 + + 调用memcpy()将Packet数据复制到缓存中,并调用Buffer::setData()设置Packet的长度。复制时剥除了不需要的层,包括`USER_LAYER`和`TAIL_LAYER`(如果有的话)。 + + 调用回调函数`cb_put_`,将Packet派发给InputSock的使用者。 + +如果是DIFOP Packet,处理与MSOP Packet一样。 + ++ 调用this_thread::sleep_for()让解析线程睡眠一小会。这是为了模拟雷达发送MSOP Packet的间隔。这个间隔时间来自`Decoder`,每个雷达有自己的值。在`Decoder`部分会说明如何算这个值。 + +如果pcap_next_ex()不能读出Packet,一般意味着到了文件结尾,则: ++ 调用pcap_close()关闭pcap文件指针 `pcap_` 。 + +用户配置RSInputParam的设置决定是否重新进行下一轮的解析。这个选项是`RSInputParam::pcap_repeat`。 ++ 如果这个选项为真,调用pcap_open_offline()重新打开PCAP文件。这时成员变量`pcap_`回到文件的开始位置。下一次调用pcap_next_ex()又可以重新得到PCAP文件的第一个Packet了。 + +### 3.4 InputRaw + +InputRaw是为了重播MSOP/DIFOP Packet而设计的Input类型。将在Packet Record/Replay章节中说明。 + +### 3.5 InputFactory + +InputFactory是创建Input实例的工厂。 + +![InputFactory](./img/class_input_factory.png) + +Input类型如下。 + +``` +enum InputType +{ + ONLINE_LIDAR = 1, // InputSock + PCAP_FILE, // InputPcap + RAW_PACKET // InputRaw +}; +``` + +#### 3.5.1 InputFactory::creatInput() + +createInput() 根据指定的类型,创建Input实例。 ++ 创建InputPcap时,需指定`sec_to_delay`。这是InputPcap回放MSOP Packet的间隔。 ++ 创建InputRaw时,需指定`cb_feed_pkt`。这个将在Packet Record/Replay章节中说明。 + +## 4 Packet解析 + +### 4.1 MSOP格式 + +这里说明MSOP格式中这些字段。 ++ 距离 `distance`、 ++ 角度 ++ 发射率 `intensity`、 ++ 通道 `ring`、 ++ 时间戳 `timestamp`、 ++ 温度 `temperature` ++ 回波模式 `echo_mode` + +其中前五个与点云直接相关。 + +MSOP格式中的点是极坐标系的坐标,包括极径和极角。距离就是这里的极径。从距离和角度可计算直角垂直坐标系的坐标,也就是点云使用的坐标。 + +#### 4.1.1 Distance + +Distance用两个字节表示。它乘以一个解析度得到真实距离。 ++ 不同的雷达的解析度可能不同。 ++ 特定于雷达的配置参数`RSDecoderConstParam::DISTANCE_RES`保存这个解析度。 + +``` +uint16_t distance; +``` +#### 4.1.2 角度 + ++ 对于机械式雷达, MSOP格式的azimuth保存点的极角(水平角)。 + + ``` + uint16_t azimuth; + ``` + + 要计算点的直角坐标系坐标,除了`distance`和`azimuth`之外,还需要一个垂直角。 + + 垂直角从DIFOP Packet得到,一个机械式激光雷达有一组固定的垂直角,每个通道一个。后面的章节将说明垂直角。 + + + 水平角是MOSP Packet中点的`azimuth`。 + ++ 对于MEMS雷达, 角度是`pitch`和`yaw`。 + + ``` + uint16_t yaw; + uint16_t pitch; + ``` + 从`distance`、`pitch`、和`yaw`,可计算直角坐标系的坐标。 + ++ 雷达的角度分辨率是`0.01`度。这意味着一圈`360`度,可以划分成`36000`个单位。 + ++ MSOP格式中,角度以`0.01`度为单位,范围是(`0`, `36000`),所以可以用`uint16_t`来表示。 + +#### 4.1.3 intensity + +`intensity`保存在1个字节中。 + +``` +uint8_t intensity; +``` + +#### 4.1.4 ring + +`ring`在后面的ChanAngles章节说明。 + +#### 4.1.5 timestamp + +RoboSense雷达使用了几种时间戳格式。 + +##### 4.1.5.1 YMD 格式 + +YMD格式定义如下,parseTimeYMD()负责解析这种时间戳格式。遵循这种格式的有RS16/RS32/RSBP等。 + +``` +typedef struct +{ + uint8_t year; + uint8_t month; + uint8_t day; + uint8_t hour; + uint8_t minute; + uint8_t second; + uint16_t ms; + uint16_t us; +} RSTimestampYMD; +``` + +##### 4.1.5.2 UTC 格式 + +UTC格式定义如下。 ++ 成员`sec[6]`保存的是秒数, ++ 成员`ss[4]`保存微秒值或纳秒值。 + +``` +typedef struct +{ + uint8_t sec[6]; + uint8_t ss[4]; +} RSTimestampUTC; +``` ++ 如果`ss[4]`保存微秒值,使用parseTimeUTCWithUs()解析。遵循这种格式的有RSHELIOS/RSM1。 ++ 如果`ss[4]`保存纳秒值,使用parseTimeUTCWithNs()解析。遵循这种格式的有RS128/RS80。 + +#### 4.1.6 temperature + +RoboSense雷达使用了几种温度格式。 + +##### 4.1.6.1 用解析度表示温度 + +一种是用2字节表示温度值,这个值乘以一个解析度得到真实温度。 ++ 特定于雷达的配置参数`RSDecoderConstParam::TEMPERATURE_RES`保存这个解析度。 + +``` +typedef struct +{ + uint8_t tt[2]; +} RSTemperature; +``` + ++ 如果这两个字节是`littlen endian`格式,使用parseTempInBe()解析。遵循这种格式的有RS16/RS32/RSBP/RSHELIOS。 ++ 如果这两个字节是`big endian`格式,使用parseTempInLe()解析。遵循这种格式的有RS80/RS128。 + +##### 4.1.6.2 相对温度 + +另一类用1个字节表示温度。这个值加上一个初始值得到真实温度。遵循这种格式的有RSM1。 ++ 特定于雷达的配置参数`RSDecoderConstParam::TEMPERATURE_RES`保存这个初始值。 + +``` +int8_t temperature; +``` + +#### 4.1.7 echo_mode + +雷达内部有多种回波模式。 ++ 最强回波, ++ 最强回波, ++ 双回波, + +MSOP格式中用一个字节表示: + +``` +int8_t return_mode; +``` + +但驱动并不在意是回波是“最强的”,还是“最后的”。因为影响MSOP解析的只是:有几个回波? + +如下是才是rs_driver关心的回波模式。 + +``` +enum RSEchoMode +{ + ECHO_SINGLE = 0, + ECHO_DUAL +}; +``` + +不同雷达有不同的回波模式`return_mode`。每个Decoder实现自己的解析函数getEchoMode(),得到rs_driver的回波模式。 + +回波模式会影响MSOP Packet的结构,还会影响点云的分帧。 + +### 4.2 ChanAngles + +#### 4.2.1 垂直角/水平角的修正 + +如前面MSOP格式的章节所说,理论上从distance、垂直角、水平角就可以计算点的直角坐标系的坐标。 + +但实践中装配雷达总是无可避免地有细微的误差,导致雷达的角度不精确,需要进行修正。雷达装配后的参数标定过程,会找出相关的修正值,写入雷达的寄存器。标定后,使用修正值调整点,就可以使其精度达到要求。 + +MEMS雷达的角度修正,在雷达内部完成,所以驱动不需要做什么;机械式雷达的角度修正,由驱动在电脑主机端完成。 + +这里说明机械式雷达的垂直角/水平角修正。 + +对于机械式雷达,每个通道的垂直角是固定的。以RSBP举例,它的理论垂直角如下。(这里有`32`个值,对应RSBP的`32`个通道) + +``` + 89.5, 81.0625, 78.25, 72.625, 67, 61.375, 55.75, 50.125, + 86.6875, 83.875, 75.4375, 69.8125, 64.1875, 58.5625, 52.9375, 47.3125, + 44.5, 38.875, 33.25, 27.625, 22, 16.375, 10.75, 5.125, + 41.6875, 36.0625, 30.4375, 24.8125, 19.1875, 13.5625, 7.9375, 2.3125 +``` + +装配过程中的误差,导致雷达的垂直角不是这里列出的理论值,水平角`azimuth`也不是从零开始。标定过程找出两组修正值,一组针对垂直角,一组针对水平角。 + +还是以RSBP为例。标定过程后,实际的垂直角可能是这样的。这里修正值已经累加了原来的垂直角。 + +``` + 89.4375, 81.0625, 78.25, 72.625, 67, 61.375, 55.75, 50.125, + 86.8125, 83.875, 75.4375, 69.8125, 64.1875, 58.5, 52.9375, 47.3125, + 44.5625, 38.875, 33.25, 27.625, 22, 16.375, 10.75, 5.125, + 41.6875, 36.1875, 30.4375, 24.8125, 19.0625, 13.5625, 7.9375, 2.3125 +``` + +同时,水平角修正值的例子如下。(这里有32个值,对应RSBP的32个通道) + +``` + 0.0625, 0.0625, -0.25, 0.625, 0, -0.375, 0.75, -0.125, + -0.3125, 0.875, -0.4375, 0.8125, 0.1875, 0.5, -0.9375, 0.3125, + 0.0, -0.875, 0.25, -0.625, 0, -0.375, 0.75, 0.125, + 0.125, 0.1875, 0.4375, 0.8125, 0.0625, 0.5625, 0.9375, 0.3125 +``` + +这两组修正值在参数标定过程中写入雷达寄存器,它们也包含在DIFOP Packet中。 + +#### 4.2.2 ChanAngles定义 + +ChanAngles从DIFOP Packet读入机械式雷达的垂直角/水平角的修正值。如果雷达修正值无效,也可以从外部文件读入。 + +如前面所说,只有机械式雷达需要ChanAngles。 + +![ChanAngles](./img/class_chan_angles.png) + ++ 成员变量chan_num_是雷达的通道数,用于决定修正值数组的大小。 ++ 成员变量vert_angles_是保存垂直角修正值的数组 ++ 成员变量horiz_angles_是保存水平角修正值的数组。 + +#### 4.2.3 ChanAngles::loadFromDifop() + +loadFromDifop()从DIFOP Packet读入角度修正值,写入成员`vert_angles_[]`和`horiz_angles_[]`。 ++ 它还调用genUserChan(), 设置用户通道编号数组。 + ++ 在DIFOP Packet中,修正值保存在RSClibrationAngle结构中。 + + 成员`value`是非负值, + + 成员`sign`则指定正负; `0`则修正值为正;除`0xFF`以外的非`0`值,则修正值为负;为`0xFF`时,修正值无效。 + +``` +typedef struct +{ + uint8_t sign; + uint16_t value; +} RSCalibrationAngle; +``` + +对于RSBP, MSOP Packet中的修正值保存在成员`vert_angle_cali[]`和`horiz_angle_cali[]`中。 + +``` +typedef struct +{ + ... + + RSCalibrationAngle vert_angle_cali[32]; + RSCalibrationAngle horiz_angle_cali[32]; + + ... +} RSBPDifopPkt; +``` + +#### 4.2.4 早期雷达适配ChanAngles + ++ 不是所有雷达的修正值都保存在RSCalibrationAngle中。比如早期的雷达RS16,它的修正值保存在成员`pitch_cali[]`中。 + + ``` + typedef struct + { + ... + + uint8_t pitch_cali[48]; + + ... + } RS16DifopPkt; + + ``` + + 为了像其他雷达一样处理RS16,将RS16DifopPkt适配到一个能兼容RSCalibrationAngle的结构 AdapterDifopPkt, + + ``` + typedef struct + { + uint16_t rpm; + RSFOV fov; + uint8_t return_mode; + RSCalibrationAngle vert_angle_cali[32]; + RSCalibrationAngle horiz_angle_cali[32]; + } AdapterDifopPkt; + ``` + + RS16使用了转换函数RS16DifopPkt2Adapter(),从RS16DifopPkt构造一个AdapterDifopPkt。 + + ``` + void RS16DifopPkt2Adapter (const RS16DifopPkt& src, AdapterDifopPkt& dst); + ``` + ++ RS32也有类似的情况。虽然它的修正值也保存在RSCalibrationAngle数组中,但角度值的含义不同。 + + ``` + typedef struct + { + RSCalibrationAngle vert_angle_cali[32]; + RSCalibrationAngle horiz_angle_cali[32]; + } RS32DifopPkt; + ``` + + 与RS16类似,也将RS32DifopPkt适配到AdapterDifopPkt。RS32使用的转换函数是RS32DifopPkt2Adapter()。 + +#### 4.2.5 ChanAngles::loadFromFile() + +有些场景下,雷达可能还没有写入有效的修正值,或者是因为还没有标定,或者是由于雷达故障。这时可以从外部文件读入角度修正值。 + +文件格式如下。 ++ 每行是对应一个通道的修正值。行中第`1`个值是垂直角,第`2`个值是水平角修正值。 ++ 每行对应一个通道。所以对于RSBP来说,应该有`32`行。这个例子略去了部分行。 + +``` +89.5,0.125 +81.0625,-0.025 +78.25,0 +72.625,0 +... +30.4375,0.625 +24.8125,0 +19.1875,-0.25 +13.5625,0 +7.9375,-0.1 +2.3125,0 +``` +loadFromFile() 解析这个文件得到修正值,写入成员`vert_angles_[]`和`horiz_angles_[]`。 ++ 它还调用genUserChan(), 设置用户通道编号数组。 + +#### 4.2.6 ChanAngles::horizAdjust() + +horizAdjust()对参数给出的水平角作修正 ++ 根据内部通道编号得到水平角修正值, ++ 水平角加入这个修正值,并返回 + +#### 4.2.7 ChanAngles::vertAdjust() + +vertAdjust()根据内部通道编号,得到修正后的垂直角。 + +#### 4.2.8 点云的ring值 + +点云中的`ring`值是从用户角度看的通道编号,它来自于ChanAngles的成员变量`user_chans_`。 + +回到RSBP的例子,如下是它的垂直角,它们按照雷达内部通道编号排列,而不是降序或升序排列。换句话说,雷达内部通道不是按照垂直角的升序或降序编号的。 + +``` + 89.5, 81.0625, 78.25, 72.625, 67, 61.375, 55.75, 50.125, + 86.6875, 83.875, 75.4375, 69.8125, 64.1875, 58.5625, 52.9375, 47.3125, + 44.5, 38.875, 33.25, 27.625, 22, 16.375, 10.75, 5.125, + 41.6875, 36.0625, 30.4375, 24.8125, 19.1875, 13.5625, 7.9375, 2.3125 +``` +但用户希望看到通道编号按照垂直角按升序或降序排列。 + +ChanAngles的成员变量`user_chans`保存的是按升序排列的编号,也就是角度小的通道在前。 + +#### 4.2.9 ChanAngles::genUserChan() + +genUserChan()根据成员变量`vert_angles_[]`中的角度值,计算升序排列的用户通道编号数组。 + +#### 4.2.10 ChanAngles::toUserChan() + +toUserChan(),从给出的雷达内部通道编号,得到用户通道编号。 + +### 4.3 Trigon + +#### 4.3.1 查表计算三角函数值 + +如前面所说,MSOP Packet中的点是极坐标系的坐标。rs_driver将点坐标,从极坐标系转换为用户使用的直角坐标系。这时需要计算角度的sin/cos值。 + +调用三角函数又耗时又耗CPU资源,优化的方式是查表。 ++ 首先确定表的范围。 + + 垂直角的范围在(`-90`,`90`)内。加上修正值,也还是在(`-90`, `90`)内。 + + 水平角的范围在(`0`, `360`)内。加上修正值,在(`-90`, `450`)内。 + ++ MSOP格式中,角度以`0.01`度为单位。rs_driver也是这样。对于(`-90`, `450`)的角度范围,需要对(`-9000`, `45000`)内的整数角度值,计算sin/cos值。 + +#### 4.3.2 Trigon定义 + +Trigon用于计算指定范围内的sin/cos值,并用于查询。 + +![Trigon](./img/class_trigon.png) + ++ 成员变量`MIN`和`MAX`保存角度范围。这里`MIN` = `-9000`, `MAX` = `45000`。 ++ 成员变量`o_sins_`保存所有角度的sin值,`o_coss_`保存所有角度的cos值。`o_sins_[]`和`o_coss_[]`是两个大小为 `MAX - MIN` 的数组。 ++ 引用`os_sins_[]`和`o_coss_[]`计算三角函数值时,需要减去一个偏移。为了免去这个麻烦,重新定义了两个指针`sins_`和`coss_`,让它们分别指向`os_sins_[9000]`和`os_cons_[9000]`。这样就可以用角度值直接引用`sins_`和`coss_`了。 + +![Trigon](./img/trigon_sinss.png) + +#### 4.3.3 Trigon::Trigon() + +Trigon的构造函数Trigon() 负责初始化`o_sins_[]`和`o_coss_[]`。 ++ 根据角度范围,给`o_sins[]`和`o_coss_[]`分配相应大小的空间, ++ 遍历范围内的角度值,调用std::sin()和std::cos(),将三角函数值分别保存到`o_sins_[]`和`o_coss_[]`中。 ++ 让`sins_`指向`sins_[]`中`0`度角的位置,这里是`sins_[9000]`。类似地设置`coss_`。 + +#### 4.3.4 Trigon::sin() + +sin()查表返回角度的sin值。 + +#### 4.3.5 Trigon::cos() + +cos()查表返回角度的cos值。 + +### 4.4 BlockIterator + +这一节"BlockIterator",仅针对机械式雷达。 + +#### 4.4.1 Packet、Block、Channel + +在MSOP格式中,每个Packet中有`BLOCKS_PER_PKT`个Block,每个Block中有`CHANNELS_PER_BLOCK`个Channel。 ++ 这里的`BLOCKS_PER_PKT`和`CHANNEL_PER_BLOCK`分别在雷达配置参数`RSDecoderConstParam`中指定。 + +对于机械式雷达,雷达持续旋转,垂直方向上的每一轮激光发射,在MSOP Packet中对应一个Block。 +以RSBP雷达为例, ++ 一轮就是`32`次激光发射,对应`32`个channel。所以`RSDecoderConstParam::CHANNELS_PER_BLOCK` = `32`。 ++ MSOP的设计初衷,当然是向每个Packet多塞几个Block,这样就有`RSDecoderConstParam::BLOCKS_PER_PKT` = `12`。 + +![msop single return](./img/msop_single_return.png) + +雷达的每轮激光发射时序包括充能、发射等步骤。每轮发射内,相邻发射的时间戳不均匀,但每轮发射的持续时间(也是相邻两轮发射的时间差)相等。 +以RSBP为例, ++ 一轮发射的时长为`55.52`纳秒,这是Block之间的时间差。 ++ 一轮发射中,`32`次发射的时间戳如下(相对于Block的相对时间,单位纳秒)。这是Block内的每个Channel相对于Block的相对时间。 + +``` + 0.00, 2.56, 5.12, 7.68, 10.24, 12.80, 15.36, 17.92, + 25.68, 28.24, 30.80, 33.36, 35.92, 38.48, 41.04, 43.60, + 1.28, 3.84, 6.40, 8.96, 11.52, 14.08, 16.64, 19.20, + 26.96, 29.52, 32.08, 34.64, 37.20, 39.76, 42.32, 44.88 +``` + +#### 4.4.2 Channel的时间戳 + +MSOP格式中,Packet头部包含一个时间戳。 + +如对于RSBP雷达,Packet的时间戳如下。 + +``` +RSTimestampYMD timestamp; +``` + +通过如下方式可以计算Channel的时间戳。 + +``` +Block的时间戳 = Packet的时间戳 + Block的持续时间 * Block数 +Channel的时间戳 = 所在Block的时间戳 + Channel对Block的相对时间戳 +``` + +#### 4.4.3 Channel的角度 + +在MSOP格式中,Block的成员中包括水平角`azimuth`。 + +雷达的旋转当然不是匀速的。但放到一个Block这么短时间内来看,认为旋转是匀速的,还是合理的。 + +所以,通过Channel占Block的时间比例,可以估计Channel对Block的相对水平角。 + +``` +Channel的水平角 = Block的水平角 + 当前Block与下一个Block的水平角差 * Channel对Block的相对时间戳 / Block的持续时间 +``` + +#### 4.4.4 双回波模式的影响 + +双回波模式下,虽然一个Packet还是塞了同样数目的Block,但是第二个回波的Block,其水平角/时间戳与第一个回波相同。 + +如下是双回波模式下,RSBP的MSOP格式。 + +![msop dual return](./img/msop_dual_return.png) + +这样,遍历Block序列时,计算Block时间戳/角度差的方式就不一样了。 + +#### 4.4.5 BlockIterator定义 + +引入BlockIterator的目的是定义一个接口,来计算: ++ Block的时间戳。这个时间戳是相对于Packet的时间戳。 ++ Block与下一次Block的水平角差。也就是当前Block内雷达旋转的水平角。 + +BlockIterator的成员如下。 ++ 成员变量`pkt_`是Packet ++ 成员变量`BLOCKS_PER_PKT`是Packet中的Block数 ++ 成员`BLOCK_DURATION`是Block的持续时间 ++ 成员az_diffs[]保存所有Block的水平角差 ++ 成员tss[]保存所有Block的时间戳 + +![](./img/classes_block_iterator.png) + +##### 4.4.5.1 BlockIterator::get() + +成员函数get()从成员az_diffs[]和tss[],得到Block的时间戳和水平角差。BlockIterator的派生类应该计算这两个数组中的值。 + +#### 4.4.6 SingleReturnBlockIterator + +SingleReturnBlockIterator实现单回波模式下的BlockIterator接口。 + +##### 4.4.6.1 SingleReturnBlockIterator() + +单回波模式下, +在构造函数中,遍历Packet中的block,并计算az_diffs[]和tss[]。 ++ Block之间的时间差是固定值,也就是`BLOCK_DURATION`。 ++ 1个Packet有`BLOCKS_PER_PKT`个Block。 + + 对于前面的Block, + + ``` + Block水平角差 = 下一个Block的水平角 - 当前Block的水平角 + ``` + + 最后一个Block的水平角差,认为等于`BLOCK_AZ_DURATION`,这时雷达理论上每个Block的水平角差。 + ++ 相邻Block可能跨`角度0`,所以它们的水平角差可能小于`0`,这时需要将它修正到[`0`, `36000`)内。 + +#### 4.4.7 DualReturnBlockIterator + +DualReturnBlockIterator实现双回波模式下的BlockIterator接口。 + +##### 4.4.7.1 DualReturnBlockIterator() + +双回波模式下,Block两两成对。 +在构造函数中,遍历Packet中的Block,并计算az_diffs[]和tss[]。遍历时步进值为2。 + ++ 步进差为2的Block, 时间差为`BLOCK_DURATION`。奇数Block和前一个偶数Block的时间戳相同。 + + 对于前面的Block, + + ``` + Block水平角差 = 下下个Block的水平角 - 当前Block的水平角 + ``` + + + 最后两个Block的角度差,认为等于`BLOCK_AZ_DURATION`,这是雷达理论上每个Block的水平角差。 + ++ 由于相邻Block可能跨`角度0`,所以它们的水平角差可能小于`0`,这时需要将它修正到 [`0`, `36000`)内。 + +#### 4.4.8 ABReturnBlockIterator + +双回波模式下,Ruby128是个特殊情况。 + +Ruby128的每个block有`128`个Channel,每个block占的空间太大,以至于每个packet只能放下`3`个Block。这样一次扫描的两个Block可能在不同的Packet中。相邻的两个packet格式如下图。 + +![msop ruby128](./img/msop_ruby128.png) + +ABReturnBlockIterator类用于计算Ruby128的双回波模式的时间戳和角度。 + +##### 4.4.8.1 ABDualReturnBlockIterator() + +根据第0个Block和第1个Block的角度是否相同,判断这是一个`AAB` Packet还是`BAA` Packet。 ++ `A`与`B`之间的时间差为`BLOCK_DURATION`。 + ++ 不论是`AAB` Packet,还是`BAA` Packet, Block的角度差都是`A`与`B`之间的角度差。 + +``` +Block水平角差 = 第三个Block的水平角 - 第一个Block的水平角 +``` + +#### 4.4.9 RS16的Packet格式 + +为了充分利用MSOP Packet的空间,RS16的Packet格式与其他机械式雷达不同。 + +在单回波模式下,RS16将相邻两个通道的数据放在同一Block中,如下图所示。 + +![](./img/rs16_msop_single_return.png) + +在双回波模式下,RS16将一个通道两个回波数据放在同一Block中,如下图所示。 + +![](./img/rs16_msop_dual_return.png) + +这样的结果是, ++ Packet中的相邻BLOCK之间的角度差不再一定是`BLOCK_AZ_DURATION`,时间差也不再一定是`BLOCK_DURATION`。 ++ 对于RS16,RSDecoderConstParam.CHANNELS_PER_BLOCK = 32。遍历所有通道时,这个值需要做一次映射,才能得到实际的通道值。 + +``` +uint16_t laser = chan % 16; +``` + +RS16SingleReturnBlockIterator和RS16DualReturnBlockIterator,分别处理RS16单回波模式和双回波模式的情况。 ++ 新加入的成员函数calcChannel(),计算Block内每个Channel的角度占比,和时间戳偏移。 + +![](./img/classes_rs16_block_iterator.png) + +#### 4.4.9 RS16SingleReturnBlockIterator + +##### 4.4.9.1 Rs16SingleReturnBlockIterator() + +在构造函数中,遍历Packet中的block,并计算az_diffs[]和tss[]。 + +与SingleReturnBlockIterator()中不同的地方是:单回波模式下,一个Block中包括相邻的两个通道数据。 ++ 缺省的角度差是`BLOCK_AZ_DURATION` * 2 ++ 缺省的时间差是`BLOCK_DURATION` * 2 + +##### 4.4.9.2 RS16SingleReturnBlockIterator::calcChannel() + +calcChannel()计算单回波模式下,32个Channel的角度占比,和时间戳偏移。 + +#### 4.4.10 RS16DualReturnBlockIterator + +##### 4.4.10.1 Rs16DualReturnBlockIterator() + +双回波模式下,Block两两成对。 + +在构造函数中,遍历Packet中的Block,并计算az_diffs[]和tss[]。与Rs16DualReturnBlockIterator不同的地方是:双回波模式下,一个Block中包括两个回波的数据。 ++ 缺省的角度差是`BLOCK_AZ_DURATION` ++ 缺省的时间差是`BLOCK_DURATION` + +##### 4.4.10.2 RS16SingleReturnBlockIterator::calcChannel() + +calcChannel()计算双回波模式下,32个Channel的角度占比,和时间戳偏移。 + +### 4.5 FOV + +机械式雷达的扫描角度是[0,360),这也是雷达输出点的角度范围。 + +也可以限制雷达的输出角度,如下图。 ++ FOV的范围是[start_angle,end_angle)。 ++ 与FOV互补的角度范围FOV_blind是FOV的盲区,雷达不会输出这个范围的点。 + +![msop ruby128](./img/fov.png) + +#### 4.5.1 FOV设置 + +FOV可以从DIFOP Packet得到。 + +``` + RSFOV fov; +``` + +RSFOV的定义如下。 + +``` +typedef struct +{ + uint16_t start_angle; + uint16_t end_angle; +} RSFOV; +``` + +在DecoderMech::decodeDifopCommon()中解析DIFOP Packet得到FOV。 ++ 这里计算雷达扫描跨过盲区的时间差,也就是DecoderMech的成员`fov_blind_ts_diff_`. + +``` +void DecoderMech::decodeDifopCommon(const T_Difop& pkt); +``` + +#### 4.5.2 FOV对BlockIterator的影响 + +在BlockIterator的各种实现中,需要考虑Packet的相邻两个Block跨过FOV盲区的情况。 +如果跨过盲区,则 ++ 第一个Block的水平角度差调整为`BLOCK_AZ_DURATION`。这时理论上每个Block的水平角差。 ++ 两个Block的时间差调整为`FOV_BLIND_DURATION`。这个值是盲区时间差,也就是前面说的`fov_blind_ts_diff_`。 + +### 4.6 分帧 + +机械式雷达和MEMS雷达的分帧策略不同。 + +#### 4.6.1 机械式雷达的分帧模式 + +机械式雷达持续旋转,输出点,驱动在某个分割位置分割前后帧。有三种分帧模式。 ++ 按Block的水平角分帧。这是默认的分帧模式。 + + 如果Block的水平角刚好跨过指定的水平角,则分帧。 + + 雷达的转动不是均匀的,所以每帧包含的Block数可能会有细微的变动,相应地,包含的点数也会变动。 + +![split angle](./img/split_angle.png) + ++ 按理论上每圈的Block数分帧。这样每帧包含的Block数和点数都是固定的。 + + Robosense雷达支持两种转速:`600`圈/分钟和`1200`圈/分钟。以`600`圈/分钟距离,相当于每圈`0.1`秒,而Block的持续时间是固定的,由此计算理论上每圈的block数(实际上是假设雷达转速均匀) + +``` + 每圈Block数 = 每圈秒数 / Block持续时间 +``` + + 理论上每圈Block数,在不同回波模式下不同。上面的计算是针对单回波模式。如果是双回波模式,则每圈Block数要加倍。 + ++ 按照使用者指定的Block数分帧。当然这样每帧的Block数和点数也都是固定的。 + +#### 4.6.2 SplitStrategy + +SplitStrategy定义机械式雷达的分帧模式接口。 ++ 使用者遍历Packet中的Block,用block的水平角调用SplitStrategy::newBlock()。应该分帧时,newBlock()返回`true`,否则返回`false`。 + +![split strategy](./img/classes_split_strategy.png) + +#### 4.6.3 SplitStrategyByAngle + +SplitStrategyByAngle按Block角度分帧。 + ++ 成员`split_angle_`保存分割帧的角度。 ++ 成员`prev_angle_`保存前一个Block的角度。 + +##### 4.6.3.1 SplitStrategyByAngle::newBlock() + +当前一个Block的角度`prev_angle_`在`split_angle_`之前,而当前Block的角度在`split_angles_`之后,则认为当前Block跨越了`split_angles_`,返回`true`。 ++ 这里考虑了Block的角度跨越`角度0`的情况。 + +#### 4.6.4 SplitStrategyByNum + +SplitStrategyByNum实现按block数分帧。 ++ 成员`max_blks_`是每帧的Block数。 ++ 成员`blks_`是当前已累积的Block数。 + +##### 4.6.4.1 SplitStrategyByAngle::newBlock() + +newBlock()简单地累加Block数到成员`blks_`,当`blk_`达到`max_blks_`时,则返回`true`。 + +#### 4.6.5 MEMS雷达的分帧模式 + +MEMS雷达的分帧是在雷达内部确定的。 ++ 一帧的Packet数是固定的。假设这个数为`N`, 则雷达给Packet编号,从`1`开始,依次编号到`N`。 ++ 对于RSM1,单回波模式下,Packet数是`630`;在双回波模式下,输出的点数要翻倍,相应的,Packet数也要翻倍,Packet数是`1260`。 + +#### 4.6.6 SplitStrategyByPktSeq + +SplitStrategyBySeq按Packet编号分帧。 ++ 注意SplitStrategyBySeq的接口与SplitStrategy不同,不是后者的派生类。 ++ 成员变量`max_seq_`是Packet编号的最大值。 ++ 成员变量`prev_seq_`是前一个Packet的编号。 ++ 成员变量`safe_seq_min_`和`safe_seq_max`,是基于`prev_seq_`的一个安全区间。稍后说明它的用处。 + +![split strategy by seq](./img/classes_split_strategy_by_seq.png) + +##### 4.6.6.1 SplitStrategyByPktSeq::newPacket() + +使用者用Packet的编号值,调用newPacket()。如果分帧,返回`true`。 + +MSOP使用UDP协议,理论上Packet可能丢包、乱序。 + +先讨论没有安全区间时,如何处理丢包、乱序。 ++ 理想情况下,如果不丢包不乱序,Packet编号从`1`到`630`, 只需要检查Packet编号是不是`630`。如果是就分帧。 ++ 那假如只有丢包呢?举个例子,如果编号为`630`的Packet丢了,则可以加入检查条件,就是当前Packet编号小于`prev_seq_`,就分帧。 ++ 在乱序的情况下,这个检查条件会导致另一个困境。举个例子,如果编号为`300`和`301`的两个Packet乱序,那么这个位置分帧,会导致原本的一帧拆分成两帧。 + +为了一定程度上,包容可能的Packet丢包、乱序情况,引入安全区间的概念。 ++ 以`prev_seq_`为参考点,划定一个范围值`RANGE`, + +``` +safe_seq_min_ = prev_seq_ - RANGE +safe_seq_max_ = prev_seq_ + RANGE +``` + +![safe range](./img/safe_range.png) + ++ 如果Packet在范围(`safe_seq_min_`, `safe_seq_max_`)内,都不算异常,丢包、乱序都不触发分帧。这样大多数情况,之前的问题可以避免。 + +### 4.7 点云的有效性校验 + +#### 4.7.1 AzimuthSection + +AzimuthSection检查水平角是否在有效范围内。 ++ 成员变量`start_`指定这个范围的起始角度,`end_`指定这个范围的结束角度。支持跨水平角`0`的情况,比如`start` = `35000`, `end` = `10`。 ++ 用户可以通过用户配置参数`RSDecoderParam::start_angle`,和`RSDecoderParam::start_angle`指定这个范围。 + +![azimuth section](./img/class_azimuth_section.png) + +##### 4.7.1.1 AzimuthSection::in() + +in()检查指定的角度`angle`是否在有效范围内。 + +#### 4.7.2 DistanceSection + +DistanceSection检查指定的`distance`是否在有效范围内。 ++ 成员`min_`和`max_`分别是这个范围的最小值和最大值。 ++ 不同雷达有不同的测距范围。雷达配置参数`RSDecoderConstParam::DISTANCE_MIN`,和`RSDecoderConstParam::DISTANCE_MAX`指定这个范围。 ++ 用户也可以通过用户配置参数`RSDecoderParam::min_distance`, 和`RSDecoderParam::max_distance`进一步限缩这个范围。 + +![distance section](./img/class_distance_section.png) + +##### 4.7.2.1 DistanceSection::in() + +in()检查指定的`distance`是否在有效范围内。 + +### 4.8 Decoder + +Decoder解析雷达MSOP/DIFOP Packet,得到点云。 ++ 它是针对所有雷达的接口类,包括机械式雷达和MEMS雷达。 + +DecoderMech派生于Decoder,给机械式雷达完成一些通用的功能,如解析DIFOP Packet。 +每个机械式雷达分别派生自DecoderMech的类,如DecoderRS16、DecoderRS32、DecoderBP、DecoderRSHELIOS、DecoderRS80、DecoderRS128等。 + +MEMS雷达的类直接派生自Decoder。 + +DecoderFactory根据指定的雷达类型,生成Decoder实例。 + +![decoder classes](./img/classes_decoder.png) + +#### 4.8.1 Decoder定义 + +如下图是Decoder的详细定义。 ++ 成员`const_param_`是雷达的参数配置。 ++ 成员`param_`是用户的参数配置。 ++ 成员`trigon_`是Trigon类的实例,提供快速的sin/con计算。定义如下的宏,可以清晰、方便调用它。 + +``` +#define SIN(angle) this->trigon_.sin(angle) +#define COS(angle) this->trigon_.cos(angle) +``` ++ 成员`packet_duration_`是MSOP Packet理论上的持续时间,也就是相邻两个Packet之间的时间差。Decoder的派生类计算这个值。 + + InputPcap回放PCAP文件时,需要这个值在播放Packet之间设置延时。 ++ 成员`echo_mode_`是回波模式。Decoder的派生类解析DIFOP Packet时,得到这个值。 ++ 成员`temperature_`是雷达温度。Decoder的 派生类解析MSOP Packet时,应该保存这个值。 ++ 成员`angles_ready_`是当前的配置信息是否已经就绪。不管这些信息是来自于DIFOP Packet,还是来自外部文件。 ++ 成员`point_cloud_`是当前累积的点云。 ++ 成员`height_`是点云的高度。Decoder的派生类设置这个值。 ++ 成员`prev_pkt_ts_`是最后一个MSOP Packet的时间戳,成员`prev_point_ts_`则是最后一个点的时间戳。 ++ 成员`cb_split_frame_`是点云分帧时,要调用的回调函数。由使用者通过成员函数setSplitCallback()设置。 + +![decoder class](./img/class_decoder.png) + +##### 4.8.1.1 RSDecoderConstParam + +RSDecoderConstParam是雷达配置参数,这些参数都是特定于雷达的常量 ++ `MSOP_LEN`是MSOP Packet大小 ++ `DIFOP_LEN`是DIFOP Packet大小 ++ `MSOP_ID[]`是MSOP Packet的标志字节。各雷达的标志字节不同,用`MSOP_ID_LEN`指定其长度。 ++ `DIFOP_ID[]`是DIFOP Packet的标志字节。各雷达的标志字节不同,用`DIFOP_ID_LEN`指定其长度。 ++ `BLOCK_ID[]`是MSOP Packet中Block的标志字节。所有雷达都是两个字节。 ++ `BLOCKS_PER_PKT`、`CHANNELS_PER_BLOCK`分别指定每个MSOP Packet中有几个Block,和每个Block中有几个Channel。 ++ `DISTANCE_MIN`、`DISTANCE_MAX`指定雷达测距范围 ++ `DISTANCE_RES`指定MSOP格式中`distance`的解析度。 ++ `TEMPERATURE_RES`指定MSOP格式中,雷达温度值的解析度。 + +``` +struct RSDecoderConstParam +{ + // packet len + uint16_t MSOP_LEN; + uint16_t DIFOP_LEN; + + // packet identity + uint8_t MSOP_ID_LEN; + uint8_t DIFOP_ID_LEN; + uint8_t MSOP_ID[8]; + uint8_t DIFOP_ID[8]; + uint8_t BLOCK_ID[2]; + + // packet structure + uint16_t BLOCKS_PER_PKT; + uint16_t CHANNELS_PER_BLOCK; + + // distance & temperature + float DISTANCE_MIN; + float DISTANCE_MAX; + float DISTANCE_RES; + float TEMPERATURE_RES; +}; +``` + +##### 4.8.1.2 Decoder::processDifopPkt() + +processDifopPkt()处理DIFOP Packet。 ++ 校验Packet的长度是否匹配。 ++ 校验Packet的标志字节是否匹配。 ++ 如果校验无误,调用decodeDifopPkt()。这是一个纯虚拟函数,由各雷达的派生类提供自己的实现。 + +##### 4.8.1.3 Decoder::processMsopPkt() + +processMsopPkt()处理MSOP Packet。 ++ 检查当前配置信息是否已经就绪(`angles_ready_`)。 + + 当`angles_readys` = `false`时,驱动还没有获得垂直角信息,这时得到的点云是扁平的。所以用户一般希望等待`angles_ready` = `true` 才输出点云。 + + 通过用户配置参数`RSDecoderParam::wait_for_difop`,可以设置是否等待配置信息就绪。 ++ 校验DIFOP Packet的长度是否匹配。 ++ 校验DIFOP Packet的标志字节是否匹配。 ++ 如果以上校验通过,调用decodeMsopPkt()。这是一个纯虚拟函数,由各雷达的派生类提供自己的实现。 + +##### 4.8.1.4 Decoder::transformPoint() + +transformPoint() 对点做坐标变换。它基于第三方开源库Eigen。 + +默认情况下,transformPoint()功能不开启。要启用这个特性,编译时使用`-DENABLE_TRANSFORM`选项。 + +``` +cmake -DENABLE_TRANSFORM . +``` + +#### 4.8.2 DecoderMech + +DecoderMech处理机械式雷达的共同特性,如转速,分帧角度、光心补偿等。 ++ 成员`chan_angles_`是ChanAngles类实例,保存角度修正信息。 ++ 成员`scan_section_`是AzimuthSection类实例,保存角度校验信息。 ++ 成员`split_strategy_`是SplitStrategy类实例,保存分帧策略。 ++ 成员`rps_`是雷达转速,单位是转/秒(round/second)。 ++ 成员`blks_per_frame_`是单回波模式下,理论上的每帧Block数。 ++ 成员`split_blks_per_frame_`是按Block数分帧时,每帧的Block数。包括按理论上每圈Block数分帧,和按用户指定的Block数分帧。 ++ 成员`block_azi_diff_`是理论上相邻block之间的角度差。 ++ 成员`fov_blind_ts_diff_`是FOV盲区的时间差 ++ 成员`lidar_alpha0_`和`lidar_Rxy_`是雷达光心相对于物理中心的位置参数。MSOP格式中的点的坐标是相对于光心的,需要借助这两个值,将它转换到相对于物理中心。 + +![decoder mech](./img/class_decoder_mech.png) + +##### 4.8.2.1 RSDecoderMechConstParam + +RSDecoderMechConstParam基于RSDecoderConstParam,增加机械式雷达特有的参数。 ++ `RX`、`RY`、`RZ`是雷达光心相对于物理中心的坐标。`lidar_alpha0_`和`lidar_Rxy_`由它们计算而来。 ++ `BLOCK_DURATION`是Block的持续时间。 ++ `CHAN_TSS[]`是Block中Channel对Block的相对时间。 ++ `CHAN_AZIS[]`是Block中Channel占Block的时间比例,也是水平角比例。 + +``` +struct RSDecoderMechConstParam +{ + RSDecoderConstParam base; + + // lens center + float RX; + float RY; + float RZ; + + // firing_ts/chan_ts + double BLOCK_DURATION; + double CHAN_TSS[128]; + float CHAN_AZIS[128]; +}; +``` ++ Decoder初始化时,从每轮激光发射中的发射时间列表,计算`CHAN_TSS[]`、`CHAN_AZIS[]`。这可以简化每个Channel的时间戳和角度的计算。 +前面的"Channel的时间戳"章节,已经列出过这个发射时间列表。如下。 + +``` + 0.00, 2.56, 5.12, 7.68, 10.24, 12.80, 15.36, 17.92, + 25.68, 28.24, 30.80, 33.36, 35.92, 38.48, 41.04, 43.60, + 1.28, 3.84, 6.40, 8.96, 11.52, 14.08, 16.64, 19.20, + 26.96, 29.52, 32.08, 34.64, 37.20, 39.76, 42.32, 44.88 +``` + +##### 4.8.2.2 DecoderMech::decodeDifopCommon() + +decodeDifopCommon()解析DIFOP Packet。 ++ 解析Packet中的`rpm`,得到`rps_`. + +``` + uint16_t rpm; + +``` + ++ 计算单回波模式下,每帧Block数,也就是`blks_per_frame_`。 + +``` +每帧Block数 = (1/rps) / Block的持续时间 +``` + ++ 计算相邻block之间的角度差,也就是`block_azi_diff_`。 + +``` +Block间的角度差 = 360 / 每帧Block数 +``` + ++ 解析得到FOV的起始角度`fov_start_angle`和终止角度`fov_end_angle`,计算FOV的大小`fov_range`。 ++ 计算与FOV互补的盲区大小。按照盲区范围比例,计算盲区的时间戳差,也就是`fov_blind_ts_diff_`。 + ++ 如果用户设置从DIFOP Packet读入角度修正值(`RSDecoderParam..config_from_file` = `false`),则调用ChanAngles::loadFromDifop()得到他们。 + + 一般角度修正值不改变,所以一旦解析成功(`angles_ready_ = true`),就没必要解析第二次。 + +#### 4.8.3 DecoderRSBP + +以RSBP举例说明机械式雷达的Decoder。 ++ RSBP的常量配置由成员函数getConstParam()生成。这个配置定义为静态本地变量。 + +![decoder rsbp](./img/class_decoder_rsbp.png) + +##### 4.8.3.1 RSDecoderConstParam设置 + +| 常量参数 | 值 | 说明 | +|:-------------|:---------|:-------------:| +| MSOP_LEN | 1248 | MSOP Packet字节数 | +| DIFOP_LEN | 1248 | DIFOP Packet字节数 | +| MSOP_ID[] | {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} | MSOP Packet标志字节,长度为8 | +| MSOP_ID_LEN | 8 | MSOP_LEN[]中标志字节的长度 | +| DIFOP_ID[] | {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} | DIFOP Packet标志字节,长度为8 | +| DIFOP_ID_LEN | 8 | DIFOP_LEN[]中的字节长度 | +| BLOCK_ID[] | {0xFF, 0xEE} | block标志字节,长度为2 | +| BLOCKS_PER_PKT | 12 | 每Packet中12个Block | +| CHANNEL_PER_BLOCK | 32 | RSBP为32线雷达 | +| DISTANCE_MIN | 0.1 | 测距最小值,单位米 | +| DISTANCE_MAX | 100.0 | 测距最大值,单位米 | +| DISTANCE_RES | 0.005 | Packet中distance的解析度,单位米 | +| TEMPERATURE_RES| 0.0625 | Packet中的温度的解析度 | + +##### 4.8.3.2 RSDecoderMechConstParam设置 + +| 常量参数 | 值 | 说明 | +|:---------------|:-----------|:-------------:| +| RX | 0.01473 | 光心相对于物理中心的X坐标 | +| RY | 0.0085 | 光心相对于物理中心的Y坐标 | +| RZ | 0.09427 | 光心相对于物理中心的Z坐标 | +| BLOCK_DURATION | 55.52 | Block的持续时间,单位纳秒 | +| CHAN_TSS[] | - | 从发射时间列表得到 | +| CHAN_AZIS[] | - | 从发射时间列表得到 | + +##### 4.8.3.2 DecoderRSBP::getEchoMode() + +getEchoMode()解析回波模式。 + +##### 4.8.3.3 DecoderRSBP::decodeDifopPkt() + +decodeDifopPkt() 解析DIFOP Packet。 ++ 调用DecoderMech::decodeDifopCommon()解析DIFOP Packet,得到转速等信息。 ++ 调用getEchoMode(),解析`RSDifopPkt::return_mode`,得到回波模式 ++ 根据回波模式,设置成员成员`split_blks_per_frame_`。如前所说,如果当前以理论上的每圈Block数分帧,则需要使用这个成员。 + +##### 4.8.3.4 DecoderRSBP::decodeMsopPkt() + +decodeMsopPkt()使用不同的模板参数调用internDecodeMsopPkt()。 ++ 单回波模式下,模板参数是SingleReturnBlockDiff, ++ 双回波模式下,模板参数是DualReturnBlockDiff。 + +##### 4.8.3.5 DecoderRSBP::internDecodeMsopPkt() + ++ 调用parseTempInLe(), 得到雷达温度,保存到`temperature_`。 ++ 调用parseTimeYMD()得到Packet的时间戳,保存到本地变量`pkt_ts`。Block时间戳的初值设置为`pkt_ts`。 ++ 构造模板参数BlockDiff的实例。 ++ 遍历Packet内所有的Block。 + + 校验Block的标志字节 + + 得到Block的角度值。 + + 计算得到Block的时间戳,保存到本地变量`block_ts`。 + + 调用SplitStrategy::newBlock(),检查是否分帧。如果是,调用回调函数`cb_split_frame_`,通知使用者。 + `cb_split_frame_`应该转移点云`pont_cloud_`,并重置它。 + ++ 遍历Block内所有的Channel。 + + 计算Channel的时间戳 + + 计算Channel的水平角 + + 调用ChanAngles::vertAdjust(),得到Channel的垂直角。 + + 调用ChanAngles::horizAdjust(),对Channel的水平角进行修正。 + + 解析Channel的`distance`。 + + 调用DistanceSection::in()校验distance,调用AzimuthSection::in()校验水平角。 + +如果合法, + + 计算点云坐标(`x`, `y`, `z`)。 + + 调用transfromPoint()做坐标转换。 + + 设置点云的`intensity`、`timestamp`,`ring`。 + + 将点保存到点云`point_cloud_`的尾部。 + +如果不合法, + + 将`NAN`点保存到点云`point_cloud_`尾部。 + ++ 当前点的时间戳保存到成员`prev_point_ts`。如果下一个Block分包,那么这个时间戳就是点云的时间戳。 ++ 将当前Packet的时间戳保存到成员`prev_pkt_ts`。这样,Decoder的使用者不需要重新解析Packet来得到它。 + +#### 4.8.4 DecoderRS16 + +RS16的处理与别的机械式雷达不同。请参考前面的“RS16的Packet格式”等章节。 + +##### 4.8.4.1 DecoderRS16::internDecodeMsopPkt() + +在internDecoderPkt()的处理中, ++ 因为Block的通道值在[0,31],需要将它映射到实际的通道值。 + +#### 4.8.5 DecoderRSM1 + +RSM1是MEMS雷达。这里说明RSM1的Decoder。 ++ DecoderRSM1的常量配置由成员函数getConstParam()生成。这个配置定义为静态本地变量。 ++ 成员`split_strategy_`是SplitStrategyBy类的实例,保存分帧策略。 ++ 成员`max_seq_`是一帧内的Packet的最大编号。`split_strategy_`引用它。 + +![decoder rsm1](./img/class_decoder_rsm1.png) + +##### 4.8.5.1 RSDecoderConstParam设置 + +| 常量参数 | 值 | 说明 | +|:-------------:|:---------:|:-------------| +| MSOP_LEN | 1210 | MSOP Packet字节数 | +| DIFOP_LEN | 256 | DIFOP Packet字节数 | +| MSOP_ID[] | {0x55, 0xAA, 0x5A, 0xA5} | MSOP Packet标志字节,长度为4 | +| MSOP_ID_LEN | 4 | MSOP_LEN[]中标志字节的长度 | +| DIFOP_ID[] | {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} | DIFOP Packet标志字节,长度为8 | +| DIFOP_ID_LEN | 8 | DIFOP_LEN[]中的字节长度 | +| BLOCK_ID[] | {0xFF, 0xEE} | block标志字节,长度为2 | +| BLOCKS_PER_PKT | 25 | 每Packet中12个Block | +| CHANNEL_PER_BLOCK | 5 | RSBP为32线雷达 | +| DISTANCE_MIN | 0.2 | 测距最小值,单位米 | +| DISTANCE_MAX | 200.0 | 测距最大值,单位米 | +| DISTANCE_RES | 0.005 | Packet中distance的解析度,单位米 | +| TEMPERATURE_RES| 80 | 雷达温度的初始值 | + +##### 4.8.5.2 DecoderRSM1::decodeDifopPkt() + +decodeDifopPkt() 解析DIFOP Packet。 ++ 调用getEchoMode(),解析`RSDifopPkt::return_mode`,得到回波模式 ++ 根据回波模式,设置成员成员`max_seq_`。 + +##### 4.8.5.3 DecodeRSM1::decodeMsopPkt() + +decodeMsopPkt()解析MSOP Packet。 ++ 解析Packet中的`temperature`字段,得到雷达温度,保存到`temperature_`。 ++ 调用parseTimeUTCWithUs()得到Packet的时间戳,保存到本地变量`pkt_ts`。 ++ 遍历Packet内所有的Block。 + + 从Block相对于Packet的偏移,得到Block的时间戳。对于RSM1, Block内的所有Channel的时间戳都是这个时间戳。 + ++ 遍历Block内所有的Channel。 + + 解析Channel的distance。 + + 调用DistanceSection::in()校验`distance`。 + + 如果distance合法, + + 计算点云坐标(`x`, `y`, `z`)。 + + 调用transfromPoint()做坐标转换。 + + 设置点云的`intensity`、`timestamp`,`ring`。 + + 将点保存到点云point_cloud_的尾部。 + + 如果`distance`不合法, + + 将`NAN`点保存到点云`point_cloud_`尾部。 + ++ 当前点的时间戳保存到成员`prev_point_ts_`。如果下一个Block分包,那么这个时间戳就是点云的时间戳。 ++ 将当前Packet的时间戳保存到成员`prev_pkt_ts_`。这样,Decoder的使用者不需要重新解析Packet来得到它。 + ++ 调用SplitStrategyBySeq::newPacket(),检查是否分帧。如果是,调用回调函数`cb_split_frame_`,通知使用者。 + `cb_split_frame_`应该转移点云`pont_cloud_`,并重置它。 + +#### 4.8.6 DecoderFactory + +DecoderFactory是创建Decoder实例的工厂。 + +![decoder factory](./img/class_decoder_factory.png) + +Decoder/雷达的类型如下。 + +``` +num LidarType +{ + RS16 = 1, + RS32, + RSBP, + RS128, + RS80, + RSHELIOS, + RSROCK, + RSM1 = 10 +}; +``` + +##### 4.8.6.1 DecoderFactory::creatDecoder() + +createDecoder() 根据指定的雷达类型,创建Decdoer实例。 + +### 4.9 LidarDriverImpl - 组合Input与Decoder + +LidarDriverImpl组合Input部分和Decoder部分。 ++ 成员`input_ptr_`是Input实例。成员`decoder_ptr_`是Decoder实例。 + + LidarDriverImpl只有一个Input实例和一个Decoder实例,所以一个LidarDriverImpl实例只支持一个雷达。如果需要支持多个雷达,就需要分别创建多个LidarDriverImpl实例。 ++ 成员`msop_handle_thread_`,`difop_handle_thread_`分别是MSOP/DIFOP Packet的处理线程。 ++ 成员`driver_param_`是RSDriverParam的实例,`difop_handle_thread_`分别是MSOP/DIFOP Packet的处理线程。 + + RSDriverParam打包了RSInputParam和RSDecoderParam,它们分别是Input和Decoder部分的参数。 + +``` +typedef struct RSDriverParam +{ + LidarType lidar_type = LidarType::RS16; ///< Lidar type + InputType input_type = InputType::ONLINE_LIDAR; ///< Input type + RSInputParam input_param; + RSDecoderParam decoder_param; +} RSDriverParam; +``` + +![lidar driver impl](./img/class_lidar_driver_impl.png) + +组合Input, ++ 成员`free_pkt_queue_`、`msop_pkt_queue_`、和`difop_pkt_queue_`三个队列分别保存空闲的Packet, 待处理的MSOP Pcket, 待处理的DIFOP Packet。 + + 这3个队列是SyncQueue类的实例。SyncQueue提供多线程访问的互斥保护。 ++ 函数packetGet()和packetPut()用来向input_ptr_注册。`input_ptr_`调用前者得到空闲的Buffer,和调用后者派发填充好Packet的Buffer。 + +组合Decoder, ++ 成员`cb_get_pc_`和`cb_put_pc_`是回调函数,由驱动的使用者提供。它们的作用类似于Input类的`cb_get_`和`cb_put_`。驱动调用`cb_get_pc_`得到空闲的点云,调用`cb_put_pc_`派发填充好的点云。 + + 驱动的使用者调用成员函数regPointCloudCallback(),设置`cb_get_pc_`和`cb_put_pc_`。 ++ 成员函数splitFrame()用来向`decoder_ptr_`注册。`decoder_ptr_`在需要分帧时,调用split_Frame()。这样LidarDriverImpl可以调用`cb_put_pc_`将点云传给使用者,同时调用`cb_get_pc_`得到空闲的点云,用于下一帧的累积。 + +#### 4.9.1 LidarDriverImpl::getPointCloud() + +LidarriverImpl的成员`cb_get_pc_`是rs_driver的使用者提供的。getPointCloud(对它加了一层包装,以便较验它是否合乎要求。 +在循环中, ++ 调用`cb_get_pc_`,得到点云, +如果点云有效, ++ 将点云大小设置为`0`。 +如果点云无效, ++ 睡眠一小会。由于getPointCloud()运行在LidarDriverImpl的处理线程中,睡眠可能导致`msop_pkt_queue_`和`difop_pkt_queue_`中的Packet无法及时得到处理。 + +#### 4.9.2 LidarDriverImpl::init() + +init()初始话LidarDriverImpl实例。 + +初始化Decoder部分, ++ 调用DecoderFactory::createDecoder(),创建Decoder实例。 ++ 调用getPointCloud()得到空闲的点云,设置`decoder_ptr_`的成员`point_cloud_`。 ++ 调用Decoder::setSplitCallback(), 传递成员函数splitFrame()作为参数。这样Decoder分帧时,会调用splitFrame()通知。 ++ 调用Decoder::getPacketDuration()得到Decoder的Packet持续时间。 + +初始化Input部分, ++ 调用InputFactory::createInput(),创建Input实例。 ++ 调用Input::regRecvCallback(),传递成员函数packetGet()和packetPut()。这样Input可以得到Buffer, 和派发填充好Packet的Buffer。 ++ 调用Input::init(),初始化Input实例。 + +#### 4.9.3 LidarDriverImpl::start() + +start()开始处理MSOP/DIFOP Packet。 ++ 启动MOSP处理线程`msop_handle_thread_`, 线程函数为processMsop()。 ++ 启动DIFOP线程`difop_handle_thread_`, 线程函数为processDifop()。 ++ 调用Input::start(), 其中启动接收线程,接收MSOP/DIFOP Packet。 + +#### 4.9.4 LidarDriverImpl::packetGet() + +packetGet()分配空闲的Buffer。 ++ 优先从`free_pkt_queue_`队列得到可用的Buffer。 ++ 如果得不到,重新分配一个Buffer。 + +#### 4.9.5 LidarDriverImpl::packetPut() + +packetPut()将收到的Packet,按照Packet类型,放入相应队列。 ++ 检查Packet的标志字节。 + + 如果是MSOP Packet,派发到`msop_pkt_queue_`;如果是DIFOP Packet, 派发到`difop_pkt_queue_`;否则,回收到`free_pkt_queue_`,等待下次使用。 ++ 检查`msop_pkt_queue_`/`difop_pkt_queue`中的Packet数。如果处理线程太忙,不能及时处理, 则释放队列中所有Buffer。 + +#### 4.9.6 LidarDriverImpl::processDifop() + +processDifop()是DIFOP处理线程的函数。在循环中, ++ 调用SyncQueue::popWait()从`difop_pkt_queue_`获得Packet, ++ 调用Decoder::processDifopPkt(),处理Difop Packet。 ++ 将Packet的Buffer回收到`free_pkt_queue_`,等待下次使用。 + +#### 4.9.7 LidarDriverImpl::processMsop() + +processMsop()是MSOP Packet处理线程的函数。在循环中, ++ 调用SyncQueue::popWait()获得Packet, ++ 调用Decoder::processMsopPkt(),处理MSOP Packet。 + + 如果Packet触发了分帧,则Decoder会调用回调函数,也就是DriverImpl::splitFrame()。 ++ 将Packet的Buffer回收到`free_pkt_queue_`,等待下次使用。 + +#### 4.9.8 LidarDriverImpl::splitFrame() + +splitFrame()在Decoder通知分帧时,派发点云。 ++ 得到点云,也就是成员`decoder_ptr`的`point_cloud_`。 ++ 校验`point_cloud_`, +如果点云有效, ++ 调用setPointCloudHeader()设置点云的头部信息, ++ 调用`cb_put_pc_`,将点云传给驱动的使用者。 ++ 调用getPointCloud()得到空闲点云,重新设置成员`decoder_ptr`的`point_cloud_`。 + +#### 4.9.9 LidarDriverImpl::getTemperature() + +getTemperature()调用Decoder::getTemperature(), 得到雷达温度。 + +## 5 Packet的录制与回放 + +使用者调试自己的程序时,点云的录制与回放是有用的。同时,点云占的空间较大,而MSOP/DIFOP Packet占的较小,所以Packet的录制与回放是更好的选择。 + +与MSOP/DIFP Packet的录制与回放相关的逻辑,散布在rs_driver的各个模块中,所以这里单独分一个章节说明。 + +![packet record and replay](./img/packet_record_replay.png) + +### 5.1 录制 + +#### 5.1.1 LidarDriverImpl::regPacketCallback() + +通过regPacketCallback(),rs_driver的使用者注册一个回调函数,得到原始的MSOP/DIFOP Packet。 ++ 回调函数保存在成员`cb_put_pkt_`。 + +#### 5.1.2 LidarDriverImpl::processMsopPkt() + +在processMsopPkt()中, ++ 调用Decoder::processMsopPkt(), ++ 调用`cb_put_pkt_`,将MSOP Packet传给调用者。 + + 设置Packet的时间戳。这个时间戳调用Decoder::prevPktTs()得到。 + + 设置这个Packet是否触发分帧。这个标志是Decoder::processMsopPkt()的返回值。 + +#### 5.1.3 LidarDriverImpl::processDifopPkt() + +在processDifopPkt()中, ++ 调用Decoder::processDifopPkt(), ++ 调用`cb_put_pkt_`,将MSOP Packet传给调用者。DIFOP Packet的时间戳不重要。 + +### 5.2 回放 + +#### 5.2.1 InputRaw + +![InputRaw](./img/class_input_raw.png) + +InputRaw回放MOSP/DIFOP Packet。 ++ 使用者从某种源(比如文件)中解析MSOP/DIFOP Packet,调用InputRaw的成员函数feedPacket(),将Packet喂给它。 + + 在feedPacket()中,InputRaw简单地调用成员`cb_put_`,将Packet推送给调用者。这样,它的后端处理就与InputSock/InputPcap一样了。 + +所以除了输出点云之外,驱动还可以直接输出Packet,以后再重新导入进行播放。 + +#### 5.2.2 LidarDriverImpl + ++ InputRaw::feedBack()在InputFactory::createInput()中被打包,最后保存在LidarDriverImpl类的成员`cb_feed_pkt_`中。 ++ 使用者调用LidarDriverImpl的成员函数decodePacket(),可以将Packet喂给它。decodePacket()简单地调用成员`cb_feed_pkt_`。 + +### 5.3 时间戳处理 + +点云的时间戳来自于MSOP Packet的时间戳。MSOP Packet的时间戳可以有两种产生方式。 ++ 用户配置参数`RSDecoderParam::use_lidar_clock`决定使用哪种方式。 ++ `use_lidar_clock` = `true`时, 使用雷达产生的时间戳,这个时间戳在Packet中保存。这种情况下,一般已经使用时间同步协议对雷达做时间同步。 ++ `use_lidar_clock` = `false`时, 忽略Packet中的时间戳,在电脑主机侧由驱动重新产生一个。 + +#### 5.3.1 使用雷达时间戳 + +录制时,设置`use_lidar_clock` = `true` ++ 解析MSOP Packet的时间戳。这个时间戳是雷达产生的。 ++ 输出的点云使用这个时间戳 ++ 如果输出Packet,也是用这个时间戳 + +回放时,设置`use_lidar_clock` = `true` ++ MSOP Packet内保存的仍然是雷达产生的时间戳。 ++ 输出点云仍然使用这个时间戳。 + +#### 5.3.2 使用主机时间戳 + +录制时,设置`use_lidar_clock` = `false` ++ rs_driver在电脑主机侧重新产生时间戳。这个时间戳记录到用户的Packet文件中;如果这时有点云输出,使用rs_driver产生的时间戳 + + 在DecoderRSBP::internDecodeMsopPacket()中,rs_driver调用getTimeHost()产生时间戳,然后调用createTimeYMD(),用这个新时间戳替换Packet中老的。 ++ 这时输出的Packet的时间戳是rs_driver产生的时间戳 + +回放时,设置`use_lidar_clock` = `true` ++ 解析MSOP Packet的时间戳。这个时间戳是录制时rs_driver在电脑主机侧产生的。 ++ 输出的点云使用这个时间戳 + + + + + From d47a04d2efa343367fb33d3d46ae816b75f222d7 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 24 Mar 2022 09:55:22 +0800 Subject: [PATCH 205/379] feat: add test cases --- doc/test_cases/rs_driver_test_case.md | 106 ++++++++++++++++++++++++++ 1 file changed, 106 insertions(+) create mode 100644 doc/test_cases/rs_driver_test_case.md diff --git a/doc/test_cases/rs_driver_test_case.md b/doc/test_cases/rs_driver_test_case.md new file mode 100644 index 00000000..d199afb6 --- /dev/null +++ b/doc/test_cases/rs_driver_test_case.md @@ -0,0 +1,106 @@ +**rs_driver 测试用例** + +## 1 简介 + +这里的测试都在Linux系统下进行。 + +测试用例级别: ++ P1 基本功能。失败将导致多数重要功能无法运行。 ++ P2 重要功能。系统中主要特性,失败则无法使用该特性。 ++ P3 可选功能。系统中次要特性,失败无法使用该特性。 + +## 2 功能测试 + +## 2.1 编译运行rs_driver + +| 级别 | 功能步骤简要说明 | 期望结果 | +|:------:|:--------------------------------------------------------|:--------------:| +| P1 | 安装libpcap/PCL/eigen库时,编译rs_driver | 编译成功 | +| P3 | ENALBE_PCAP_PARSE=OFF,不安装libpcap库时,编译rs_driver | 编译成功 | +| P3 | ENABLE_TRANSFORM=OFF,不安装eigen库时,编译rs_driver | 编译成功 | +| P3 | COMPILE_TOOLS=OFF,不安装PCL库时,编译rs_driver | 编译成功 | +| P1 | 用rs_driver_viewer连接在线雷达 | rs_driver_viewer显示点云 | +| P1 | 用demo_online连接在线雷达,点为XYZI/XYZIRT,打印点。 | 点属性正常 | + +## 2.2 rs_driver输出点云的正确性 + +这里需要测试点云正确性的雷达包括:RS16/RS32/RSBP/RSHELIOS/RS80/RS128/RSM1。 + +| 级别 | 功能步骤简要说明 | 期望结果 | +|:------:|:--------------------------------------------------------|:------------------------------:| +| P2 | 用rs_driver_viewer依次连接每种雷达,雷达工作在单回波模式下 | rs_driver_viewer正常显示点云 | +| P2 | 用rs_driver_viewer依次连接每种雷达,雷达工作在双回波模式下 | rs_driver_viewer正常显示点云 | + +## 2.3 rs_driver连接在线雷达 + +| 级别 | 功能步骤简要说明 | 期望结果 | +|:------:|:--------------------------------------------------------|:------------------------------:| +| P1 | 用demo_online连接在线雷达,雷达工作在广播模式下, | demo_online正常打印点云 | +| P2 | 用demo_online连接在线雷达,雷达工作在组播模式下 | demo_online正常打印点云 | +| P2 | 用demo_online连接在线雷达,雷达工作在单播模式下 | demo_online正常打印点云 | +| P2 | 用demo_online连接在线雷达,雷达包带USER_LAYER | demo_online正常打印点云 | +| P2 | 用demo_online连接在线雷达,雷达包带TAIL_LAYER | demo_online正常打印点云 | +| P2 | 启动demo_online两个实例,连接两台雷达,雷达指定不同目标端口、相同目标IP | demo_online正常打印点云 | +| P2 | 启动demo_online两个实例,连接两台雷达,雷达指定相同目标端口、不同目标IP | demo_online正常打印点云 | +| P2 | 用demo_online连接在线雷达,雷达不做时间同步,user_lidar_clock=true(或false),打印点的时间戳 | 时间戳是雷达时间(或主机时间) | +| P2 | 用demo_online连接在线雷达,dense_points = true(或false),打印点云大小 | 点云大小是(或不是)雷达线数的整数倍 | +| P3 | 用rs_driver_viewer连接在线雷达,设置错误的DIFOP端口,wait_for_difop=false | 显示扁平点云 | +| P3 | 用rs_driver_viewer接在线雷达,设置错误的DIFOP端口,wait_for_difop=true | 不显示点云 | +| P2 | 用rs_driver_viewer连接在线雷达,config_from_file=true,angle_path=angle.csv | 正常显示(非扁平的)点云 | +| P2 | 用rs_driver_viewer连接在线雷达,split_frame_mode=by_angle,split_angle=0/90/180/270 | 正常显示点云 | +| P3 | 用rs_driver_viewer连接在线雷达,split_frame_mode=by_fixed_pkts,num_pkts_split=N | 显示点云 | +| P3 | 用rs_driver_viewer连接在线雷达,split_frame_mode=by_custome_pkts | 显示点云 | +| P3 | 用rs_driver_viewer连接在线雷达,start_angle=90, end_angle=180 | 显示半圈的点云 | +| P3 | 用rs_driver_viewer连接在线雷达,min_distance=1, end_angle=10 | 显示被裁剪的点云 | + +## 2.4 rs_driver解析PCAP文件 +| 级别 | 功能步骤简要说明 | 期望结果 | +|:------:|:--------------------------------------------------------|:------------------------------:| +| P3 | 用demo_pcap解析PCAP文件,雷达工作在广播模式下 | 正常打印点云 | +| P2 | 用rs_driver_viewer解析PCAP文件 | rs_driver_viewer正常显示点云 | +| P3 | 用rs_driver_viewer解析PCAP文件, pcap_repeat=true(或false) | 循环播放PCAP中的点云(或播放一遍退出) | +| P3 | 用rs_driver_viewer解析PCAP文件, pcap_rate=0.5/1/2 | 点云播放速度变慢(或正常播放、加快) | +| P3 | 用rs_driver_viewer解析PCAP文件, PCAP的包带VLAN层 | demo_pcap正常打印点云 | + +## 2.5 rs_driver错误输出 + +| 级别 | 功能步骤简要说明 | 期望结果 | +|:------:|:--------------------------------------------------------|:------------------------------:| +| P1 | 用demo_online连接在线雷达,网络设置错误。 | 驱动打印错误提示无法收到MSOP/DIFOP包 | +| P1 | 用demo_online连接在线雷达,雷达类型设置错误。 | 驱动打印错误提示包的大小或格式错误 | +| P1 | 用demo_pcap连接在线雷达,指定不存在的PCAP文件。 | 驱动打印错误提示文件路径无误 | + +## 2.6 其他功能 + +| 级别 | 功能步骤简要说明 | 期望结果 | +|:------:|:--------------------------------------------------------|:------------------------------:| +| P1 | 用demo_online连接在线雷达,ENABLE_TRASFORM=TRUE,设置转换参数。 | 点云坐标变换正确 | + +## 3 性能测试 + +### 3.1 针对工控机 + +在当下主流性能的工控机上,做如下测试。 + +| 级别 | 功能步骤简要说明 | 期望结果 | +|:------:|:--------------------------------------------------------|:------------------------------:| +| P1 | 用demo_online连接在线的RSHELIOS/RS128/RSM1雷达,测试demo_online的CPU占用率 | 低于期望值(值待定) | +| P1 | 用demo_online连接在线的RSHELIOS/RS128/RSM1雷达,测试输出的点云大小 | 丢包率低于期望值(值待定) | +| P1 | 启动demo_online两个实例,连接两个在线的RSHELIOS/RS128/RSM1雷达,测试demo_online的CPU占用率 | 低于期望值(值待定) | +| P1 | 用demo_online两个实例,连接两个在线的RSHELIOS/RS128/RSM1雷达,测试输出的点云大小 | 丢包率低于期望值(值待定) | + +### 3.2 针对ARM板 + +在当下主流性能的ARM板上,做如下测试。 + +| 级别 | 功能步骤简要说明 | 期望结果 | +|:------:|:--------------------------------------------------------|:------------------------------:| +| P1 | 用demo_online连接在线的RSM1雷达,测试demo_online的CPU占用率 | 低于期望值(值待定) | +| P1 | 用demo_online连接在线的RSM1雷达,测试输出的点云大小 | 丢包率低于期望值(值待定) | +| P1 | 启动demo_online两个实例,连接两个在线的RSM1雷达,测试demo_online的CPU占用率 | 低于期望值(值待定) | +| P1 | 用demo_online两个实例,连接两个在线的RSM1雷达,测试输出的点云大小 | 丢包率低于期望值(值待定) | + + + + + From 687e09839c06de4ef8146b9e829dcef1aaa4d90c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 24 Mar 2022 10:44:22 +0800 Subject: [PATCH 206/379] fix: add msop timeout --- src/rs_driver/driver/input/sock_input.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index a29b48d9..e6c22ec8 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -233,10 +233,11 @@ inline void SockInput::recvPacket() struct timeval tv; tv.tv_sec = 0; - tv.tv_usec = 500000; + tv.tv_usec = 1000000; int retval = select(max_fd + 1, &rfds, NULL, NULL, &tv); if (retval == 0) { + excb_(Error(ERRCODE_MSOPTIMEOUT)); continue; } else if (retval == -1) From cd61eb1bb4684b4852997b68424f323007683cf2 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 24 Mar 2022 15:55:28 +0800 Subject: [PATCH 207/379] fix: fix msop timeout --- src/rs_driver/driver/input/sock_input.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index e6c22ec8..cd7bdcf0 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -232,8 +232,8 @@ inline void SockInput::recvPacket() int max_fd = std::max(fds_[0], fds_[1]); struct timeval tv; - tv.tv_sec = 0; - tv.tv_usec = 1000000; + tv.tv_sec = 1; + tv.tv_usec = 0; int retval = select(max_fd + 1, &rfds, NULL, NULL, &tv); if (retval == 0) { From 828f9c2836265e253d6037e8bda7be1f063f4575 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 24 Mar 2022 16:56:29 +0800 Subject: [PATCH 208/379] format: move pkt len --- src/rs_driver/common/common_header.h | 4 ---- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 4 ++++ src/rs_driver/driver/decoder/decoder_base.hpp | 6 ++++++ 3 files changed, 10 insertions(+), 4 deletions(-) diff --git a/src/rs_driver/common/common_header.h b/src/rs_driver/common/common_header.h index 5d97abe0..f1f00cbe 100644 --- a/src/rs_driver/common/common_header.h +++ b/src/rs_driver/common/common_header.h @@ -89,10 +89,6 @@ inline void setConsoleColor(WORD c) /*Camera*/ typedef std::pair CameraTrigger; -/*Packet Length*/ -const size_t MECH_PKT_LEN = 1248; -const size_t MEMS_MSOP_LEN = 1210; -const size_t MEMS_DIFOP_LEN = 256; /*Output style*/ #ifndef RS_INFOL #if defined(_WIN32) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index feac8146..61487ca0 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -37,9 +37,13 @@ namespace robosense { namespace lidar { +const size_t MEMS_MSOP_LEN = 1210; +const size_t MEMS_DIFOP_LEN = 256; + const uint32_t SINGLE_PKT_NUM = 630; const uint32_t DUAL_PKT_NUM = 1260; const int ANGLE_OFFSET = 32768; + #pragma pack(push, 1) typedef struct diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 98eb49c7..30f7c55c 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -56,14 +56,20 @@ DEFINE_MEMBER_CHECKER(z) DEFINE_MEMBER_CHECKER(intensity) DEFINE_MEMBER_CHECKER(ring) DEFINE_MEMBER_CHECKER(timestamp) + #define RS_SWAP_SHORT(x) ((((x)&0xFF) << 8) | (((x)&0xFF00) >> 8)) #define RS_SWAP_LONG(x) ((((x)&0xFF) << 24) | (((x)&0xFF00) << 8) | (((x)&0xFF0000) >> 8) | (((x)&0xFF000000) >> 24)) #define RS_TO_RADS(x) ((x) * (M_PI) / 180) + constexpr float RS_ANGLE_RESOLUTION = 0.01; constexpr float MICRO = 1000000.0; constexpr float NANO = 1000000000.0; constexpr int RS_ONE_ROUND = 36000; constexpr uint16_t PROTOCOL_VER_0 = 0x00; + +/*Packet Length*/ +const size_t MECH_PKT_LEN = 1248; + /* Echo mode definition */ enum RSEchoMode { From b6107d41dfdfdf00d700c541f10a939ec01922d7 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 25 Mar 2022 09:33:29 +0800 Subject: [PATCH 209/379] feat: support M2 --- demo/demo_online.cpp | 2 +- demo/demo_pcap.cpp | 4 +- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 18 +- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 280 ++++++++++++++++++ src/rs_driver/driver/decoder/decoder_base.hpp | 1 + .../driver/decoder/decoder_factory.hpp | 4 + src/rs_driver/driver/driver_param.h | 10 +- src/rs_driver/driver/input/input_factory.hpp | 1 + 8 files changed, 309 insertions(+), 11 deletions(-) create mode 100644 src/rs_driver/driver/decoder/decoder_RSM2.hpp diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 5562204b..aec1e34b 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -83,7 +83,7 @@ int main(int argc, char* argv[]) RSDriverParam param; ///< Create a parameter object param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct + param.lidar_type = LidarType::RSM2; ///< Set the lidar type. Make sure this type is correct param.wait_for_difop = false; ///< true: start sending point cloud until receive difop packet param.print(); diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 4ad22359..d1121007 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -82,11 +82,11 @@ int main(int argc, char* argv[]) RSDriverParam param; ///< Create a parameter object param.input_param.read_pcap = true; ///< Set read_pcap to true - param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file directory + param.input_param.pcap_path = "/home/sti/dev/share/pcap/M2/M2.pcap"; ///< Set the pcap file directory param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 param.wait_for_difop = false; - param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct + param.lidar_type = LidarType::RSM2; ///< Set the lidar type. Make sure this type is correct param.print(); diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 61487ca0..51bf4198 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -151,8 +151,8 @@ class DecoderRSM1 : public DecoderBase int& height); private: - uint32_t last_pkt_cnt_; uint32_t max_pkt_num_; + uint32_t last_pkt_cnt_; double last_pkt_time_; }; @@ -160,8 +160,8 @@ template inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param) : DecoderBase(param, lidar_const_param) - , last_pkt_cnt_(1) , max_pkt_num_(SINGLE_PKT_NUM) + , last_pkt_cnt_(1) , last_pkt_time_(0) { this->msop_pkt_len_ = MEMS_MSOP_LEN; @@ -222,7 +222,7 @@ inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* p int& height, int& azimuth) { height = this->lidar_const_param_.LASER_NUM; - RSM1MsopPkt* mpkt_ptr = (RSM1MsopPkt*)pkt; + const RSM1MsopPkt* mpkt_ptr = (RSM1MsopPkt*)pkt; if (mpkt_ptr->header.id != this->lidar_const_param_.MSOP_ID) { return RSDecoderResult::WRONG_PKT_HEADER; @@ -250,17 +250,21 @@ inline RSDecoderResult DecoderRSM1::decodeMsopPkt(const uint8_t* p double point_time = pkt_timestamp + blk.time_offset * 1e-6; for (size_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) { + const RSM1Channel& channel = blk.channel[channel_idx]; + typename T_PointCloud::PointT point; bool pointValid = false; - float distance = RS_SWAP_SHORT(blk.channel[channel_idx].distance) * this->lidar_const_param_.DIS_RESOLUTION; + float distance = RS_SWAP_SHORT(channel.distance) * this->lidar_const_param_.DIS_RESOLUTION; if (distance <= this->param_.max_distance && distance >= this->param_.min_distance) { - int pitch = RS_SWAP_SHORT(blk.channel[channel_idx].pitch) - ANGLE_OFFSET; - int yaw = RS_SWAP_SHORT(blk.channel[channel_idx].yaw) - ANGLE_OFFSET; - uint8_t intensity = blk.channel[channel_idx].intensity; + int pitch = RS_SWAP_SHORT(channel.pitch) - ANGLE_OFFSET; + int yaw = RS_SWAP_SHORT(channel.yaw) - ANGLE_OFFSET; float x = distance * this->checkCosTable(pitch) * this->checkCosTable(yaw); float y = distance * this->checkCosTable(pitch) * this->checkSinTable(yaw); float z = distance * this->checkSinTable(pitch); + + uint8_t intensity = channel.intensity; + this->transformPoint(x, y, z); setX(point, x); setY(point, y); diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp new file mode 100644 index 00000000..8bc9699a --- /dev/null +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -0,0 +1,280 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include + +namespace robosense +{ +namespace lidar +{ +const size_t M2_MSOP_LEN = 1336; +const size_t M2_DIFOP_LEN = 256; + +const uint32_t M2_SINGLE_PKT_NUM = 1260; +const uint32_t M2_DUAL_PKT_NUM = 2520; + +#pragma pack(push, 1) + +typedef struct +{ + uint16_t distance; + int16_t x; + int16_t y; + int16_t z; + uint8_t intensity; + uint8_t point_attribute; +} RSM2Channel; + +typedef struct +{ + uint8_t time_offset; + uint8_t return_seq; + RSM2Channel channel[5]; +} RSM2Block; + +typedef struct +{ + uint32_t id; + uint16_t pkt_cnt; + uint16_t protocol_version; + uint8_t return_mode; + uint8_t time_mode; + RSTimestampUTC timestamp; + uint8_t reserved[10]; + uint8_t lidar_type; + int8_t temperature; +} RSM2MsopHeader; + +typedef struct +{ + RSM2MsopHeader header; + RSM2Block blocks[25]; + uint8_t reserved[4]; +} RSM2MsopPkt; + +#pragma pack(pop) + +template +class DecoderRSM2 : public DecoderBase +{ +public: + DecoderRSM2(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); + RSDecoderResult decodeDifopPkt(const uint8_t* pkt); + RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); + double getLidarTime(const uint8_t* pkt); + RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size, typename T_PointCloud::VectorT& pointcloud_vec, + int& height); + +private: + uint32_t max_pkt_num_; + uint32_t last_pkt_cnt_; + double last_pkt_time_; +}; + +template +inline DecoderRSM2::DecoderRSM2(const RSDecoderParam& param, + const LidarConstantParameter& lidar_const_param) + : DecoderBase(param, lidar_const_param) + , max_pkt_num_(M2_SINGLE_PKT_NUM) + , last_pkt_cnt_(1) + , last_pkt_time_(0) +{ + this->msop_pkt_len_ = M2_MSOP_LEN; + this->difop_pkt_len_ = M2_DIFOP_LEN; + + if (this->param_.max_distance > 200.0f) + { + this->param_.max_distance = 200.0f; + } + if (this->param_.min_distance < 0.2f || this->param_.min_distance > this->param_.max_distance) + { + this->param_.min_distance = 0.2f; + } + this->time_duration_between_blocks_ = 5 * 1e-6; +} + +template +inline double DecoderRSM2::getLidarTime(const uint8_t* pkt) +{ + return this->template calculateTimeUTC(pkt, LidarType::RSM2); +} + +template +inline RSDecoderResult DecoderRSM2::processMsopPkt(const uint8_t* pkt, size_t size, + typename T_PointCloud::VectorT& pointcloud_vec, + int& height) +{ + if (size != this->msop_pkt_len_) + { + return WRONG_PKT_LENGTH; + } + + int azimuth = 0; + RSDecoderResult ret = decodeMsopPkt(pkt, pointcloud_vec, height, azimuth); + this->pkt_count_++; + switch (this->param_.split_frame_mode) + { + case SplitFrameMode::SPLIT_BY_ANGLE: + case SplitFrameMode::SPLIT_BY_FIXED_PKTS: + return ret; + case SplitFrameMode::SPLIT_BY_CUSTOM_PKTS: + if (this->pkt_count_ >= this->param_.num_pkts_split) + { + this->pkt_count_ = 0; + this->trigger_index_ = 0; + this->prev_angle_diff_ = RS_ONE_ROUND; + return FRAME_SPLIT; + } + break; + default: + break; + } + return DECODE_OK; +} + +inline int16_t RS_SWAP_INT16(int16_t value) +{ + uint8_t* v = (uint8_t*)&value; + + uint8_t temp; + temp = v[0]; + v[0] = v[1]; + v[1] = temp; + + return value; +} + +template +inline RSDecoderResult DecoderRSM2::decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, + int& height, int& azimuth) +{ + height = this->lidar_const_param_.LASER_NUM; + const RSM2MsopPkt* mpkt_ptr = (RSM2MsopPkt*)pkt; + if (mpkt_ptr->header.id != this->lidar_const_param_.MSOP_ID) + { + return RSDecoderResult::WRONG_PKT_HEADER; + } + this->current_temperature_ = static_cast(mpkt_ptr->header.temperature - 80); + this->protocol_ver_ = RS_SWAP_SHORT(mpkt_ptr->header.protocol_version); + double pkt_timestamp = 0; + switch (mpkt_ptr->blocks[0].return_seq) + { + case 0: + pkt_timestamp = this->get_point_time_func_(pkt); + break; + case 1: + pkt_timestamp = this->get_point_time_func_(pkt); + last_pkt_time_ = pkt_timestamp; + break; + case 2: + pkt_timestamp = last_pkt_time_; + break; + } + + for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) + { + const RSM2Block& blk = mpkt_ptr->blocks[blk_idx]; + double point_time = pkt_timestamp + blk.time_offset * 1e-6; + for (size_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) + { + const RSM2Channel& channel = blk.channel[channel_idx]; + + typename T_PointCloud::PointT point; + bool pointValid = false; + float distance = RS_SWAP_SHORT(channel.distance) * this->lidar_const_param_.DIS_RESOLUTION; + if (distance <= this->param_.max_distance && distance >= this->param_.min_distance) + { + float x = RS_SWAP_INT16(channel.x) / 32768.0 * distance; + float y = RS_SWAP_INT16(channel.y) / 32768.0 * distance; + float z = RS_SWAP_INT16(channel.z) / 32768.0 * distance; + + uint8_t intensity = channel.intensity; + + this->transformPoint(x, y, z); + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, intensity); + pointValid = true; + } + else if (!this->param_.is_dense) + { + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + pointValid = true; + } + + if (pointValid) + { + setTimestamp(point, point_time); + setRing(point, channel_idx + 1); + vec.emplace_back(std::move(point)); + } + } + } + unsigned int pkt_cnt = RS_SWAP_SHORT(mpkt_ptr->header.pkt_cnt); + + // TODO whatif packet loss or seq unorder + if (pkt_cnt == max_pkt_num_ || pkt_cnt < last_pkt_cnt_) + { + last_pkt_cnt_ = 1; + return RSDecoderResult::FRAME_SPLIT; + } + last_pkt_cnt_ = pkt_cnt; + return RSDecoderResult::DECODE_OK; +} + +template +inline RSDecoderResult DecoderRSM2::decodeDifopPkt(const uint8_t* pkt) +{ + RSM1DifopPkt* dpkt_ptr = (RSM1DifopPkt*)pkt; + if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) + { + return RSDecoderResult::WRONG_PKT_HEADER; + } + if (!this->difop_flag_) + { + this->echo_mode_ = this->getEchoMode(LidarType::RSM2, dpkt_ptr->return_mode); + if (this->echo_mode_ == RSEchoMode::ECHO_DUAL) + { + max_pkt_num_ = M2_DUAL_PKT_NUM; + } + this->difop_flag_ = true; + } + return RSDecoderResult::DECODE_OK; +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 30f7c55c..9f5b1503 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -896,6 +896,7 @@ inline RSEchoMode DecoderBase::getEchoMode(const LidarType& type, return RSEchoMode::ECHO_SINGLE; } case LidarType::RSM1: + case LidarType::RSM2: switch (return_mode) { case 0x00: diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 5e3814a9..cc81fab4 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -37,6 +37,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include #include #include @@ -89,6 +90,9 @@ DecoderFactory::createDecoder(const RSDriverParam& param) case LidarType::RSM1: ret_ptr = std::make_shared>(param.decoder_param, getRSM1ConstantParam()); break; + case LidarType::RSM2: + ret_ptr = std::make_shared>(param.decoder_param, getRSM1ConstantParam()); + break; case LidarType::RSHELIOS: ret_ptr = std::make_shared>(param.decoder_param, getRSHELIOSConstantParam()); break; diff --git a/src/rs_driver/driver/driver_param.h b/src/rs_driver/driver/driver_param.h index 6db65de0..8139f66c 100644 --- a/src/rs_driver/driver/driver_param.h +++ b/src/rs_driver/driver/driver_param.h @@ -47,7 +47,8 @@ enum LidarType ///< LiDAR type RS80, RSHELIOS, RSROCK, - RSM1 = 10 + RSM1 = 10, + RSM2 }; enum SplitFrameMode @@ -205,6 +206,9 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter case LidarType::RSM1: str = "RSM1"; break; + case LidarType::RSM2: + str = "RSM2"; + break; case LidarType::RSHELIOS: str = "RSHELIOS"; break; @@ -243,6 +247,10 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter { return lidar::LidarType::RSM1; } + else if (type == "RSM2") + { + return lidar::LidarType::RSM2; + } else if (type == "RSHELIOS") { return lidar::LidarType::RSHELIOS; diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 1441e673..94bc7a7f 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -71,6 +71,7 @@ inline long long msecToDelay(LidarType type, double replay_rate) duration = RS80_PCAP_SLEEP_DURATION; break; case LidarType::RSM1: + case LidarType::RSM2: duration = RSM1_PCAP_SLEEP_DURATION; break; case LidarType::RSHELIOS: From 70bfcc3e53bdc242cfaf08830087c68b6a2d1534 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 29 Mar 2022 09:37:32 +0800 Subject: [PATCH 210/379] feat: update docs --- doc/howto/how_to_decode_online_lidar.md | 22 ++++++++++++++------ doc/img/11_rs_driver_point_cloud.png | Bin 0 -> 10953 bytes doc/img/11_rs_driver_point_cloud_vector.png | Bin 0 -> 8287 bytes 3 files changed, 16 insertions(+), 6 deletions(-) create mode 100644 doc/img/11_rs_driver_point_cloud.png create mode 100644 doc/img/11_rs_driver_point_cloud_vector.png diff --git a/doc/howto/how_to_decode_online_lidar.md b/doc/howto/how_to_decode_online_lidar.md index df6cd0c2..6b690eca 100644 --- a/doc/howto/how_to_decode_online_lidar.md +++ b/doc/howto/how_to_decode_online_lidar.md @@ -101,7 +101,17 @@ Here user may add new member variables, remove member variables, or change the o Here user may add new members, and change the order of these members, but should not change or remove them. -### 3.3 Define the driver object +### 3.3 Point in Point Cloud + +Here is an example of 5_lasers Lidar. + +The Lidar scans block by block. It starts from b0c0(block 0 channel/laser 0), b0c1, b0c2, b0c3, b0c4, and then go to b1c0, b1c1, b1c2, b1c3, b1c4, and so on. +![](../img/11_rs_driver_point_cloud.png) + +At the same time, it saves the points in a point vector, point by point, as below. +![](../img/11_rs_driver_point_cloud_vector.png) + +### 3.4 Define the driver object Define a driver object. @@ -113,7 +123,7 @@ int main() } ``` -### 3.4 Configure the driver parameter +### 3.5 Configure the driver parameter Define a RSDriverParam variable and configure it. + `InputType::ONLINE_LIDAR` means that the driver get packets from a online Lidar. @@ -133,7 +143,7 @@ int main() } ``` -### 3.5 Define and register Point Cloud callbacks +### 3.6 Define and register Point Cloud callbacks As said above, user is supposed to provide free point cloud to the driver. @@ -168,7 +178,7 @@ int main() } ``` -### 3.6 Define and register exception callbacks +### 3.7 Define and register exception callbacks When an error happens, the driver will inform user. User is supposed to get it via a callback function. @@ -192,7 +202,7 @@ driver.regExceptionCallback(exceptionCallback); ///XSa1mL7Tkloy9aj}+~=Qs-_^M| zXZ`1*r`D?Js_I%@UGLt{TM=q1vRLS3=x}gwSn_gG8nAK}c6Fj6!+t@hm%*?C%~?** z4Gs>w_umDd#D+}{2loz6UP@fcJL5Fd=8M+cT7OV2$I@MxeONWJIpGg!B4VxlZwO}< zTV->$QEYV$^>ZB_8|pq~6~NE4v=ZuSH3;w+!yVyaykRGPjNGXK<4-2|ZO4vT^A z?Wg}uwbm~e>MxKy)tcPy?JLgM`k#nGjlXNllQi{|4$C)s8WqKMH^LcsS|`f2QvbYF zlN7lhfopaw)M&RM1EVyQ5^W9yh9R{!{IVqI5Z zDA<;r$zPa~ZVzDM=RrB*s4P9Tgdsv?i%nEpRgR}WaCay$s(+Q;=d>?U80*n;bsGm#YXH`%$F{@%Svoguywx^;XBT&7XI>swt+`GUi>-HDY=B zp|=%b$qVufx6#THh7GfSMoIe>iO7@Z-YAJQRM9xM7c18V%h-|h&uD7E6x;zax0^4{ ze3dR(fFzqG`k*c65ihnrIC7ZrgbBJRZe1+l#7w<)#gRLXq-#KI3TeivF?3;K;}0A; za#-;R_^WXicp_H!;FD_o5CV4e4Q(3WuMIl(?O5^s8qeT1s2$w8g}NKb?rZ7!Y|i@I z*K(6pOyZ{56|h^D<63FqSQWf_J;_1h_bOEwJ;dZUdak!dk7_AN=qvevn=OXt!SJX2 z2scV~DKz`#`9nP6SK4qk$J9vOE3DR+40eGa-SGv`(r9MV_KOR=p*@8!Tq8!KM$FM7 ziFz=w0wK9+NG37Eu}0`4Tcb!zrs7%iPlJLx?s*6A zSR{`2?)XegpclJkmm-F@lO*ME2y}CE#Ovb1PK~@oKcXy6tV0GN#leUjQZYN^SsQJA9v3%ea;ri1) zLdUEH=fUNQyc%5b!PBv-Uh0J~hM0e544S0RWBOBS>f1*?F6;a0$k;1N?PS4Jan%^= zm`vM<;MJRhj@a8PFq>aIejX%<^Xn7mh_UW>UyY#14L|U?Z8T=u4cwI_&b!iWlBv-K zoGh!&%l4GFAWpZlmr?d_uaL)>ybxZej&47@+nHs+A3rA&1&Tl;rnh?cGm%fYirIP~ z$WOo2X-PEi;>Sme^_sCS>(|0shKEwYK{1&KIlPI{qk8=UJVrm_;<6^QB{TC-;lZV3 zCAQXmzcgp~g;GgE0kalE88moi%(1d+OOugfoAmFw1atcukDak5{I%qyGY=QdSd-#O zw~?KnlIW&vv}no!mp1jwB{n>H3#CJHk>UlI>z~+9uy!G+L{)2J;El6x^BRO-YRn%y zofzG$zSD3E@bwaAkx>V>Ch&JIhK-Xb`p5du3er&}zb%>@wb~%8%{gG^SQSZ{y=R6( zmG<70lIiPR93lrY1B%RS-}M*ow+w|gIbQmRbLr@+D)6K`JVPp+7X9*(1MEKlB{3E1 z$&$w++v}+|T_BV7+fD9L=U>~hXYIw*`a+?NAqP9`rW(Kh=KIh$_NZJ<(IT5OT|8G+ ze#-f=Pv1I{b_(`+%##R{2nR5d)~|naZgs9pwXrKHa`MDiT@?-QB?-;<2s_OW!@cP4 z>@W+GrW{)wQt9?mkMRb|pliPm!4k@xJ}4 zP(~*xl6{I&dhdG`{Fj(ChoZt^GXiHm_XGWpMEjErLWIhBct6Qi!akt_1BA3)&E`h9xmfLz<49@At1hdBksEZc zCCIIb(o(GJ?u)qLC`8bdo6ukY3Xo ziMxrIF#!>UgOeODG8CwO6rDI3a7$0C&BwN=yV?flcoH+A*1Q$YRx>l#FosYY;qeb`O7Ve8BoTeicOzJ7dn5cBM# zbs{U4N;*=}oRn#FmTaJCs<@90yiezsO;i4I0`%t=o>_W)HoMSNs6pB9SP$@~4hIiV#( zVARMiBZFw#P|xLkU!n<#$7KcW2P1oI;`55-@t_8Z{D!4yg@XKd{7J`5*#jxT0^%h! zw3u_jxPNcGy8~rZ8LyjGsk9Urx{TTh)ro}&A}_M3lF@J^3f}5v{%->?B=m?{57j%5 z4_(rHTEBj<>)%~-`&fjiT4OS}=z0|EUwySa_T2Zd;>HJSqX5}*xDw4x=4c$p7zXEW zURvDXhPq1&rW6Lj{_t33*dBHO@rKIL*f%`oK-!A1aW(uf?c^rO)ilMp3N|`<-FhvN zpaY%sR#-Fwp-AUfp-UC~IYv6R7OQMA(XBY?Nl4!|OioYX;OI1!y)^nt-bP!O4#drI zoDzyDw?DLOa8xOZOZsp>8;Q5vQ<`n{Qt2fRq1Z_pk%25odvR|To{BHX9|TIUbeBp( z1is6L3@VW3qm}*qHhH5a3UqV&aY5wt!#Of!yr;CMTKbMqFXESD&lCG&$ImU8+-gVZ zT}-QJ$Zq@@%L|awVGU?=R2pvPI^Hka|NNJ!T(C(HEt8%BwG5l(bg9J&`l5nq2kq+a zvxxS0By=+La&2%-;@9^|%qqQfwFOe3S|Hc111FvqO7G9IF?5@(5%;3AU=2l$h^KKV zq-aa_iQ#wFrJtlKhBl#}2FM`ktKM;ZJ7kdiEvLR9(TAv%v;>yQmtqa?FkFcysiBZ4 zDIk=*Pf@XxNHMEf=6W~${o=V8m_}$-V77 zk4!f9S9!Lz&yZ`npn|MMaYT7R^;celENHQVfG*{Dork5cWXPl)I<8Sq~G3FI!+*-tKDoOW^+mpELP!Nt$(u)i7mx1LU#TN0?uZ^xs~OUv7_0Opf<%(H z0l4IsPgJ%hZRyJX@;gDDl}!A7qqV(o)eE|9R`(!MP!6*4KetqoA zUKBf+goe@p9+)OD8q@nP+w-N%ytlhZt>jPZOqn%_P-WeJd2b1RSF)g%n@~F`-IqH>&ehA1kiz{nCDDHU!Io|1 z_A{u(pcA&o7(HHhl9(n4!W3DefELhBENiE)+tR^2NGJnn#a_7BBToOOGEU1?1ZQS| zPL_#R!S(ZCM@i!n{KbXU`}u{pX?1!Pd0Kpt%(kyT;6y}2(H$tts%(WpLfD&co*Vmp zH#K%1@6UG~{73~mn_7X%fk&$05)T=e8bjAKiSmbO$;!k;5*^UCSCl67L!Zc7HYdQ#*`# z2!HhRSL2Y8`M`xt3Ao@rHQgiX=jm<)kh+^Rhf7DH1lYm6cz5EkYS(azW(7Wy>k#hZMe8UP5xkG zZB(on!yL#PKwpA3#Y6eN+eE-c?tK`FrUU67NWrnyv}q@<%p}0%Giq17hjd$q|62qk z+jhJHjhGdiK9gEkqbhf*4j0qm-j;0Iyp1sYSvh&jpU7Me#_1SN&DP(TknRF%fjn(1ewbm_G&$(PgpAYOx@x$ z$wqp+d<;ZOanOBuOO%8pP<0#x29F%TAAt+5_EV5(2-1!P{hI>NH%=JH$j5Eihf$5V zZ}!Zjsc^L93Nnme2SM?1XzzaKn42T~pVjE}8vP-HM=VBnNKs-B(b_AlhrV-ZO3ZOs zgmUzeNQBDJt-@7NrPL?kbAWH=gXWW_^QqVphgB$ul4f=J@oZNvB5qdCdZCyZ^`Lpqug8Podvt~*Lr+GNqGVcvdejcNL{r60OC_G)l*F( z%gaH6bj`@Z~vg@I;|Lf%kSouE`1Z+p1UI#TJ0N#JFijWXB>5K|M_g#t8b3waO-=O zJ^X#x+P#thS)AXBtNK2kgtu+qwEm^kgmDG_&$rlhQQBS>kr~ESM3fspi+q}!c-dqP zpqp`Ku}i?T@EazlExb9!K!9tlBa!0KL>%gyAfN!Ymwr2Ql{G;_LT6fn2W=QV5babT zk)Y;R8gAoWe18bK(uUahiSha0QhsA|nQ4K#X(QOo(R^Pg&nVb@*o%KzK9u>}r}jrB zV0Jwy;rE9$oO-7&)r$VQ3#sxkQMhbQVx;w9xBgOxzf7ettviWZzlR?ls^`_&Uq3?} ze>sY7l$|;z&{$NSU-K(?M#0*T8O=;waz0HF7b9(@DY3P(Df`@SZKy5HqU{#{Yvf7P z9;ci0&RT^(P>uwH42F6d!12sPJmwY6<~6_2GJ>`Z97#*^8rm{0FI|U6*owJZcVX}M z_(9TZpwjKV+tcXZg!`zJCpka6*U4ikvD%2(%8^gO=>b(rCf(icRDnl2uD35SU?X?P zVE;rDuPj;?D-qO`{Z4yyi({bv;4_qhiqhphn=kB<%C1&4&&F%!pY40Hbu#QySD>Q! zKkc__Xl(!VjSt9h)%w6oPwdy0zs+>Nes09ZDA$o7Ktqr33)y2Uc2fRj1tN#?u~Vw;Ho2WwiEMSW>o`ZAe~A59prVziu*kgIr(j(y52^lN?GAM{&1QHQt=Tp zY(L4Qh5CzLa5w>Vi9?VSJZhaSp_ejspY}Gg)Tm`LRqWs3a5ff}GCIC`CQukbq5>~! z@XWf5n*&Ry&#qfmiy1oIlT~=j>Ng40dw(;os`oEc;2CMK3f!YP)729>lL8eAx``-D zO;H^Pg}72GXWmq4T-+*JyhLNOPT$6^vTs^*%GJx5t7Z2oM=CFt79bMaTi#K=6!^`lfdbW|Ik09q zv+Zh5Cl`OFh4by#kd$j-B?r&fdP^_0<0$iad$G}l^t*%~bKv`EVV*~3HD>ivo&!^S zxf35MTS?5=&Q1_tI+UV>o5mjN#%7bsHf^*we?L#n-KbEM4^7hk1BU1dvkwU*Rl_}> zD0w9muzXi7SuhXN$)(>_v~o!vpv)KOBcfX%1kTBkm$H#8uWaB&go)Bo)sMtmi59d7 z=>9{fu=T-rYSDIgo41v|g2{d&hmVL-+KDrF{!t}wa)5DC%V=W#x8V4QB8G-XkxK27 zA4jpmwwR%0$vmu8QcFGnPdO?zXeEK2w+H+*O#)qWIxISRbTO`qON-CDNnz*P;tt4m zE9DWadt~n55FE}J0W0dLF5aqnyeFEx&+eP4+rO9(_Zf6EjlQdGqI`{^&A9!6T*-nd za+p~no}(7O3WLK68?jG*Dhg!4Hk%)06+sou^~guS7L{1cHzq5ReX@r(HrJh2AtSpY zjDXRiNeth@oEh8ddcK_4L&58j-MY)~2`LRpT zguGnzl#t7|tH1?6;hyJmL{ySzE|a}qaZWq8^YUn5&$rV(%UM=Jq~^`cnzEVVCb#8> zI^G3SetxgOAGj%{*a;NmeM%8|Y%e)V2P2CvNcq++cTJu9`KF&7S;^|rTbuj#U8rI) z8plQ_{cU>w^vtW(GGR$nY0qdFDtxwTQYlMqC?pHyvS0>rss^Jp*{;IL+)m^|thox8 zKdh>dqvBHWdn#gJ6|_1xq~7<8z3ma56E&E$(OPv~a$ZieZNaW2TIY0*0S?^|WBshl zs^-;#W$dtAdcd}{sK&pF|3}lBu7tO>U1?5D`8QEL`BmqdI%5qOw;~XBc`6uf_W$S* zqdj}FAv4xNT?}{#2GL1he_Md`hjM?cO0HW_80V|Z_NRJr)3jk^6)C1M+W|_6gDEP?V-7hV^uHMwD<4p-= zDruXsLDvjrJo5O>8h=@_(mh$^=!83v6VESF0M_sQ-zqK;!=u*;iga&xAG+fc7g)Vw z5q~IrCwnQ_y{-mlSr!WWw7#g?yypW)QOR>DQKZR=SGMgb?@1{PAL+Kga1!1yUITd% zT{ZvFF|!0>jkkC(>5m}TfrS5mSRC~BP8;8JS5b7IJEOSPxw1=A4I4jG*}VtfCeILU zfUjIlTWStn8XiA zjBV!CS!)apsYq3k4fd2N-Ukf8H&A=uKS%j^4oMog`w<@=2j|muxWP`9*;yHO9+@8lL}{Z=MExbPTAp} zP6{#dBhtMUYpIW>WW4~-jZJOVCp|3J%?Wj2L@;VD)na_R60-U}tF1tSczs9vU5U95`{UlagB#gjKw zLJ$ZbJ`ysi3U7P&W6YN`{tdO-%uVOnu&K&+CdnRPN!qV}W}$$?@Hgk^ zIN4`_FVtt|O3kA%fgFTyCDvQoh)_i6qlyO0Ebt%YVMXn?e|AGCDtuWZwdvZp2J4YB z$qgC0t7bE7BcI04l{Cy6CB?-9ebA?TwmKGvrOh>h8P{^(Ew=s&BZoZ%?q#ZPO!v=F z6aFs9M~Kk@E7*PFSz7cc1{EAfrTC4J0LYj4Y4J&W;$U+6FSLmCeT!THf^TLq5EeFG zPp%4m|HSIO6gwUd(NC8{lw`H_G?rG=uT}h1E<})muD1Dt>jFczMmR)Ji_YnF}!|W z9*99hMOm|E*I(4^Fn_^qLjLtbym6kF-^kiKx&en+nd?=iqFMF|a;6`XnmsS!6k^QVeASiD7T=Kp~M z@cO;QG71KjD{@5jYB6BU$v}q6&=7Z$EH^?yX?v}z!Nkq|n6LeZx`7Ug#4q0dM`4u` zt(m&!Y68!1|ctd!9NFz}FqAw_tbE+4tW1M&&=O!(qcX97r9mvHRq& zL`(>tIki-^arnV1B(iM3o@ByW54}h9| zzrA75gA7{htx$ia>)oUUo1Mm1E-nDd=+XfGR224blMY)ty|U!h4YN-M-iLLmE{n@4 zAL%)~`=mMLUDoya46&gyEskEx3`W(l;F9L zf|@i?j}T|^o1iuu4JiX;R1_FTzZ)Y9t*^(k`&@`mrKF7_AI;_bVs5i-)^jVEC|{_cE1bsrxX%enF>`@Is?a@2X$Ff1()rHD9`>MMf1{)?uyj}8?n$KSU+7w=y( zlTBt7TVWZ(XN5#qu5*uK2g_#=+qxzsPc%+t)S$#v2k zfHdQ1L@b~4LvaUTD`M*+9*QJjd<{B^FDZ&cV!xOR@U{09)qI!$kK8}H3eKR8zSMuWx5 z1zl2R!{H*7>d_5SzreBC38G&i>)b`3volLis@;Fo^xNn1y*(XG<%)bw z?vRp~bz@N~f4w?q?s#AbTzbm*J%i@HuJ-Z`7L7<-yuD2rm=?D!mau~z-w-0w6}jsD zb9BQtZ*ogDRSzf0B6>&Dz; z_W`_mOR+fLEt}ftz{jyRlkN6lrT4SsuEEHv5n}UUjxp!$bA%FUg6eI`Ms15c?g>l@ zL6KcGv&d8Y5tq+&}OB@eH15`*P*`de?=e6m%FkE@ZWZuG(!Zxhwj|awLX* zqdr{(g&!g}d;IL7j&$~pUkm1$69muY5E=hLEJLc#7VaW1G$#{#;O=}{JNJ1Vai#Es z_8GsnguUz!Yh}ak#J6Us1EG6=@gVue@i%x5J-WwfccL>x&eQe7(9jUQREfHEp1e}D z47raNG@A+@r~Ic3TaHL87OVyMet5Y^6p40mE8$&r%l@QYbI?HzM-2X*DG_Vc-vuvK z@kc}a?y#>YI*NHolVl1Ze~#?VaB}YHVN2;yS&mEy{E!+7>8v`_3wskhr@^C@vyv}e z`sWBH$zCUL;x8==51n+xoacKv`#<3(82_!noEr3K9a_@`I?`0R&DC}Z5{VOR;;4?b zp`%l9iT#Dl=d9%9ek@`fOEn{4@koLIB5k+YuE%?Jz0bX8(`4nI#HmAE|2}_~{k!i? z%7DA1g{x$*&zfu2GIr78)XAWMQ`3jAKTey#_WJsoweNO%U$I*gT?t>kaPi z4I?Iy7pb|#AizXijjuV3o8q!vU3cj5Wo+Q}whqc<(b_+=?JmsA4PD$Qio^|JIF9r- zdtiL?Yo1iRpliE&t6HBlBYXVZF-6WdOsbP7y<+upw&>#&{tDej`tV{fu5MbXO@%=B zm?p^O*rG?`v-KN|75mLY>2UiM;|QH1*%Dq_VSs@r20DDBDrHxBM5tO;B}wZL>5bY9 zn7%eJ=!%QZV-j+AO*2&F!1xt5yl#^{U4Jj8sitdSwC@`VqPKm!D9z{f9NvDfyd>_M zLF>2Ivd1=Vs2aXEvL&L2WuKY9DU5#d7H(^_B{xH{oZ)8^;0c!@f$8FtvA%dfS!Vt! zg8M*t720M_ePu>xKnGeQ?y7TKoe8`ZPo-S!%m=>CtDUCnkMGU=o>Y>qr1c!Qt2j2K zv?P#SY(!LHz=V(WXV?kCk+P1FamQiZ29xeAU+P0gadhzxl^E}gixkt{rvi;ycSCjD zvMBr4+jHt-n-2*;+;U-I0y;xYiGUQ-&EE<_{f}C6^fvFUgw?XS*b8QitotX&sm}q~ zm207&#FcDSk_U?G1atAZbvtTOh@$F-+^vQ?T%D#tI_FN_rJpLeHT>(09&^VLMs-j| z_zBFEMlUFlv*N=g3QQqnHi+XBi)xuSQdY}C@Gw{{UJ?5!KjHrGutqmsTh63O^vr4d zW3gK4GgX;dsdLkKlC-at%+QpeFcl8aj5v6Xk~y*1L;d9E$0&h!n)08sXB7>3uSdr- z;n?}C8WFORP6z6iGOcbw_z6i{4qq}nqc+UeZuwj_Cd$PHKUXiemzlkUr-y!KbMSbtgoc3?{!9ado&TJh2WLQXJR|_SW;}Uw>&+jl`*UGR9Mn`t8mbYYNio8ALyu-KiwqWM+cDv66)J*;%ji`??>d*d^x63GV!sdI zCWpvShYxIbn{Z9d>q^%djbV5hi%(p?kv~SYlMMC(Ue6W$*MZE-PrPT|GY+Dmd$a^q zHgV@yE=hPK!03k+P?)S9O8P0a5*FY^77-C@teA^#LZU#sZs((1y(9%Vh&XrN70mU#F8 ze@~u@&c;6;LEh`R-nvEF^Y^-)%t=an>()QF@@bsfQ&b~RA8aXL5el?Kt zN(aizGClptLBUMvP9DYkJD-Qh$hjeMv5-J=%zwCh=^h7!ykUDj-SiPk zgpp~0Bw8H*7&}=wzrNO;NqO6gwzWEHy%f8d&-b?jODvs_c!E33)fCu69!ouZ9`fr8 z*yGmozw*J2(AEdSzhXqi`*3x9*<&dS8PTM_wI09V9Lsz9ucQ}GTKHefC^xpyztTJH zZ_@wu_TvS;!oPjRQ~tkQ^1Fw>6t`UV`|e$`$r?`!)K0I$sLcSyHt6E@-BBNuH_A*no%KTKUSrKV~p7W$Dns z{;rGxu7VnY#N&&>1~Aku<2aq2>C`5j&m}kIN${x+W7ffCT?JIjzs$Z@r?i!IRO{x4 z054kZV(Ge4-%zb!BQ>hSGcQv=SI>eUzfd-^_$4b?qvbA$zpR4-Ntx+k z7j&6GGLG&BMq~K>A*T)3sccx%eUm?h+Q|Xsc9c9$IRo`mDlpRJELgpc_Ky=DyG_-= zppl8CmBSW&D#IH+$5vYjpahQ1cTVmSuXXrHBhUShg>DygENh@2hMz=+H#2?#H14v7 zRo5qMDZPS{qZMOvp}N(?3ZK{$*xHYC4Y zyv!+S50LC^vhn-;MKSJ;y?yMuO9t;%c8ZnccNT4b1@XD~mEXQ2d@K_=ON-@>t!uLG zGc&-6&{K(GQcE8~COJTGIYtZ1jmw#3P%LX-%FSJPxb_gB>T}~EVA%dn_I#9+0(-LXSBBQ64@Njt z0f&h3HV_771$@ZWv(n@!J{FPcNTOjqPPgov%|xV-#IM=!NH*x3Cv%-E=Sw8J92z0%jFsCZ;!lTs8s8)((K#pGd;9S_&E-Z zS`OQTTv0b19GHlAYsmnN=QC@eRD?w)zg|+C49i3h+Tf5BZ7%=t2JoF!tr^_ZWRustJg{dUXH(eeUui8~~dO_;oyWmDAF1 zyiCBzK7y`n&jOFLflh5Dym#p5Zx~0h1utpOC*vj`Gg1R69aQ~OP3}c+`E1|rz^zps z?(qnbFJbv_E_SVEatG2=p76z5H2K^%w_`y<&AGz?F(v6}J{k>Ry5;a&JaX&SOr234 zxqeHwwFwGasB#J5FX45UG{hJD#$kjOTnw|BJ8rw$3zlj!&3U@)$_@zta?Q`aUPOiz8FBzCAY%O!Kp5$^=cY2fEbZaam(A`&TzP023&1 zm_+9~Bq98|d$j61OJX{aOZI^#O~wO@mS6p11@}kWM)$ku6-&6ei<+9!?o^RP!{ki! z$oii-#W4XYjk~7*E>GH!n(V)OuXxZ1Zjr)EAYjg1I$HDmSY$a+&Oa8eHAY25%XlTW zgbn!aD$C4=8ozV^2xMBI5vx-g>XX;f{ zVB0|e`Dq|@fd7YOW2zmd-R#dEAPJ$TC8*RcIqaUl6H2wwLMp22Pk&3>7hV9 z-&0JL;cz)Gx%Hg6e6oIvbp7RIk}2 zW;sjbcRCY~6Ehfb;CaPd5PxP^vC}LB*_%g6elauI1_b24+92}u55d)p{CYSy5wx-}>wOT% zgH^HMKE<7xI+oF8T&Euh@Fz}oE&`#Jn7{UuT6NwwBU<6wnE}(r&Rx%Og9=aJFFic{cBns zsQ&+2RMP9IyU{(LH5tr1aa;KJ5lm$=Sfr+uTcT9^gC$O zdjm4T^1h@&sY8FqTBd9%cH!|cWknrE$Kq@otzIv~6GW%=KSnxer|oaRXMKCleC;jI z!e5mWc*ZopCuq-mCKDi}Q67b;JJ5Q)q8oHkK>yC{(IDZ~cnUSNH3PF1H}-p8 z=0$pb3xC|B-rKcI?WzW<5z?;~bU)2TNkw7Bz;ZsheJ92=bHT!B?QM?ehhEuWIlhUS zN{QHp6SI2#G()xbp969AFu7SDYYg$K$8@^BR>)K`0;}gD%ijCBh=r;YA%qQCVFCy>;NX& zA@6DOr^n7QJllW=l(|DSD%g%JN?L8M_dQ!P5u}LhRc*`Jb9FuyAZoV8SWqAfUnZ~z zU=OKs0?erg#s{p5mDwKc7t(TDj3l|>OOIvDaA(aVZ4KwQS^^H6Nr1KrXJawc>IP~b z&06XjFag)QrS@2Ez3@tt>fHMe{*-fIEqy9hXC_c(KN|=75P>v_SirnUhd$ZadpS1O z2dG~Y^XunB(#(7D^`-_M5E_ut!4gfPkg4Gl7-m2m`OeM@a`ft$>-O0oJh~=rJj49~ z42M)TUbXh+SqyTaTfCJqp~6SSGCTE_>*=3KOKj5`lT~H{*;w}1%fM?s|M+{DAVNAv z9xAxP3mTR&qyh)S+TYolY1U94YI1gBBExO$Y+5&A2Wy(!Z!y2Pdgr4LvEKha$7AVe z6lw#wX$#=ve$BYp zW#+m($OBtH3L1-)yNvW`T>fF;y&oI*x}d114tmpWOCWiJl{Iu^tZXB<=O**vdn-0C z_pLQ_><*)3lbwhqOSZoTA%nLMJx^Obbz|p03#6cV=0s<+JmYS0hv5v}ZkVTW*qqJC zPlXrhtDK#F$*+##UWbYhA8d_i);BY?{Huj`LD^gq@|>x zdV|wi^n9t8(sWm*Xb=v|W8AyK$=vDlKt=Ud`9dUorF)BHd5|-&vp71Yl?;o(7Ma)5 zNYdSmT!R@5YiI)HDbJHNAWiHI6#hsKHJqzw>Gx*&fLgG|W#?^_EqLWsSr_K$8?dFV>2B{d zoukJd=uO9{<)Dfp``M(Ej?1zxk4z#MHNx|AU1_RrVHcLIbB8LXv2oYZ!$BljrY{c7 zn!w(1RI9TY!$HWJ^LfZ*zr%wy9a`%+B#|=m{pF|~E<#;3Fyu1eg0BUxXnM>=*U^@^ z8_W6$R0VxslIlK3)8zM)Kg$C}2BFDlJ?pD7fu-vxm`=FSG2FaqMfGjLVf6U;!otYO zU1hFZN%+x|LPNW)?Tzc)&Y%f{H*Y71>2huf_P+t4A1#k?J|CZg&$W`KPm=D5O%Hko zG?E7*?j3UORFl=g8Yp%lybJWN(BkuhKU|A5#sEH+$bcL#Z=g42;-e&$ZVbabDfRNv z8q)3PVS64MkySb{0^6f#aJIAlAc|$ATSqf;L7<7AyBl-#W3TIW8#h5MOEOK4D*M@W zl+d()U1E2}jMsyD7-=J!=hu7DMKv~Z;>dEv5{>~Nzlll%Zewb@eKNp);MC3V)eAjfj-y-_c2M`@AS0Xx#{Xmu{_)++~{nmxVk+rR7Vga zBxY{H+-E-85y@J0&*?3I7?JDV=TZOXucEb zMa1ES3srU_7PWLrI&O`t246nMS=LV*NfYOo!TD` z6UY5-={5UF$yS(Gx|6hnfqs38b5Oj?9e7*&a-W*hphA%DT557v%w^D>Q1)S%nSG^G zH-?Ad#}m*9#tpUq=imagN0Y|wu!ryv^^t1ADgu6lKEuOu1tNMrM}-1bF8L?vilsaD z$SwoU7>9LZo$Nso>dSCOk%GprQ2beOVI)Va;4wDnx!8+=EFZ-|uJZ01o)@|uh0Sl(PCT z+j9UxDGw8!oRE{&Ai%VZJqNM$&lnkJIWh*$C1eJ_o46uAUAh(zz|P4v?^Nch=MG-C zD;>$L+E2SaZLNB!OnWT~$%KV2B=*~7#zT6eiXI_jT-AMjwL#1&-S>8~z<1h}rZ^^9AKH0I+LBxb}aJ}o%N}pNAmdj^{Iu|w-wVH(GT0lQr zz((ZNj16)Bw!9%ropb+bvx2G_LN=%S{Z=VOu22HfQF=-PI{BEhupr5C@EESrN_m7J z<2$DC=QIbdTMXqI8%c4@k`);KB#%2Pu%U6+>RZf1SL>y#>qSJxNo=P*JXL$T|G|3S z(0roM+slYly+%z|?J4sM|KTiMvojJNU|IC-_aU+)B}sS#%B<*-P~vcfyooS<+)3P7 zv*rug7f*yZSJvdVbM2cnM!gro}t^DDw_jKNJ|Ok3V=XS^y9tg=gtTF%ZQ} zq94bdpj@U)*?}jdYoGdMWa1^Wou5X&XA~$r4_n$5ZT|6C85tobYv=j2R5v1>!nHA{ zKFEekG?410G*^()(&bl<=&O5eD(W@yb7W7M3$BJMc=PBPO6q$`c9d8FBtWL{9eZJ5 z8L|^V6qm)D3{8xXQML;|){J`RmgFH!F2#uB{9n;vh~5Z@eeV1 zr0^9z92UTm9PtDr(I+>W8Mfqr6N?fu<`4g1!h`6jG?kruW!l3Wr550{1&ay#kxO&(T>Lnje(OM?nh!iehHgclx5mU&K&d=wDoy2~7Jg^(U#>A!U!q_E+|!F8ISS6l_xl?0 z=jTvKIS0#lz&!y&5b;qxL*IroWCmyRph&S5?`aXLUW;|snCU-QzxJ+Kh(5BEVeYriHsXq|yv|G^G2o%@qU2e5Y&aWzn zza9Z&+Exuma>Wt*ei^;pdK!ag$c*eB*wtNE)*LaCuf^&|4Ghd+`Mn%arEx4qcjJGqJ{he}+pr9>-vZ}%Q; zn|UzUul+(4+(ot!>!)%o@NU_O{Axy)pUqQZmD9mH=u*nIhQiO4u?-Z+qO9SP%{|9F zJldvsvf+48JNmr|hG%FFhAqh1h)+UK7Cm$e$+jTBRpAFV+!W|1f2| zTA-g^xPCsn!XlNeJm28Qps4KiCaBlU6q7`lW6~I{D;%+alB}nn)VOCr`UGRMQJ!mP zJGhy<0Jc=He8Tg6NuKXX@74gQkbW`|KNU0)vO!{A{d@}8nA}n1o^!&UdyNm4A*m9z z|3JkiJhA4XIQ+6Eadlu9j*pAK5?*T;_@(zly-bgq&# zj0>UMe1Fs7$1LdY?m?+lwtS@W3_u%dYGy6MVw;ZDR1=L$6*8)5N^yo4G>?E*3L+-$-jSto+9Y9SxaBSP zip7A(;X^SKEB7^979wSu+>Gf@4O<`Q&b9Tg{S82YIt_Yrm>h%+jrofSl9lpVyO~#= zC7coI^9?vUjdeqQX{*=6(wvjk&L&JMjY9s3v6YEY;Sv32e)cQG5`k-eNR~fgM|DC= z*Sj2x;*+7U-Jje0-{w}VBQ*I2z7MUtVDX5#IP2OadF8ipTE0mvJBIxrI=>nDY{2?i zW>M4Sb|{z0N8IM0kDQGiLu5Jna$ND<+lPg$f^l;4@1*Y;dR(8c_j0A_Ip|9iF2|L7 z9!66Oel9X~^+DLjx-D^#n@QE=Rt5U7Bg>%T3nU`w4-AbP5YT8_O`>@CTqH|^X6n7B zKUwU4=r#ZfEHzK!8+(XrX-7L@q^8_ibe=-agSNOt$|sNHxZe8Q^>IfA7|%52!oIgp zf2To~MK`T?1C{(U`aTXMjo{sY8lSo68KRf_!e~5qB++tb!2USzmw?_gz7cD70XgkT zDBxpjVpY-J_^8#^st9U*W)}}F?Y52>_%ZzGNRE933t1etm2f_w(*QjSrWc!pBg;Li zuNJf~3LbGp`{BPN#g046a&RUr&)&&;Wk#TN+Osa$OTD;=zbjmlKY0xcPapSYvuj{n z#e1*_2-g+Y9(!`AVU6{JXeB?ssgEs{Ud}KHL(H@ Date: Thu, 31 Mar 2022 15:00:03 +0800 Subject: [PATCH 211/379] feat: add option ENABLE_RECVMMSG --- CMakeLists.txt | 5 ++++ src/rs_driver/driver/input/sock_input.hpp | 29 +++++++++++++++++++++++ 2 files changed, 34 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9f787fe2..b633d803 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -22,6 +22,7 @@ option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" option(ENABLE_PUBLISH_RAW_MSG "Publish raw messages" OFF) option(ENABLE_PUBLISH_CAM_MSG "Publish camera trigger messages" OFF) option(ENABLE_TRANSFORM "Enable transform functions" OFF) +option(ENABLE_RECVMMSG "Enable recvmmsg() to receive MSOP message" OFF) #======================== # Project setup @@ -118,6 +119,10 @@ if(${ENABLE_HIGH_PRIORITY_THREAD}) add_definitions("-DENABLE_HIGH_PRIORITY_THREAD") endif(${ENABLE_HIGH_PRIORITY_THREAD}) +if(${ENABLE_RECVMMSG}) + add_definitions("-DENABLE_RECVMMSG") +endif(${ENABLE_RECVMMSG}) + if(${ENABLE_PUBLISH_RAW_MSG}) add_definitions("-DENABLE_PUBLISH_RAW_MSG") endif(${ENABLE_PUBLISH_RAW_MSG}) diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index cd7bdcf0..5775ae4d 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -251,6 +251,34 @@ inline void SockInput::recvPacket() if (FD_ISSET(fds_[0], &rfds)) { +#ifdef ENABLE_RECVMMSG +#define VLEN 1 + struct mmsghdr msgs[VLEN]; + struct iovec iovecs[VLEN]; + std::shared_ptr pkts[VLEN]; + int i, ret; + + memset(msgs, 0, sizeof(msgs)); + for (i = 0; i < VLEN; i++) + { + pkts[i] = cb_get_(MAX_PKT_LEN); + pkts[i]->resetData(); + iovecs[i].iov_base = pkts[i]->data(); + iovecs[i].iov_len = MAX_PKT_LEN; + msgs[i].msg_hdr.msg_iov = &iovecs[i]; + msgs[i].msg_hdr.msg_iovlen = 1; + } + + struct timespec timeout; + timeout.tv_sec = 0; + timeout.tv_nsec = 0; + ret = recvmmsg(fds_[0], msgs, VLEN, 0, &timeout); + for (i = 0; i < ret; i++) + { + pkts[i]->setData(sock_offset_, msgs[i].msg_len - sock_offset_ - sock_tail_); + pushPacket(pkts[i]); + } +#else std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); pkt->resetData(); ssize_t ret = recvfrom(fds_[0], pkt->data(), MAX_PKT_LEN, 0, NULL, NULL); @@ -264,6 +292,7 @@ inline void SockInput::recvPacket() pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); pushPacket(pkt); } +#endif } else if (FD_ISSET(fds_[1], &rfds)) { From d8be85ae5fc7140991e904576d9be417215b46bd Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 31 Mar 2022 15:07:43 +0800 Subject: [PATCH 212/379] fix: fix compiling warnings --- CMakeLists.txt | 18 +++++++++--------- src/rs_driver/driver/input/sock_input.hpp | 2 +- src/rs_driver/msg/pcl_point_cloud_msg.h | 10 +++++----- 3 files changed, 15 insertions(+), 15 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b633d803..bd6c70f1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -18,10 +18,10 @@ option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) # Compile Features #============================= option(ENABLE_PCAP_PARSE "Enable PCAP file parse" ON) -option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) option(ENABLE_PUBLISH_RAW_MSG "Publish raw messages" OFF) option(ENABLE_PUBLISH_CAM_MSG "Publish camera trigger messages" OFF) option(ENABLE_TRANSFORM "Enable transform functions" OFF) +option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) option(ENABLE_RECVMMSG "Enable recvmmsg() to receive MSOP message" OFF) #======================== @@ -115,14 +115,6 @@ if(${ENABLE_PCAP_PARSE}) add_definitions("-DENABLE_PCAP_PARSE") endif(${ENABLE_PCAP_PARSE}) -if(${ENABLE_HIGH_PRIORITY_THREAD}) - add_definitions("-DENABLE_HIGH_PRIORITY_THREAD") -endif(${ENABLE_HIGH_PRIORITY_THREAD}) - -if(${ENABLE_RECVMMSG}) - add_definitions("-DENABLE_RECVMMSG") -endif(${ENABLE_RECVMMSG}) - if(${ENABLE_PUBLISH_RAW_MSG}) add_definitions("-DENABLE_PUBLISH_RAW_MSG") endif(${ENABLE_PUBLISH_RAW_MSG}) @@ -131,6 +123,14 @@ if(${ENABLE_PUBLISH_CAM_MSG}) add_definitions("-DENABLE_PUBLISH_CAM_MSG") endif(${ENABLE_PUBLISH_CAM_MSG}) +if(${ENABLE_HIGH_PRIORITY_THREAD}) + add_definitions("-DENABLE_HIGH_PRIORITY_THREAD") +endif(${ENABLE_HIGH_PRIORITY_THREAD}) + +if(${ENABLE_RECVMMSG}) + add_definitions("-DENABLE_RECVMMSG") +endif(${ENABLE_RECVMMSG}) + #======================== # Build Demos #======================== diff --git a/src/rs_driver/driver/input/sock_input.hpp b/src/rs_driver/driver/input/sock_input.hpp index 5775ae4d..13e70b8c 100644 --- a/src/rs_driver/driver/input/sock_input.hpp +++ b/src/rs_driver/driver/input/sock_input.hpp @@ -81,7 +81,7 @@ inline void SockInput::higherThreadPrioty(std::thread::native_handle_type handle sch.sched_priority = 63; if (pthread_setschedparam(handle, SCHED_RR, &sch)) { - std::cout << "setschedparam failed: " << std::strerror(errno) << '\n'; + std::cout << "setschedparam failed: " << std::strerror(errno) << std::endl; } #endif } diff --git a/src/rs_driver/msg/pcl_point_cloud_msg.h b/src/rs_driver/msg/pcl_point_cloud_msg.h index ca622bdf..afdd2c91 100644 --- a/src/rs_driver/msg/pcl_point_cloud_msg.h +++ b/src/rs_driver/msg/pcl_point_cloud_msg.h @@ -40,14 +40,14 @@ typedef pcl::PointXYZI PointXYZI; struct PointXYZIRT { PCL_ADD_POINT4D; - uint8_t intensity; - uint16_t ring = 0; + std::uint8_t intensity; + std::uint16_t ring = 0; double timestamp = 0; EIGEN_MAKE_ALIGNED_OPERATOR_NEW } EIGEN_ALIGN16; -POINT_CLOUD_REGISTER_POINT_STRUCT(PointXYZIRT, (float, x, x)(float, y, y)(float, z, z)(uint8_t, intensity, intensity)( - uint16_t, ring, ring)(double, timestamp, timestamp)) +POINT_CLOUD_REGISTER_POINT_STRUCT(PointXYZIRT, (float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)( + std::uint16_t, ring, ring)(double, timestamp, timestamp)) template class PointCloudT : public pcl::PointCloud @@ -58,5 +58,5 @@ class PointCloudT : public pcl::PointCloud double timestamp = 0.0; std::string frame_id = ""; ///< Point cloud frame id - uint32_t seq = 0; ///< Sequence number of message + std::uint32_t seq = 0; ///< Sequence number of message }; From 1853c99b859a1a88ae77ade198f6ded9515101b8 Mon Sep 17 00:00:00 2001 From: Yufan Fang Date: Fri, 1 Apr 2022 16:52:52 +0800 Subject: [PATCH 213/379] fix: fix memory usage increase when transformation is enabled --- src/rs_driver/driver/decoder/decoder_base.hpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 30f7c55c..9f4a6ba1 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -771,12 +771,12 @@ template inline void DecoderBase::transformPoint(float& x, float& y, float& z) { #ifdef ENABLE_TRANSFORM - Eigen::AngleAxisd current_rotation_x(param_.transform_param.roll, Eigen::Vector3d::UnitX()); - Eigen::AngleAxisd current_rotation_y(param_.transform_param.pitch, Eigen::Vector3d::UnitY()); - Eigen::AngleAxisd current_rotation_z(param_.transform_param.yaw, Eigen::Vector3d::UnitZ()); - Eigen::Translation3d current_translation(param_.transform_param.x, param_.transform_param.y, - param_.transform_param.z); - Eigen::Matrix4d trans = (current_translation * current_rotation_z * current_rotation_y * current_rotation_x).matrix(); + static Eigen::AngleAxisd current_rotation_x(param_.transform_param.roll, Eigen::Vector3d::UnitX()); + static Eigen::AngleAxisd current_rotation_y(param_.transform_param.pitch, Eigen::Vector3d::UnitY()); + static Eigen::AngleAxisd current_rotation_z(param_.transform_param.yaw, Eigen::Vector3d::UnitZ()); + static Eigen::Translation3d current_translation(param_.transform_param.x, param_.transform_param.y, + param_.transform_param.z); + static Eigen::Matrix4d trans = (current_translation * current_rotation_z * current_rotation_y * current_rotation_x).matrix(); Eigen::Vector4d target_ori(x, y, z, 1); Eigen::Vector4d target_rotate = trans * target_ori; x = target_rotate(0); From 245ab0f4a04362ca64505e9de02b14ca3555ce87 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 7 Apr 2022 10:40:34 +0800 Subject: [PATCH 214/379] feat: support ruby_plus --- .../driver/decoder/decoder_RS128.hpp | 12 + .../driver/decoder/decoder_RSRUBY_PLUS.hpp | 278 ++++++++++++++++++ .../driver/decoder/decoder_factory.hpp | 4 + src/rs_driver/driver/driver_param.hpp | 10 +- 4 files changed, 303 insertions(+), 1 deletion(-) create mode 100644 src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 7e9a4401..6f7c1fed 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -90,6 +90,10 @@ class DecoderRS128 : public DecoderMech explicit DecoderRS128(const RSDecoderParam& param, const std::function& excb); + explicit DecoderRS128(const RSDecoderMechConstParam& const_param, + const RSDecoderParam& param, + const std::function& excb); + #ifndef UNIT_TEST protected: #endif @@ -182,6 +186,14 @@ inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, { } +template +inline DecoderRS128::DecoderRS128(const RSDecoderMechConstParam& const_param, + const RSDecoderParam& param, + const std::function& excb) + : DecoderMech(const_param, param, excb) +{ +} + template inline void DecoderRS128::decodeDifopPkt(const uint8_t* packet, size_t size) { diff --git a/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp b/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp new file mode 100644 index 00000000..e6121262 --- /dev/null +++ b/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp @@ -0,0 +1,278 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include +#include + +namespace robosense +{ +namespace lidar +{ + +template +class DecoderRSRUBY_PLUS : public DecoderRS128 +{ +public: + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + //virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRSRUBY_PLUS() = default; + + explicit DecoderRSRUBY_PLUS(const RSDecoderParam& param, + const std::function& excb); + +#ifndef UNIT_TEST +protected: +#endif + + static RSDecoderMechConstParam& getConstParam(); + static RSEchoMode getEchoMode(uint8_t mode); + + template + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); +}; + +template +inline RSDecoderMechConstParam& DecoderRSRUBY_PLUS::getConstParam() +{ + static RSDecoderMechConstParam param = + { + 1248 // msop len + , 1248 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x5A} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFE} // block id + , 128 // laser number + , 3 // blocks per packet + , 128 // channels per block + , 1.0f // distance min + , 250.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.02892f // RX + , -0.013f // RY + , 0.0f // RZ + }; + + INIT_ONLY_ONCE(); + + float blk_ts = 50.984f; + float firing_tss[] = + { + 0.24f, 0.24f, 0.24f, 0.24f, 1.084f, 1.084f, 1.084f, 1.084f, + 1.932f, 1.932f, 1.932f, 1.932f, 2.872f, 2.872f, 2.872f, 2.872f, + 3.824f, 3.824f, 3.824f, 3.824f, 4.684f, 4.684f, 4.684f, 4.684f, + 5.540f, 5.540f, 5.540f, 5.540f, 6.496f, 6.496f, 6.496f, 6.496f, + 7.440f, 7.440f, 7.440f, 7.440f, 9.348f, 9.348f, 9.348f, 9.348f, + 11.260f, 11.260f, 11.260f, 11.260f, 13.264f, 13.264f, 13.264f, 13.264f, + 15.280f, 15.280f, 15.280f, 15.280f, 17.204f, 17.204f, 17.204f, 17.204f, + 19.124f, 19.124f, 19.124f, 19.124f, 21.144f, 21.144f, 21.144f, 21.144f, + + 23.152f, 23.152f, 23.152f, 23.152f, 25.060f, 25.060f, 25.060f, 25.060f, + 26.972f, 26.972f, 26.972f, 26.972f, 28.976f, 28.976f, 28.976f, 28.976f, + 30.992f, 30.992f, 30.992f, 30.992f, 32.916f, 32.916f, 32.916f, 32.916f, + 34.836f, 34.836f, 34.836f, 34.836f, 36.856f, 36.856f, 36.856f, 36.856f, + 38.864f, 38.864f, 38.864f, 38.864f, 40.272f, 40.272f, 40.272f, 40.272f, + 41.684f, 41.684f, 41.684f, 41.684f, 43.188f, 43.188f, 43.188f, 43.188f, + 44.704f, 44.704f, 44.704f, 44.704f, 46.128f, 46.128f, 46.128f, 46.128f, + 47.548f, 47.548f, 47.548f, 47.548f, 49.068f, 49.068f, 49.068f, 49.068f + }; + + param.BLOCK_DURATION = blk_ts / 1000000; + for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) + { + param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; + param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; + } + + return param; +} + +template +inline RSEchoMode DecoderRSRUBY_PLUS::getEchoMode(uint8_t mode) +{ + switch (mode) + { + case 0x00: + case 0x01: + case 0x02: + return RSEchoMode::ECHO_SINGLE; + case 0x03: + case 0x04: + case 0x05: + default: + return RSEchoMode::ECHO_DUAL; + } +} + +template +inline void DecoderRSRUBY_PLUS::decodeDifopPkt(const uint8_t* packet, size_t size) +{ + const RS128DifopPkt& pkt = *(const RS128DifopPkt*)(packet); + this->template decodeDifopCommon(pkt); + + this->echo_mode_ = getEchoMode (pkt.return_mode); + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; +} + + +template +inline DecoderRSRUBY_PLUS::DecoderRSRUBY_PLUS(const RSDecoderParam& param, + const std::function& excb) + : DecoderRS128(getConstParam(), param, excb) +{ +} + +#if 0 +template +inline bool DecoderRSRUBY_PLUS::decodeMsopPkt(const uint8_t* pkt, size_t size) +{ + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) + { + return internDecodeMsopPkt>(pkt, size); + } + else + { + return internDecodeMsopPkt>(pkt, size); + } +} + +template +template +inline bool DecoderRSRUBY_PLUS::internDecodeMsopPkt(const uint8_t* packet, size_t size) +{ + const RS128MsopPkt& pkt = *(const RS128MsopPkt*)(packet); + bool ret = false; + + this->temperature_ = parseTempInBe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) + { + pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 1e-6; + } + else + { + uint64_t ts = getTimeHost(); + + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = ts * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeUTCWithNs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + } + } + + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + this->block_az_diff_, this->fov_blind_ts_diff_); + + double block_ts = pkt_ts; + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + { + const RS128MsopBlock& block = pkt.blocks[blk]; + + if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) + { + this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + break; + } + + int32_t block_az = ntohs(block.azimuth); + if (this->split_strategy_->newBlock(block_az)) + { + this->cb_split_frame_(this->height_, this->prev_point_ts_); + ret = true; + } + + int32_t block_az_diff; + float block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) + { + const RSChannel& channel = block.channels[chan]; + + double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + int32_t angle_horiz = block_az + + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); + + int32_t angle_vert = this->chan_angles_.vertAdjust(chan); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + + if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) + { + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); + } + else if (!this->param_.dense_points) + { + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); + } + + this->prev_point_ts_ = chan_ts; + } + } + + this->prev_pkt_ts_ = pkt_ts; + return ret; +} +#endif + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 66a05d5c..2e7c7dcb 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -37,6 +37,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include namespace robosense @@ -79,6 +80,9 @@ inline std::shared_ptr> DecoderFactory::crea case LidarType::RS128: ret_ptr = std::make_shared>(param, excb); break; + case LidarType::RSRUBY_PLUS: + ret_ptr = std::make_shared>(param, excb); + break; case LidarType::RSM1: ret_ptr = std::make_shared>(param, excb); break; diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 7955c8b4..72f673b1 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -47,6 +47,7 @@ enum LidarType ///< LiDAR type RSBP, RS128, RS80, + RSRUBY_PLUS, RSHELIOS, RSROCK, RSM1 = 10 @@ -72,6 +73,9 @@ inline std::string lidarTypeToStr(const LidarType& type) case LidarType::RS80: str = "RS80"; break; + case LidarType::RSRUBY_PLUS: + str = "RSRUBY_PLUS"; + break; case LidarType::RSM1: str = "RSM1"; break; @@ -110,6 +114,10 @@ inline LidarType strToLidarType(const std::string& type) { return lidar::LidarType::RS80; } + else if (type == "RSRUBY_PLUS") + { + return lidar::LidarType::RSRUBY_PLUS; + } else if (type == "RSM1") { return lidar::LidarType::RSM1; @@ -125,7 +133,7 @@ inline LidarType strToLidarType(const std::string& type) else { RS_ERROR << "Wrong lidar type: " << type << RS_REND; - RS_ERROR << "Please setup the correct type: RS16, RS32, RSBP, RS128, RS80, RSM1, RSHELIOS" << RS_REND; + RS_ERROR << "Please setup the correct type: RS16, RS32, RSBP, RS128, RS80, RSRUBY_PLUS, RSM1, RSHELIOS" << RS_REND; exit(-1); } } From 8d283e368fb04140a0d3d5489b4ae23c4c438a51 Mon Sep 17 00:00:00 2001 From: Yufan Fang Date: Thu, 7 Apr 2022 14:44:01 +0800 Subject: [PATCH 215/379] fix: use member variable for transformation static non-member variable causes occasional failure of transformation function on client's Xavier platform --- src/rs_driver/driver/decoder/decoder_base.hpp | 20 ++++++++++++------- 1 file changed, 13 insertions(+), 7 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_base.hpp b/src/rs_driver/driver/decoder/decoder_base.hpp index 9f4a6ba1..e39e5151 100644 --- a/src/rs_driver/driver/decoder/decoder_base.hpp +++ b/src/rs_driver/driver/decoder/decoder_base.hpp @@ -348,6 +348,9 @@ class DecoderBase std::function check_camera_trigger_func_; int lidar_alph0_; // atan2(Ry, Rx) * 180 / M_PI * 100 float lidar_Rxy_; // sqrt(Rx*Rx + Ry*Ry) +#ifdef ENABLE_TRANSFORM + Eigen::Matrix4d trans_; +#endif private: std::vector cos_lookup_table_; @@ -447,6 +450,15 @@ inline DecoderBase::DecoderBase(const RSDecoderParam& param, /* Calulate the lidar_alph0 and lidar_Rxy */ lidar_alph0_ = std::atan2(lidar_const_param_.RY, lidar_const_param_.RX) * 180 / M_PI * 100; lidar_Rxy_ = std::sqrt(lidar_const_param_.RX * lidar_const_param_.RX + lidar_const_param_.RY * lidar_const_param_.RY); + +#ifdef ENABLE_TRANSFORM + Eigen::AngleAxisd current_rotation_x(param_.transform_param.roll, Eigen::Vector3d::UnitX()); + Eigen::AngleAxisd current_rotation_y(param_.transform_param.pitch, Eigen::Vector3d::UnitY()); + Eigen::AngleAxisd current_rotation_z(param_.transform_param.yaw, Eigen::Vector3d::UnitZ()); + Eigen::Translation3d current_translation(param_.transform_param.x, param_.transform_param.y, + param_.transform_param.z); + trans_ = (current_translation * current_rotation_z * current_rotation_y * current_rotation_x).matrix(); +#endif } template @@ -771,14 +783,8 @@ template inline void DecoderBase::transformPoint(float& x, float& y, float& z) { #ifdef ENABLE_TRANSFORM - static Eigen::AngleAxisd current_rotation_x(param_.transform_param.roll, Eigen::Vector3d::UnitX()); - static Eigen::AngleAxisd current_rotation_y(param_.transform_param.pitch, Eigen::Vector3d::UnitY()); - static Eigen::AngleAxisd current_rotation_z(param_.transform_param.yaw, Eigen::Vector3d::UnitZ()); - static Eigen::Translation3d current_translation(param_.transform_param.x, param_.transform_param.y, - param_.transform_param.z); - static Eigen::Matrix4d trans = (current_translation * current_rotation_z * current_rotation_y * current_rotation_x).matrix(); Eigen::Vector4d target_ori(x, y, z, 1); - Eigen::Vector4d target_rotate = trans * target_ori; + Eigen::Vector4d target_rotate = trans_ * target_ori; x = target_rotate(0); y = target_rotate(1); z = target_rotate(2); From 07ca12b86cc82001a86acdb00d51feb63a12efe0 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 7 Apr 2022 17:58:32 +0800 Subject: [PATCH 216/379] feat: support helios_16 --- .../driver/decoder/decoder_RSHELIOS_16P.hpp | 282 ++++++++++++++++++ .../driver/decoder/decoder_factory.hpp | 4 + src/rs_driver/driver/driver_param.hpp | 10 +- 3 files changed, 295 insertions(+), 1 deletion(-) create mode 100644 src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp new file mode 100644 index 00000000..718c18e3 --- /dev/null +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp @@ -0,0 +1,282 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include +#include + +namespace robosense +{ +namespace lidar +{ + +template +class DecoderRSHELIOS_16P : public DecoderMech +{ +public: + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRSHELIOS_16P() = default; + + explicit DecoderRSHELIOS_16P(const RSDecoderParam& param, + const std::function& excb); + +#ifndef UNIT_TEST +protected: +#endif + + static RSDecoderMechConstParam& getConstParam(); + static RSEchoMode getEchoMode(uint8_t mode); + + void calcParam(); + template + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); +}; + +template +inline RSDecoderMechConstParam& DecoderRSHELIOS_16P::getConstParam() +{ + static RSDecoderMechConstParam param = + { + 1248 // msop len + , 1248 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x5A} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 16 // laser number + , 12 // blocks per packet + , 32 // channels per block + , 0.4f // distance min + , 200.0f // distance max + , 0.0025f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.03498f // RX + , -0.015f // RY + , 0.0f // RZ + }; + + float blk_ts = 55.56f; + param.BLOCK_DURATION = blk_ts / 1000000; + + return param; +} + +template +inline void DecoderRSHELIOS_16P::calcParam() +{ + float blk_ts = 55.56f; + float firing_tss[] = + { + 0.00f, 3.15f, 6.30f, 9.45f, 13.26f, 17.08f, 20.56f, 23.71f, + 26.53f, 27.77f, 31.49f, 32.73f, 36.46f, 38.94f, 41.42f, 43.91f, + 55.56f, 58.70f, 61.85f, 65.00f, 68.82f, 72.64f, 76.12f, 79.27f, + 82.08f, 83.32f, 87.05f, 88.29f, 92.01f, 94.50f, 96.98f, 99.46f + }; + + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) + { + Rs16SingleReturnBlockIterator::calcChannel(blk_ts, firing_tss, + this->mech_const_param_.CHAN_AZIS, this->mech_const_param_.CHAN_TSS); + } + else + { + Rs16DualReturnBlockIterator::calcChannel(blk_ts, firing_tss, + this->mech_const_param_.CHAN_AZIS, this->mech_const_param_.CHAN_TSS); + } +} + +template +inline RSEchoMode DecoderRSHELIOS_16P::getEchoMode(uint8_t mode) +{ + switch (mode) + { + case 0x00: // dual return + return RSEchoMode::ECHO_DUAL; + case 0x04: // strongest return + case 0x05: // last return + case 0x06: // nearest return + default: + return RSEchoMode::ECHO_SINGLE; + } +} + +template +inline DecoderRSHELIOS_16P::DecoderRSHELIOS_16P(const RSDecoderParam& param, + const std::function& excb) + : DecoderMech(getConstParam(), param, excb) +{ + this->height_ = 16; + this->packet_duration_ = + this->mech_const_param_.BLOCK_DURATION * this->const_param_.BLOCKS_PER_PKT * 2; + + calcParam(); +} + +template +inline void DecoderRSHELIOS_16P::decodeDifopPkt(const uint8_t* packet, size_t size) +{ + const RSHELIOSDifopPkt& pkt = *(const RSHELIOSDifopPkt*)(packet); + this->template decodeDifopCommon(pkt); + + RSEchoMode echo_mode = getEchoMode (pkt.return_mode); + if (this->echo_mode_ != echo_mode) + { + this->echo_mode_ = echo_mode; + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; + + calcParam(); + } +} + +template +inline bool DecoderRSHELIOS_16P::decodeMsopPkt(const uint8_t* pkt, size_t size) +{ + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) + { + return internDecodeMsopPkt>(pkt, size); + } + else + { + return internDecodeMsopPkt>(pkt, size); + } +} + +template +template +inline bool DecoderRSHELIOS_16P::internDecodeMsopPkt(const uint8_t* packet, size_t size) +{ + const RSHELIOSMsopPkt& pkt = *(const RSHELIOSMsopPkt*)(packet); + bool ret = false; + + this->temperature_ = parseTempInLe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) + { + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 1e-6; + } + else + { + uint64_t ts = getTimeHost(); + + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = ts * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + } + } + + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + this->block_az_diff_, this->fov_blind_ts_diff_); + + double block_ts = pkt_ts; + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + { + const RSHELIOSMsopBlock& block = pkt.blocks[blk]; + + if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) + { + this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + break; + } + + int32_t block_az = ntohs(block.azimuth); + if (this->split_strategy_->newBlock(block_az)) + { + this->cb_split_frame_(this->height_, this->prev_point_ts_); + ret = true; + } + + int32_t block_az_diff; + float block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) + { + const RSChannel& channel = block.channels[chan]; + + double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + int32_t angle_horiz = block_az + + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); + + uint16_t laser = chan % 16; + int32_t angle_vert = this->chan_angles_.vertAdjust(laser); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(laser, angle_horiz); + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + + if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) + { + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, chan_ts); + setRing(point, (this->chan_angles_.toUserChan(laser))); + + this->point_cloud_->points.emplace_back(point); + } + else if (!this->param_.dense_points) + { + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, chan_ts); + setRing(point, (this->chan_angles_.toUserChan(laser))); + + this->point_cloud_->points.emplace_back(point); + } + + this->prev_point_ts_ = chan_ts; + } + } + + this->prev_pkt_ts_ = pkt_ts; + return ret; +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 2e7c7dcb..d92543a5 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -35,6 +35,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include #include #include @@ -74,6 +75,9 @@ inline std::shared_ptr> DecoderFactory::crea case LidarType::RSHELIOS: ret_ptr = std::make_shared>(param, excb); break; + case LidarType::RSHELIOS_16P: + ret_ptr = std::make_shared>(param, excb); + break; case LidarType::RS80: ret_ptr = std::make_shared>(param, excb); break; diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 72f673b1..6ceb38fd 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -49,6 +49,7 @@ enum LidarType ///< LiDAR type RS80, RSRUBY_PLUS, RSHELIOS, + RSHELIOS_16P, RSROCK, RSM1 = 10 }; @@ -82,6 +83,9 @@ inline std::string lidarTypeToStr(const LidarType& type) case LidarType::RSHELIOS: str = "RSHELIOS"; break; + case LidarType::RSHELIOS_16P: + str = "RSHELIOS_16P"; + break; case LidarType::RSROCK: str = "RSROCK"; break; @@ -126,6 +130,10 @@ inline LidarType strToLidarType(const std::string& type) { return lidar::LidarType::RSHELIOS; } + else if (type == "RSHELIOS_16P") + { + return lidar::LidarType::RSHELIOS_16P; + } else if (type == "RSROCK") { return lidar::LidarType::RSROCK; @@ -133,7 +141,7 @@ inline LidarType strToLidarType(const std::string& type) else { RS_ERROR << "Wrong lidar type: " << type << RS_REND; - RS_ERROR << "Please setup the correct type: RS16, RS32, RSBP, RS128, RS80, RSRUBY_PLUS, RSM1, RSHELIOS" << RS_REND; + RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS128, RS80, RSRUBY_PLUS, RSM1." << RS_REND; exit(-1); } } From 2edf342cb710d35d37cd6bc714104d192e532da1 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 7 Apr 2022 17:59:32 +0800 Subject: [PATCH 217/379] feat: format --- src/rs_driver/driver/decoder/decoder_RS16.hpp | 1 - src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp | 4 ++-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 9aecb516..b244063e 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -109,7 +109,6 @@ template class DecoderRS16 : public DecoderMech { public: - virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRS16() = default; diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index a1f5a883..1441655e 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -24,7 +24,7 @@ to endorse or promote products derived from this software without specific prior THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -PECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. @@ -235,7 +235,7 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa } } - T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); double block_ts = pkt_ts; From 9411a1ee0cf672c64fd73551f0e037d936381db5 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 7 Apr 2022 18:21:12 +0800 Subject: [PATCH 218/379] feat: format --- src/rs_driver/driver/decoder/decoder.hpp | 2 -- src/rs_driver/driver/decoder/decoder_RS128.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS16.hpp | 3 +-- src/rs_driver/driver/decoder/decoder_RS32.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp | 3 +-- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 5 ++--- src/rs_driver/driver/decoder/decoder_mech.hpp | 1 - 10 files changed, 9 insertions(+), 15 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 7f91f77f..9a1120da 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -284,7 +284,6 @@ class Decoder #define SIN(angle) this->trigon_.sin(angle) #define COS(angle) this->trigon_.cos(angle) - uint16_t height_; double packet_duration_; DistanceSection distance_section_; // invalid section of distance @@ -310,7 +309,6 @@ inline Decoder::Decoder(const RSDecoderConstParam& const_param, , param_(param) , excb_(excb) , write_pkt_ts_(false) - , height_(0) , packet_duration_(0) , distance_section_(const_param.DISTANCE_MIN, const_param.DISTANCE_MAX, param.min_distance, param.max_distance) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 6f7c1fed..e89a9c40 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -262,7 +262,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->height_, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index b244063e..ca975e3a 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -203,7 +203,6 @@ inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, const std::function& excb) : DecoderMech(getConstParam(), param, excb) { - this->height_ = 16; this->packet_duration_ = this->mech_const_param_.BLOCK_DURATION * this->const_param_.BLOCKS_PER_PKT * 2; @@ -287,7 +286,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->height_, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 90fc9728..be2c9466 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -269,7 +269,7 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->height_, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 6ab71d2d..effbeccc 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -246,7 +246,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->height_, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 65825db9..612e3305 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -240,7 +240,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->height_, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 1441655e..0a043221 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -252,7 +252,7 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->height_, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp index 718c18e3..7a79d2c1 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp @@ -138,7 +138,6 @@ inline DecoderRSHELIOS_16P::DecoderRSHELIOS_16P(const RSDecoderPar const std::function& excb) : DecoderMech(getConstParam(), param, excb) { - this->height_ = 16; this->packet_duration_ = this->mech_const_param_.BLOCK_DURATION * this->const_param_.BLOCKS_PER_PKT * 2; @@ -219,7 +218,7 @@ inline bool DecoderRSHELIOS_16P::internDecodeMsopPkt(const uint8_t int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->height_, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 80133e98..8a1e220d 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -171,7 +171,7 @@ inline RSDecoderConstParam& DecoderRSM1::getConstParam() , {0x55, 0xAA, 0x5A, 0xA5} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0x00, 0x00} - , 0 // no meaning for M1 + , 5 // laser number , 25 // blocks per packet , 5 // channels per block , 0.2f // distance min @@ -190,7 +190,6 @@ inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, , max_seq_(SINGLE_PKT_NUM) , split_strategy_(&max_seq_) { - this->height_ = this->const_param_.CHANNELS_PER_BLOCK; this->packet_duration_ = FRAME_DURATION / SINGLE_PKT_NUM; this->angles_ready_ = true; } @@ -298,7 +297,7 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); if (split_strategy_.newPacket(pkt_seq)) { - this->cb_split_frame_(this->height_, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index 01c3d5d5..11ea441f 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -116,7 +116,6 @@ inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& con , block_az_diff_(20) , fov_blind_ts_diff_(0) { - this->height_ = this->const_param_.CHANNELS_PER_BLOCK; this->packet_duration_ = this->mech_const_param_.BLOCK_DURATION * this->const_param_.BLOCKS_PER_PKT; From 3f301b4134405b19a2dbea44a3cd39c4f61744c7 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 7 Apr 2022 18:45:53 +0800 Subject: [PATCH 219/379] fix: fix blks_per_frame for 16 lasers lidar --- src/rs_driver/driver/decoder/decoder_RS16.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index ca975e3a..f4cafae5 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -223,7 +223,7 @@ inline void DecoderRS16::decodeDifopPkt(const uint8_t* packet, siz { this->echo_mode_ = echo_mode; this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? - (this->blks_per_frame_ << 1) : this->blks_per_frame_; + this->blks_per_frame_ : (this->blks_per_frame_ >> 1); calcParam(); } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp index 7a79d2c1..10ee441c 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp @@ -155,7 +155,7 @@ inline void DecoderRSHELIOS_16P::decodeDifopPkt(const uint8_t* pac { this->echo_mode_ = echo_mode; this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? - (this->blks_per_frame_ << 1) : this->blks_per_frame_; + this->blks_per_frame_ : (this->blks_per_frame_ >> 1); calcParam(); } From 354058d5c983fcd7bbf36e2f1919280a44bf541f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 14 Apr 2022 17:06:10 +0800 Subject: [PATCH 220/379] feat: recover demo_online and demo_pcap --- demo/demo_online.cpp | 2 +- demo/demo_pcap.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index aec1e34b..5562204b 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -83,7 +83,7 @@ int main(int argc, char* argv[]) RSDriverParam param; ///< Create a parameter object param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.lidar_type = LidarType::RSM2; ///< Set the lidar type. Make sure this type is correct + param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct param.wait_for_difop = false; ///< true: start sending point cloud until receive difop packet param.print(); diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index d1121007..4ad22359 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -82,11 +82,11 @@ int main(int argc, char* argv[]) RSDriverParam param; ///< Create a parameter object param.input_param.read_pcap = true; ///< Set read_pcap to true - param.input_param.pcap_path = "/home/sti/dev/share/pcap/M2/M2.pcap"; ///< Set the pcap file directory + param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file directory param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 param.wait_for_difop = false; - param.lidar_type = LidarType::RSM2; ///< Set the lidar type. Make sure this type is correct + param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct param.print(); From 0a252df320c602f0e916274f321ee266580062a5 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 15 Apr 2022 15:22:01 +0800 Subject: [PATCH 221/379] fix: fix ruby_plus firing table --- .../driver/decoder/decoder_RSRUBY_PLUS.hpp | 38 ++++++++++--------- 1 file changed, 20 insertions(+), 18 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp b/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp index e6121262..64de33a6 100644 --- a/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp @@ -89,26 +89,28 @@ inline RSDecoderMechConstParam& DecoderRSRUBY_PLUS::getConstParam( INIT_ONLY_ONCE(); - float blk_ts = 50.984f; + float blk_ts = 55.56f; float firing_tss[] = { - 0.24f, 0.24f, 0.24f, 0.24f, 1.084f, 1.084f, 1.084f, 1.084f, - 1.932f, 1.932f, 1.932f, 1.932f, 2.872f, 2.872f, 2.872f, 2.872f, - 3.824f, 3.824f, 3.824f, 3.824f, 4.684f, 4.684f, 4.684f, 4.684f, - 5.540f, 5.540f, 5.540f, 5.540f, 6.496f, 6.496f, 6.496f, 6.496f, - 7.440f, 7.440f, 7.440f, 7.440f, 9.348f, 9.348f, 9.348f, 9.348f, - 11.260f, 11.260f, 11.260f, 11.260f, 13.264f, 13.264f, 13.264f, 13.264f, - 15.280f, 15.280f, 15.280f, 15.280f, 17.204f, 17.204f, 17.204f, 17.204f, - 19.124f, 19.124f, 19.124f, 19.124f, 21.144f, 21.144f, 21.144f, 21.144f, - - 23.152f, 23.152f, 23.152f, 23.152f, 25.060f, 25.060f, 25.060f, 25.060f, - 26.972f, 26.972f, 26.972f, 26.972f, 28.976f, 28.976f, 28.976f, 28.976f, - 30.992f, 30.992f, 30.992f, 30.992f, 32.916f, 32.916f, 32.916f, 32.916f, - 34.836f, 34.836f, 34.836f, 34.836f, 36.856f, 36.856f, 36.856f, 36.856f, - 38.864f, 38.864f, 38.864f, 38.864f, 40.272f, 40.272f, 40.272f, 40.272f, - 41.684f, 41.684f, 41.684f, 41.684f, 43.188f, 43.188f, 43.188f, 43.188f, - 44.704f, 44.704f, 44.704f, 44.704f, 46.128f, 46.128f, 46.128f, 46.128f, - 47.548f, 47.548f, 47.548f, 47.548f, 49.068f, 49.068f, 49.068f, 49.068f + 0.0f, 0.0f, 0.0f, 0.0f, 1.217f, 1.217f, 1.217f, 1.217f, + 2.434f, 2.434f, 2.434f, 2.434f, 3.652f, 3.652f, 3.652f, 3.652f, + 4.869f, 4.869f, 4.869f, 4.869f, 6.086f, 6.086f, 6.086f, 6.086f, + 7.304f, 7.304f, 7.304f, 7.304f, 8.521f, 8.521f, 8.521f, 8.521f, + + 9.739f, 9.739f, 9.739f, 9.739f, 11.323f, 11.323f, 11.323f, 11.323f, + 12.907f, 12.907f, 12.907f, 12.907f, 14.924f, 14.924f, 14.924f, 14.924f, + 16.941f, 16.941f, 16.941f, 16.941f, 18.959f, 18.959f, 18.959f, 18.959f, + 20.976f, 20.976f, 20.976f, 20.976f, 23.127f, 23.127f, 23.127f, 23.127f, + + 25.278f, 25.278f, 25.278f, 25.278f, 27.428f, 27.428f, 27.428f, 27.428f, + 29.579f, 29.579f, 29.579f, 29.579f, 31.963f, 31.963f, 31.963f, 31.963f, + 34.347f, 34.347f, 34.347f, 34.347f, 36.498f, 36.498f, 36.498f, 36.498f, + 38.648f, 38.648f, 38.648f, 38.648f, 40.666f, 40.666f, 40.666f, 40.666f, + + 42.683f, 42.683f, 42.683f, 42.683f, 44.267f, 44.267f, 44.267f, 44.267f, + 45.851f, 45.851f, 45.851f, 45.851f, 47.435f, 47.435f, 47.435f, 47.435f, + 49.019f, 49.019f, 49.019f, 49.019f, 50.603f, 50.603f, 50.603f, 50.603f, + 52.187f, 52.187f, 52.187f, 52.187f, 53.771f, 53.771f, 53.771f, 53.771f, }; param.BLOCK_DURATION = blk_ts / 1000000; From 934610a8949a9cd0e8791f278154d3b528181332 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 19 Apr 2022 09:38:52 +0800 Subject: [PATCH 222/379] format --- demo/demo_online.cpp | 5 +---- src/rs_driver/msg/pcl_point_cloud_msg.hpp | 2 +- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 710616d5..2c82009d 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -83,10 +83,7 @@ int main(int argc, char* argv[]) param.input_type = InputType::ONLINE_LIDAR; param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 - param.input_param.user_layer_bytes = 8; - param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct - param.decoder_param.wait_for_difop = true; ///< true: start sending point cloud until receive difop packet - param.decoder_param.use_lidar_clock = false; + param.lidar_type = LidarType::RS32; ///< Set the lidar type. Make sure this type is correct param.print(); LidarDriver driver; diff --git a/src/rs_driver/msg/pcl_point_cloud_msg.hpp b/src/rs_driver/msg/pcl_point_cloud_msg.hpp index f9a51575..b9c59a99 100644 --- a/src/rs_driver/msg/pcl_point_cloud_msg.hpp +++ b/src/rs_driver/msg/pcl_point_cloud_msg.hpp @@ -47,7 +47,7 @@ struct PointXYZIRT } EIGEN_ALIGN16; POINT_CLOUD_REGISTER_POINT_STRUCT(PointXYZIRT, (float, x, x)(float, y, y)(float, z, z) - (uint8_t, intensity, intensity)(uint16_t, ring, ring)(double, timestamp, timestamp)) + (std::uint8_t, intensity, intensity)(std::uint16_t, ring, ring)(double, timestamp, timestamp)) template class PointCloudT : public pcl::PointCloud From 76013bdb78d07af11a29da8fcdd27fe15cddcee8 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 21 Apr 2022 19:07:55 +0800 Subject: [PATCH 223/379] feat: tag v1.4.6 --- CHANGELOG.md | 10 ++++++++++ CMakeLists.txt | 2 +- 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 7e8605b8..0be27b16 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,15 @@ # Changelog +## v1.4.6 - 2022-04-21 + +### Added +- Check msop timeout +- Support M2 +- add cmake option ENABLE_RECVMMSG + +### Changed +- Optimize point cloud transform + ## v1.4.5 - 2022-03-09 ### Added diff --git a/CMakeLists.txt b/CMakeLists.txt index bd6c70f1..cfd5c1d6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.4.5) +project(rs_driver VERSION 1.4.6) #============================= # Compile Demos&Tools From b9333ac9ab90b1257ec730dd44d4aae255527c7b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 22 Apr 2022 12:15:22 +0800 Subject: [PATCH 224/379] feat: support M2 --- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 269 ++++++++---------- .../driver/decoder/decoder_factory.hpp | 7 +- src/rs_driver/driver/driver_param.hpp | 47 +-- 3 files changed, 152 insertions(+), 171 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index 8bc9699a..a4a69af4 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -31,20 +31,27 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once -#include +#include namespace robosense { namespace lidar { -const size_t M2_MSOP_LEN = 1336; -const size_t M2_DIFOP_LEN = 256; - -const uint32_t M2_SINGLE_PKT_NUM = 1260; -const uint32_t M2_DUAL_PKT_NUM = 2520; - #pragma pack(push, 1) +typedef struct +{ + uint8_t id[4]; + uint16_t pkt_seq; + uint16_t protocol_version; + uint8_t return_mode; + uint8_t time_mode; + RSTimestampUTC timestamp; + uint8_t reserved[10]; + uint8_t lidar_type; + int8_t temperature; +} RSM2MsopHeader; + typedef struct { uint16_t distance; @@ -62,19 +69,6 @@ typedef struct RSM2Channel channel[5]; } RSM2Block; -typedef struct -{ - uint32_t id; - uint16_t pkt_cnt; - uint16_t protocol_version; - uint8_t return_mode; - uint8_t time_mode; - RSTimestampUTC timestamp; - uint8_t reserved[10]; - uint8_t lidar_type; - int8_t temperature; -} RSM2MsopHeader; - typedef struct { RSM2MsopHeader header; @@ -85,81 +79,86 @@ typedef struct #pragma pack(pop) template -class DecoderRSM2 : public DecoderBase +class DecoderRSM2 : public Decoder { public: - DecoderRSM2(const RSDecoderParam& param, const LidarConstantParameter& lidar_const_param); - RSDecoderResult decodeDifopPkt(const uint8_t* pkt); - RSDecoderResult decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, int& height, int& azimuth); - double getLidarTime(const uint8_t* pkt); - RSDecoderResult processMsopPkt(const uint8_t* pkt, size_t size, typename T_PointCloud::VectorT& pointcloud_vec, - int& height); + + constexpr static double FRAME_DURATION = 0.1; + constexpr static uint32_t SINGLE_PKT_NUM = 1260; + constexpr static uint32_t DUAL_PKT_NUM = 2520; + + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRSM2() = default; + + explicit DecoderRSM2(const RSDecoderParam& param, + const std::function& excb); private: - uint32_t max_pkt_num_; - uint32_t last_pkt_cnt_; - double last_pkt_time_; + + static RSDecoderConstParam& getConstParam(); + RSEchoMode getEchoMode(uint8_t mode); + + uint16_t max_seq_; + SplitStrategyBySeq split_strategy_; }; template -inline DecoderRSM2::DecoderRSM2(const RSDecoderParam& param, - const LidarConstantParameter& lidar_const_param) - : DecoderBase(param, lidar_const_param) - , max_pkt_num_(M2_SINGLE_PKT_NUM) - , last_pkt_cnt_(1) - , last_pkt_time_(0) +inline RSDecoderConstParam& DecoderRSM2::getConstParam() { - this->msop_pkt_len_ = M2_MSOP_LEN; - this->difop_pkt_len_ = M2_DIFOP_LEN; - - if (this->param_.max_distance > 200.0f) - { - this->param_.max_distance = 200.0f; - } - if (this->param_.min_distance < 0.2f || this->param_.min_distance > this->param_.max_distance) + static RSDecoderConstParam param = { - this->param_.min_distance = 0.2f; - } - this->time_duration_between_blocks_ = 5 * 1e-6; + 1336 // msop len + , 256 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x5A, 0xA5} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0x00, 0x00} + , 5 // laser number + , 25 // blocks per packet + , 5 // channels per block + , 0.2f // distance min + , 200.0f // distance max + , 0.005f // distance resolution + , 80.0f // initial value of temperature + }; + + return param; } template -inline double DecoderRSM2::getLidarTime(const uint8_t* pkt) +inline DecoderRSM2::DecoderRSM2(const RSDecoderParam& param, + const std::function& excb) + : Decoder(getConstParam(), param, excb) + , max_seq_(SINGLE_PKT_NUM) + , split_strategy_(&max_seq_) { - return this->template calculateTimeUTC(pkt, LidarType::RSM2); + this->packet_duration_ = FRAME_DURATION / SINGLE_PKT_NUM; + this->angles_ready_ = true; } template -inline RSDecoderResult DecoderRSM2::processMsopPkt(const uint8_t* pkt, size_t size, - typename T_PointCloud::VectorT& pointcloud_vec, - int& height) +inline RSEchoMode DecoderRSM2::getEchoMode(uint8_t mode) { - if (size != this->msop_pkt_len_) - { - return WRONG_PKT_LENGTH; - } - - int azimuth = 0; - RSDecoderResult ret = decodeMsopPkt(pkt, pointcloud_vec, height, azimuth); - this->pkt_count_++; - switch (this->param_.split_frame_mode) + switch (mode) { - case SplitFrameMode::SPLIT_BY_ANGLE: - case SplitFrameMode::SPLIT_BY_FIXED_PKTS: - return ret; - case SplitFrameMode::SPLIT_BY_CUSTOM_PKTS: - if (this->pkt_count_ >= this->param_.num_pkts_split) - { - this->pkt_count_ = 0; - this->trigger_index_ = 0; - this->prev_angle_diff_ = RS_ONE_ROUND; - return FRAME_SPLIT; - } - break; + case 0x00: // dual return + return RSEchoMode::ECHO_DUAL; + case 0x04: // strongest return + case 0x05: // last return + case 0x06: // first return default: - break; + return RSEchoMode::ECHO_SINGLE; } - return DECODE_OK; +} + +template +inline void DecoderRSM2::decodeDifopPkt(const uint8_t* packet, size_t size) +{ + const RSM1DifopPkt& pkt = *(RSM1DifopPkt*)packet; + this->echo_mode_ = this->getEchoMode(pkt.return_mode); + max_seq_ = (this->echo_mode_ == ECHO_SINGLE) ? SINGLE_PKT_NUM : DUAL_PKT_NUM; } inline int16_t RS_SWAP_INT16(int16_t value) @@ -175,105 +174,87 @@ inline int16_t RS_SWAP_INT16(int16_t value) } template -inline RSDecoderResult DecoderRSM2::decodeMsopPkt(const uint8_t* pkt, typename T_PointCloud::VectorT& vec, - int& height, int& azimuth) +inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size_t size) { - height = this->lidar_const_param_.LASER_NUM; - const RSM2MsopPkt* mpkt_ptr = (RSM2MsopPkt*)pkt; - if (mpkt_ptr->header.id != this->lidar_const_param_.MSOP_ID) + const RSM2MsopPkt& pkt = *(RSM2MsopPkt*)packet; + bool ret = false; + + this->temperature_ = static_cast(pkt.header.temperature - this->const_param_.TEMPERATURE_RES); + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) { - return RSDecoderResult::WRONG_PKT_HEADER; + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 1e-6; } - this->current_temperature_ = static_cast(mpkt_ptr->header.temperature - 80); - this->protocol_ver_ = RS_SWAP_SHORT(mpkt_ptr->header.protocol_version); - double pkt_timestamp = 0; - switch (mpkt_ptr->blocks[0].return_seq) + else { - case 0: - pkt_timestamp = this->get_point_time_func_(pkt); - break; - case 1: - pkt_timestamp = this->get_point_time_func_(pkt); - last_pkt_time_ = pkt_timestamp; - break; - case 2: - pkt_timestamp = last_pkt_time_; - break; - } + uint64_t ts = getTimeHost(); - for (size_t blk_idx = 0; blk_idx < this->lidar_const_param_.BLOCKS_PER_PKT; blk_idx++) + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = getTimeHost() * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + } + } + + for (size_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { - const RSM2Block& blk = mpkt_ptr->blocks[blk_idx]; - double point_time = pkt_timestamp + blk.time_offset * 1e-6; - for (size_t channel_idx = 0; channel_idx < this->lidar_const_param_.CHANNELS_PER_BLOCK; channel_idx++) + const RSM2Block& block = pkt.blocks[blk]; + + double point_time = pkt_ts + block.time_offset * 1e-6; + + for (size_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { - const RSM2Channel& channel = blk.channel[channel_idx]; + const RSM2Channel& channel = block.channel[chan]; + + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; - typename T_PointCloud::PointT point; - bool pointValid = false; - float distance = RS_SWAP_SHORT(channel.distance) * this->lidar_const_param_.DIS_RESOLUTION; - if (distance <= this->param_.max_distance && distance >= this->param_.min_distance) + if (this->distance_section_.in(distance)) { float x = RS_SWAP_INT16(channel.x) / 32768.0 * distance; float y = RS_SWAP_INT16(channel.y) / 32768.0 * distance; float z = RS_SWAP_INT16(channel.z) / 32768.0 * distance; - - uint8_t intensity = channel.intensity; - this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; setX(point, x); setY(point, y); setZ(point, z); - setIntensity(point, intensity); - pointValid = true; + setIntensity(point, channel.intensity); + setTimestamp(point, point_time); + setRing(point, chan); + + this->point_cloud_->points.emplace_back(point); } - else if (!this->param_.is_dense) + else if (!this->param_.dense_points) { + typename T_PointCloud::PointT point; setX(point, NAN); setY(point, NAN); setZ(point, NAN); setIntensity(point, 0); - pointValid = true; - } - - if (pointValid) - { setTimestamp(point, point_time); - setRing(point, channel_idx + 1); - vec.emplace_back(std::move(point)); + setRing(point, chan); + + this->point_cloud_->points.emplace_back(point); } } - } - unsigned int pkt_cnt = RS_SWAP_SHORT(mpkt_ptr->header.pkt_cnt); - // TODO whatif packet loss or seq unorder - if (pkt_cnt == max_pkt_num_ || pkt_cnt < last_pkt_cnt_) - { - last_pkt_cnt_ = 1; - return RSDecoderResult::FRAME_SPLIT; + this->prev_point_ts_ = point_time; } - last_pkt_cnt_ = pkt_cnt; - return RSDecoderResult::DECODE_OK; -} -template -inline RSDecoderResult DecoderRSM2::decodeDifopPkt(const uint8_t* pkt) -{ - RSM1DifopPkt* dpkt_ptr = (RSM1DifopPkt*)pkt; - if (dpkt_ptr->id != this->lidar_const_param_.DIFOP_ID) - { - return RSDecoderResult::WRONG_PKT_HEADER; - } - if (!this->difop_flag_) + this->prev_pkt_ts_ = pkt_ts; + + uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); + if (split_strategy_.newPacket(pkt_seq)) { - this->echo_mode_ = this->getEchoMode(LidarType::RSM2, dpkt_ptr->return_mode); - if (this->echo_mode_ == RSEchoMode::ECHO_DUAL) - { - max_pkt_num_ = M2_DUAL_PKT_NUM; - } - this->difop_flag_ = true; + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + ret = true; } - return RSDecoderResult::DECODE_OK; + + return ret; } } // namespace lidar diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index d7c01cc1..1018c487 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -40,7 +40,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -//#include +#include + namespace robosense { namespace lidar @@ -90,11 +91,9 @@ inline std::shared_ptr> DecoderFactory::crea case LidarType::RSM1: ret_ptr = std::make_shared>(param, excb); break; -#if 0 case LidarType::RSM2: - ret_ptr = std::make_shared>(param.decoder_param, getRSM1ConstantParam()); + ret_ptr = std::make_shared>(param, excb); break; -#endif default: RS_ERROR << "Wrong LiDAR Type. Please check your LiDAR Version! " << RS_REND; exit(-1); diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index a81d506f..5559acc3 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -69,26 +69,26 @@ inline std::string lidarTypeToStr(const LidarType& type) case LidarType::RSBP: str = "RSBP"; break; - case LidarType::RS128: - str = "RS128"; + case LidarType::RSHELIOS: + str = "RSHELIOS"; + break; + case LidarType::RSHELIOS_16P: + str = "RSHELIOS_16P"; break; case LidarType::RS80: str = "RS80"; break; + case LidarType::RS128: + str = "RS128"; + break; case LidarType::RSRUBY_PLUS: str = "RSRUBY_PLUS"; break; case LidarType::RSM1: str = "RSM1"; break; - case LidarType::RSHELIOS: - str = "RSHELIOS"; - break; - case LidarType::RSHELIOS_16P: - str = "RSHELIOS_16P"; - break; - case LidarType::RSROCK: - str = "RSROCK"; + case LidarType::RSM2: + str = "RSM2"; break; default: str = "ERROR"; @@ -111,14 +111,22 @@ inline LidarType strToLidarType(const std::string& type) { return lidar::LidarType::RSBP; } - else if (type == "RS128") + else if (type == "RSHELIOS") { - return lidar::LidarType::RS128; + return lidar::LidarType::RSHELIOS; + } + else if (type == "RSHELIOS_16P") + { + return lidar::LidarType::RSHELIOS_16P; } else if (type == "RS80") { return lidar::LidarType::RS80; } + else if (type == "RS128") + { + return lidar::LidarType::RS128; + } else if (type == "RSRUBY_PLUS") { return lidar::LidarType::RSRUBY_PLUS; @@ -127,22 +135,15 @@ inline LidarType strToLidarType(const std::string& type) { return lidar::LidarType::RSM1; } - else if (type == "RSHELIOS") - { - return lidar::LidarType::RSHELIOS; - } - else if (type == "RSHELIOS_16P") - { - return lidar::LidarType::RSHELIOS_16P; - } - else if (type == "RSROCK") + else if (type == "RSM2") { - return lidar::LidarType::RSROCK; + return lidar::LidarType::RSM2; } else { RS_ERROR << "Wrong lidar type: " << type << RS_REND; - RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS128, RS80, RSRUBY_PLUS, RSM1." << RS_REND; + RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS80, RS128, RSRUBY_PLUS, RSM1, RSM2." + << RS_REND; exit(-1); } } From 8c857a9f822de45ce9f8395ee65fd3488b54e4ae Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 22 Apr 2022 17:57:32 +0800 Subject: [PATCH 225/379] format: format --- src/rs_driver/api/lidar_driver.hpp | 10 +- src/rs_driver/driver/decoder/decoder.hpp | 34 +++---- .../driver/decoder/decoder_RS128.hpp | 18 ++-- src/rs_driver/driver/decoder/decoder_RS16.hpp | 10 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 10 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 10 +- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 10 +- .../driver/decoder/decoder_RSHELIOS.hpp | 10 +- .../driver/decoder/decoder_RSHELIOS_16P.hpp | 10 +- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 8 +- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 8 +- .../driver/decoder/decoder_RSRUBY_PLUS.hpp | 8 +- .../driver/decoder/decoder_factory.hpp | 28 +++--- src/rs_driver/driver/decoder/decoder_mech.hpp | 9 +- src/rs_driver/driver/input/input.hpp | 35 +++---- src/rs_driver/driver/input/input_factory.hpp | 12 +-- src/rs_driver/driver/input/input_pcap.hpp | 21 +++-- src/rs_driver/driver/input/input_raw.hpp | 6 +- src/rs_driver/driver/input/input_sock.hpp | 18 ++-- src/rs_driver/driver/lidar_driver_impl.hpp | 92 +++++++++---------- 20 files changed, 173 insertions(+), 194 deletions(-) diff --git a/src/rs_driver/api/lidar_driver.hpp b/src/rs_driver/api/lidar_driver.hpp index 7865dbd2..4e2ec9b9 100644 --- a/src/rs_driver/api/lidar_driver.hpp +++ b/src/rs_driver/api/lidar_driver.hpp @@ -63,10 +63,10 @@ class LidarDriver * called * @param callback The callback function */ - inline void regPointCloudCallback(const std::function(void)>& cb_get_pc, - const std::function)>& cb_put_pc) + inline void regPointCloudCallback(const std::function(void)>& cb_get_cloud, + const std::function)>& cb_put_cloud) { - driver_ptr_->regPointCloudCallback(cb_get_pc, cb_put_pc); + driver_ptr_->regPointCloudCallback(cb_get_cloud, cb_put_cloud); } /** @@ -83,9 +83,9 @@ class LidarDriver * @brief Register the exception message callback function to driver. When error occurs, this function will be called * @param callback The callback function */ - inline void regExceptionCallback(const std::function& cb_excp) + inline void regExceptionCallback(const std::function& cb_excep) { - driver_ptr_->regExceptionCallback(cb_excp); + driver_ptr_->regExceptionCallback(cb_excep); } /** diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 9a1120da..3bb78161 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -257,9 +257,7 @@ class Decoder void processDifopPkt(const uint8_t* pkt, size_t size); bool processMsopPkt(const uint8_t* pkt, size_t size); - explicit Decoder(const RSDecoderConstParam& const_param, - const RSDecoderParam& param, - const std::function& excb); + explicit Decoder(const RSDecoderConstParam& const_param, const RSDecoderParam& param); float getTemperature(); double getPacketDuration(); @@ -267,7 +265,10 @@ class Decoder double prevPktTs(); void transformPoint(float& x, float& y, float& z); - void setSplitCallback(const std::function& cb_split_frame); + void regCallback( + const std::function& cb_excep, + const std::function& cb_split_frame); + std::shared_ptr point_cloud_; // accumulated point cloud currently #ifndef UNIT_TEST @@ -277,7 +278,7 @@ class Decoder RSDecoderConstParam const_param_; // const param RSDecoderParam param_; // user param std::function cb_split_frame_; - std::function excb_; + std::function cb_excep_; bool write_pkt_ts_; Trigon trigon_; @@ -296,22 +297,21 @@ class Decoder }; template -inline void Decoder::setSplitCallback(const std::function& cb_split_frame) +inline void Decoder::regCallback( + const std::function& cb_excep, + const std::function& cb_split_frame) { + cb_excep_ = cb_excep; cb_split_frame_ = cb_split_frame; } template -inline Decoder::Decoder(const RSDecoderConstParam& const_param, - const RSDecoderParam& param, - const std::function& excb) +inline Decoder::Decoder(const RSDecoderConstParam& const_param, const RSDecoderParam& param) : const_param_(const_param) , param_(param) - , excb_(excb) , write_pkt_ts_(false) , packet_duration_(0) - , distance_section_(const_param.DISTANCE_MIN, const_param.DISTANCE_MAX, - param.min_distance, param.max_distance) + , distance_section_(const_param.DISTANCE_MIN, const_param.DISTANCE_MAX, param.min_distance, param.max_distance) , echo_mode_(ECHO_SINGLE) , temperature_(0.0) , angles_ready_(false) @@ -367,13 +367,13 @@ inline void Decoder::processDifopPkt(const uint8_t* pkt, size_t si { if (size != this->const_param_.DIFOP_LEN) { - this->excb_(Error(ERRCODE_WRONGPKTLENGTH)); + this->cb_excep_(Error(ERRCODE_WRONGPKTLENGTH)); return; } if (memcmp(pkt, this->const_param_.DIFOP_ID, const_param_.DIFOP_ID_LEN) != 0) { - this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); return; } @@ -385,19 +385,19 @@ inline bool Decoder::processMsopPkt(const uint8_t* pkt, size_t siz { if (param_.wait_for_difop && !angles_ready_) { - excb_(Error(ERRCODE_NODIFOPRECV)); + cb_excep_(Error(ERRCODE_NODIFOPRECV)); return false; } if (size != this->const_param_.MSOP_LEN) { - this->excb_(Error(ERRCODE_WRONGPKTLENGTH)); + this->cb_excep_(Error(ERRCODE_WRONGPKTLENGTH)); return false; } if (memcmp(pkt, this->const_param_.MSOP_ID, const_param_.MSOP_ID_LEN) != 0) { - this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); return false; } diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index e89a9c40..0c529a57 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -87,12 +87,10 @@ class DecoderRS128 : public DecoderMech virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRS128() = default; - explicit DecoderRS128(const RSDecoderParam& param, - const std::function& excb); + explicit DecoderRS128(const RSDecoderParam& param); explicit DecoderRS128(const RSDecoderMechConstParam& const_param, - const RSDecoderParam& param, - const std::function& excb); + const RSDecoderParam& param); #ifndef UNIT_TEST protected: @@ -180,17 +178,15 @@ inline RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) } template -inline DecoderRS128::DecoderRS128(const RSDecoderParam& param, - const std::function& excb) - : DecoderMech(getConstParam(), param, excb) +inline DecoderRS128::DecoderRS128(const RSDecoderParam& param) + : DecoderMech(getConstParam(), param) { } template inline DecoderRS128::DecoderRS128(const RSDecoderMechConstParam& const_param, - const RSDecoderParam& param, - const std::function& excb) - : DecoderMech(const_param, param, excb) + const RSDecoderParam& param) + : DecoderMech(const_param, param) { } @@ -255,7 +251,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { - this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index f4cafae5..b7a4d01d 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -113,8 +113,7 @@ class DecoderRS16 : public DecoderMech virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRS16() = default; - explicit DecoderRS16(const RSDecoderParam& param, - const std::function& excb); + explicit DecoderRS16(const RSDecoderParam& param); #ifndef UNIT_TEST protected: @@ -199,9 +198,8 @@ inline RSEchoMode DecoderRS16::getEchoMode(uint8_t mode) } template -inline DecoderRS16::DecoderRS16(const RSDecoderParam& param, - const std::function& excb) - : DecoderMech(getConstParam(), param, excb) +inline DecoderRS16::DecoderRS16(const RSDecoderParam& param) + : DecoderMech(getConstParam(), param) { this->packet_duration_ = this->mech_const_param_.BLOCK_DURATION * this->const_param_.BLOCKS_PER_PKT * 2; @@ -279,7 +277,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { - this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index be2c9466..241d4843 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -116,8 +116,7 @@ class DecoderRS32 : public DecoderMech virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRS32() = default; - explicit DecoderRS32(const RSDecoderParam& param, - const std::function& excb); + explicit DecoderRS32(const RSDecoderParam& param); #ifndef UNIT_TEST protected: @@ -192,9 +191,8 @@ inline RSEchoMode DecoderRS32::getEchoMode(uint8_t mode) } template -inline DecoderRS32::DecoderRS32(const RSDecoderParam& param, - const std::function& excb) - : DecoderMech(getConstParam(), param, excb) +inline DecoderRS32::DecoderRS32(const RSDecoderParam& param) + : DecoderMech(getConstParam(), param) { } @@ -262,7 +260,7 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { - this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index effbeccc..af74f181 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -89,8 +89,7 @@ class DecoderRS80 : public DecoderMech virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRS80() = default; - explicit DecoderRS80(const RSDecoderParam& param, - const std::function& excb); + explicit DecoderRS80(const RSDecoderParam& param); #ifndef UNIT_TEST protected: @@ -172,9 +171,8 @@ inline RSEchoMode DecoderRS80::getEchoMode(uint8_t mode) } template -inline DecoderRS80::DecoderRS80(const RSDecoderParam& param, - const std::function& excb) - : DecoderMech(getConstParam(), param, excb) +inline DecoderRS80::DecoderRS80(const RSDecoderParam& param) + : DecoderMech(getConstParam(), param) { } @@ -239,7 +237,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { - this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 612e3305..463b216b 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -90,8 +90,7 @@ class DecoderRSBP : public DecoderMech virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRSBP() = default; - explicit DecoderRSBP(const RSDecoderParam& param, - const std::function& excb); + explicit DecoderRSBP(const RSDecoderParam& param); #ifndef UNIT_TEST protected: @@ -166,9 +165,8 @@ inline RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) } template -inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param, - const std::function& excb) - : DecoderMech(getConstParam(), param, excb) +inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param) + : DecoderMech(getConstParam(), param) { } @@ -233,7 +231,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { - this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 0a043221..1403fa41 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -101,8 +101,7 @@ class DecoderRSHELIOS : public DecoderMech virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRSHELIOS() = default; - explicit DecoderRSHELIOS(const RSDecoderParam& param, - const std::function& excb); + explicit DecoderRSHELIOS(const RSDecoderParam& param); #ifndef UNIT_TEST protected: @@ -178,9 +177,8 @@ inline RSEchoMode DecoderRSHELIOS::getEchoMode(uint8_t mode) } template -inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param, - const std::function& excb) - : DecoderMech(getConstParam(), param, excb) +inline DecoderRSHELIOS::DecoderRSHELIOS(const RSDecoderParam& param) + : DecoderMech(getConstParam(), param) { } @@ -245,7 +243,7 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { - this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp index 10ee441c..8c1ceeac 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp @@ -47,8 +47,7 @@ class DecoderRSHELIOS_16P : public DecoderMech virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRSHELIOS_16P() = default; - explicit DecoderRSHELIOS_16P(const RSDecoderParam& param, - const std::function& excb); + explicit DecoderRSHELIOS_16P(const RSDecoderParam& param); #ifndef UNIT_TEST protected: @@ -134,9 +133,8 @@ inline RSEchoMode DecoderRSHELIOS_16P::getEchoMode(uint8_t mode) } template -inline DecoderRSHELIOS_16P::DecoderRSHELIOS_16P(const RSDecoderParam& param, - const std::function& excb) - : DecoderMech(getConstParam(), param, excb) +inline DecoderRSHELIOS_16P::DecoderRSHELIOS_16P(const RSDecoderParam& param) + : DecoderMech(getConstParam(), param) { this->packet_duration_ = this->mech_const_param_.BLOCK_DURATION * this->const_param_.BLOCKS_PER_PKT * 2; @@ -211,7 +209,7 @@ inline bool DecoderRSHELIOS_16P::internDecodeMsopPkt(const uint8_t if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { - this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 8a1e220d..66dcb73d 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -147,8 +147,7 @@ class DecoderRSM1 : public Decoder virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRSM1() = default; - explicit DecoderRSM1(const RSDecoderParam& param, - const std::function& excb); + explicit DecoderRSM1(const RSDecoderParam& param); private: @@ -184,9 +183,8 @@ inline RSDecoderConstParam& DecoderRSM1::getConstParam() } template -inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param, - const std::function& excb) - : Decoder(getConstParam(), param, excb) +inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param) + : Decoder(getConstParam(), param) , max_seq_(SINGLE_PKT_NUM) , split_strategy_(&max_seq_) { diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index a4a69af4..426f9d75 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -91,8 +91,7 @@ class DecoderRSM2 : public Decoder virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRSM2() = default; - explicit DecoderRSM2(const RSDecoderParam& param, - const std::function& excb); + explicit DecoderRSM2(const RSDecoderParam& param); private: @@ -128,9 +127,8 @@ inline RSDecoderConstParam& DecoderRSM2::getConstParam() } template -inline DecoderRSM2::DecoderRSM2(const RSDecoderParam& param, - const std::function& excb) - : Decoder(getConstParam(), param, excb) +inline DecoderRSM2::DecoderRSM2(const RSDecoderParam& param) + : Decoder(getConstParam(), param) , max_seq_(SINGLE_PKT_NUM) , split_strategy_(&max_seq_) { diff --git a/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp b/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp index 64de33a6..3a5a9027 100644 --- a/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp @@ -47,8 +47,7 @@ class DecoderRSRUBY_PLUS : public DecoderRS128 //virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); virtual ~DecoderRSRUBY_PLUS() = default; - explicit DecoderRSRUBY_PLUS(const RSDecoderParam& param, - const std::function& excb); + explicit DecoderRSRUBY_PLUS(const RSDecoderParam& param); #ifndef UNIT_TEST protected: @@ -153,9 +152,8 @@ inline void DecoderRSRUBY_PLUS::decodeDifopPkt(const uint8_t* pack template -inline DecoderRSRUBY_PLUS::DecoderRSRUBY_PLUS(const RSDecoderParam& param, - const std::function& excb) - : DecoderRS128(getConstParam(), param, excb) +inline DecoderRSRUBY_PLUS::DecoderRSRUBY_PLUS(const RSDecoderParam& param) + : DecoderRS128(getConstParam(), param) { } diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 1018c487..b02d33a6 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -52,47 +52,47 @@ class DecoderFactory { public: - static std::shared_ptr> createDecoder(LidarType type, - const RSDecoderParam& param, const std::function& excb); + static std::shared_ptr> createDecoder( + LidarType type, const RSDecoderParam& param); }; template -inline std::shared_ptr> DecoderFactory::createDecoder(LidarType type, - const RSDecoderParam& param, const std::function& excb) +inline std::shared_ptr> DecoderFactory::createDecoder( + LidarType type, const RSDecoderParam& param) { std::shared_ptr> ret_ptr; switch (type) { case LidarType::RS16: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared>(param); break; case LidarType::RS32: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared>(param); break; case LidarType::RSBP: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared>(param); break; case LidarType::RSHELIOS: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared>(param); break; case LidarType::RSHELIOS_16P: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared>(param); break; case LidarType::RS80: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared>(param); break; case LidarType::RS128: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared>(param); break; case LidarType::RSRUBY_PLUS: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared>(param); break; case LidarType::RSM1: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared>(param); break; case LidarType::RSM2: - ret_ptr = std::make_shared>(param, excb); + ret_ptr = std::make_shared>(param); break; default: RS_ERROR << "Wrong LiDAR Type. Please check your LiDAR Version! " << RS_REND; diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index 11ea441f..adce75e1 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -74,9 +74,7 @@ class DecoderMech : public Decoder virtual ~DecoderMech() = default; - explicit DecoderMech(const RSDecoderMechConstParam& const_param, - const RSDecoderParam& param, - const std::function& excb); + explicit DecoderMech(const RSDecoderMechConstParam& const_param, const RSDecoderParam& param); void print(); @@ -104,9 +102,8 @@ class DecoderMech : public Decoder template inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& const_param, - const RSDecoderParam& param, - const std::function& excb) - : Decoder(const_param.base, param, excb) + const RSDecoderParam& param) + : Decoder(const_param.base, param) , mech_const_param_(const_param) , chan_angles_(this->const_param_.LASER_NUM) , scan_section_(this->param_.start_angle * 100, this->param_.end_angle * 100) diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index 4871fae2..e0e0c240 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -40,9 +40,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #define MAX_PKT_LEN 1500 -#define ETH_HDR_LEN 42 -#define VLAN_LEN 4 -#define SOME_IP_LEN 16 namespace robosense { @@ -51,10 +48,12 @@ namespace lidar class Input { public: - Input(const RSInputParam& input_param, const std::function& excb); + Input(const RSInputParam& input_param); - inline void regRecvCallback(const std::function(size_t)>& cb_get, - const std::function)>& cb_put); + inline void regCallback( + const std::function& cb_excep, + const std::function(size_t)>& cb_get_pkt, + const std::function)>& cb_put_pkt); virtual bool init() = 0; virtual bool start() = 0; @@ -67,27 +66,29 @@ class Input inline void pushPacket(std::shared_ptr pkt); RSInputParam input_param_; - std::function(size_t size)> cb_get_; - std::function)> cb_put_; - std::function excb_; + std::function(size_t size)> cb_get_pkt_; + std::function)> cb_put_pkt_; + std::function cb_excep_; std::thread recv_thread_; bool to_exit_recv_; bool init_flag_; bool start_flag_; }; -inline Input::Input(const RSInputParam& input_param, - const std::function& excb) - : input_param_(input_param), excb_(excb), to_exit_recv_(false), +inline Input::Input(const RSInputParam& input_param) + : input_param_(input_param), to_exit_recv_(false), init_flag_(false), start_flag_(false) { } -inline void Input::regRecvCallback(const std::function(size_t)>& cb_get, - const std::function)>& cb_put) +inline void Input::regCallback( + const std::function& cb_excep, + const std::function(size_t)>& cb_get_pkt, + const std::function)>& cb_put_pkt) { - cb_get_ = cb_get; - cb_put_ = cb_put; + cb_excep_ = cb_excep; + cb_get_pkt_ = cb_get_pkt; + cb_put_pkt_ = cb_put_pkt; } inline void Input::stop() @@ -103,7 +104,7 @@ inline void Input::stop() inline void Input::pushPacket(std::shared_ptr pkt) { - cb_put_(pkt); + cb_put_pkt_(pkt); } } // namespace lidar diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index c287626f..61edb28a 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -46,13 +46,11 @@ namespace lidar class InputFactory { public: - static std::shared_ptr createInput(InputType type, - const RSInputParam& param, const std::function& excb, + static std::shared_ptr createInput(InputType type, const RSInputParam& param, double sec_to_delay, std::function& cb_feed_pkt); }; -inline std::shared_ptr InputFactory::createInput(InputType type, - const RSInputParam& param, const std::function& excb, +inline std::shared_ptr InputFactory::createInput(InputType type, const RSInputParam& param, double sec_to_delay, std::function& cb_feed_pkt) { std::shared_ptr input; @@ -61,21 +59,21 @@ inline std::shared_ptr InputFactory::createInput(InputType type, { case InputType::ONLINE_LIDAR: { - input = std::make_shared(param, excb); + input = std::make_shared(param); } break; #ifdef ENABLE_PCAP_PARSE case InputType::PCAP_FILE: { - input = std::make_shared(param, excb, sec_to_delay); + input = std::make_shared(param, sec_to_delay); } break; #endif case InputType::RAW_PACKET: { - std::shared_ptr inputRaw = std::make_shared(param, excb); + std::shared_ptr inputRaw = std::make_shared(param); cb_feed_pkt = std::bind(&InputRaw::feedPacket, inputRaw, std::placeholders::_1, std::placeholders::_2); input = inputRaw; diff --git a/src/rs_driver/driver/input/input_pcap.hpp b/src/rs_driver/driver/input/input_pcap.hpp index e8b0880c..76783bc7 100644 --- a/src/rs_driver/driver/input/input_pcap.hpp +++ b/src/rs_driver/driver/input/input_pcap.hpp @@ -36,6 +36,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include +#define ETH_HDR_LEN 42 +#define VLAN_HDR_LEN 4 + namespace robosense { namespace lidar @@ -43,13 +46,13 @@ namespace lidar class InputPcap : public Input { public: - InputPcap(const RSInputParam& input_param, const std::function& excb, double sec_to_delay) - : Input(input_param, excb), pcap_(NULL), pcap_offset_(ETH_HDR_LEN), pcap_tail_(0), difop_filter_valid_(false), + InputPcap(const RSInputParam& input_param, double sec_to_delay) + : Input(input_param), pcap_(NULL), pcap_offset_(ETH_HDR_LEN), pcap_tail_(0), difop_filter_valid_(false), msec_to_delay_(sec_to_delay*1000000) { if (input_param.use_vlan) { - pcap_offset_ += VLAN_LEN; + pcap_offset_ += VLAN_HDR_LEN; } pcap_offset_ += input_param.user_layer_bytes; @@ -97,7 +100,7 @@ inline bool InputPcap::init() pcap_ = pcap_open_offline(input_param_.pcap_path.c_str(), errbuf); if (pcap_ == NULL) { - excb_(Error(ERRCODE_PCAPWRONGPATH)); + cb_excep_(Error(ERRCODE_PCAPWRONGPATH)); return false; } @@ -120,7 +123,7 @@ inline bool InputPcap::start() if (!init_flag_) { - excb_(Error(ERRCODE_STARTBEFOREINIT)); + cb_excep_(Error(ERRCODE_STARTBEFOREINIT)); return false; } @@ -154,7 +157,7 @@ inline void InputPcap::recvPacket() if (input_param_.pcap_repeat) { - excb_(Error(ERRCODE_PCAPREPEAT)); + cb_excep_(Error(ERRCODE_PCAPREPEAT)); char errbuf[PCAP_ERRBUF_SIZE]; pcap_ = pcap_open_offline(input_param_.pcap_path.c_str(), errbuf); @@ -162,21 +165,21 @@ inline void InputPcap::recvPacket() } else { - excb_(Error(ERRCODE_PCAPEXIT)); + cb_excep_(Error(ERRCODE_PCAPEXIT)); break; } } if (pcap_offline_filter(&msop_filter_, header, pkt_data) != 0) { - std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_ - pcap_tail_); pkt->setData(0, header->len - pcap_offset_ - pcap_tail_); pushPacket(pkt); } else if (difop_filter_valid_ && (pcap_offline_filter(&difop_filter_, header, pkt_data) != 0)) { - std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_ - pcap_tail_); pkt->setData(0, header->len - pcap_offset_ - pcap_tail_); pushPacket(pkt); diff --git a/src/rs_driver/driver/input/input_raw.hpp b/src/rs_driver/driver/input/input_raw.hpp index f7cd65bb..acd4bdd9 100644 --- a/src/rs_driver/driver/input/input_raw.hpp +++ b/src/rs_driver/driver/input/input_raw.hpp @@ -49,15 +49,15 @@ class InputRaw : public Input void feedPacket(const uint8_t* data, size_t size); - InputRaw(const RSInputParam& input_param, const std::function& excb) - : Input(input_param, excb) + InputRaw(const RSInputParam& input_param) + : Input(input_param) { } }; inline void InputRaw::feedPacket(const uint8_t* data, size_t size) { - std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); memcpy(pkt->data(), data, size); pkt->setData(0, size); pushPacket(pkt); diff --git a/src/rs_driver/driver/input/input_sock.hpp b/src/rs_driver/driver/input/input_sock.hpp index 8bb8a507..ce40973e 100644 --- a/src/rs_driver/driver/input/input_sock.hpp +++ b/src/rs_driver/driver/input/input_sock.hpp @@ -60,8 +60,8 @@ namespace lidar class InputSock : public Input { public: - InputSock(const RSInputParam& input_param, const std::function& excb) - : Input(input_param, excb), sock_offset_(0), sock_tail_(0) + InputSock(const RSInputParam& input_param) + : Input(input_param), sock_offset_(0), sock_tail_(0) { sock_offset_ += input_param.user_layer_bytes; sock_tail_ += input_param.tail_layer_bytes; @@ -100,7 +100,9 @@ inline void InputSock::higherThreadPrioty(std::thread::native_handle_type handle inline bool InputSock::init() { if (init_flag_) + { return true; + } int msop_fd = -1, difop_fd = -1; @@ -130,11 +132,13 @@ inline bool InputSock::init() inline bool InputSock::start() { if (start_flag_) + { return true; + } if (!init_flag_) { - excb_(Error(ERRCODE_STARTBEFOREINIT)); + cb_excep_(Error(ERRCODE_STARTBEFOREINIT)); return false; } @@ -250,7 +254,7 @@ inline void InputSock::recvPacket() int retval = select(max_fd + 1, &rfds, NULL, NULL, &tv); if (retval == 0) { - excb_(Error(ERRCODE_MSOPTIMEOUT)); + cb_excep_(Error(ERRCODE_MSOPTIMEOUT)); continue; } else if (retval == -1) @@ -275,7 +279,7 @@ inline void InputSock::recvPacket() memset(msgs, 0, sizeof(msgs)); for (i = 0; i < VLEN; i++) { - pkts[i] = cb_get_(MAX_PKT_LEN); + pkts[i] = cb_get_pkt_(MAX_PKT_LEN); iovecs[i].iov_base = pkts[i]->buf(); iovecs[i].iov_len = pkts[i]->bufSize(); msgs[i].msg_hdr.msg_iov = &iovecs[i]; @@ -294,7 +298,7 @@ inline void InputSock::recvPacket() #else - std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); ssize_t ret = recvfrom(fds_[0], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret <= 0) { @@ -311,7 +315,7 @@ inline void InputSock::recvPacket() } else if (FD_ISSET(fds_[1], &rfds)) { - std::shared_ptr pkt = cb_get_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); ssize_t ret = recvfrom(fds_[1], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret < 0) { diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 7910982c..298b73a1 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -66,10 +66,11 @@ class LidarDriverImpl LidarDriverImpl(); ~LidarDriverImpl(); - void regPointCloudCallback(const std::function(void)>& cb_get_pc, - const std::function)>& cb_put_pc); + void regPointCloudCallback( + const std::function(void)>& cb_get_cloud, + const std::function)>& cb_put_cloud); void regPacketCallback(const std::function& cb_put_pkt); - void regExceptionCallback(const std::function& cb_excp); + void regExceptionCallback(const std::function& cb_excep); bool init(const RSDriverParam& param); bool start(); @@ -94,10 +95,10 @@ class LidarDriverImpl void setPointCloudHeader(std::shared_ptr msg, uint16_t height, double chan_ts); RSDriverParam driver_param_; - std::function(void)> cb_get_pc_; - std::function)> cb_put_pc_; + std::function(void)> cb_get_cloud_; + std::function)> cb_put_cloud_; std::function cb_put_pkt_; - std::function cb_excp_; + std::function cb_excep_; std::function cb_feed_pkt_; std::shared_ptr input_ptr_; @@ -107,16 +108,16 @@ class LidarDriverImpl SyncQueue> difop_pkt_queue_; std::thread msop_handle_thread_; std::thread difop_handle_thread_; + uint32_t pkt_seq_; + uint32_t point_cloud_seq_; bool to_exit_handle_; bool init_flag_; bool start_flag_; - uint32_t pkt_seq_; - uint32_t point_cloud_seq_; }; template inline LidarDriverImpl::LidarDriverImpl() - : init_flag_(false), start_flag_(false), pkt_seq_(0), point_cloud_seq_(0) + : pkt_seq_(0), point_cloud_seq_(0), init_flag_(false), start_flag_(false) { } @@ -131,25 +132,24 @@ std::shared_ptr LidarDriverImpl::getPointCloud() { while (1) { - std::shared_ptr pc = cb_get_pc_(); - if (pc) + std::shared_ptr cloud = cb_get_cloud_(); + if (cloud) { - pc->points.resize(0); - return pc; + cloud->points.resize(0); + return cloud; } runExceptionCallback(Error(ERRCODE_POINTCLOUDNULL)); - std::this_thread::sleep_for(std::chrono::milliseconds(300)); } } template -void LidarDriverImpl::regPointCloudCallback( - const std::function(void)>& cb_get, - const std::function)>& cb_put) +void LidarDriverImpl::regPointCloudCallback( + const std::function(void)>& cb_get_cloud, + const std::function)>& cb_put_cloud) { - cb_get_pc_ = cb_get; - cb_put_pc_ = cb_put; + cb_get_cloud_ = cb_get_cloud; + cb_put_cloud_ = cb_put_cloud; } template @@ -161,9 +161,9 @@ inline void LidarDriverImpl::regPacketCallback( template inline void LidarDriverImpl::regExceptionCallback( - const std::function& cb_excp) + const std::function& cb_excep) { - cb_excp_ = cb_excp; + cb_excep_ = cb_excep; } template @@ -177,16 +177,15 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) // // decoder // - decoder_ptr_ = DecoderFactory::createDecoder( - param.lidar_type, param.decoder_param, - std::bind(&LidarDriverImpl::runExceptionCallback, this, std::placeholders::_1)); + decoder_ptr_ = DecoderFactory::createDecoder(param.lidar_type, param.decoder_param); // rewrite pkt timestamp or not ? decoder_ptr_->enableWritePktTs((cb_put_pkt_ == nullptr) ? false : true); // point cloud related decoder_ptr_->point_cloud_ = getPointCloud(); - decoder_ptr_->setSplitCallback( + decoder_ptr_->regCallback( + std::bind(&LidarDriverImpl::runExceptionCallback, this, std::placeholders::_1), std::bind(&LidarDriverImpl::splitFrame, this, std::placeholders::_1, std::placeholders::_2)); double packet_duration = decoder_ptr_->getPacketDuration(); @@ -195,11 +194,10 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) // input // - input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, - std::bind(&LidarDriverImpl::runExceptionCallback, this, std::placeholders::_1), - packet_duration, cb_feed_pkt_); + input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, packet_duration, cb_feed_pkt_); - input_ptr_->regRecvCallback( + input_ptr_->regCallback( + std::bind(&LidarDriverImpl::runExceptionCallback, this, std::placeholders::_1), std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), std::bind(&LidarDriverImpl::packetPut, this, std::placeholders::_1)); @@ -246,19 +244,18 @@ inline bool LidarDriverImpl::start() template inline void LidarDriverImpl::stop() { - if (input_ptr_ != nullptr) + if (!start_flag_) { - input_ptr_->stop(); + return; } - if (start_flag_) - { - to_exit_handle_ = true; - msop_handle_thread_.join(); - difop_handle_thread_.join(); + input_ptr_->stop(); - start_flag_ = false; - } + to_exit_handle_ = true; + msop_handle_thread_.join(); + difop_handle_thread_.join(); + + start_flag_ = false; } template @@ -272,10 +269,11 @@ inline bool LidarDriverImpl::getTemperature(float& temp) { if (decoder_ptr_ != nullptr) { - temp = decoder_ptr_->getTemperature(); - return true; + return false; } - return false; + + temp = decoder_ptr_->getTemperature(); + return true; } template @@ -299,9 +297,9 @@ inline void LidarDriverImpl::runPacketCallBack(std::shared_ptr inline void LidarDriverImpl::runExceptionCallback(const Error& error) { - if (cb_excp_) + if (cb_excep_) { - cb_excp_(error); + cb_excep_(error); } } @@ -386,11 +384,11 @@ inline void LidarDriverImpl::processDifop() template void LidarDriverImpl::splitFrame(uint16_t height, double ts) { - std::shared_ptr pc = decoder_ptr_->point_cloud_; - if (pc->points.size() > 0) + std::shared_ptr cloud = decoder_ptr_->point_cloud_; + if (cloud->points.size() > 0) { - setPointCloudHeader(pc, height, ts); - cb_put_pc_(pc); + setPointCloudHeader(cloud, height, ts); + cb_put_cloud_(cloud); decoder_ptr_->point_cloud_ = getPointCloud(); } else From 18777aae43cbe2e6c7b858efb75f0884a94841aa Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 22 Apr 2022 18:35:43 +0800 Subject: [PATCH 226/379] feat: use faster transform --- src/rs_driver/driver/decoder/decoder.hpp | 20 +++++++++++++------- 1 file changed, 13 insertions(+), 7 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 3bb78161..8bde9cc3 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -281,6 +281,10 @@ class Decoder std::function cb_excep_; bool write_pkt_ts_; +#ifdef ENABLE_TRANSFORM + Eigen::Matrix4d trans_; +#endif + Trigon trigon_; #define SIN(angle) this->trigon_.sin(angle) #define COS(angle) this->trigon_.cos(angle) @@ -318,6 +322,14 @@ inline Decoder::Decoder(const RSDecoderConstParam& const_param, co , prev_pkt_ts_(0.0) , prev_point_ts_(0.0) { +#ifdef ENABLE_TRANSFORM + Eigen::AngleAxisd current_rotation_x(param_.transform_param.roll, Eigen::Vector3d::UnitX()); + Eigen::AngleAxisd current_rotation_y(param_.transform_param.pitch, Eigen::Vector3d::UnitY()); + Eigen::AngleAxisd current_rotation_z(param_.transform_param.yaw, Eigen::Vector3d::UnitZ()); + Eigen::Translation3d current_translation(param_.transform_param.x, param_.transform_param.y, + param_.transform_param.z); + trans_ = (current_translation * current_rotation_z * current_rotation_y * current_rotation_x).matrix(); +#endif } template @@ -348,14 +360,8 @@ template inline void Decoder::transformPoint(float& x, float& y, float& z) { #ifdef ENABLE_TRANSFORM - Eigen::AngleAxisd current_rotation_x(param_.transform_param.roll, Eigen::Vector3d::UnitX()); - Eigen::AngleAxisd current_rotation_y(param_.transform_param.pitch, Eigen::Vector3d::UnitY()); - Eigen::AngleAxisd current_rotation_z(param_.transform_param.yaw, Eigen::Vector3d::UnitZ()); - Eigen::Translation3d current_translation(param_.transform_param.x, param_.transform_param.y, - param_.transform_param.z); - Eigen::Matrix4d trans = (current_translation * current_rotation_z * current_rotation_y * current_rotation_x).matrix(); Eigen::Vector4d target_ori(x, y, z, 1); - Eigen::Vector4d target_rotate = trans * target_ori; + Eigen::Vector4d target_rotate = trans_ * target_ori; x = target_rotate(0); y = target_rotate(1); z = target_rotate(2); From f1d85b037ee015b0d316d650c33fde82a2d9ddb6 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sun, 24 Apr 2022 10:06:54 +0800 Subject: [PATCH 227/379] feat: limit count of error print --- src/rs_driver/common/error_code.hpp | 85 ++++++++++++---------- src/rs_driver/driver/decoder/decoder.hpp | 10 +-- src/rs_driver/driver/lidar_driver_impl.hpp | 4 +- 3 files changed, 54 insertions(+), 45 deletions(-) diff --git a/src/rs_driver/common/error_code.hpp b/src/rs_driver/common/error_code.hpp index 1506ec9b..648adb12 100644 --- a/src/rs_driver/common/error_code.hpp +++ b/src/rs_driver/common/error_code.hpp @@ -33,6 +33,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include +#include namespace robosense { @@ -51,26 +52,26 @@ enum class ErrCodeType WARNING_CODE, ///< Program may not work normally ERROR_CODE ///< Program will exit immediately }; + enum ErrCode { - ERRCODE_SUCCESS = 0x00, ///< Normal - ERRCODE_PCAPREPEAT = 0x01, ///< Pcap file will play repeatedly - ERRCODE_PCAPEXIT = 0x02, ///< Pcap thread will exit - ERRCODE_MSOPTIMEOUT = 0x41, ///< Msop packets receive overtime (1 sec) - ERRCODE_DIFOPTIMEOUT = 0x42, ///< Difop packets receive overtime (2 sec) - ERRCODE_MSOPINCOMPLETE = 0x43, ///< Incomplete msop packets received - ERRCODE_DIFOPINCOMPLETE = 0x44, ///< Incomplete difop packets received - ERRCODE_NODIFOPRECV = 0x45, ///< Point cloud decoding process will not start until the difop packet receive - ERRCODE_ZEROPOINTS = 0x46, ///< Size of the point cloud is zero - ERRCODE_STARTBEFOREINIT = 0x47, ///< start() function is called before initializing successfully - ERRCODE_PCAPWRONGPATH = 0x48, ///< Input directory of pcap file is wrong - ERRCODE_MSOPPORTBUZY = 0x49, ///< Input msop port is already used - ERRCODE_DIFOPPORTBUZY = 0x50, ///< Input difop port is already used - ERRCODE_WRONGPKTHEADER = 0x51, ///< Packet header is wrong - ERRCODE_WRONGPKTLENGTH = 0x52, ///< Packet length is wrong - ERRCODE_PKTNULL = 0x53, ///< Input packet is null - ERRCODE_PKTBUFOVERFLOW = 0x54, ///< Packet buffer is over flow - ERRCODE_POINTCLOUDNULL = 0x55 ///< PointCloud buffer is invalid + ERRCODE_SUCCESS = 0x00, ///< Normal + ERRCODE_PCAPREPEAT = 0x01, ///< Pcap file will play repeatedly + ERRCODE_PCAPEXIT = 0x02, ///< Pcap thread will exit + + ERRCODE_MSOPTIMEOUT = 0x40, ///< Msop packets receive overtime (1 sec) + ERRCODE_DIFOPTIMEOUT = 0x41, ///< Difop packets receive overtime (2 sec) + ERRCODE_NODIFOPRECV = 0x42, ///< Point cloud decoding process will not start until the difop packet receive + ERRCODE_WRONGPKTHEADER = 0x43, ///< Packet header is wrong + ERRCODE_WRONGPKTLENGTH = 0x44, ///< Packet length is wrong + ERRCODE_ZEROPOINTS = 0x45, ///< Size of the point cloud is zero + + ERRCODE_STARTBEFOREINIT = 0x80, ///< start() function is called before initializing successfully + ERRCODE_MSOPPORTBUZY = 0x81, ///< Input msop port is already used + ERRCODE_DIFOPPORTBUZY = 0x82, ///< Input difop port is already used + ERRCODE_PCAPWRONGPATH = 0x83, ///< Input directory of pcap file is wrong + ERRCODE_POINTCLOUDNULL = 0x84, ///< PointCloud buffer is invalid + ERRCODE_PKTBUFOVERFLOW = 0x85, ///< Packet buffer is over flow }; struct Error @@ -79,11 +80,11 @@ struct Error ErrCodeType error_code_type; explicit Error(const ErrCode& code) : error_code(code) { - if (error_code <= 0x40) + if (error_code < 0x40) { error_code_type = ErrCodeType::INFO_CODE; } - else if (error_code <= 0x80) + else if (error_code < 0x80) { error_code_type = ErrCodeType::WARNING_CODE; } @@ -96,45 +97,53 @@ struct Error { switch (error_code) { - case ERRCODE_PCAPWRONGPATH: - return "ERRCODE_PCAPWRONGPATH"; - case ERRCODE_MSOPPORTBUZY: - return "ERRCODE_MSOPPORTBUZY"; - case ERRCODE_DIFOPPORTBUZY: - return "ERRCODE_DIFOPPORTBUZY"; case ERRCODE_PCAPREPEAT: return "Info_PcapRepeat"; case ERRCODE_PCAPEXIT: return "Info_PcapExit"; + case ERRCODE_MSOPTIMEOUT: return "ERRCODE_MSOPTIMEOUT"; case ERRCODE_DIFOPTIMEOUT: return "ERRCODE_DIFOPTIMEOUT"; - case ERRCODE_MSOPINCOMPLETE: - return "ERRCODE_MSOPINCOMPLETE"; - case ERRCODE_DIFOPINCOMPLETE: - return "ERRCODE_DIFOPINCOMPLETE"; case ERRCODE_NODIFOPRECV: return "ERRCODE_NODIFOPRECV"; - case ERRCODE_ZEROPOINTS: - return "ERRCODE_ZEROPOINTS"; - case ERRCODE_STARTBEFOREINIT: - return "ERRCODE_STARTBEFOREINIT"; case ERRCODE_WRONGPKTHEADER: return "ERRCODE_WRONGPKTHEADER"; case ERRCODE_WRONGPKTLENGTH: return "ERRCODE_WRONGPKTLENGTH"; - case ERRCODE_PKTNULL: - return "ERRCODE_PKTNULL"; - case ERRCODE_PKTBUFOVERFLOW: - return "ERRCODE_PKTBUFOVERFLOW"; + case ERRCODE_ZEROPOINTS: + return "ERRCODE_ZEROPOINTS"; + + case ERRCODE_STARTBEFOREINIT: + return "ERRCODE_STARTBEFOREINIT"; + case ERRCODE_MSOPPORTBUZY: + return "ERRCODE_MSOPPORTBUZY"; + case ERRCODE_DIFOPPORTBUZY: + return "ERRCODE_DIFOPPORTBUZY"; + case ERRCODE_PCAPWRONGPATH: + return "ERRCODE_PCAPWRONGPATH"; case ERRCODE_POINTCLOUDNULL: return "ERRCODE_POINTCLOUDNULL"; + case ERRCODE_PKTBUFOVERFLOW: + return "ERRCODE_PKTBUFOVERFLOW"; + default: return "ERRCODE_SUCCESS"; } } }; +#define LIMIT_CALL(func, sec) \ +{ \ + static time_t prev_tm = 0; \ + time_t cur_tm = time(NULL); \ + if ((cur_tm - prev_tm) > sec) \ + { \ + func; \ + prev_tm = cur_tm; \ + } \ +} + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 8bde9cc3..de4656b3 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -373,13 +373,13 @@ inline void Decoder::processDifopPkt(const uint8_t* pkt, size_t si { if (size != this->const_param_.DIFOP_LEN) { - this->cb_excep_(Error(ERRCODE_WRONGPKTLENGTH)); + LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGPKTLENGTH)), 1); return; } if (memcmp(pkt, this->const_param_.DIFOP_ID, const_param_.DIFOP_ID_LEN) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)), 1); return; } @@ -391,19 +391,19 @@ inline bool Decoder::processMsopPkt(const uint8_t* pkt, size_t siz { if (param_.wait_for_difop && !angles_ready_) { - cb_excep_(Error(ERRCODE_NODIFOPRECV)); + LIMIT_CALL(cb_excep_(Error(ERRCODE_NODIFOPRECV)), 1); return false; } if (size != this->const_param_.MSOP_LEN) { - this->cb_excep_(Error(ERRCODE_WRONGPKTLENGTH)); + LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGPKTLENGTH)), 1); return false; } if (memcmp(pkt, this->const_param_.MSOP_ID, const_param_.MSOP_ID_LEN) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)), 1); return false; } diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 298b73a1..9da2bf7e 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -139,7 +139,7 @@ std::shared_ptr LidarDriverImpl::getPointCloud() return cloud; } - runExceptionCallback(Error(ERRCODE_POINTCLOUDNULL)); + LIMIT_CALL(runExceptionCallback(Error(ERRCODE_POINTCLOUDNULL)), 1); } } @@ -340,7 +340,7 @@ inline void LidarDriverImpl::packetPut(std::shared_ptr pkt size_t sz = queue->push(pkt); if (sz > PACKET_POOL_MAX) { - runExceptionCallback(Error(ERRCODE_PKTBUFOVERFLOW)); + LIMIT_CALL(runExceptionCallback(Error(ERRCODE_PKTBUFOVERFLOW)), 1); queue->clear(); } } From e677772a9501f39e1824d91b7195cf554e15d456 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sun, 24 Apr 2022 19:45:41 +0800 Subject: [PATCH 228/379] feat: skip to compile pcap lib --- CMakeLists.txt | 25 ++++++++++--------------- 1 file changed, 10 insertions(+), 15 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index bda179aa..e3913e42 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -87,21 +87,6 @@ else() list(APPEND EXTERNAL_LIBS pthread) endif(WIN32) -#======================== -# PCAP -#======================== -if(WIN32) - - set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/cmake) - find_package(PCAP REQUIRED) - include_directories(${PCAP_INCLUDE_DIR}) - list(APPEND EXTERNAL_LIBS ${PCAP_LIBRARY}) - -else() - - list(APPEND EXTERNAL_LIBS pcap) - -endif(WIN32) #======================== # Build Features @@ -122,6 +107,16 @@ if(${ENABLE_PCAP_PARSE}) message(=============================================================) add_definitions("-DENABLE_PCAP_PARSE") + + if(WIN32) + set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/cmake) + find_package(PCAP REQUIRED) + include_directories(${PCAP_INCLUDE_DIR}) + list(APPEND EXTERNAL_LIBS ${PCAP_LIBRARY}) + else() + list(APPEND EXTERNAL_LIBS pcap) + endif(WIN32) + endif(${ENABLE_PCAP_PARSE}) if(${ENABLE_TRANSFORM}) From efed50a21f65d968420ee74ced088e69ab1dc4ac Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sun, 24 Apr 2022 19:57:54 +0800 Subject: [PATCH 229/379] feat: add cmake option ENABLE_PCL_POINTCLOUD --- CMakeLists.txt | 1 + demo/CMakeLists.txt | 6 +++++- demo/demo_online.cpp | 4 +--- demo/demo_pcap.cpp | 4 +--- 4 files changed, 8 insertions(+), 7 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e3913e42..bae1b2dc 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -22,6 +22,7 @@ option(ENABLE_PCAP_PARSE "Enable PCAP file parse" ON) option(ENABLE_TRANSFORM "Enable transform functions" OFF) option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) option(ENABLE_RECVMMSG "Enable recvmmsg() to receive MSOP message" OFF) +option(ENABLE_PCL_POINTCLOUD "Enable PCL Point Cloud" OFF) #============================= # Compile Demos, Tools, Tests diff --git a/demo/CMakeLists.txt b/demo/CMakeLists.txt index abb51662..6f4b9b86 100644 --- a/demo/CMakeLists.txt +++ b/demo/CMakeLists.txt @@ -4,11 +4,15 @@ message(=============================================================) message("-- Ready to compile demos") message(=============================================================) -find_package(PCL QUIET REQUIRED) +if(${ENABLE_PCL_POINTCLOUD}) + +find_package(PCL REQUIRED) include_directories(${PCL_INCLUDE_DIRS}) link_directories(${PCL_LIBRARY_DIRS}) add_definitions(${PCL_DEFINITIONS}) +endif(${ENABLE_PCL_POINTCLOUD}) + include_directories(${DRIVER_INCLUDE_DIRS}) add_executable(demo_online diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index fb57f3ab..c6478f79 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -32,9 +32,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include -#define PCL_POINTCLOUD - -#ifdef PCL_POINTCLOUD +#ifdef ENABLE_PCL_POINTCLOUD #include #else #include diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 07c8d7fd..b9c81523 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -32,9 +32,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include -#define PCL_POINTCLOUD - -#ifdef PCL_POINTCLOUD +#ifdef ENABLE_PCL_POINTCLOUD #include #else #include From cb8a5532017e6956ccccc3d8a680609063a9aa64 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sun, 24 Apr 2022 20:33:53 +0800 Subject: [PATCH 230/379] feat: fix compiling error on windows --- src/rs_driver/driver/decoder/decoder.hpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index de4656b3..95b0a3e6 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -48,8 +48,13 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #endif -#include +#ifdef __linux__ #include +#elif _WIN32 +#include +#endif + +#include #include #include #include From baeaf176aa4cf2164c07a27435ac519a058d6158 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sun, 24 Apr 2022 20:37:00 +0800 Subject: [PATCH 231/379] fix: fix compiling error on windows --- src/rs_driver/driver/decoder/basic_attr.hpp | 2 +- src/rs_driver/driver/decoder/decoder.hpp | 12 ++++++------ 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index e4623a9a..b1b53c8c 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -32,7 +32,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#include +//#include #include #include #include diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 95b0a3e6..c4bfdefc 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -32,6 +32,12 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once +#ifdef __linux__ +#include +#elif _WIN32 +#include +#endif + #include #include #include @@ -48,12 +54,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #endif -#ifdef __linux__ -#include -#elif _WIN32 -#include -#endif - #include #include #include From 95e02ba2d4dc5a13ddea48e21704fbc3c4d976ef Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 25 Apr 2022 09:56:44 +0800 Subject: [PATCH 232/379] fix: fix tests --- src/rs_driver/driver/decoder/basic_attr.hpp | 7 ++++++- src/rs_driver/driver/decoder/decoder.hpp | 6 ------ test/decoder_rs32_test.cpp | 7 ++++--- test/decoder_rsbp_test.cpp | 7 ++++--- test/decoder_test.cpp | 23 +++++++++++++-------- 5 files changed, 28 insertions(+), 22 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index b1b53c8c..64ec9d10 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -32,7 +32,12 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -//#include +#ifdef __linux__ +#include +#elif _WIN32 +#include +#endif + #include #include #include diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index c4bfdefc..92148b97 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -32,12 +32,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#ifdef __linux__ -#include -#elif _WIN32 -#include -#endif - #include #include #include diff --git a/test/decoder_rs32_test.cpp b/test/decoder_rs32_test.cpp index 385e3374..800004ac 100644 --- a/test/decoder_rs32_test.cpp +++ b/test/decoder_rs32_test.cpp @@ -62,7 +62,8 @@ TEST(TestDecoderRS32, decodeDifopPkt) { // const_param RSDecoderParam param; - DecoderRS32 decoder(param, errCallback); + DecoderRS32 decoder(param); + decoder.regCallback(errCallback, nullptr); ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.split_blks_per_frame_, 1801); @@ -183,7 +184,8 @@ TEST(TestDecoderRS32, decodeMsopPkt) // dense_points = false, use_lidar_clock = true RSDecoderParam param; - DecoderRS32 decoder(param, errCallback); + DecoderRS32 decoder(param); + decoder.regCallback(errCallback, splitFrame); ASSERT_EQ(decoder.chan_angles_.user_chans_.size(), 32); decoder.chan_angles_.user_chans_[0] = 2; decoder.chan_angles_.user_chans_[1] = 1; @@ -191,7 +193,6 @@ TEST(TestDecoderRS32, decodeMsopPkt) decoder.param_.use_lidar_clock = true; decoder.point_cloud_ = std::make_shared(); - decoder.setSplitCallback(splitFrame); decoder.decodeMsopPkt(pkt, sizeof(pkt)); ASSERT_EQ(decoder.getTemperature(), 2.1875); diff --git a/test/decoder_rsbp_test.cpp b/test/decoder_rsbp_test.cpp index dd9fb319..4937f64c 100644 --- a/test/decoder_rsbp_test.cpp +++ b/test/decoder_rsbp_test.cpp @@ -27,7 +27,8 @@ TEST(TestDecoderRSBP, decodeDifopPkt) { // const_param RSDecoderParam param; - DecoderRSBP decoder(param, errCallback); + DecoderRSBP decoder(param); + decoder.regCallback(errCallback, nullptr); ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.split_blks_per_frame_, 1801); @@ -149,7 +150,8 @@ TEST(TestDecoderRSBP, decodeMsopPkt) // dense_points = false, use_lidar_clock = true RSDecoderParam param; - DecoderRSBP decoder(param, errCallback); + DecoderRSBP decoder(param); + decoder.regCallback(errCallback, splitFrame); ASSERT_EQ(decoder.chan_angles_.user_chans_.size(), 32); decoder.chan_angles_.user_chans_[0] = 2; @@ -158,7 +160,6 @@ TEST(TestDecoderRSBP, decodeMsopPkt) decoder.param_.use_lidar_clock = true; decoder.point_cloud_ = std::make_shared(); - decoder.setSplitCallback(splitFrame); decoder.decodeMsopPkt(pkt, sizeof(pkt)); ASSERT_EQ(decoder.getTemperature(), 2.1875); diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 3f7c1a01..7604b9fa 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -30,9 +30,8 @@ class MyDecoder : public DecoderMech { public: MyDecoder(const RSDecoderMechConstParam& const_param, - const RSDecoderParam& param, - const std::function& excb) - : DecoderMech(const_param, param, excb) + const RSDecoderParam& param) + : DecoderMech(const_param, param) { } @@ -66,7 +65,8 @@ TEST(TestDecoder, angles_from_file) param.angle_path = "../rs_driver/test/res/angle.csv"; errCode = ERRCODE_SUCCESS; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param); + decoder.regCallback(errCallback, nullptr); ASSERT_EQ(errCode, ERRCODE_SUCCESS); ASSERT_TRUE(decoder.angles_ready_); @@ -81,7 +81,8 @@ TEST(TestDecoder, angles_from_file_fail) param.config_from_file = true; param.angle_path = "../rs_driver/test/res/non_exist.csv"; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param); + decoder.regCallback(errCallback, nullptr); ASSERT_FALSE(decoder.angles_ready_); } @@ -98,7 +99,8 @@ TEST(TestDecoder, processDifopPkt_fail) }; RSDecoderParam param; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param); + decoder.regCallback(errCallback, nullptr); // wrong difop length MyDifopPkt pkt = {0}; @@ -132,7 +134,8 @@ TEST(TestDecoder, processDifopPkt) RSDecoderParam param; param.config_from_file = false; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param); + decoder.regCallback(errCallback, nullptr); ASSERT_FALSE(decoder.angles_ready_); // @@ -213,7 +216,8 @@ TEST(TestDecoder, processDifopPkt_invalid_rpm) }; RSDecoderParam param; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param); + decoder.regCallback(errCallback, nullptr); uint8_t pkt[] = { @@ -241,7 +245,8 @@ TEST(TestDecoder, processMsopPkt) MyMsopPkt pkt; RSDecoderParam param; - MyDecoder decoder(const_param, param, errCallback); + MyDecoder decoder(const_param, param); + decoder.regCallback(errCallback, nullptr); // wait_for_difop = true, angles not ready decoder.param_.wait_for_difop = true; From 0852ac084d523cd21e8c5e4681a6964df2f691c3 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 25 Apr 2022 10:08:33 +0800 Subject: [PATCH 233/379] feat: change version to v1.5.1 --- CMakeLists.txt | 2 +- src/rs_driver/macro/version.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index bae1b2dc..e1db28c2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.5.0) +project(rs_driver VERSION 1.5.1) #======================== # Project setup diff --git a/src/rs_driver/macro/version.hpp b/src/rs_driver/macro/version.hpp index c4cec339..e85056ad 100644 --- a/src/rs_driver/macro/version.hpp +++ b/src/rs_driver/macro/version.hpp @@ -1,3 +1,3 @@ #define RSLIDAR_VERSION_MAJOR 1 #define RSLIDAR_VERSION_MINOR 5 -#define RSLIDAR_VERSION_PATCH 0 +#define RSLIDAR_VERSION_PATCH 1 From c400fc5d7e916473a5845c60aa40de34b175dacc Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 26 Apr 2022 10:07:28 +0800 Subject: [PATCH 234/379] fix: fix compiling warnings on windows --- src/rs_driver/common/common_header.hpp | 152 ------------------ src/rs_driver/common/rs_common.hpp | 54 +++++++ src/rs_driver/common/rs_log.hpp | 46 ++++++ src/rs_driver/driver/decoder/basic_attr.hpp | 6 +- .../driver/decoder/block_iterator.hpp | 46 +++--- src/rs_driver/driver/decoder/chan_angles.hpp | 3 +- .../driver/decoder/decoder_RS128.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS16.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 6 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 2 +- .../driver/decoder/decoder_RSHELIOS.hpp | 2 +- .../driver/decoder/decoder_RSHELIOS_16P.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 4 +- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 11 +- src/rs_driver/driver/decoder/decoder_mech.hpp | 16 +- src/rs_driver/driver/decoder/trigon.hpp | 6 +- src/rs_driver/driver/driver_param.hpp | 4 +- src/rs_driver/driver/input/input_sock.hpp | 18 +-- test/ab_dual_return_block_iterator_test.cpp | 6 +- test/dual_return_block_iterator_test.cpp | 4 +- test/rs16_dual_return_block_iterator_test.cpp | 4 +- ...rs16_single_return_block_iterator_test.cpp | 4 +- test/single_return_block_iterator_test.cpp | 4 +- 24 files changed, 169 insertions(+), 237 deletions(-) delete mode 100644 src/rs_driver/common/common_header.hpp create mode 100644 src/rs_driver/common/rs_common.hpp create mode 100644 src/rs_driver/common/rs_log.hpp diff --git a/src/rs_driver/common/common_header.hpp b/src/rs_driver/common/common_header.hpp deleted file mode 100644 index c8e08f09..00000000 --- a/src/rs_driver/common/common_header.hpp +++ /dev/null @@ -1,152 +0,0 @@ -/********************************************************************************************************************* -Copyright (c) 2020 RoboSense -All rights reserved - -By downloading, copying, installing or using the software you agree to this license. If you do not agree to this -license, do not download, install, copy or use the software. - -License Agreement -For RoboSense LiDAR SDK Library -(3-clause BSD License) - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the -following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following -disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following -disclaimer in the documentation and/or other materials provided with the distribution. - -3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used -to endorse or promote products derived from this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, -INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*********************************************************************************************************************/ - -#pragma once - -#include - -#if defined(_WIN32) - -#include -#include -inline void setConsoleColor(WORD c) -{ - HANDLE hConsole = GetStdHandle(STD_OUTPUT_HANDLE); - SetConsoleTextAttribute(hConsole, c); -} - -#endif - -/*Output style*/ -#ifndef RS_INFOL -#if defined(_WIN32) -inline std::ostream& _RS_INFOL() -{ - setConsoleColor(FOREGROUND_GREEN); - return std::cout; -} -#define RS_INFOL _RS_INFOL() -#else -#define RS_INFOL (std::cout << "\033[32m") -#endif -#endif - -#ifndef RS_INFO -#if defined(_WIN32) -inline std::ostream& _RS_INFO() -{ - setConsoleColor(FOREGROUND_GREEN | FOREGROUND_INTENSITY); - return std::cout; -} -#define RS_INFO _RS_INFO() -#else -#define RS_INFO (std::cout << "\033[1m\033[32m") -#endif -#endif - -#ifndef RS_WARNING -#if defined(_WIN32) -inline std::ostream& _RS_WARNING() -{ - setConsoleColor(FOREGROUND_GREEN | FOREGROUND_RED | FOREGROUND_INTENSITY); - return std::cout; -} -#define RS_WARNING _RS_WARNING() -#else -#define RS_WARNING (std::cout << "\033[1m\033[33m") -#endif -#endif - -#ifndef RS_ERROR -#if defined(_WIN32) -inline std::ostream& _RS_ERROR() -{ - setConsoleColor(FOREGROUND_RED | FOREGROUND_INTENSITY); - return std::cout; -} -#define RS_ERROR _RS_ERROR() -#else -#define RS_ERROR (std::cout << "\033[1m\033[31m") -#endif -#endif - -#ifndef RS_DEBUG -#if defined(_WIN32) -inline std::ostream& _RS_DEBUG() -{ - setConsoleColor(FOREGROUND_GREEN); - return std::cout; -} -#define RS_DEBUG _RS_DEBUG() -#else -#define RS_DEBUG (std::cout << "\033[1m\033[36m") -#endif -#endif - -#ifndef RS_TITLE -#if defined(_WIN32) -inline std::ostream& _RS_TITLE() -{ - setConsoleColor(FOREGROUND_BLUE | FOREGROUND_RED | FOREGROUND_INTENSITY); - return std::cout; -} -#define RS_TITLE _RS_TITLE() -#else -#define RS_TITLE (std::cout << "\033[1m\033[35m") -#endif -#endif - -#ifndef RS_MSG -#if defined(_WIN32) -inline std::ostream& _RS_MSG() -{ - setConsoleColor(FOREGROUND_GREEN | FOREGROUND_RED | FOREGROUND_BLUE | FOREGROUND_INTENSITY); - return std::cout; -} -#define RS_MSG _RS_MSG() -#else -#define RS_MSG (std::cout << "\033[1m\033[37m") -#endif -#endif - -#ifndef RS_REND -#if defined(_WIN32) -inline std::ostream& RS_REND(std::ostream& stream) -{ - stream << std::endl; - setConsoleColor(-1); - return stream; -} -#else -#define RS_REND "\033[0m" << std::endl -#endif -#endif diff --git a/src/rs_driver/common/rs_common.hpp b/src/rs_driver/common/rs_common.hpp new file mode 100644 index 00000000..3e3c3f82 --- /dev/null +++ b/src/rs_driver/common/rs_common.hpp @@ -0,0 +1,54 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +// +// define ntohs() +// +#ifdef __linux__ +#include +#elif _WIN32 +#include +#endif + +// +// define M_PI +// +#if 0 +#ifndef _USE_MATH_DEFINES +#define _USE_MATH_DEFINES // for VC++, required to use const M_IP in +#endif +#endif + +#include + diff --git a/src/rs_driver/common/rs_log.hpp b/src/rs_driver/common/rs_log.hpp new file mode 100644 index 00000000..94087e56 --- /dev/null +++ b/src/rs_driver/common/rs_log.hpp @@ -0,0 +1,46 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include + +#define RS_ERROR std::cout << "\033[1m\033[31m" // bold red +#define RS_WARNING std::cout << "\033[1m\033[33m" // bold yellow +#define RS_INFO std::cout << "\033[1m\033[32m" // bold green +#define RS_INFOL std::cout << "\033[32m" // green +#define RS_DEBUG std::cout << "\033[1m\033[36m" // bold cyan +#define RS_REND "\033[0m" << std::endl + +#define RS_TITLE std::cout << "\033[1m\033[35m" // bold magenta +#define RS_MSG std::cout << "\033[1m\033[37m" // bold white + diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index 64ec9d10..dbc6bc63 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -32,11 +32,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#ifdef __linux__ -#include -#elif _WIN32 -#include -#endif +#include #include #include diff --git a/src/rs_driver/driver/decoder/block_iterator.hpp b/src/rs_driver/driver/decoder/block_iterator.hpp index c450a391..0e504167 100644 --- a/src/rs_driver/driver/decoder/block_iterator.hpp +++ b/src/rs_driver/driver/decoder/block_iterator.hpp @@ -31,6 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once + namespace robosense { namespace lidar @@ -43,14 +44,14 @@ class BlockIterator static const int MAX_BLOCKS_PER_PKT = 12; - void get(uint16_t blk, int32_t& az_diff, float& ts) + void get(uint16_t blk, int32_t& az_diff, double& ts) { az_diff = az_diffs[blk]; ts = tss[blk]; } BlockIterator(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, - uint16_t block_az_duration, float fov_blind_duration) + uint16_t block_az_duration, double fov_blind_duration) : pkt_(pkt), BLOCKS_PER_PKT(blocks_per_pkt), BLOCK_DURATION(block_duration), BLOCK_AZ_DURATION(block_az_duration), FOV_BLIND_DURATION(fov_blind_duration) { @@ -58,13 +59,14 @@ class BlockIterator } protected: + const T_Packet& pkt_; const uint16_t BLOCKS_PER_PKT; const double BLOCK_DURATION; const uint16_t BLOCK_AZ_DURATION; - const float FOV_BLIND_DURATION; + const double FOV_BLIND_DURATION; int32_t az_diffs[MAX_BLOCKS_PER_PKT]; - float tss[MAX_BLOCKS_PER_PKT]; + double tss[MAX_BLOCKS_PER_PKT]; }; template @@ -73,14 +75,14 @@ class SingleReturnBlockIterator : public BlockIterator public: SingleReturnBlockIterator(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, - uint16_t block_az_duration, float fov_blind_duration) + uint16_t block_az_duration, double fov_blind_duration) : BlockIterator(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) { - float tss = 0; + double tss = 0; uint16_t blk = 0; for (; blk < (this->BLOCKS_PER_PKT - 1); blk++) { - float ts_diff = this->BLOCK_DURATION; + double ts_diff = this->BLOCK_DURATION; int32_t az_diff = ntohs(this->pkt_.blocks[blk+1].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); if (az_diff < 0) { az_diff += 36000; } @@ -108,14 +110,14 @@ class DualReturnBlockIterator : public BlockIterator public: DualReturnBlockIterator(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, - uint16_t block_az_duration, float fov_blind_duration) + uint16_t block_az_duration, double fov_blind_duration) : BlockIterator(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) { - float tss = 0; + double tss = 0; uint16_t blk = 0; for (; blk < (this->BLOCKS_PER_PKT - 2); blk = blk + 2) { - float ts_diff = this->BLOCK_DURATION; + double ts_diff = this->BLOCK_DURATION; int32_t az_diff = ntohs(this->pkt_.blocks[blk+2].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); if (az_diff < 0) { az_diff += 36000; } @@ -143,10 +145,10 @@ class ABDualReturnBlockIterator : public BlockIterator public: ABDualReturnBlockIterator(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, - uint16_t block_az_duration, float fov_blind_duration) + uint16_t block_az_duration, double fov_blind_duration) : BlockIterator(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) { - float ts_diff = this->BLOCK_DURATION; + double ts_diff = this->BLOCK_DURATION; int32_t az_diff = ntohs(this->pkt_.blocks[2].azimuth) - ntohs(this->pkt_.blocks[0].azimuth); if (az_diff < 0) { az_diff += 36000; } @@ -159,7 +161,7 @@ class ABDualReturnBlockIterator : public BlockIterator if (ntohs(this->pkt_.blocks[0].azimuth) == ntohs(this->pkt_.blocks[1].azimuth)) // AAB { - float tss = 0; + double tss = 0; this->az_diffs[0] = this->az_diffs[1] = az_diff; this->tss[0] = this->tss[1] = tss; @@ -169,7 +171,7 @@ class ABDualReturnBlockIterator : public BlockIterator } else // ABB { - float tss = 0; + double tss = 0; this->az_diffs[0] = az_diff; this->tss[0] = tss; @@ -191,19 +193,19 @@ class Rs16SingleReturnBlockIterator : public BlockIterator for (uint16_t chan = 0; chan < 32; chan++) { az_percents[chan] = firing_tss[chan] / (blk_ts * 2); - ts_diffs[chan] = firing_tss[chan] / 1000000; + ts_diffs[chan] = (double)firing_tss[chan] / 1000000; } } Rs16SingleReturnBlockIterator(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, - uint16_t block_az_duration, float fov_blind_duration) + uint16_t block_az_duration, double fov_blind_duration) : BlockIterator(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) { - float tss = 0; + double tss = 0; uint16_t blk = 0; for (; blk < (this->BLOCKS_PER_PKT - 1); blk++) { - float ts_diff = this->BLOCK_DURATION * 2; + double ts_diff = this->BLOCK_DURATION * 2; int32_t az_diff = ntohs(this->pkt_.blocks[blk+1].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); if (az_diff < 0) { az_diff += 36000; } @@ -236,19 +238,19 @@ class Rs16DualReturnBlockIterator : public BlockIterator for (uint16_t chan = 0; chan < 32; chan++) { az_percents[chan] = firing_tss[chan%16] / blk_ts; - ts_diffs[chan] = firing_tss[chan%16] / 1000000; + ts_diffs[chan] = (double)firing_tss[chan%16] / 1000000; } } Rs16DualReturnBlockIterator(const T_Packet& pkt, uint16_t blocks_per_pkt, double block_duration, - uint16_t block_az_duration, float fov_blind_duration) + uint16_t block_az_duration, double fov_blind_duration) : BlockIterator(pkt, blocks_per_pkt, block_duration, block_az_duration, fov_blind_duration) { - float tss = 0; + double tss = 0; uint16_t blk = 0; for (; blk < (this->BLOCKS_PER_PKT - 1); blk++) { - float ts_diff = this->BLOCK_DURATION; + double ts_diff = this->BLOCK_DURATION; int32_t az_diff = ntohs(this->pkt_.blocks[blk+1].azimuth) - ntohs(this->pkt_.blocks[blk].azimuth); if (az_diff < 0) { az_diff += 36000; } diff --git a/src/rs_driver/driver/decoder/chan_angles.hpp b/src/rs_driver/driver/decoder/chan_angles.hpp index ff9fa687..80cc49b6 100644 --- a/src/rs_driver/driver/decoder/chan_angles.hpp +++ b/src/rs_driver/driver/decoder/chan_angles.hpp @@ -32,7 +32,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#include +#include + #include #include diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 0c529a57..0da36742 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -263,7 +263,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe } int32_t block_az_diff; - float block_ts_off; + double block_ts_off; iter.get(blk, block_az_diff, block_ts_off); for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index b7a4d01d..2ee2d7a1 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -289,7 +289,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az_diff; - float block_ts_off; + double block_ts_off; iter.get(blk, block_az_diff, block_ts_off); for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 241d4843..b5e8febc 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -95,14 +95,14 @@ inline void RS32DifopPkt2Adapter (const RS32DifopPkt& src, AdapterDifopPkt& dst) dst.vert_angle_cali[i].sign = src.vert_angle_cali[i].sign; v = ntohs(src.vert_angle_cali[i].value); - v = std::round(v * 0.1f); + v = (uint16_t)std::round(v * 0.1f); dst.vert_angle_cali[i].value = htons(v); // horiz_angles dst.horiz_angle_cali[i].sign = src.horiz_angle_cali[i].sign; v = ntohs(src.horiz_angle_cali[i].value); - v = std::round(v * 0.1f); + v = (uint16_t)std::round(v * 0.1f); dst.horiz_angle_cali[i].value = htons(v); } } @@ -272,7 +272,7 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az_diff; - float block_ts_off; + double block_ts_off; iter.get(blk, block_az_diff, block_ts_off); for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index af74f181..0c2d0760 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -249,7 +249,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az_diff; - float block_ts_off; + double block_ts_off; iter.get(blk, block_az_diff, block_ts_off); for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 463b216b..ecd7f59e 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -243,7 +243,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet } int32_t block_az_diff; - float block_ts_off; + double block_ts_off; iter.get(blk, block_az_diff, block_ts_off); for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 1403fa41..5b9e5731 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -255,7 +255,7 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa } int32_t block_az_diff; - float block_ts_off; + double block_ts_off; iter.get(blk, block_az_diff, block_ts_off); for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp index 8c1ceeac..363d77b8 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp @@ -221,7 +221,7 @@ inline bool DecoderRSHELIOS_16P::internDecodeMsopPkt(const uint8_t } int32_t block_az_diff; - float block_ts_off; + double block_ts_off; iter.get(blk, block_az_diff, block_ts_off); for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 66dcb73d..7b432afc 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -241,13 +241,13 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size } } - for (size_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSM1Block& block = pkt.blocks[blk]; double point_time = pkt_ts + block.time_offset * 1e-6; - for (size_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSM1Channel& channel = block.channel[chan]; diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index 426f9d75..3d1cea1a 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -86,6 +86,7 @@ class DecoderRSM2 : public Decoder constexpr static double FRAME_DURATION = 0.1; constexpr static uint32_t SINGLE_PKT_NUM = 1260; constexpr static uint32_t DUAL_PKT_NUM = 2520; + constexpr static int VECTOR_BASE = 32768; virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); @@ -197,13 +198,13 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size } } - for (size_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSM2Block& block = pkt.blocks[blk]; double point_time = pkt_ts + block.time_offset * 1e-6; - for (size_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSM2Channel& channel = block.channel[chan]; @@ -211,9 +212,9 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size if (this->distance_section_.in(distance)) { - float x = RS_SWAP_INT16(channel.x) / 32768.0 * distance; - float y = RS_SWAP_INT16(channel.y) / 32768.0 * distance; - float z = RS_SWAP_INT16(channel.z) / 32768.0 * distance; + float x = RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; + float y = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; + float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; this->transformPoint(x, y, z); typename T_PointCloud::PointT point; diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index adce75e1..e618ff9c 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -94,7 +94,7 @@ class DecoderMech : public Decoder uint16_t blks_per_frame_; // blocks per frame/round uint16_t split_blks_per_frame_; // blocks in msop pkt per frame/round. uint16_t block_az_diff_; // azimuth difference between adjacent blocks. - float fov_blind_ts_diff_; // timestamp difference across blind section(defined by fov) + double fov_blind_ts_diff_; // timestamp difference across blind section(defined by fov) int lidar_alph0_; // lens center related float lidar_Rxy_; // lens center related @@ -106,12 +106,12 @@ inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& con : Decoder(const_param.base, param) , mech_const_param_(const_param) , chan_angles_(this->const_param_.LASER_NUM) - , scan_section_(this->param_.start_angle * 100, this->param_.end_angle * 100) + , scan_section_((int32_t)(this->param_.start_angle * 100), (int32_t)(this->param_.end_angle * 100)) , rps_(10) - , blks_per_frame_(1/(10*this->mech_const_param_.BLOCK_DURATION)) + , blks_per_frame_((uint16_t)(1 / (10 * this->mech_const_param_.BLOCK_DURATION))) , split_blks_per_frame_(blks_per_frame_) , block_az_diff_(20) - , fov_blind_ts_diff_(0) + , fov_blind_ts_diff_(0.0) { this->packet_duration_ = this->mech_const_param_.BLOCK_DURATION * this->const_param_.BLOCKS_PER_PKT; @@ -134,7 +134,7 @@ inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& con } // lens center: (alph0, Rxy) - lidar_alph0_ = std::atan2(mech_const_param_.RY, mech_const_param_.RX) * 180 / M_PI * 100; + lidar_alph0_ = (int)(std::atan2(mech_const_param_.RY, mech_const_param_.RX) * 180 / M_PI * 100); lidar_Rxy_ = std::sqrt(mech_const_param_.RX * mech_const_param_.RX + mech_const_param_.RY * mech_const_param_.RY); @@ -182,11 +182,11 @@ inline void DecoderMech::decodeDifopCommon(const T_Difop& pkt) } // blocks per frame - this->blks_per_frame_ = 1 / (this->rps_ * this->mech_const_param_.BLOCK_DURATION); + this->blks_per_frame_ = (uint16_t)(1 / (this->rps_ * this->mech_const_param_.BLOCK_DURATION)); // block diff of azimuth this->block_az_diff_ = - std::round(RS_ONE_ROUND * this->rps_ * this->mech_const_param_.BLOCK_DURATION); + (uint16_t)std::round(RS_ONE_ROUND * this->rps_ * this->mech_const_param_.BLOCK_DURATION); // fov related uint16_t fov_start_angle = ntohs(pkt.fov.start_angle); @@ -197,7 +197,7 @@ inline void DecoderMech::decodeDifopCommon(const T_Difop& pkt) // fov blind diff of timestamp this->fov_blind_ts_diff_ = - (float)fov_blind_range / ((float)RS_ONE_ROUND * (float)this->rps_); + (double)fov_blind_range / ((double)RS_ONE_ROUND * (double)this->rps_); // load angles if (!this->param_.config_from_file && !this->angles_ready_) diff --git a/src/rs_driver/driver/decoder/trigon.hpp b/src/rs_driver/driver/decoder/trigon.hpp index 18274cc1..b2eda826 100644 --- a/src/rs_driver/driver/decoder/trigon.hpp +++ b/src/rs_driver/driver/decoder/trigon.hpp @@ -32,11 +32,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#ifndef _USE_MATH_DEFINES -#define _USE_MATH_DEFINES // for VC++, required to use const M_IP in -#endif - -#include +#include namespace robosense { diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 5559acc3..a5552ed8 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -32,7 +32,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#include +#include #include #include @@ -289,7 +289,7 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter void print() const { RS_INFO << "------------------------------------------------------" << RS_REND; - RS_INFOL << " RoboSense Driver Parameters " << RS_REND; + RS_INFO << " RoboSense Driver Parameters " << RS_REND; RS_INFOL << "input type: " << inputTypeToStr(input_type) << RS_REND; RS_INFOL << "lidar_type: " << lidarTypeToStr(lidar_type) << RS_REND; RS_INFOL << "------------------------------------------------------" << RS_REND; diff --git a/src/rs_driver/driver/input/input_sock.hpp b/src/rs_driver/driver/input/input_sock.hpp index ce40973e..50851732 100644 --- a/src/rs_driver/driver/input/input_sock.hpp +++ b/src/rs_driver/driver/input/input_sock.hpp @@ -34,23 +34,11 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include -#ifdef __linux__ - -#include -#include -#include -#include -#include - -#elif _WIN32 - -#include -#include - -#endif - #include #include +#include +#include +#include #include namespace robosense diff --git a/test/ab_dual_return_block_iterator_test.cpp b/test/ab_dual_return_block_iterator_test.cpp index 32a6fce5..fdde7e06 100644 --- a/test/ab_dual_return_block_iterator_test.cpp +++ b/test/ab_dual_return_block_iterator_test.cpp @@ -41,7 +41,7 @@ TEST(TestABDualPacketTraverser, ctor) 2.0f); // fov_blind_duration int32_t az_diff; - float ts; + double ts; // first block iter.get (0, az_diff, ts); @@ -75,7 +75,7 @@ TEST(TestABDualPacketTraverser, ctor) 2.0f); // fov_blind_duration int32_t az_diff; - float ts; + double ts; // first block iter.get (0, az_diff, ts); @@ -113,7 +113,7 @@ TEST(TestABDualPacketTraverser, ctor_fov) 2.0f); // fov_blind_duration int32_t az_diff; - float ts; + double ts; // first block iter.get (0, az_diff, ts); diff --git a/test/dual_return_block_iterator_test.cpp b/test/dual_return_block_iterator_test.cpp index 8b64d95f..14223d8b 100644 --- a/test/dual_return_block_iterator_test.cpp +++ b/test/dual_return_block_iterator_test.cpp @@ -42,7 +42,7 @@ TEST(TestDualPacketTraverser, ctor) 2.0f); // fov_blind_duration int32_t az_diff; - float ts; + double ts; // first block iter.get (0, az_diff, ts); @@ -89,7 +89,7 @@ TEST(TestDualPacketTraverser, ctor_fov) 2.0f); // fov_blind_duration int32_t az_diff; - float ts; + double ts; // first block iter.get (0, az_diff, ts); diff --git a/test/rs16_dual_return_block_iterator_test.cpp b/test/rs16_dual_return_block_iterator_test.cpp index 8ae25a72..29cd9335 100644 --- a/test/rs16_dual_return_block_iterator_test.cpp +++ b/test/rs16_dual_return_block_iterator_test.cpp @@ -39,7 +39,7 @@ TEST(TestRs16DualReturnBlockIterator, ctor) 2.0f); // fov_blind_duration int32_t az_diff; - float ts; + double ts; // first block iter.get (0, az_diff, ts); @@ -73,7 +73,7 @@ TEST(TestRs16DualReturnBlockIterator, ctor_fov) 2.0f); // fov_blind_duration int32_t az_diff; - float ts; + double ts; // first block iter.get (0, az_diff, ts); diff --git a/test/rs16_single_return_block_iterator_test.cpp b/test/rs16_single_return_block_iterator_test.cpp index eac5eaf2..0174c797 100644 --- a/test/rs16_single_return_block_iterator_test.cpp +++ b/test/rs16_single_return_block_iterator_test.cpp @@ -39,7 +39,7 @@ TEST(TestRs16SingleReturnBlockIterator, ctor) 2.0f); // fov_blind_duration int32_t az_diff; - float ts; + double ts; // first block iter.get (0, az_diff, ts); @@ -73,7 +73,7 @@ TEST(TestRs16SingleReturnBlockIterator, ctor_fov) 2.0f); // fov_blind_duration int32_t az_diff; - float ts; + double ts; // first block iter.get (0, az_diff, ts); diff --git a/test/single_return_block_iterator_test.cpp b/test/single_return_block_iterator_test.cpp index 417574e8..e3899909 100644 --- a/test/single_return_block_iterator_test.cpp +++ b/test/single_return_block_iterator_test.cpp @@ -39,7 +39,7 @@ TEST(TestSingleReturnBlockIterator, ctor) 2.0f); // fov_blind_duration int32_t az_diff; - float ts; + double ts; // first block iter.get (0, az_diff, ts); @@ -71,7 +71,7 @@ TEST(TestSingleReturnBlockIterator, ctor_fov) 2.0f); // fov_blind_duration int32_t az_diff; - float ts; + double ts; // first block iter.get (0, az_diff, ts); From 899c7089321b5e32dc21cd1ff4299e48909764cf Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 26 Apr 2022 10:17:13 +0800 Subject: [PATCH 235/379] fix: fix compiling warnings --- src/rs_driver/driver/input/input_sock.hpp | 29 ++++++++++++----------- 1 file changed, 15 insertions(+), 14 deletions(-) diff --git a/src/rs_driver/driver/input/input_sock.hpp b/src/rs_driver/driver/input/input_sock.hpp index 50851732..c23a335c 100644 --- a/src/rs_driver/driver/input/input_sock.hpp +++ b/src/rs_driver/driver/input/input_sock.hpp @@ -150,21 +150,20 @@ inline InputSock::~InputSock() inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp) { int fd; - int flags; int ret; int reuse = 1; fd = socket(PF_INET, SOCK_DGRAM, 0); if (fd < 0) { - std::cerr << "socket: " << std::strerror(errno) << std::endl; + perror("socket: "); goto failSocket; } ret = setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &reuse, sizeof(reuse)); if (ret < 0) { - std::cerr << "setsockopt: " << std::strerror(errno) << std::endl; + perror("setsockopt: "); goto failOption; } @@ -181,7 +180,7 @@ inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, con ret = bind(fd, (struct sockaddr*)&host_addr, sizeof(host_addr)); if (ret < 0) { - std::cerr << "bind: " << std::strerror(errno) << std::endl; + perror("bind: "); goto failBind; } @@ -200,17 +199,19 @@ inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, con ret = setsockopt(fd, IPPROTO_IP, IP_ADD_MEMBERSHIP, &ipm, sizeof(ipm)); if (ret < 0) { - std::cerr << "setsockopt: " << std::strerror(errno) << std::endl; + perror("setsockopt: "); goto failGroup; } } - flags = fcntl(fd, F_GETFL, 0); - ret = fcntl(fd, F_SETFL, flags | O_NONBLOCK); - if (ret < 0) { - std::cerr << "setsockopt: " << std::strerror(errno) << std::endl; - goto failNonBlock; + int flags = fcntl(fd, F_GETFL, 0); + ret = fcntl(fd, F_SETFL, flags | O_NONBLOCK); + if (ret < 0) + { + perror("fcntl: "); + goto failNonBlock; + } } return fd; @@ -234,7 +235,7 @@ inline void InputSock::recvPacket() FD_SET(fds_[0], &rfds); if (fds_[1] >= 0) FD_SET(fds_[1], &rfds); - int max_fd = std::max(fds_[0], fds_[1]); + int max_fd = ((fds_[0] > fds_[1]) ? fds_[0] : fds_[1]); struct timeval tv; tv.tv_sec = 1; @@ -250,7 +251,7 @@ inline void InputSock::recvPacket() if (errno == EINTR) continue; - std::cerr << "select: " << std::strerror(errno) << std::endl; + perror("select: "); break; } @@ -290,7 +291,7 @@ inline void InputSock::recvPacket() ssize_t ret = recvfrom(fds_[0], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret <= 0) { - std::cout << "recv packet failed" << std::endl; + perror("recvfrom: "); break; } else if (ret > 0) @@ -307,7 +308,7 @@ inline void InputSock::recvPacket() ssize_t ret = recvfrom(fds_[1], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret < 0) { - std::cout << "recv packet failed" << std::endl; + perror("recvfrom: "); break; } else if (ret > 0) From 42edef38db5afaa895ed7e8be72cf16807dc34d9 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 26 Apr 2022 15:18:31 +0800 Subject: [PATCH 236/379] =?UTF-8?q?fix=EF=BC=9Afix=20compiling=20warnings?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/rs_driver/common/rs_common.hpp | 2 - src/rs_driver/driver/input/input_factory.hpp | 7 +- .../driver/input/{ => unix}/input_sock.hpp | 0 src/rs_driver/driver/input/win/input_sock.hpp | 281 ++++++++++++++++++ src/rs_driver/driver/lidar_driver_impl.hpp | 4 +- 5 files changed, 289 insertions(+), 5 deletions(-) rename src/rs_driver/driver/input/{ => unix}/input_sock.hpp (100%) create mode 100644 src/rs_driver/driver/input/win/input_sock.hpp diff --git a/src/rs_driver/common/rs_common.hpp b/src/rs_driver/common/rs_common.hpp index 3e3c3f82..2fb93a11 100644 --- a/src/rs_driver/common/rs_common.hpp +++ b/src/rs_driver/common/rs_common.hpp @@ -44,11 +44,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. // // define M_PI // -#if 0 #ifndef _USE_MATH_DEFINES #define _USE_MATH_DEFINES // for VC++, required to use const M_IP in #endif -#endif #include diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 61edb28a..f761e214 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -32,12 +32,17 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include -#include #include #ifdef ENABLE_PCAP_PARSE #include #endif +#ifdef __linux__ +#include +#elif _WIN32 +#include +#endif + namespace robosense { namespace lidar diff --git a/src/rs_driver/driver/input/input_sock.hpp b/src/rs_driver/driver/input/unix/input_sock.hpp similarity index 100% rename from src/rs_driver/driver/input/input_sock.hpp rename to src/rs_driver/driver/input/unix/input_sock.hpp diff --git a/src/rs_driver/driver/input/win/input_sock.hpp b/src/rs_driver/driver/input/win/input_sock.hpp new file mode 100644 index 00000000..5e5a8878 --- /dev/null +++ b/src/rs_driver/driver/input/win/input_sock.hpp @@ -0,0 +1,281 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include + +#include +#include + +#pragma warning(disable : 4244) + +namespace robosense +{ +namespace lidar +{ +class InputSock : public Input +{ +public: + InputSock(const RSInputParam& input_param) + : Input(input_param), sock_offset_(0), sock_tail_(0) + { + sock_offset_ += input_param.user_layer_bytes; + sock_tail_ += input_param.tail_layer_bytes; + } + + virtual bool init(); + virtual bool start(); + virtual ~InputSock(); + +private: + inline void recvPacket(); + inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); + +private: + int fds_[2]; + size_t sock_offset_; + size_t sock_tail_; +}; + +inline bool InputSock::init() +{ + int msop_fd = -1, difop_fd = -1; + + if (init_flag_) + { + return true; + } + + WORD version = MAKEWORD(2, 2); + WSADATA wsaData; + int ret = WSAStartup(version, &wsaData); + if(ret < 0) + goto failWsa; + + msop_fd = createSocket(input_param_.msop_port, input_param_.host_address, input_param_.group_address); + if (msop_fd < 0) + goto failMsop; + + if ((input_param_.difop_port != 0) && (input_param_.difop_port != input_param_.msop_port)) + { + difop_fd = createSocket(input_param_.difop_port, input_param_.host_address, input_param_.group_address); + if (difop_fd < 0) + goto failDifop; + } + + fds_[0] = msop_fd; + fds_[1] = difop_fd; + + init_flag_ = true; + return true; + +failDifop: + closesocket(msop_fd); +failMsop: + if (difop_fd >= 0) + closesocket(difop_fd); +failWsa: + return false; +} + +inline bool InputSock::start() +{ + if (start_flag_) + { + return true; + } + + if (!init_flag_) + { + cb_excep_(Error(ERRCODE_STARTBEFOREINIT)); + return false; + } + + recv_thread_ = std::thread(std::bind(&InputSock::recvPacket, this)); + + start_flag_ = true; + return true; +} + +inline InputSock::~InputSock() +{ + stop(); + + closesocket(fds_[0]); + if (fds_[1] >= 0) + closesocket(fds_[1]); +} + +inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp) +{ + int fd; + int ret; + int reuse = 1; + + fd = socket(PF_INET, SOCK_DGRAM, 0); + if (fd < 0) + { + perror("socket: "); + goto failSocket; + } + + ret = setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, (const char*)&reuse, sizeof(reuse)); + if (ret < 0) + { + perror("setsockopt: "); + goto failOption; + } + + struct sockaddr_in host_addr; + memset(&host_addr, 0, sizeof(host_addr)); + host_addr.sin_family = AF_INET; + host_addr.sin_port = htons(port); + host_addr.sin_addr.s_addr = INADDR_ANY; + if (hostIp != "0.0.0.0" && grpIp == "0.0.0.0") + { + inet_pton(AF_INET, hostIp.c_str(), &(host_addr.sin_addr)); + } + + ret = bind(fd, (struct sockaddr*)&host_addr, sizeof(host_addr)); + if (ret < 0) + { + perror("bind: "); + goto failBind; + } + + if (grpIp != "0.0.0.0") + { +#if 0 + struct ip_mreqn ipm; + memset(&ipm, 0, sizeof(ipm)); + inet_pton(AF_INET, grpIp.c_str(), &(ipm.imr_multiaddr)); + inet_pton(AF_INET, hostIp.c_str(), &(ipm.imr_address)); +#else + struct ip_mreq ipm; + inet_pton(AF_INET, grpIp.c_str(), &(ipm.imr_multiaddr)); + inet_pton(AF_INET, hostIp.c_str(), &(ipm.imr_interface)); +#endif + ret = setsockopt(fd, IPPROTO_IP, IP_ADD_MEMBERSHIP, (const char*)&ipm, sizeof(ipm)); + if (ret < 0) + { + perror("setsockopt: "); + goto failGroup; + } + } + + { + u_long mode = 1; + ret = ioctlsocket(fd, FIONBIO, &mode); + if (ret < 0) + { + perror("ioctlsocket: "); + goto failNonBlock; + } + } + + return fd; + +failNonBlock: +failGroup: +failBind: +failOption: + closesocket(fd); +failSocket: + return -1; +} + +inline void InputSock::recvPacket() +{ + fd_set rfds; + + while (!to_exit_recv_) + { + FD_ZERO(&rfds); + FD_SET(fds_[0], &rfds); + if (fds_[1] >= 0) + FD_SET(fds_[1], &rfds); + int max_fd = ((fds_[0] > fds_[1]) ? fds_[0] : fds_[1]); + + struct timeval tv; + tv.tv_sec = 1; + tv.tv_usec = 0; + int retval = select(max_fd + 1, &rfds, NULL, NULL, &tv); + if (retval == 0) + { + cb_excep_(Error(ERRCODE_MSOPTIMEOUT)); + continue; + } + else if (retval == -1) + { + if (errno == EINTR) + continue; + + perror("select: "); + break; + } + + if (FD_ISSET(fds_[0], &rfds)) + { + std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); + int ret = recvfrom(fds_[0], (char*)pkt->buf(), (int)pkt->bufSize(), 0, NULL, NULL); + if (ret <= 0) + { + perror("recvfrom: "); + break; + } + else if (ret > 0) + { + pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); + pushPacket(pkt); + } + } + else if (FD_ISSET(fds_[1], &rfds)) + { + std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); + int ret = recvfrom(fds_[1], (char*)pkt->buf(), (int)pkt->bufSize(), 0, NULL, NULL); + if (ret < 0) + { + perror("recvfrom: "); + break; + } + else if (ret > 0) + { + pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); + pushPacket(pkt); + } + } + } +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 9da2bf7e..5b6e46ca 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -407,12 +407,12 @@ void LidarDriverImpl::setPointCloudHeader(std::shared_ptris_dense) { msg->height = 1; - msg->width = msg->points.size(); + msg->width = (uint32_t)msg->points.size(); } else { msg->height = height; - msg->width = msg->points.size() / msg->height; + msg->width = (uint32_t)msg->points.size() / msg->height; } } From 38dc87170e3e00d9fd039e436b5b0c43a1a5e8b2 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 26 Apr 2022 15:20:45 +0800 Subject: [PATCH 237/379] feat: support windows --- win/demo_online/demo_online.vcxproj | 137 ++++++++++++++++++++++++++++ win/rs_driver.sln | 31 +++++++ 2 files changed, 168 insertions(+) create mode 100644 win/demo_online/demo_online.vcxproj create mode 100644 win/rs_driver.sln diff --git a/win/demo_online/demo_online.vcxproj b/win/demo_online/demo_online.vcxproj new file mode 100644 index 00000000..b6e9fe62 --- /dev/null +++ b/win/demo_online/demo_online.vcxproj @@ -0,0 +1,137 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + + + + 15.0 + {A30B3B76-84F3-4A17-B42B-6284FCC3138F} + demoonline + 10.0.17763.0 + + + + Application + true + v141 + MultiByte + + + Application + false + v141 + true + MultiByte + + + Application + true + v141 + MultiByte + + + Application + false + v141 + true + MultiByte + + + + + + + + + + + + + + + + + + + + + + + Level3 + Disabled + true + true + ../../../src/ + _CRT_SECURE_NO_WARNINGS;%(PreprocessorDefinitions) + + + Console + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);Ws2_32.lib + + + + + Level3 + Disabled + true + true + ../../src + _MBCS;%(PreprocessorDefinitions);_CRT_SECURE_NO_WARNINGS + + + Console + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);Ws2_32.lib + + + + + Level3 + MaxSpeed + true + true + true + true + + + Console + true + true + + + + + Level3 + MaxSpeed + true + true + true + true + + + Console + true + true + + + + + + \ No newline at end of file diff --git a/win/rs_driver.sln b/win/rs_driver.sln new file mode 100644 index 00000000..56aee33c --- /dev/null +++ b/win/rs_driver.sln @@ -0,0 +1,31 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio 15 +VisualStudioVersion = 15.0.28307.1927 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "demo_online", "demo_online\demo_online.vcxproj", "{A30B3B76-84F3-4A17-B42B-6284FCC3138F}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {A30B3B76-84F3-4A17-B42B-6284FCC3138F}.Debug|x64.ActiveCfg = Debug|x64 + {A30B3B76-84F3-4A17-B42B-6284FCC3138F}.Debug|x64.Build.0 = Debug|x64 + {A30B3B76-84F3-4A17-B42B-6284FCC3138F}.Debug|x86.ActiveCfg = Debug|Win32 + {A30B3B76-84F3-4A17-B42B-6284FCC3138F}.Debug|x86.Build.0 = Debug|Win32 + {A30B3B76-84F3-4A17-B42B-6284FCC3138F}.Release|x64.ActiveCfg = Release|x64 + {A30B3B76-84F3-4A17-B42B-6284FCC3138F}.Release|x64.Build.0 = Release|x64 + {A30B3B76-84F3-4A17-B42B-6284FCC3138F}.Release|x86.ActiveCfg = Release|Win32 + {A30B3B76-84F3-4A17-B42B-6284FCC3138F}.Release|x86.Build.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection + GlobalSection(ExtensibilityGlobals) = postSolution + SolutionGuid = {56237513-8A68-4EC5-9B6B-BAB05BA945B4} + EndGlobalSection +EndGlobal From 48866625c7bd56ecac66d1768351c6e6d76f9ea3 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 26 Apr 2022 16:09:56 +0800 Subject: [PATCH 238/379] feat: add project demo_online and demo_pcap --- src/rs_driver/driver/input/input_pcap.hpp | 8 +++++++- win/rs_driver.sln | 10 ++++++++++ 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/src/rs_driver/driver/input/input_pcap.hpp b/src/rs_driver/driver/input/input_pcap.hpp index 76783bc7..4bbd1593 100644 --- a/src/rs_driver/driver/input/input_pcap.hpp +++ b/src/rs_driver/driver/input/input_pcap.hpp @@ -34,6 +34,12 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include + +#ifdef __linux__ +#elif _WIN32 +#define WIN32 +#endif + #include #define ETH_HDR_LEN 42 @@ -48,7 +54,7 @@ class InputPcap : public Input public: InputPcap(const RSInputParam& input_param, double sec_to_delay) : Input(input_param), pcap_(NULL), pcap_offset_(ETH_HDR_LEN), pcap_tail_(0), difop_filter_valid_(false), - msec_to_delay_(sec_to_delay*1000000) + msec_to_delay_((uint64_t)(sec_to_delay*1000000)) { if (input_param.use_vlan) { diff --git a/win/rs_driver.sln b/win/rs_driver.sln index 56aee33c..33dd0633 100644 --- a/win/rs_driver.sln +++ b/win/rs_driver.sln @@ -5,6 +5,8 @@ VisualStudioVersion = 15.0.28307.1927 MinimumVisualStudioVersion = 10.0.40219.1 Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "demo_online", "demo_online\demo_online.vcxproj", "{A30B3B76-84F3-4A17-B42B-6284FCC3138F}" EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "demo_pcap", "demo_pcap\demo_pcap.vcxproj", "{E7971DE6-C89C-4572-A3A4-07BE68897D30}" +EndProject Global GlobalSection(SolutionConfigurationPlatforms) = preSolution Debug|x64 = Debug|x64 @@ -21,6 +23,14 @@ Global {A30B3B76-84F3-4A17-B42B-6284FCC3138F}.Release|x64.Build.0 = Release|x64 {A30B3B76-84F3-4A17-B42B-6284FCC3138F}.Release|x86.ActiveCfg = Release|Win32 {A30B3B76-84F3-4A17-B42B-6284FCC3138F}.Release|x86.Build.0 = Release|Win32 + {E7971DE6-C89C-4572-A3A4-07BE68897D30}.Debug|x64.ActiveCfg = Debug|x64 + {E7971DE6-C89C-4572-A3A4-07BE68897D30}.Debug|x64.Build.0 = Debug|x64 + {E7971DE6-C89C-4572-A3A4-07BE68897D30}.Debug|x86.ActiveCfg = Debug|Win32 + {E7971DE6-C89C-4572-A3A4-07BE68897D30}.Debug|x86.Build.0 = Debug|Win32 + {E7971DE6-C89C-4572-A3A4-07BE68897D30}.Release|x64.ActiveCfg = Release|x64 + {E7971DE6-C89C-4572-A3A4-07BE68897D30}.Release|x64.Build.0 = Release|x64 + {E7971DE6-C89C-4572-A3A4-07BE68897D30}.Release|x86.ActiveCfg = Release|Win32 + {E7971DE6-C89C-4572-A3A4-07BE68897D30}.Release|x86.Build.0 = Release|Win32 EndGlobalSection GlobalSection(SolutionProperties) = preSolution HideSolutionNode = FALSE From e5628f639927adbbf9efc1d3db5c3248702f247d Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 26 Apr 2022 16:11:19 +0800 Subject: [PATCH 239/379] feat: add demo_pcap --- win/demo_pcap/demo_pcap.vcxproj | 135 ++++++++++++++++++++++++++++++++ 1 file changed, 135 insertions(+) create mode 100644 win/demo_pcap/demo_pcap.vcxproj diff --git a/win/demo_pcap/demo_pcap.vcxproj b/win/demo_pcap/demo_pcap.vcxproj new file mode 100644 index 00000000..e3c4a2da --- /dev/null +++ b/win/demo_pcap/demo_pcap.vcxproj @@ -0,0 +1,135 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + 15.0 + {E7971DE6-C89C-4572-A3A4-07BE68897D30} + demopcap + 10.0.17763.0 + + + + Application + true + v141 + MultiByte + + + Application + false + v141 + true + MultiByte + + + Application + true + v141 + MultiByte + + + Application + false + v141 + true + MultiByte + + + + + + + + + + + + + + + + + + + + + + + Level3 + Disabled + true + true + ../../src;../../Include + _MBCS;%(PreprocessorDefinitions);_CRT_SECURE_NO_WARNINGS;ENABLE_PCAP_PARSE + + + Console + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);Ws2_32.lib;wpcap.lib + ../../Lib/x64 + + + + + Level3 + Disabled + true + true + + + Console + + + + + Level3 + MaxSpeed + true + true + true + true + + + Console + true + true + + + + + Level3 + MaxSpeed + true + true + true + true + + + Console + true + true + + + + + + + + + \ No newline at end of file From 2cd105524af7522a2b6c9a5ce81b151e5b74fd0a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 28 Apr 2022 11:47:53 +0800 Subject: [PATCH 240/379] feat: update docs --- doc/src_intro/img/class_decoder.png | Bin 37670 -> 36553 bytes doc/src_intro/img/class_input.png | Bin 14447 -> 15741 bytes doc/src_intro/img/class_input_factory.png | Bin 7171 -> 7169 bytes doc/src_intro/img/class_lidar_driver_impl.png | Bin 64595 -> 66141 bytes doc/src_intro/rs_driver_intro.md | 52 +++++++++--------- 5 files changed, 27 insertions(+), 25 deletions(-) diff --git a/doc/src_intro/img/class_decoder.png b/doc/src_intro/img/class_decoder.png index 3c9d19ab10a6d72d28f3e16f9c69b00508236c40..a2c723e86c3e2621b81440b884d331ebbb1e6981 100644 GIT binary patch literal 36553 zcmagG2Uw2(-#>gsv=IgYO*-&|dt*XR6v-tX6XpRuOK`eA;86xKpf zqd3c#QIuOW>)ALqm<@{BoqJ9q9}Qp#2v{phcBl>J}7 zlLZ;V9H0D{efIIpKyhESTgMAO`vg8RE%o^qejAI~CIs^DWv0t|x_)|ff8^0wwKKma zY2Hsw@yp327w+G`|K0DOZ=#Eegn4**13vU@OI`Z;=4|Wh*SyNg%Dd&|+t-%A@h9n$ zNPG6|Nt1TlC@CqKQ(4L6>FK$)G>Q9pY1a4+>xh{+3+!*=V>#jge(^1)<+LSPV`Rmx~~2D`g~|e+uVGU zzP|pKjvZ&4o;_n(T3S*%`$r`{K7P0F$Zp&{vZCUa-zz^_7sl@46Eeqdm0tHGb!Tgt zRXK^2eP%_harM()>J1xQp555j`RrLo)4BBlzgL1uO}J?P$(9Yo-6UR?m!F@``|{<> zFW+1y086sagam`4h~icTVem$o7H;n%^3zKr`L}^OB%n^(x+u$ z$k)EeDfZ;Cx2vtKt!c2@&4`HgR5@FA9e7@#ca@eTBqFkzjaYnIQhQt5^YMqL=}0>d zG^EAE#Kpx;^ZeYfN(mxWj6YNR z>!{n3nhK<)k#YK}iE3_gGJAUH*j+z?BwY&L z-2L!jgEwdY?lX80G_&c){L8EMcYXCPT(}^2ddXK@N=lfVcWu|f{=rgL@y0V_V z1uZR_Wbtg-{=Po%X{onztVfOKO zPW_mT+VyB{(~hw3Y$U#2yI6KQ+@)@^aXzM$sYv=1kE(h#d@o)(AUM$*(>f_fS10?{ zU&(0Qzy2vlN8;Az&6}%Fetmo4ZdB`J!-kmlx5~UW@BCSXo+K&pFn?4t6Yy+P40w;a zS6Jn;FZ4gW$-m#+=>q%9P_t%|MZ|Z(NJp33d5yQLpxLoo~V8HR?kE@&>%m(>-dyA#+I>>zb^l2|I zucoFZQUndl zr!9(Mi$7{kWMpJ#a!OWK0)Bk$+cPy)<=G(#%KrUs?Qt9^BV|_i`;R|l z>d97nWR}%8Hh5z3@{zZquRG0FR23C%s&1BU(KxeX#}4H)Yjr&*&>ad{RDb2@kB6-; zp)PM*ttc+uk5Zk|bu~R*&$SwrN$OyuA*m!MM_u^Y^0$wAR#quh2Ok+zrd*wRdwbnI zJ@+RjCf0gB+n%Z@FQ2lJnMc=e?5@z^!-q#3!}c1ietPh^bA0^9{QP{0!8NI%w{3K( z#D}V>sUhc@>NYnw4?aA70>zI^&MP*_?th-E)z#aZIKQyqjYec?Zmvn8P*G742jSG; z-#@)k-hyTa#mp@%^3hbRW-g(r^ko8<&+c-CLX2BZLZRlw$TUSfVdF(Q;rf{m{q@?DR)+bLcUSQ_c&r%M? zXFyj=L60O}C}h2l`*h_$ePcuGFxUt~Qcw^X8X8JVvU6}4 zFj4z0_+mRbZ}sPAi*FyEipj`aIra0C5jiQQ$Ryhs$_kDZV4 zn(9t*_wzGa7`>Ce|Y+*u!V(1Tzq^1hlKUz>({yM z?Cr(x{0KI;(fFeitmEzN{eE&%11E0&ftW?n<?WTd0Zm3Di~%4T-* zq!Q7c(QYY1LPErHU>{Q`#3Ar`StHcm(ILxy=gys%9}5Zuu~Xd?=%X~b_MMW`6Wr9@ z-Ax93$k^?&j*Tt0-PPR6su26$dM3K9jp8$QcV}Tyk-44SwuBvOH!iU3_>;X-g40;* z@r0ASlHK|+bXg`PIhmDIf8z6v{x=_+BWS3@$z*a&jHsgGHOZYjz0tdI&A1}$c#7qp zXdje*8fG58yt0pNFK>J5IXGNj2(LN$)ip3ENRXWO{d>?lb+xrG>)F_Nm4jk3D^PRyu5ezUXF*w+J`i9*e!dpk zOhI9xw(Oyv9Q3O0WRA_7wNzDAiPlqJU(ddEYv&n3?cS23ZyLV?Lk;}-z1lTAY%Tos z&6{k_o%U^ahxANLJiXJ?(}^>0QEXfoyIG{0$J4_@8z@9}Vf^8B)C7sJ#H3u$6* z?jjZ>A1f>qQh$6Q?%T&_>q*$t5jf~>{RMhxgQ;B~=jIp=9y~~zdXUz8U6JL$fdh4c zQ*oNy*rqP7uIqr30K07M?Q3e$mwv6R)ZDK?@46*7^N9lpft5Z=#$$GF4m)6ddwaXr z>-yjnxrwvYic(Til9jc!$%X5~vGICV0Y1ch4RmxilF(Lj;&z&gFI|s|qrZMS4WAb0 z=F3yXH_n44X45Zj?jQ>Yc-*Bai>a=bK7G{3C$7-on(OrQTv9kdlB8oDE6WbmNc?P@ zYjsaAKgZYx63T`))_v?lNnKsqLz<@dI_Cnr`nt2rudA_LY?pa-5qAeQ{N=`^;Fce*7FZgUC>8&bai#H(o&0xie8>kB*~aprl>ti_-352v&+8d1mjV{3;EG+Exrg7hP)zHoZ0HJTfe)0mvkkmg! z{>HAkoR!7o=H{0EnTk(Vb~Act)QuYlQuK^UH_J#%Q;{6&gJOq%zVF(+?W0}5*^?|R zEcg!HH7TdE{=}FVT7qZwXjs7mY&cnh#| z(T>H%MgO0lUZXQr+TUsEFEj`MVs>l{-9|@8H-h4jHGlOJ0}Tma<@t*j`>m}xFEDO9 zKQZCFw)`=h;A!>2bHc|Q+Z!1e7+UWfe&N6PUQbX&{CoFu13>?pEx$=@>ZZq!H=+zozq~D?;5$Of33b1R+Rcc9R-%L{~(0o5QfI$Dd5we#sg z3m}cSx;mwTf&z7Nk~260tSTw_(#9V@erQlk&CJe~mHAYz=#IX? zE%}AAJNfBTBC2y9P{f{`U%yT+eXmnSW#Qix`y5;iWt1!>m_FO`0FQ!=QL{JQDA@ zvb1o~s@%G{tBVdmM90>4tIEE8{Ot7A?p>RBR8F#@mE5YWrMSBb;^w<}d&j?<0Y=$Z~R)-jB{Kz4Qc>J`cE7QCXRknc2fL^<}b^jg#|&S-y_g zP8t$;L*kxeADWt*sQ|rNi;S-OV{iFfGh^JL%2QNSbnDI?ZG6M!=uwulXU{@N;=Fg{ zb(vY%P~W|y2Z^c%__teHT0>u-{+N33i~v?F^v96Rmv7%907h{=#3Ipc7FO5R-jJ`8 zpoz*-edKjL*Go@SY3MQdATDh&Y+GgAX>ojVtVK>l`^{aoyee&}SU7k=9g2Dp0)4zb5MHq;>1ov48N^ z&(F&kSru+RI`BV9;U@B(oT^P^$NGp?GvkL!0#f|s?6@aOZ#ZTW6`OU82l5Ymk8k|F z>}R zDq~Kl{MWjGch274bjOYzV+4DM;`JT7%d~zYW792{))D$QkS=gVbg8MS*bME^AZ(Wv z6clW4A7a9uCiX7CIy9su95m+2?HC; zVr)k1O8X4}=WT6mqP`}Umh37jDj|4Jd)I1T;t--3XDM&UanyYOeP&>*v@7)!krdV$wCDsO3Z#s_ z#<0_CkZ`RQJq{gOCwfA~JS_X{pJkd#hkMqd{CI(d09{h|mYd0OfovR?ZW_muM6Z3C ze*HiZdI!Tf^>BzH0%BsNql*Royj!Fk!%?FIH^ug}uN^EAy+pNULe3Wswyrg^JFS%2 z?N67abD6c2&Pbzvz32|VKR_m=Zr(FMUye>rhn+nAMq4LIj+zC1f|TSw_JX~ni3k=| zbw@`YNWYL-zd&bf85yY?4jwMr$HUwtL{Z`xfs}C9_vQJ4Vv|QlER>G!cGQft*d@Ar z^sPS^MG*~1Y)s}R!N9^~e*WCPS?pb&56`j> z7JiBg%ZUfB(r|F#K6qx?BjRP(s@$s?WF=Xk2%`&ga1NDG; zyUGaP4>@@$$GWED;*}#b-7$%Yj{(K1UEAr?KZi_jC>Ar_)mu^%*@^whx@psS)G1;+ z0N6y~SV2;>yFsY)E8k~G;o$4=f@v%GjK{a;m}u~_kHR6RIofiq&Xg$q@jmmFfITqWCs+ z($a&E&d7Omvq$}=P~=X0a$NlRQ-n;8rD#r0PS%1oT7L+qTAvmlck|{hiDPI7a!1Ei zQcXtRaIC6t)6BgL6homfi5TP=_C|eMdIuU>U0t0F+&-0(l*IqyMac}Ds32=7yhDjx zu5ND9exq`wTCJdIxm8unFouBR21mtEBwC<8lAf1Zi1@y$V&eoOF=y;OU|$O)YPO-xG3t&#!R?u{W0$&M-t&1@Ti7v zh1k*p!s*ffdu=Tz&s^2{$JejT=sA_OJ@tGhsg$x3Q!_GU<-s5&^*we~;FRO|>CX>0 zdNUNyr_&HfBYW1V|46ErY4>(yRaS-AJc_Of)ez$G1r?U0p8bx8rt0 z>k1%4VbwJ-aMN@g%GKp6P!KKODFIQXRQ{hrp=)-uNS_J<(oEX}{n zuQdz_Gj*6XNTnoYGDPRc=v-yBs}B+bKnXwa@D#tGAa!G7qx`9YSN{tm{=+34^#vp) z8G#0`?9oY*)Acj8Jb^b}`T3az`WEVxCLgOaOc?zqYxB3Cv2t*1z+T6B71*;UeTGaG z4k-@>*u}%cDqm*mhlXG2F1t-0fl@q)Ds_>%n_K$(H#yw(E$ySd*y>$|8h(#j=r0pb zuLHxS(VLzJuFbatVOJk|%5{HcexcDCI*H)-W(2cCVZ*6ql?0_(=U#Mc$O~^)IyMiLlV3=Xs%)XhLh4CM zO}%jWGAoJ;N%Y0s%t*BW0mN|YBQIPa@7~QyBAi&*rCI=&y}is(OMD;wEGZE^dFm91 z0z3Q@K)cH0ntOmw`1$z>QtCjszvl=JGdReOb|kZ;>!Aie6ovXcm^YwyT#ATERYB2` zzf$H4IZp_$=WK2s;D@yWk|y)^FeMW9pleT>blus%s+_wH#KUp9Wu_0!@yK{XEZpa} z*lE*)rJFA{9UZRNcINNz69n|o)z@#qKYRt%ws|T10B@NF1$-kDSKAWp!1L!#s5wbj zu9$nsf6LRpXiI%MG_)apADqM{RD%RKNRzm|v@9$g5a5$iQmoug!=1@lgqbdSs_TJ2 zYL|$PjXN!%qOdTELzkmPE_457PoWnxuD6UE!v;xJ2 zVBczLYTHh~?@C$Q0&t<2e*XMA=w#I+Iy0-UUOC=xEb2X_1D)~9*RND0fGO9-_g(U% zZ|lh^LXzQswOhctGQyxDwsStQN~KBa)zZtKlQ4)N$zQXo?A=~!#8J3Ud^`_U0Qf`q z`)l1PAWmx{#BWN`8Imny5x*2iy5&3!(p>XdTxw&5Bnvs^TxF$-uF*o$s332M*zNs3 z7GWc>whZL%2kQ{b@7Ap*DD%{$x--9(v8WyWVWFY7LcSeh=is0c%~m;n;)IQOopt)C z?omRU02JjTH-s)<@n+FmC}p|7iTR^b@qz6NpWi%sq#8$MdPd?l1O&q@Wsbwc70om| zLc>i|mtkRVAccc}PC#fPI5ZmsXewwYH-qVdT6l$2@_ufD!M+j~cN z0T2&f-^XKYF;#hmb>__@wGU6P)8wqpjOJ=ZADHulWKIoV-^|i7^6gt!-#3j}Z!QEV z{V=>5KY9>9Eo_`g3v^E)<$)q2w+FTj|5RjnPt8zEkZtfkcC7XM28LP3aj113sWg@! z=59VpeYrldHDrs|m0k!S)xpX}=Tdh%xWc&qVSNLpIt&N%qf-G&N7oxIDkNb2PyajC zk?iDlGFg2n)~7w%m}4}{lvZbfGB#@&jFL`1=3b_|~LKp+=z9fL_}Cmcj) zU*C8_s8U~6=qE@&pfhUw%Z+fg8;QCBh6%hkKD&4IuZ6WWQR9HuS_ytUSzM!9A$g5_ zGXbUhJo+t6FZ}d&m6Ln|m5b2E7`fyK1_G&<&}tXIeWN11>$ubbg)$Kmc2j%%23)i1_` z@arxiVDlDNRTs9ZKv>2(j=dg06C<}=*7s)aiGaxcx0dJpwhm_W-rch#rh|KSNa{D=4IjnOf`kNSJOvD!fzn zKT=WUjV#+4VL8AEcSh93cg`m#G)M{Dw8H5@suId; zc5Wg~&&*JfiVV}u-?>RVDHQd|R{=@*3gqnkIDQ)`97kFJE${2suacLbNLbhsJqF5x zWw}D&_|8Fboemqq+J-uCVCuBTCNj~jWcWCQJUP0K#8AkEItEjIR0O3T>a7M=#7@6n z`F>;f3kJAcY3b=!T?c_Qp|_``U%7G~Tlg(@2v*4Do@BqW_+2f?8iz_(K||0DdNQlN zr(x5*`}OtRJkiRAPWA4TkYIoqGJh=iN@HA!=(W6(gvHC^9G0oaN=uwg?Np--iW~Oo z{)jKoeN$dil7rGZ>NZ>9S-`k&-@a`kW@e^_N%I%v{#=Y1Y1nUUoM<>6ckdW{{E{V2 zIce$UmMDhwR!g1skerGNN$U>?a`ZhoadiImgDvaMk)B-J<#}uecALyX=aVOJy11av zk&-)pc>DOgMVg}->^L_+e?1f@=vQvIDOSFh6@AK?wSPNYRjp7eE+DS;4?k?Q-5+}k zEtJeNl5ZpdjvfCz&J;^IpP9*%PG_xM!%c|($aEcfRY#TMc+)<^q#KH)sih?~UIf+I z=7Hiv5D_R}ox+xvc=ntJrtP|8^I!0?wHvlH1&#ob0mJFRPPi1Zj0#Pbl42GU6N3Z} zDpu8VRTy#%Iu!ek&@WWNMj6zkt*W6)uCA_W!u<$9?1oQ{_=FaON0esyD+&Rq&bU`V z1slj$0*=Vfw8mlcKp#PEC||oiGdGtHqnbDh;frkFaZt-%PlUIY(*0XJ)}9LJx*~+M zRdj4D-K$rxcDuIGDj41reeiEtSNK66&O8)uB6ounLOYHqz*0*h?zk3Ysma+{dSvkc z@F1JsiZdd@P|Crxk19F>xiVwjFw)&amiF)Iqqg6Sa?sfd*zl)+~^2MTv|p(OHWTlcY`%Vx<7wbkHTss zG;K)q+Fo8Inh*Bygvi;^B|UEYH|jnf**@v-)8Qb*zo=aDq+x4xYpGg>`=BZfEi?0D zf>ImFVwYlNxL)S1xIkEjjF|B1JG9WIwzdMcop0qh>SWJXG@Y@S^m{!o&BsSVXad5A z@#e@kMMTW;--*NL&b@?bM^vT@7dGN7Gs7Z*DzNqJ+ERSX`H?^=(3BH4S z^};}aBg zy=kNVNmNk+W?`2jIntilg=|G%{(crhRNk|PAHr%%$h*f(h<03!Qm^&uTPI;t)rLE2 zYa69v$C~rX?!-+022=oTXs=(Lj}r> zS3ovgM5D+xrG*GYI1uvm2}vhjJOEF9-68?H4YO5wfn0zLzAP@ft}eiX zYaSTb44Vh&Euyk=!C{q@r@=2285PwBhQa;;jU*Q}{7LA&;|umH(D=&U8=07hkO=Ad z)Rze=s+=oVHf8KRA+@}^x|uBrSq>b#(P}puHn#h9bG7bgE0z7~8 z_m2UT&LXsZGFe|wk00^CdZ6=veEq9v(P3ZPw-9d+SS{m+;=+y{`L9%wC|WYgDh_|l zpWibsY9A{2UFwKJJuoVsXqK%x2+N@;1SyR&oC zime&9#Jh zV&~$*djWD1c?u%WLC!;Tz~@C3@9IwEKOktSB7F28BP7NYO4!QxT-dNzbOn>IUE7b; zRxPAapD_zI?T_(!GE-SJNU>0dgFWu2P>4|CKPp;=+F8{fpI%@8y#)2c!y8Osu)1sLc8a~(}yXEBE%O7;a zZ;Jqbu5lioRSI}Z4V8X!W`>TmTUIvW-o1PAD$xxJ)`Gy5@FLrQ0H~6mu|Z+7>MG97 zrP9*U3Pt{m=pra80n^X-*ut$ssqAWE#TYOR0m<{ zsv8(EY!)%L6qlmuRP#(u5&NuS+IDU|&2E<#>R}P+`~)E$2|*gM>%%povw=gUPk1B- z&NlSwrbou80HNy}7?ex;UjL8biSm?H!XiQgAK7Ug5K!IoDnVt2zS`DNTb!~I2H73C zAUk_NH&~`GKZ2qYxhqmQkh1H$#|ebUk2_y%%K07zOD4Fiq@=U+h~<93ofH)~*)q*l z@<|^rk6*D$4J_qpzL}SI9;v1Z`#bc&IT6t08dqi|3^SFg_0xf630(zAn;g6fWwg6z zuh{JB?0f5i=7xVKL~3=eh%WYSE0s)aAU0my5hjVh!u>S`_o7n9m_)CApXxOC+?QWp z<2R--GB(!w_;FFUYb&-o7%xA3dKds5@FH&=eWRML0$;8LwjdGQCQN8@(yh8J9+s(V zot>S|iPeA-zkuA!d64FbN24M3NtQndy6s)xZG_}D_u{5R@&;UVQt8zge=LRgDPs;Z z!D@5vf|kR8hR!S6C9ZtV`fpd*OQ1BM|pJbWkIKWKWwqAnACd$HN*PQnadW&PT%7#;i>0LTfH`Y zCB2o`KBvw%;2*-s ztISR$hk?bCva>HiG!{@$;KYH~fE>e6O@!Q`df93IGVPtGjU*4&S4gvV+K5E4VO6m^t3q%3iBah(Sri22bYok-Vv=B_vjYPYNh;bLBARQZv60e{c58EI4n!~St4s}(6g*0Ps zpxnB09SOu9(i=>8eeZN^3J+qf*!Aj=&L9L-=&I{XtDvcVl9DCAU1KS|krb4}7xt#i zN&>P^vmk{ufh0JTx{V00J9~IUfuA#hM&49V{&V}8surLZR?FGXF99Ke<1#P{cp%Mf zmG@ysu&!6C2HH$392Te}TlXH9#JMPZ-g~ogC2rqWAEb0(Q(k}-p|O8I4Z4qQjXNEr z!M>&A;EyVkNcGf zzik`Z7rLirV4w`Rq=;<6i-Cbwq^r@pIH5neB2o$o&ePqs43#W%GxyR4`4O`-_JoxCq zhZ(nE(JKxw?;jIExP^h6n;VMoJD8pFTmfRrp6vfrBf&`-gw%0+sqn#W-M-xlvf&|D zuk@E!ioa#jf0pB)FXLV(2UUx^7K@&gylM#941yat@aWIV;U&KC)-1MSx^G1{U61?w zH-W_;xVP;n;~F8${8u3SyiO8pQX`gv2yJhk%+AQ5hpXK$8UdgGc-3a9*B~#_dr1T z*y#yJMS*NZ`Tt1*a30&3eA61Y#(DKYmP*K#LZD2h;o)J{SPD|-Ni&DFYos#ov3dlO zeu(j3Nln!O-~a>cXe9bgdPYV+Vxh#Hv9z`pKGp-WOBb%W=K{82A2zNoIq5mDRS8s} z??^Mr&Rjxp2U%R8e0>NV`GAgvGQ3(B7;|@=T}uLN6_b`u8uCDF9DUhvg<`iSPEZ9h zx8c51-*W&U$p0ib6Shj{VFkL&b#Fj>H%CNSy_Jmb7=lEFuah2m>-eu zA0943#$W)wSl7uZOX@%apeO7oBHn6dW~T4qq-1ohUO#5=<+g=4kFv3g(PCnVoCKUZ zA{>jwq*#86M>v^C6r!wy6JVC6)(f2AJ2dq48g%E*j*e*jT0I+^YltC=?cA9_1UvuH zQ&KWB4FT?`!+|gDLhv^t1PjE~gLF4k!*%M!JPpwNC4?zt!)Z}DQ$&WBCsKeo+*k(L>q;^b)&LvNM=*du|n*QvvQ_VC_&e4bB4q*y%IMi?{(4&lBfFtw+H zg$7%emLGg>%%@tvk(I3v^C{kM+hS!p9PI4+P?`+^0faGJkuC@I7ZLwFm^N1{D=Q6g zO^^E3bb9BC`+meD&JM?%pYtL?!O&+lBsm3ygrcTqM(;=Eud-oYME$A%1{@8*9Sx^=|i|Wl?KqCoRDAubJX( z3>VpWXjkS1qQ2>tiq?6!x}FD-nScy4kC_pt$_rQX8iu-#K_Ip9UZt{3YA>lYjFn0L zVbb16)x=Y6Ib7&^y4_V8<8BX5-MKUnWE!%(D8&BI=Pj#GH`tl~>XP65tNWYP@7HQ! zGeLpwau-FWIuSVtr04T>7KJu$+~^+=(2PEX!M@9o?9eW4%0q3FMmvK-S7wTdj)<77 zo%W9XW_!8?RfsTVz&jlU?@*8d*u3TTr#YrlM4si+Vs?ulz1qE7I5}NWF%1`L8e!Ko z1FNL(enlutSFc9g*mt^RXov%vwMSe!_RS%I9Yj?sx@7rG_mq>tn~xtpbpMd|F;CeW zf>|BW*U@Jn4av)xqCI1Gv=izy-mev&8(08Rlf=lMsl7ctpbE^o?)eO=9D6Ex1Q-Za z7~V)rvY3Ulj}JjC2rLVdPcNihAj1ovQb$*p7M$gMcMu^0!A0Jxc*L>t3FM5uP|G6G z*rBO0qaS{iqL|dPS4H~SxoG9Xf@4{upxuRA@(3VxA@XC zn_o$3D{N_mS3QYEO0axJTM{y;dW{wHqd(~X`EpcF#V6Y$sz~bfR{+DApBue?7yWw zD1YLY)+B0BPybr}nWNZ^DP`Wv`VaXRK7M|UPaCeoWBu~w%c;`hMg&##U-*dmTqpmk zD$KkWwK0ix4~Q5tcwZ1~2Hv+}6SWY$51;b9YS>B>ej}n?P{1~_@&C6NVww^a`~P+> za!do=FdzC0w)e!lck2<4B&+~b^p4B?S_EV|^LwSbSRP1^kkjzJFEG+_a6jt&C)bsq z#*mILixfQcyPChSiGcW9F#DH#^X4U#aISj`0Ac_oGJXgK2sk+U{9pDi{lbL*_||0Y ziD4^EL1kro;VWYp{Yl)RR%IF3+S(eSsihTLqOvmn{P|^O9wl`O1$8qYP2A>iE7}h+ z&KG7ac%KcEC@8;RPH3m55P*<4j|HUH!~cQhc)|5TKIQnlt&F^UArxv%w>&ztZ;z4^ zsxH()M4vBxdh-ZP5%ClELx*%A&H&ZukVGXVG1#D2IeL6kemXW&O6~mA>7x8EZzcRe8kWje>(N!2`ak?d3z_30*b?Aw32fig=B__e*(VRY%W@dh)MP+65BtG)-P{Mt<5qC^KZXR2QohvLWiQJX&uT(ZQ)V=j2SnRTFXGx|u zHXTr|9Q^Jhbpj%{KOjIle6;JB=sV1?%-`LKk^;DnqvyLq!kx!B8LZdB|wA7gD!v> z>vlu{s(psU3B~X8!=Kw58X8!UzDH1U5~stLnu-LRaUNl9=wd{pk_ch;Ad*2Xk#uz@ zK5xf(Y7_t_CKjBW*uZg2NNF%* z;^5}bz&WkB0tGqCy!j)3%=ewIT(XdH#xXnil!yx8j&dxgH{j@#|)XK$?54% zg}L?N=+#6r9C|4c%7+wWmqCtY(#vkXL?p-gQeV=F?Uy>Y{s zBuXZqkBLDo>uhQYhg65z!$@MDbEwP;a2pdN{X;{AD1Nt(_gq)J6cd9;qZZ-|kPbw5 z?Ye~cmp8N+3S|)5`Dl#?!+#H6&MZzn>8`(L9mx0pp$h+}VL@V8?8uu&BTx~6YFm5| zOotGZK=H^cQ=c8t77iH&k-C5qE}ot=IgZZ_#UBRzk5n-UV>TdO8`1x)#ihwC*aj+R z*3uR@5RCjQzQ}`)LJCJHyBW6$mWJm4jKIK)sx&`?AsFKuDzUp7f2~7JL-L3iO(8$!U2u);Pjn@X8ynO&8&1twIlcs zmO=`Ld8dgiYjd+kX&8^OTVKv5GDc6p$(G4 z|MPSeCTVK9OR{)6A=08SwT@alIx@n;MCVFZAUWTqQU~Z9u5!8v5VVE>IP{ka^9M?q zj|()m?9<;Bl=F&?YHCXid0P^s(EHwT1fKi%yil$0%S~Xf2+iLLs&5LuR zS%JOjvaK)EWk0@pmbnL-*Sbp`5f~-FG|{tH>7C~Bx&n|-Ajcs;7X_gcsIlDnL?Zzzm1S2&oc(gs_rL@4gaqJ8&~JU{_=IvNQAmqFW1fBTVG1h9iJ!qhYXN&Sw1&$A^hGQ_*8C08qYuM?# zp#vfNrl9m1Yv_!0p81PsD6L;z6oru0)If9)gCfLq+U_TI?X(64=l$YIBcr2lq1PP! z9<%@}5r0!WRUh0wHs(+v>p)w+)x}%y*6k%bTU&c-U$?fFmVUC=-N)0QhVVjt{grFj z$)9h3(&EC|S{L1#q%@{)@$GdIVz#`_=gA*pcr>IFv%F1y}6%7dJ@bK~?ToIuW zu`yOVlw)ye!2!8k!uf|iPsmpzu?)1r_oW=}GD5aO7A_J}+*KmML4>WL#&19flT;v~ ziqZI;oYxaN-eFqJq>51rQUCQc%)}@e5rM}O1AIqo_1@lvA8_m5y$)E41f;?%I(b>^ zeP7BH6cu3(fC{S6#J6RH_b(8$VHFkFeu4pmdl(FElTBz$4@Pxj*n|*dPO5B25Wx%} zn0ORGjJpH{@~eUT#i2WgZD8gIkk4rrU^dMXlg4_b1o+pFRP89@>=tVep14{nvPleh19 zLpsh8G1eRtgYc*xrdyMdzejS1Ivm*!45Nk-YyoqjU>6u6qi0~antm6UZp&z0fB+la z>{x&Q75q?44CZmQ@Tib-Q)NlXMXvz*BtUpqY_y5M`vgqIIAmIwhZu$31sK8$t|S2h zfiEU|(q-@5)iW??1>H_-wgx=`SGgvxvN@H5bt_$@cc2o__qi7=0F>+a9KI5faL4Ona!J0~-yB0z4yP%mF~EaLF&Ww+;90p>2jd#|}IT!LT0x8vj-c zvmn?jZRpjAAV)#Q5>rVmE~3jhv@J41K`ccQRie)~MKp#{Cm2I8&oXNdl1n6{e=CKi367z1`al#smodM@zYR@_gH zKhn-F-t-ysLxh%+1Vvso`x5aRonvsk(cX#fkC5Sdk`ngD&T8Z)#=hYAeOV60VZZ|t z@~!_s9nm#3q!80`&4U-PE9qu^eX!ZGN5;L({%)0Mn2VId)YNFYN)L%5I&4-xwRE{U|O|Tq$4hL_)6ph-^ z3~>q2Z@Ryb;n1@iP7;5K2L^#A6K)C4DkR&s@t~oCvw!~t4p8Gbk%;NkttuyXADfVlwFgaF$+=&&O=9!M;w>9CN9GzoH^P4KjE{JtzLJ%%I;QZ53rD19R33ZXa< z&lW=Jfp`QGkmLnqK9R1?#Vi`$O2W~aGqosOEAR|~YZ%BYIUHncDNLxQo>Ckf#DECj zo;~;VK6Id(DiZP_#;MZzMd+W6?h+TjlI{;yWcjxqPr18zi;vi?qTTLXcURig#l@TL7JbrB9=jj>`cCZRiX)Lz zPEF#JS#^|eQWJ!xJ|r;ij}2+_x6JC;j&G>Yq~3XuKM-0W`t5p1<%GiodAO%yt}mYk zOf4Fl0#FXB?*`~#MD^`V640RBVJFv=++P3{n*`5?HcLcUpFO*jrO?tZ*Ev9ii#Sov zDu$>B1eyV8DtJN&OakTO^PPkDz{|6g0?r2>JB9~r+0{hi0b7{%LC&3cdJK7!O-!d& z&=@A5=~-AX@S~b-g5+l&gkRBQ<|iF=<*cR6(Rr+UkOaZbn3$T{K*Gey`Rwc+kmp3D zvyfCFo%bI`MEB&{uj*F~9>kU-8Xt}okurjW!fh5=sOQW(M9G52wJW{DwQC zP?voeA@zR-##>p`)L|Zi;kCor=1vx7xG0!0?`Q8ON{Jk_;jh8Ch03Y#G0PH?lF8!2 z<>i_bxz|t%Tz`F;BvI2RLAjfNI+Kvcnq+13R2#_AI9oLV7%CS8TxNkrQu0TXRm`C7 z?LsjM5CAdE0Q|a+1WFeVvfv6WgT9z)@Svg$q6mUQLR74;f>9Ey2O?}UsIB=I|9Y3w zvyq6waked6qM`BNv$-K+6DYJM&t??^1sQR(&6_rT0ZeoLv$kw%ZhjtPwLtwg#SM10 z?B}dv!mVO%VNd?RmjR7GYM)p7-Z_1I*0NaT5~lN1-9mygtLZj_IdAvomH64N)hgCf zhJ-?H7ndaMuuz?OH!cPSgNxyQ@o>`Ysg3%H8Fwa(*!Ap)Ze?4Q;wjvj0EL8`hnWV> zU{5yE-e=an?vGkD(bHpN_$F`>s3I=xESdtIG2!CwPHkmng=jB72x_{!!?oJE7Rde5 z`0O86f%ot*gCU(~`^}!}pE;uniZ+(hfcPslbF@G(y>VEnosHy>9X0wiOy7DjL&0sw15s-m4BY^NMiHJylNO+D+?N{7U z*q_uWki=**gex;#H4Hss3I(vL6ZsWXvF4B8s?YvCgOO-r3LOqNfuLbzp$UxHdz9a# zpTa4oK&?a%qJo=yDDEPVFRV#CfzXVo@>hk8%H;bL@Hh+H9@{%U90(hLXh&m$rl^ld zIuTK3Tp@HuXB>$h+OODSm{_13dJP?MBY+!n&Ec965)$I##5@yZEJP5A`RsMs&yFtE zyDr~4d2=QHSEwrR#s>A>`m3lW7|PzbUFBprT8gynur_1|4&-bT;}N|rx-g{hUMcyv3F9Y+|6*!`HfkJ0=q ziIemgxaTq+-9S7%1W!aE5j+5F(G^}Ck#~jfQ+d`B-Mk@el@kv~`h~zA@r*fwG}4{k z7x-Q`=+mohAPh~Q(L~-IIYryadgN`jfJ(7870=asgbY$A07iS>fV=u6^dE^MKJ`C0 zU6b+)L!ju}aquJ7v3ltueo2y-mnW&?r~mwV$AYls@aP*no+^EL9Qnag`vg2XrWJ%E98+6}J4cS;!`?W2I#LSX^v@IQRuhX{OrQ z?S#@m!a2et4Xn!oDSh=x?EpQ5B3Dvcnv3(P1VQR?BCo_Gt2C{Z?hCXjID6_2fypRceNtUPf7!ttyZGcQ<@DXZiYCKgDK%3CD(9tLSmA?G= z(GHw5n|v2LiD1;Q#P~6edH-}$8Dj?9$tUA-~~l z9+17JOFGRPX4|kiJBh5%#5sdliNc&yA9zB>&YSg32lnsWGVJ*ei3P?1j`_Uv|LN<@ z18UCq|9^-iV<|;tsm@f2P%2}aP^YvSZ755d(qfsSAtRFFL}@`POO&ETgphqHp^&7B zF-D6m23f|=_whEq-+S-(x6J%8cZQpDKA-pUdOf$-x1M&=ZiNrDD8ixawuuJ+p29e< zy1+<7q$_{@ASxXPwU7if>kZ?R_`fNWe44T3ugbqQ$-q3QL?;^;muqu+xcHI(QyQ87 z>aRC+>19syuL9~3+BViN%x#zO1>^9VTRk#gl)m-o24^?7p5n4_bF-!zZzH8ryq2Du zHyL9%;Rs*+MMhPL3>x1i^Q`CPc zFfBf}Y9_aOe;I6%zGBSV9>J-TZ1xL?fYi?o8!Nn9+TJbgp+XO?m1`O@N3Cny%aaE< z-(g9FjZFBw;H^YjsDab^pdXQT3$yV*UCJ|Ftq_eUT z(*wQ&tTJGKXCUM-%I*Aj7nKjZ{NH$iZ;Va*7|D8Wvl_%#;DVZ^#YK~3FD@OzKrhZ? z?ms?a1;%Urv}4#=gy0`3?;6em;pg{zy^r)XKBOPrGrXom0)g5K@k%t64|m^l&SbL( z_LGBhGY^LT){PBU&P#cY0HfY3D?MF_t@#9N-(S(>o8APTwp_Nf zEc~9bouVHN|MVNW~;et5B!0niPS)_M)w19PW)U_W2Msfu&@85 z&%WZSAY*g~FA5uOJ0YBM??gi%%U(y2oqn~d<`w92vT&PITM*OIy=(# zTnC*1EOJAw(YAQZz(Ip@;6+l|o8?DK4j%>!d>=2D3xzdFb|`(}JONR2q0!y!?K>mr zwy|;Ha6_Uza=|Lrm=PTT{hf%@!~GF2zkq&7q$A2?>gwtQ9_3BCNzE_;VEz^62h`z6 z)Va%-eE55?ic0DHKequexIWfEV;uwrQraqN$EKzxxtu`EXw*1Av9a}~*>o_iu*0I| z82JE83UVXx8^PA{e26pP+eBec_KQ5Z>{F(s2I9V=I0KYGL~f#mBC3vK2y8gv=2g-! z5x1m2ZhB@J}kmD5U4??0gh6+ksC69EevPURCQ#-ow~_ zmP^wSwTqxhnx~Ab)Ge-WLfOFlM-gs|C_o|sF?x$dQ)K3pn8z;q5m2KjqSH<#BI2g* z^Jym;UoK~LIDXVu4`9uaFsIA{l1L~wWC$XUOfNp$m?UTs4298E_sAIQ2kVuRzUjEh zXfPGwJ2cA~2_p@3vAej~7Lx)Oo+#jlY!dNMx<*F!^9-e)0l$;j!urkl*_AKd5g@Wq z3AtXHMtg@1JR+gp1TmIKc%g6Ky^D{tOI7o-SDk<7_!*uyT%8g&y1;i_6C!Vc?@;$5 zMIlCh8WD;OinH=G_Nv)6o0ymwvYq;s_$Ufj5jgKYeuGztZ=|S2K_Z0s8m^uubtR|1 z;~xS|5tTAJ!ZY{6!{|3rR;~!!uo=b@qkQ$3ZaPX&ZUPl2c0LR-y8rXexP@uG3xZlM zq%<5`G?djUd||NN=NC=y*{|Q$CF-B~xZJNc9PHN$rwkPwho7FCi#RX=4nc)FQILt$ zFp!Xr_zEkdyJX4;(lLc`7Kvi|xQtNwAdtpyVdK%M15p*<&=h0HiJ4uW<{SL{)6 zHH;j&?BkJ!=A*^MPk()rZtzO8^N+S?uTnp|{+?;@QWI2A2yaG^vH};af1u~YTQgFE zl=?IdKigwC-&jdW=`^Ki`lR}^-T{&LP<&Cm3F{75g5|rGo{}}I$Fh1|4HvEpO7GV= zb`sYjak2{Io)?b7>qBiMrD%2T9bV4vPVykwfD$7<@~?Ew;hvTsd(0X_o&0i-|T2~n!(vu zA3HW$)JGiUao5$Ga3Fxpxlftm&nDCuwJ>PU(YtMn1>?mNYea=<4Du)PcIapH&63`a z8F}2%Ys*!X9p52ht>lzYTi1S|mUO~orOikMksyksbxDW4tfY-Rn zOc&WiH#H`4BqS011dgZHySHPagLG*1M4aFFQ8TVQ;AmeH#(w2)-x~|Hfp~Ae`^7n=*WN)JLoJsLHQk1*&P3eha|@K2|`9m zhZMKIefy@L2RrT#F4=&X8FD(kThz6Mg@uJF8#d_GUs&7UjkbrzTqedyBu>{!k|{{+BJL6J&GCRo97T! zs4wf)9r%u3RG1>kK~L-K+l+0EXJn>32Oo$C{str1&J}coXjUQkhsJYwGB;L_S||~@ zL^CeBfO((Vozd7%DwPlgP%cB|t|(s>2x3AxFH)<;8xb)7{8h2Ozqq=(qCb&iR-!5} z`+eEV%RdN|5<$8mfgU1{lA1u$;nX2SGv{Y#MJZz8qfQ#uwT4F+hR_FvcMbyapGiEm z;)QLdDJNR711Ac-$5|9N6eNL9>m)0#dpSFIoqOw`Fi;CS9=j|4$07EjO+(l{NQl{i z5TG5%K$k~Wb^O@dE1w_iw_{_g6==Bd0I)Kek<|#?lfzHoo+2(DmssihDIzl;aD{@! z2auq8^LQ5#ON!Rr2mA_%GO;0IDm5j6NA=21oh8DdXJoVjbd)D6APRqEnx%&bCD8=1 z5;(#AFk{+mK+{T|tf>%KdwFHkq;NAUhy@aLHEXPQq4pE&*sdPswJqkegL2WSHc~Pp zv*@U!u{a2rjuZO_;;=8+VJDqb^d*0!NH;>CKm&flAW`{t`o0}&rh1Ke{pi=CLGTqL zFgy`rbUo;ustQ}+`jf6I5|Q7>8d^GED|^-RiB{@Bv+890@Q2v&Wpfg~>(n9X_w1;( zmn%51M92S;=?0g#y*Vb3tjsOIOh^-wAewH#qyQt(5F_t;1k*{0T(R7JUwroMS1>xcQNZl+65S={e2!PHMQS`qa zK{X&s+dChY8xKrLny4!UQWUU}09kO5Ufkf3si=^==V@{UE5>);ylymvMA^wVnu3h6 z_Tq?Su3&=*lTqN)twrI(Wz(_|QX$01Ti5Q)m>e*9qS&H6 ze`#y7F<9OxarZ3?*m$|2L4y{1bA=8Qil!_a1!6p&@MPop-hK;e`V2Mw*I%YFDTz4Z+YsFyL9PJl|<`Qk;mi2m=?sgsxR`i9p}nHElNya>srWk|(7 zzTi8SL=GL|7F_*j`}(thjmY|u%P&<`1%tIOyE;=1@j`Zy?QPv#vjIV8NbI z$eIRm#hQK)RXJRM9mX%GqgLt($yDKH1G_iA3wGFO2jswCF1RODRDO(n5zE%zef;=z z<0uzP_l-)0JzOU7wh^RFAJQ91yubp0jAn(HwB(Q883yvtw%881BFTcWO6mimeJr<|Z?yC9P=~u(#a*_PV9)9of_ml{ zq@3F{qHE_Kx63ScImkE)iL#!Gt`aF_chrx<+kEX>U93lZUEZCZYXD z6HF>K|4j0(r^&X?xvPI3d-s&dX+btE%>_y|d%8VSD}@@!8X0fk$UfPFRamiWkh;Lf zYNDsF-~gjo{65W_VJ3W3;HnkCi^8Q372I`lyok$9aF7w9$YCpv5Yj%X=k!!pk3(cq z5@3;HUUtyPL&~$JC#|3g5LF-%3%=;4R1bejcb7(tFWbG_?!F>RUL+zdI6K%=S9;sK zLH7en|De#&syd$wZj0=4@@f^{?p0B}qf3|K+~mHJ56%%mF;Znb+xnn>cJI%;451?- z$yLYP{9t{T)w~wpGcg@SnJ-Rd!cBR%hDE9>u5S8GXfZgBZw%aQ$c-3>Zw=9g7_ee@ z{chdy;!H1nKWtiv<0L(fNA)!inzYBKqxM<{*+Vl`>Bs7O;Vzz@Mq%3XIQDfP|8#3^ zp7fx5oRUuQ0gxXP(6(>uNhqPIB}}$%z*}2A_5`vLA#cFLuh8ST%XD<j*gYP)C=`d`-HrVQknn7q>;pL0@J;Ss3svN6d< zUrHf+Od&SwcPw9}d)_@%laA@%9r_*iQpfppDJV#F>!E$=v8sjfP)|D^}EbiI~VH;b~G^VUZE;533T zM7D>BgG8%|6Rs;wB9!oW-Hk%?CXyBCfEbNLSjV(09=aKT9?hIYBFjOP8}tVv358?? z(1b-fg)+%_{}*iB8@H}f$cVg!@bDNqSkMCDmbbkKGn+8v+SC?6hjHai!vLw&Rp=^GG8_|PO0kGm0SKiWxK=s)H2!x8`{O3`-PC7 zKX0=3e_^^?CJ0DvW6mJaqoS+*Ehu@$N2qhM=ynu4=!(BjYj9<<-y7 zw|4hiXOW`j`f!G{pjtG`H3W(XPx69P*~URby-$|I{ZOs#v5hP}4hm=RjGZGwxB%b_ zZhsQPC+anjZnUHR@l}ki?_|#(CUyQP$B;wrEawGdPFlJzxn<*+dsAHs(Jq5e`uXYY zk&^u$8rjr?Rvc(_EHShjz*5jB6)p2o2v9oo2NR~kwT_G&DKde-MJC_5a|hnXuXY-0 z0)#CBT%*b|O9=>gWVzGG0^o#M_uaX7@7_tCQ$yUmwPMZZN8pMXsQ=Xc`js}^!+ox zDC*;O+qoA4kHLFqBwmB9%n0DtN*GXi{`{)8#vYxu%IGKWe<1Fmv*ZK_m#9ZJY?kjX zDoQ}X^pIks^aYBBJSuViSn#=b@88z~*ybNSntAg+Z3`)QwwZfvMCUTN|N1(4URZlrdj%)W3V%FZoB zV8`H9Bbc;>Q@HWT6XPGYO@WxACC%{sRGS>p*W$6Y>sC7B@qqul`qlJhIH=-z4rY&k z+cRx7&-@G`m_SWE=Q|rBhN!uGeaVh~^+lc#EPmI=wFJ8hVHK&P`##xTc3OYJxiG&+ z=kDD*N#fLcO3K|etSCVP?i)Ee>lV!1?WyRSMaaam!E-CQ+(4cbO#cvgf#}>tESCsA zkN&bj3n}zz4%9Hx_|JbQ+CVVEP7nN5ctFu)IS&88tkkl&sZD&@okuh zIpr4U@wjd{!X|Fw^p|h>T!OL;UwUfj(RJNB&f~|=`h*I(ZgiNvvWg8~v8BL7Pq(1s z$nX|<-Nkeo0}{dfvIm1ADCtsX@4$n-xVyNa!$=rHu?Jw9kNB3BLe6J98ak%G;gl1eh0N` zW4-rZiIXZP!_eFHZLd>UY;zI6{ce|>eak*AfrMJKXZvxB4h-M4CVZhw79y86kVri;Dwhg@ia@&NfGD2)0bB zgH(%JLbFdF1{P>W;R38~8|-~@3sI4L%df{vNJuTA-RTo&U-MsIH(T%Vh}b*#Xe8Ft z+KCevEGB)SeuU3j*Xxh^X=vDyf(K%~Z=XqRP0ez6>mB=Q`)3U{jypKOR~Vu% zS<|E@b?%CwA}mS^4Q1)U-JGtPvzeAEK2!!Z&JS8!FLiLn6@Q)sD6{41HXG#^iY7NE=vwJ%oGD}`(wk?0&aPFt^3)QM zIZ4npd_knN)D7agqXaBk??Z=Uct&0xrtFgV>=_#NAhq=FP-{o)qSS0kp z1BVXXg*r3*=byKuWvQXW$_FzMjvHBw%6+Qog_wF_i8-P41;Ha-k<5qMoX*jSa@<1txs71kv zv#I)3Q+#F}PDxQY!LQ3Z{3aSh3XPxUc~1SDb944z7$8K12Ef6H#m{wcUa*t~3@=+y zvwb|Luc9PDdu)G9NoT-wMWc`Sz~sQ8vCL)r_~(~T+9CjV%cuxtns+C6kAJA1MtI%u zs#){qT~WG#L$N(w&U94J8PB<$?dW&J^#*P>`+W!Sa#MVj21y))KJ-q4k;fh^3TZL4 zLj(??s7jA7=6DoxP`(l1gd+JuVk{poSR@>Ax+DS;D<2OdZ zzgG9F;*zP!a~A7&qvy~;EJdTjnR;!w0zNX7uGHWq^J@CiwVj2^)VJ*WduosnrCzV*=fVz4QXuy-G=?S^aW3JodAR`XQFcvHz~;5`-QZB0MG`hXPk zZMCIAfiHGN#}XDijFvjxV~A|`hQ+U2H##NCv)8EDUvLXlvXGuV7}EMfY*lE8Obl(H zxB(PnzRhNrpSaAL5RNUzMUJ8z>(^SOME-YAuMm1{=-_q|*7kWeYn=A7x9xb7Fd2qD zU(UF|W%!)tCmWFf&6@yo8kTrIswzCNsz8P>D-kCK2@EbzR3>bAzgwo}vf+YN$`bW( zQljRNVTLJcH8ro~OyopI$DX6JAS3-gWz`zAKVWX@{656nz2~6gN=#Y{2$89IB-mMP z8)m(DwcZ@PP`*ZFU7eg1i)J7hp%bR6O)vA3)-qCia`lE z3QAj$RZ!npgRNBr#&>xMq&b#cgm{ofo_cnDo4up=%&ivg`q_K-BvM0(gwoU8FribH zCcamQFLTJ|aZuq9mw1$AJ5XE9=lD>8@j z7<~zX~s#30(fe z5)h&z`mXynbOYgRI`6@dxTr|^?!n_ zKeh;64hQPAdKVNx1lxr6?0k_oN-OT86x0=z?P6eIM#P$dwz8Dm>fQNwbW{z!$QKaP z5ee}N#t@O$DeYt9@e(pg0&h}3nuOE_M`)|wqF%lBU_ zn9>*#PE1q#aooXvqf$f^it6r_m~(`Igj%$`b=6;|i?xxG?xH{^Zf(zNBx*xJlyuaj zvde|li?bF_;c^?lQb%jUj+06XQu80EM)G)yC)XeUb9UyZxn7R3UJX9y)2tTUs6vA$ z3<9R3gREa(xq5Xu7>G&Ofwx@FWT)QdGO0nq*DK^BA^lM|JrK?My`^;@k-d8?@`X_wKf0WWIZ zWsk18AKgSDX8FstkFv3jwIz0<8?U)`ZN=KPj_WtN^%9XhY=?$9YtL`5K!8}VEa*EM zJAxwsGGkE??AX3tBCZtlB+3~717)v2jPp18k%~sdG;x}Cnl!Cax)vP%^q+s8N|SD? zY_?dUsW12~xG*IMxWvqP>rrVBJ{)w9snMC5uLn7*NDG#U*5?|U8$eNRU#v{=hN)`0 zI7Vz3aKeEu#yY|D5%{fodUR?%?%$9WM8cO#nZWAbBA&UZ{DhGpro>N4H z(_X@2BoC__YgJ6$A#PxY?Q?nn;d(+bCc@sGHlbY=S6|=F>NCYQkfmLlLV!aJIkpG2^KC?A8tc$a*`#$rR@Lr-&CU zWUJ_3M5RS@x+*EDyO zVGD*Og8n;(c#m)C>Qj(pwG&7IYeu=^agibkirKnT>3@Vn9omin@CK6=QTk%jPNfWb zQxS2f8PQK&-3I;Dy$KT3DE3mLm^%-wb3-OMubkjq8K zLkg?#Er7xvWTIhNW%JXg6Tw5uAG~}-M^lGR#KFmFR_hHc+#~Z?@xRrMn+W3*_98>>9|8c)P#LbW}ekk*aol@;k2$Rx&U(Zd8$uEIIQr8~(Tp|LQhX<==J2+vm$P zq{j>_)O97v#DXwC)?}|5R13za_vcRRkx05Z+RMhfuj6PIB^{$K+Hb0g!)DR2v+kRA z`Dxp1Vw4q{c#qeZ92{4j0BmAI$yP(yM1q#Z8kZ1~D7p#}B_%YiJ}}0aotx6q6yX3s zvsYBz6TQBlU+KSCpw-ly(YG9us9~%oOjw=KXE47-7PIfvbS~yt(C&NeY-lf$3QE|ivEIBVy(?e zMCSkdL>)B-gtN^J8W)@iiC%$Y4fG-T=HwBfeR{|*a#yYb z#`m@=Snk&sT=o&W?Rbb&XE@7piO zd4>Dn^wO+<;a-3{_C-mV!97&OsR{@if3LmHFOBwA+gy=Os)_gWzBo2YrFPwf#S@mG zTs1fWZQKM>A9!d_zMjj@EzV(2qUS`#8%H?!f4^i~pYXYBvM-bc&B=UqV;OonG4Bt} zk7?4>H3O~CQ;FGfSeYauI<7LvL`|0wrPx{%x;4@FR#zZjjDhc4AtzZpmL|gN0~6H|i^ZHw%pAR+#OIHkTwbWH)3B&8d{?fQ$<*6WQ& z7@vIP*fF!-`_2D3=Op7}yOKgF6feRqd4Kc#S^bm#gYDCtv42*4x>XC8f5N!AkSR_h zzX^icy6rStH)GpLS=uNY)$CDet7?)%-PCNZ*yKF+Xo*O(m{q?FGCOQUU+`(wX~nyx zEtI_ib)))XsoSu}&6%6+_0G;U7J)Q&{Juy7Qm9OkFs~KUu4RI7$rj>NIzVQ7*RWPE z;+MTit#A#eiCxyx7oA}!T{w!2%*{81>GxErIDbBM#|~YAWeKL?J=laD!|X993@KIk zoq`oKa)?WQ35B)r_EPt{pthQEd~piLUB=N5Y@Ca?Z*O5n$3=p8Ajv{xb&#*WRBcj$K#_fG26E0k^R$03Q^F!kH@VN++6{q_3j@z?1)$Q&b{-I+1xL{TWA z%rTuVeiQ;_kl!a^3*6prk>QdR255k5e0^N2NbGPraI;WGVfS=54nB9!X zDV57mmBxQwpbOQr^3kq@O;=Su{LyrZAW0WkD@1)XVh;tzVD*n`lv~X zrA%$mu*jY4%bG-NSB_3x{mw4Sdt|(eS*vg%1{T?&3z{B0=tSOMQvHhZTJxnnlv6mw z$1Hu@12JtwY3L@|p0m7SQRM;)h+Hs^gTTKJGxrAWm`QLQsTf36OQjgC^Ki$$BCr#A zVxkSuyEqd>&kSKGPfD8be=v{yE39K;00`CuWDfDpcGFAz zI%3PHL0eiD(k)o1qYyv&oP7CisfL!;uy|;H(=ZQv1w0cPCePgs$J2&k_ z{4#OJCr``%mLYL=&LJV{Y@{~OXV6cHgio-VC>qm6y(L1eXgH|Lsu_5gyC!LmRn(be zBW77}e_25Zljg?=*-EcSj_KY#4V-)wd-IT+IJ3t2`tFcjR*(c*ZX>ATKOlE28G z(eH9-Jr30~SVHJXZ6U>)EBX<#B64v0C+$kM+Iin;Suhk&e!fQoqi!J6Yp7qvYo)y4 zlBr%oPTzeq#BKde*Qch6NH>rg(H$aghGi_;=zY0aHO*u3^wfoF+5SUAmi4}$g}f6e zw8X!6!AN`!D(dRFHKz|yy80s*6v|_WIWc*(MrS-0ap)-&9>tSC?$2Bw<~ddCY^U5F zDmJgQU(s%eO@^2|jAUm}#CALj<=pGVGe#Rv-6#1s^31d(BRR8Dzizj3QlaUD0`Z{y zf&PS+l%ik>AH)bCR@2mjK`G_06CGYaFVBIXSNl=yX%eCV^JxOobZkQnz?B2KlGR1qUo>4BO2mZZCj*Jd!z4ubFFBf zra4@TB82C*I^D+FU|rce4vS<)o}(fYzJk*FAC6kZ+{?*x(Gpy-+_Qfi2aoRH!Cirm zW)BHO6Y=r=#zda2UVaoo z4#GwKd0#MEZ>J?oIkuU;Gjao(kD+0K!@D@1NdC?2PLC`V$7U1eL_luETK!JlC`ri1mHS>rmMj`XxU%T8XIi$==#sx=4i5GGe9DSRPvZ(CFx-y4kNz z0xYb6O6LVMvK^C0DNjqYZN?cU9Dzb8vGzyR$E~gPOB@Z70CyWXZ{MPOdVEm3s#4*x z+52cs6QAg_jivfx>P7X|(T80wA#0fyTCGOPL~vNo0EBp!6TcbPw%7RI0vzr0SFbFb zZ|Cw(=DfHUGP|9QrRB`lJ{G}0Hd`EaSy*m%Y%G6&`EWu^YBQlPx_=C;OW8tX3?~0w z@0@b?=j^!r?oU38zqQYQE>hUcwN-KMKV5PA@GAeCle_D-ZrOH2M<-Q=PMSaFpFd#r zsjY{;LRf7lrxjl@QOz7if)XKTW0K)6K7c-#cTO_x~~Aefy*CereazrEPwv S@RuJY{AF)5QC4i_6Z2o^a0Q3} literal 37670 zcmZ_02RxT;-#>mDQOcf0NLC0TGb?+QRjCM}j6x(bitHlUBW0ISq7+JI8I_Du85P+o zAqt8A`@FCFdG6=={eJ)ZbziURQoiFn&*S)f-s^Kjo9@%2r`tkD5Cpw}zP33*P_W}4 z>-9AFld)y$Mqn4)o@bjp+Tl|1`NALK^3GW|DC)Ka(X;Tv&H&wNsocrEs z^yxYxH__zvHvX?){GUJMmKI-rcjqwG&YgF4vuqC@Y<_)m{K3!biz`A#DZwqnyC3sv z=or0tnXsilwEkoNyYPXf_wJtDRb>9rpXfju5NkmcK7Z5e9xXeD=b!~ z37t(j{Lq#CSZ&}^-$I!ZJ56Ygd76d2G?!TT|KkVCN6Sri(nr+T+1dS8SE>gbPWM$5 z9ojmD3m^WZzxI*o#ful&MMb@Z-kb03KX*?4)TvWdzcVs2%I@E9jO4ozH8J5lF*Q}| zbKP$bum7)a(GN~`)Gj>Q9IF>^QB+)P?pONkVxf`zotoEU3Ojf1Tv_8))@40@@?_*@ z*%O14Z*J@F+t=Lp&@DbGDNOd{Yq@9#mrcjZxdPP!#5~00Dt-xdwF|P5Xs5O zR<(gj-@bk8yk)}e7Z5OfaqSP^Azv>qnSqZVyB?iBYIXRqeRIra(H%P|2qxwfNgFx` z2L~>0?&0emwM7qmRMgaXap%=49zGoU_ASQZ_C5-NcaI;z8y6YPDssF&n8Ney*+6cs z=YFBmx96@l4$n%Te9c2>7#h+MgAY2?nqDM}?{a# zW~`oo>rK!6SUcA&tgVe>g@lD8@bP^UKR4ggJ9vw z9Mn)&R<=BFKu249BZmY(Z=BxJ($dJpg#M8uM=TE>)YaBbm9o8+bzwQ0ZsSIm<@rhK z;Hz6zntMK0d!PI=>t}i7h+(3zi2!kSW$}!FfdBjiGe!1I)c_Xeu93FH4TO`UBNKC1 zSDxMmLP${1^w=?83jPp{8QqqsoXlkLL)`<_-jlfPDSynvD%R{u)PG1HK75!UEG#St z4R?3RV>Nya?e}W@7wELZzI{72GBQ$MUmtwk)A!uDhzAd3gQxV^2&~R8Q;*8Z>U&BK z%}#V}-*aKb>eg0SS=sdS%x&8bey$B_7@pk7Z>Q4K z)SUQGzMbF~5us&ZU?773{QeQzG2YbJNEs0kK?K*->`_!!77!7M^yW!erm*|*=_wOk z_`o;~4Go?*K@=7hJ&m@vlcPAbZ*(hujW+Azs#40%qcl=dQr|w;@s*aArtLW|Lkteb zsp}dTZ1^%fOkUTkjNKdG+%loc>S)1+Fgteas*?BEApVm}_Qa;#yu2;5N zt18cJS9w)0qqYn-$8vKixbt9L@3N~W2n}Q7O?ZG2g@vN&(S331t6W5x_xQdjZ2@w7 z@deE@YYTMs^9eRz*ZU-Ere*IfW^%=GpU#}Qg~fI^H@6HGUrE)AtC`}5ur_c%gp7=g zy1Tn`c~$*Q{r#1hnGaZ6nw~u?ho=~S>y~i!lP7P|WlvUl$MLEfy1TpQ=jCZ(=d!W0 z>l73eXls)T&&cz<|n-=UmM5p zt`Uaz`_K^z+5YDbNy0v2-14W0td7W(6pr6A^775C@!Op$vH_fJnxFQR^M`?xzf2_3w5j9yPq z&)LN#2e0PZ<0p;nP_acPJ8g+SUD(zEq9mXF z`i}nCv13&z&)jYo`yZW_d9hTl?y&Ub`Nn50EyJjbTGrOqp;HGQ-OCXwckarqoU%MJ z_u=X8+jBjKY=_Vd3}2?FrSVHh7?0KcT=@Eamvbk7h5N@X8V@;Kj~^E}c=w1o}%X<@#s|VrLXVrQ4z0is%~UtWL!^8SyffVucmfWWqhb9l1t8+>D8-Ob|+7Y zc&9!%|MP^Rl9DDrQ#Njm;+ZehzNf}t-zatKgk&Jv1_wGrZJ$tq@M~fB>co3aqsKVjL z=eoG;Y<@*WMGbx?yQ#ND16%vUHn2+jPFru{Q{%aL^Cot`zL60Xfy%^1MYAaw>-p5_ z)8wU&jE_5f?|b;+!AV9AsbjB-ei${4{~Q_{i$KL3PPM&2VfwW9%s|zdvPX|13JQd1 z7+008U`G1{htP?1(OT_}AHRg}&c?=8^N#C=k~a`gx)N9wT8(p|?K@J;g`azM!?F5wSyS8;V zQ7oPnH5gU-%?eOtqgTCiJ;cw{iK;gV$UznsS_U3|f!tTGjJw~w$#Z*O%FJw*r55Bo z`{lVH$Cb&k_UmsS`?x(u%Pz>zzZM_Qtm-!t997KTdDh3LsI2T7uUeq~mMvS(uCAOH z5HK`07Tmpi_vI^BwhIXG@$p@bisCP~GVaJy7xDG=?Yr-^k@JnqOM_x>uBGz4O~bGhBI5VPOdqVPR=) zXwWQr+FfY4^gUKN`R||KiRI2C*pe z8XNagYB2Jtja)tbx%P%p9y2fR>%aQZQ72w!8lZ^Zb&HCg$V%ewR=@wF_Rm$6#wz84 z)2jaSqCQwMQBkOFdx0pDl9B|s?=r~$P!#q2IEoO@<}F*iI4|nxgul}H)q66_45*ix z`FTrAVt9DC@!#jq$(3CFyRWa$`Y}U@hQ@{s8wPf5+_+IWa8dgAr_Ro6t1CY{jyUWJ zT0Tq1$T`LXpQQ2DB5V$X`-dL8@@F^I(< zb@eKV>9MKvJ0mhPdD7C;H3eC=0VDx743wjjp&)sAt709FUo~L+^7H4 zFI-R)6BDzuvorn5MU?K_zkmO<75beCr*RG*ec?E?Q65czuG7&wMGuYIc0ELTz zYT5$vF^08g>j*n+Vtsx6LAGDwVq%VOe-%_-EGa7L@t5+rfUn;cD1~POx-!OF&Mm8p zHraGCD=1=S#uI?nZe?-S>Z!j^UU!+Htr40*6V@RGQB+j4_~nX}sku3&T2`Ej?{s~C z|8;S3)pMvdEx9^ZP^l=uO;GS&#Bk4ad@#7rtY7C*d_Mie!+Z&*^-R3HS6$xRI+Haz zI%*FHEHg?rGpCm+L%0x8aq*G|wcucbDCz4rZ3;_I->mF2MI!8JA(rTw&ugok&CSgO zzxUAJh4;3il9Cb8(b2EQ2~$&35}HqZ{rWzmCQ*?UAe*QU-^f|@3sq8dn7V*{{O`&N z&~x~aNm;_KJ!7}xxo=#*wNfAH9XASE&&b$9l3Tqv-W+s~G}VA}H=J|?n6YuptgU0v z*1dbzQ`n(Ak?>kZM#l5kx5McUyZ`v08juJt;Mcc?-UlboEYG`0iVuCYJ9SDzmVvw< zH&lF&xyAH7I(-G4;>+CVOR^i7o12%N?ti4)E0XR&8JwFdz_n#dZeij2hK2@UntFh4 zlE8ZX+{cpNA}K6PbEwq10c;C5HstQnO8FNll_n3o#E7!9ljZ}DeKw-R(U{&S3m_lY zlXE*cRS#QPMa6O}G&VJbZak56tEPqr2tgMMndFwZGmDFh{8CbkdRKWUh@_O15k3QRSmvQhzr#dG}i z)|I94EFu`2HoL5hiO9ZpFYdzMWmmoJ+d z!#B?2l})c-Gk}}S{QA|5hDTxf*#-4!D=N|f9Y7o*wo+yo|m-K0U7u`ZE=CYNx1ZFq-6@J9j{-n7O$(^2QxHxwI^Uy&)(p zEFde(3Qi9uS--OMlUr36Qp3cjrz)k^)s$%duR1%Kw5ipy7^z-&a=qN%XhwiA6Zf&e&nHRcqlF7i_DVSw`n0w zRCs*mC8ZV=oN~X}kRTQA+b$%}SZer8w~)v2+sZwo5q%-q};cNN^YSaS2? z{y%#3Nb%z89ze3M-~N=^JdqCgbxPt$#rj*fZjo<{ih?B%N?ieJh=CEZf;j%Vm7@VqUV<1v}@Ncu3g8&y8Q{eg{hu2^^0nm znVC$0?)U0ew^Vw3PI(fje(HlXXh_qiPrSH}(7e3ujg5`c=e}7D)SQ2C?0Z|&`}dqE zYav-#e1Ol_($m|N5}IS;BO+)xB(0;s7aE(JY0#OyQ6KGCVP@$-wow;Ii^wd^%^VV z>T3-FKb}ScbI1kOe-fzq^5x6>cj8tLPSDHk-hDVpX4v-M8kFhb!@XbbOO~PnU`^oq zY6pfuvcaz6)W1bD1HQtvWVPe659|^X!HepcV}ldnqk3dWkp3(4GrSGp3dLsxHu6L6O+eY zqjb#7?dh^4(wX@6yL>*Dq0|YN>)}@K_Mag#hD># zw6#Z>RP{?g$8)eHR8>_gT;9+?7P+LsUk|3xp4hf`O{lKZ$aMygBkI_vH1iP6}eJU zQi%G8SvPNzTl7P3Zv(0e!9*^XB~EtsA>5QS1rJ`l64xRPptVmivSqlTzn>eoHpxwa zc?d;?`{1&K-%; zSVr{~Ce$-XG14+Jdp$j+gQx6NgMxzg_|NN?p2ilPnVBI>w+^^CIE22ry99uRNUM)$` zb`y8A=+kxj>vAV3=2pSs(-#s`)JQQm*mW{=e*P?|VWzl9yqc$v&)v#-O`S~wy?k0_g!>`-gLQ+!?h4!D)zsR+dRye3LCZ92>i${=_$UfO|Q{UJ)%vAIl zl#N;N&BkZX@*7Ue=c~u0P{kGc)6e_lCZ$5c5;)#XyGDtU9F7&UT~+mIk%@gFm%*i9 zkfK^ukNpsJnw0nv+rD@V3V6XayP7|yvUF(e#84zVjAoXY>cmu1j9Vk7QTA<<{Rn={5bWV@XLVtNb@wSN7*w~nfjV%l)n`Fr({`vC! z$}R}c-#$L!!~!3CU1Zcv>X4|1A0E1K1_lKUjf{kW@4v5Z6uNhM1E-|5MyjNZougw| zaB%REqXVO}P=7aZNfYRGP(q$(Ylc>tQh>gYAAq{4h2LhvnycKWprC**djB1l=<(KT z+sOUJAz>A~ZX-vHnbJBP8MYXXt2LdY5#3gkp^J-tUOqmfpSZcX-vHsgei|1OlMnjM zYUVRH1+~%3ejday2kjl?+tpPpJtM<>-#&%|2M%;WDRKT#X0I)HJunbuZ)9@PKs(>G zTO(n`AMg>R(cFCRR^_wV!!2>|r&4nt-Mw?C@X)tiUw^%}0Hj)G8u~3^C<9;_yI1X6N z{b*=UXJ|9z*qt~L0WIm&r<%PHcK(;X;`qW_|JZ^hcLT(UCV563#&Mo40Q*@%X*~j!r;QBkEtgpo26K z3egZEkmI-bR(2SI4R7AC9({BQ(j)yLTN{~;3lH(VcF6TBv4bSk_{~y+Ttd5wkBMSs zwuj)w1*|&#@ku0jwEdr7-v?~8KtaI~LLeUvzrLX|(f3fC^UOf;0ddj>T%2iQj8934 z0BIu&{KM|szb4<%l7P|Flqq#s*T`t2$i7U{__+JA2$wo4a4s<+!SS2Yg%!mVDch^i z_`U$pMa9NG#~m=Ww6ydH;EG9U=)ZJOD0^Ps z>g+VFE;<;;r+#&pLvwJ)xR$Lg-*&yLN#(aC)5G7F;|5)o3z!Ve$oXBb9$yC_HE^;! zZp&^bdcmJ^3C>?K5@&7kk`9|Wse%}>NV6F%^v$xcooh3{L-*1*ld6@0o!m zMoFL)M?k&sY$0pr>3;d7)Ksd%n}Xlp-^(%|x|JcPEmMyNiv_ukc?fzz=C9~yya!q( zq`7v6R6feDxwv*Ax##)#&vHO`?aJrAwch3Jd48E)oQZ>jMqFGR%0DSu42WH=c(wPy0rvTY1#Y1S z^>!81M=It+tR%+9_#qMiXCD%O_^dx4n(EP6p!b#tdTxjfU5>w`x#)*%rGl84n1a!y zh@KKnC<*S}Ez!H(-em*Zg7oU?=&S>(dd};?wPu)+tb1AuO_NI4B!e2QyTY}H4n=U> z^7Hjeq}L9Kht%COGPd~to{oKfg;U{iEw_SutAx>e$ECSZ8KoGmn6bTAdMub>ORB|< zXgl0pz?@DjuA?I( z^(`%W?$1c$W@vJ9gN=>N*{Qb%ITaytAizGtN?BNGxw*Mh2jb*VAk)Q%dUdXFoY^;ur9ZQ<@SK(}(6q$*@Zrq> z_E7+UIba_6zI(CrDh>9Lh23I_@qKqU%lY%?O%Gjsx-_R?&mG!jm0`JT_biH8Cg3Ow zE9)$_BUNGTpKEvAMH6V()6+jkr68?%{3{n^jRfYDl$5T$q#Ds!Ur)f(rp)Tl1J`<; zrGD>h!ukKWG%+v@TX$L@e)l0&#lm^EHB9{NUgfsoHBt z$DmJ>H)-zYPv$LKUhHTrfQ^L`slK)%>;Ca^I5vjE%wPi?>1#?C*H-_cvpy>@O7(=# z!J~e``h@IOf($9VFSThxG=U6lKoEI)?9nbRkHiz=L8hz+TB-H~EwiNd63&~JXP*5*KAd0qec*aY`L~n_+7%cq97`Jx!icSH6mC&)c_-zbc`q*L3}Y_vI!O zBqD(QG8OyK1)Us#?G!RF?{>MIr`GA-uu0b_*I=B)9cTV7`w$vXj}_FrnV|IIJ5C9i zF+tKsSvhl`8hR*%x}x{pK3a}U`J3fWaiOg!io_=;hub$rJH{Qb zddUrdGEsJ_SBCU~$yy*Lb_u>OfF#;6c z--I76jIJNt4B|uf5FlK8505y&PXSTU^+2~Wqq?zM*8O9m`uX{hfRvcx2saPM8oZvZ zW5ieErho4jxrJX*_s8JN(%M z

z0IP#yOGxvJ3XysSG2ipI|@BR?izQ#;$24izmJzmJ7b51Px)?2Nh9pd6taV^8b zp$FPX&EoIJ%;vP&UoMZjX=5J8r}+DEi$3|@4n%=n@O!o7UTq`fgU=O*V@?<*8uCHh zv_q-~>5;uC{%6R<$MAIpkBG!XR%%KLSQ=Ns0|)|J<$#-o6t=^W)TkKf)pR0gheE$Pi;q^+ukDj3I%tJ_nVD(tBl_R)pvIq~uwU7k*XMthZubHqABQpOFzqvXUTdHZ(;F+h=}H+kiLIA|ry@ z_^kLq2|=KMT9qGPcVX?X@5tB~xJ1=K?)3C@5E9YawbcNWIjtP)y(UGpIy{P=1X;r% zDPIEYQV_jn@!vp77+BowBp>|cSQO*>4wwl9#Sb$ zEVL6{CKB~+_-&B|m->YjHz$5OIY#sjejrxB9%_U-9zBwW+R$<%0LCS5C;9M*!SV4( zy!5?FuHU~o9w{*aG4Vs%KA4VzWSpgT<9cw$ZZ{4F9!1mJHF?htW-DLSH$VCRl&;=4 z1F(a^Qo!tiUTTlFW_<%{Cl}1Q+LbvY$(Wp4uMICq=`fgrs%l~kp4GcQ)&^{q(A2us z-sxy+Qmi5*MwUU6Jmj%09NMDVOF8R^v;{TAhS(R$4HZ`bQn2fh{9dgjlh%*4#h7%Yfs z+4Hy@vY0`O{(bD`iF*Pt>8k437s@3C4JHd5N(4XWgk>af7{AULeS`J6yu2)aUGbAEOAr_l&Y{&z76iBq2S z*}1cKJGcxxszs+9Z1j1aoLv+8ylwbnfx!(!_}k?tJ9y#JqQSHp3r76M!ZB6Vg8@b9 z;o*^%k+Ijt=0>6k9QM%{24uho;Vp)8s~FPFL4kPK#|S_I2fQk}2}{oI*SB7uKJlUl z#l>`_k$>nUo-G0tQ29KubH4Rg#`SB+{hxlzwZog4*HbT!B<}BgaB{!#%{`lgk5`99 z=&R08f8?%PncE12uc0lIA-S+w%Y|*h3<3vA`a?k(NT@^KzsF(^07G}enN^7Z2zz@@ z_ho@W0pr0tRw0NhLWawMl|hy_-#`789=3?T)PMfWhun<#!8`Q`C}rQi9f?-PFE7ur zZQC}oZ$Z`=oSbaCarD4}a0DRz&Yy39GqQ(wzx&8&&H10558V!7S+bK!73_R9tX}0m zolkr{$X{%3*1h!_7Kp>@%95v-*ItArYFC%t2H+brGykhABI$)aNQ-6Xc;bYYx{S*s z_m7vMd=4R$Vf8$k5A`D;rVvKNX%8hNzjSRwx1r|DiVM$$$zk&9F_d0iPU&1Y1ahDZ>?W_Xf!M zgRrl?;!vfAAc}hQ3iOl({C2-%TUYyf7^YuHdV25Cil{E8G>amUcC)A>38vp|9A2gE zLR`<-;(CL#;I~;=4~1;ENaa$|GUs-q$NSQ)3U1;{PjaN%4o*khw{N1ESqens*R-%; zg$P!U8Ud1W(bEZN3(H|@Kv@cb#5{wRp*?>ez+Xl9ja&kJ7gs{SLGrS*2|#^Vi49N|VG(lM zco-U9j@HyZ*^iJ1faz*nYa?s{c(4dP^ zU_V44e1(J{>HhzNqn`mak|{>SoSNRf;|Qgp-wV_KU8&6#l4B#$LwZcXt_>ov&B!(j zWDfIfqz|{N30GkYl^_rJZDxL68{tx%n!_F4*M3q7#VF3jNPSA#M4gO$271(oy^V94aH{QqGSN{5#!PRg- zq~TOn){9GXLL~SK(I9{TsA*^f#KkviEC_4BxzyItA$K#0txk&cX|C-*b7t4>l(aN1 zq+W^|Ww3vfGBYK9_9B30fE#<~fV`Ac9MK7H9m#n81GPm*p|Qu1;U2W0s3-(P^-%$N)h`%pYeRdzbm!ERcyOJF7Va0@bGnjXK%1B4Qy?*P>-XcCde;}3RmwL5$UwvaQWWgOgEE7@tBH%|p;uKtN1Xlz;p7?aI(#{yX$l{o^w8!F%iO-dePRF0|hZd+MW`|ZcJ2EU|=9#eF<_W8M;N1-31b~*PrdNxo)~EQ={bh`~-&T&vh5o)s{wBNxFhnOcHD4tm3e7n~>bTa20lK91lEitQJt+$l2RU|#}GuM zC9JHh>^ieGW$sh@ESP1$@PR2rm8Tm^X{s8@!o_7(k_n20cPR7udXVfHC@G48i)8~# z70;e&-?6S{(ePP`D=8^?HDGSzMeEb1jX?7M?LHO=9MJgq?|sE~2H+3r>Ui$N9Tv9+ zfffgRP;1-U>&PC4|H)|H{6S|T7G%l^WQ3r?LwPbn#SS`4rn`YlLqO~thMQx(@-8DE z7=lVV-BpmAyZ3~9Ug@=fczsKwFB)^_vFJc{svVr1oS;&SetLr1(cVr^%pd@Ms`vgn z((!}C&HiFDcHfJNw(+0Iw~n`Wblf}84B<{#v`pLQC+f$YT)v)!-+&?Ol zPW8WY;n0jMOI|}B4McF5oQ6Q29Qhf?F(K$Po6yF_U15xW01Pw2#`7y z31qAreKtVMY6i$BbH*P&e9(~K5RW-}?ba|<%||>bl}}@z$@bn zxed@R5FVjXTU+slMe@>k(J(h2!eg=N>wigrqN4RMX*Ojqzw5^@6UyslLQ+&*P1Hw<_ zFwOMUojZ1Hz;BfP{_rv}8i^Ubx(k2FMMDI`MFD}CN^U4Gb<;ge)|<=uBA^fdExNw5 znuh55YU_)-5cs7;Fo+o|21h!(yD#C!kaGqoh1Fg4m><~z`fumtwC?E9qmGV_o}ADB zQ7A%z((IsR4#X9Jl|lE>wzA@CzPj}a9=%wFH=<+%bS6kD4MpG5$dZQ z#0+TeC@Tco1yQ`)f#iKqh%}&BLn0z$(bp0ZE-`FX7EO``!O=jV{P^+Xh>gX-t0Hw1 z(?f^!kTyi_rnB5ZFa4+!k^n2nN?O(U?ScqEvxzGhzv-S_SPM7f8$4t@kV}A$WHuUc z{v(y6_~eNpO-77bxp-^h4&FT>NDVLI$Fc#@Dyy_veeB-=3&R)StH;dCIm#4DzkbzMHq4+8$(zK)~swgpqoR;y1C6 zkk0}@AxSNsa3pf2+hk9Vw-J{Zx0lA>pCpEIB)CVn*a z4nYh&4d8?o3|aGOjB(@tCBZz=veZU`3qB$s9R;K}6hu;KfYgLdPmA1ERT^)$|L-E; zjnu3O1Y!otQJfnAcJX24goeXi{i~O{v|BgYxQiAislhN4LbzxP9@Xz&bfva|fy{UJ zZ1+R2$_0{0_r}bKKEW0d|9kRHBt{I30oU9=)fgb*cne_@uY`5L!$JbNwio{7A;peiXxA`Cvbx8o#o&A0`r{dzi1 z>}_-qn&xI_b6_kL7ZxJ?h`Z_xzJ@y2g#{g5c*HyxA|u<@tv2I|Mp6HN0VZuZ1eG%| z0maPxKO^~32>cjAHn+60(nrKv5X4m(c{*lhjJYMi>pT#T>o@*qC0^Ua%K z8OC!{Z#PheXz1Sb1acxh6EcE^J4QwTvjXP~?v|ZF`YC;BGdZyc6fY_vp^ZzvWpbT{ zH;xui95F-h4b3Q;yO5P8f`P|@?!%GF^oR9X4+*f`p@o5{M{UZ<%cBDEn6Aq8PcmRc z8p;mias%$oNO}xGeDxZ4WlO$mbWo!a<1(G4HY%iT^VEN#5t1!}wZZDEi&Sv6s7-h7 z*mYrL(Z8ckzi~5B-_^y8N002?z#lYH%EFXQ>lqlv65bls4kJbc1l53SAuL!TcyQ28 zvfebEXI-9)U*0~9+ff6G;QydWjqv*sVrle;1>HvoPBQEEJYhzBl6!1Ntwzj`+?Ig;?7kE zcJB63VC%6+oe!plC=Z*Y9)uqxdS-T36PC@$>-{^#j>;z4q6M6Yal0Clzec!*|9t=L zqK&@C*Mk-oB@4$`Z1YbA=C|nj2j-9dlQ!sC@@w@|kt-2$3egBgegKYL>>mkq`;-bz zXr<*?i`La%1;@nqCwTfy@-<;4A26aW7G6l^L@U>YL^BK1P+-@t@^=gdIt%(njQZDV zsh}G)!R3#?aijeyZpNr)EZ?^$|1iC4KZ#ia8|H1;M7KD&! z%(1Y*2Y_BM@$T+*Yauz8Edo+AZ6aBA@Dh>CEiLHCDdctPrXrsN(sv3<{v)l-uWqUy zEq!|V#XBMK?De?$7;W{AZv;GqGNJOjDn|_M7-^(!`|PFwPc$(u2$nqrs|3W?lg=NJ zp`mGQwl*{AjH{K8Oh}_=K@5~%g+##s|IbO;@t?>nBpq^M2h1%DQ)!5)I$4fUESV)C zC{*S1m4lRFp(3+mDiZCz5ndB!j&e=uGzFx{Nm!WeP`RG&J0C(C3>aj^^}BhhqG2|I zmX$-wI6FPC84Bk>-x}1P8O&pl$QcnJ1o4W!-5%%O@4in7NeVZI8}MeuOkO@)~Tw+}KiNxB}rVMWxI8)&F8F zh8duY3qFmAUW4;wJRrbv1*#9*)zIA99jNYx_H+kmv@U7y*WrC}e}~~p%h5L$MLU8# zq1=K~y!%1u`5!7h_^{in)EF_b2%+ru{;aWSIo&wk_P=+FYiIrTkfSla@t410b+&PT zybVY4UjsNj>J{LuttLT75+Cm!5~4T>&Eo%>EqT)L%OIZ;W5m@R`A+MmxF0jNz7W%Q zr_I`Po)X0zFkVnZ#Jj~71KFw(6oV{zCHFmce?8zx8=7O7F*>H8lQV;Rht|}LrBN+t zw9r;0&WI{2arl0ici_Dy2msY}LR)qq6LdV^jgtv}AOJpig8s zZAR>|x&`?FMXc8*j2a-Dj)Vv$)ISQ#{jV9g<&8^UyJ;<-aCN1_P~5(8O!6f^Nlet! z!W}ync|s(J5KW~^gJT2fj?}YB;)aSy+S{at3=xg2>f~?=5VK>7If@${h$_G_KiZ4t zeaaUku0+Tt3d17gQ~dyPOpsx)^73-h$sy;+b8}tUkquZ3vn6X(f8D~%|D!h>paoy|@ zhb8(?>|Gs!_uI!h?B3F1LRzDJQ~1tk*iv?A(umCtZ@r|t`maMQ{+Wk1nX&|Rh(zF` zsOH!KeNnkEg`T*|kS9-6Q11WSk`J9_n0=RNh@e+LODSbic$O@e3H=(GsbRP@@*|>l zDp9EH)_h19rl(0e0L~vmGh+$56!mDXNTO1sXCp8*Oaj?mI^F9pTUEMmMG}o9f`<+r z0udw#?6mB=cVj{98Zd=`F1_$vf*}pK{i(}3?z|r>ky&@ic{2Z3!rEsenqMA&p0GX&s1j))mHTjnNaco zs=LuWAw^nG12O?47^pZnB;Qu*!Suotsv^f-= zg#2ji45)}kM%%Hl{Z|%usRk}y!%W-+aIm&^Qd*im)E_oZPCfXcxfrUB*T=8tq6l_( zb>$%cB>pgN)_vx+J|7ug1mV^Uy1R@~AI~q(HoUs7z=+y~_(7VS3(K$R zj~j_Hgkl>)Y0qHVi-g43ReM2SlCC;vIc~xz$n0PP6&YA224Pd-yKjS#4ZE03I6;6X zFnFETA1c7Ko>U01_X*OC;%B47>dSwtMx&J>oT_#$B{iv)7E=+_Xv%QvWt>1B;P?p& zujT{b(Y>=JX9vj~FfJ#cqQZ?;Uszg7llqdqPZ!$w(or0Z!NU+4tvvR}oPcv(Wp-@y zYGynRx%hb`C`c9efr5Z7L5|1V+IQnJ22GKAvFj;5fC)jCe)sJ2TS7q;1)yRtxnm6s zdQ~Ge#<|Quq&=e0Kw209jYuH!L7=EK#WT6j&Xt$R<+pRz&92!~e6pjQVK{qcITY+l z_%mw@yfx21zfO}%2;!Ss2o(SiNtDOp18C}>oETZNF*W6%k7Ed4>ZyZDpC|a8`0-5y zBXpQV@|zi?0Q3Plt zqB4;n0wTJkbyYB)VD$In_AdI@@BQm^hT+>EG4PSMY3Aq8CiKAc2XP3Q=G?!}f(dx0 z5?v-eB*P%zXWzON0quhvM=HE`Pw({UyB|7m073)00J4(*@N(o0VjsQf>T&wm}OAwmXr|UAbc$3whQ6 z4+Aac$rTau^uEQvFSe5nw0=E?Ffk^Nr(6!~fvHeZ^8?&Em6(;7nyLo{pVTzTGh_gU z>%kvQZEQX|_mi#{f?(3Scdv_V3c=PR1A#(9LK0SG1RAa$VrO`-!J(lLsO$>2xhbOF zbCF3|2!3$9Nc9WGDiGbSGheh(i5zhE$l{C0&(PPe8*!OA{cqt0eR$$41!B|x4U2}j zvz&d{v)a1#<KI}bc;b+Y^i(&@?jWmXGd3!p3J|=} zq;Jl?XT3yw_|p{t*7zOYvQe!BEIyTJjzY)*8gV*bI?zkQIkpY#8PE;;Go# z)fF$Ad^s*I5+c%GEv+t$MZo_gkAe`W#JLKjN_`cH-l(Yc*o%9=G}c2@2PMYIJY9%H zP^Z4sfpQNo6I75PARr*VBhZN&OnG-Wj|bDZN40i!3VIfp8r;RF2gO zuX{bVxdtwR7{qr(RyquO@xu?;(ZTRvHbeUfg``GGuDCohr0Dzv;{FO!ucXNeh>yEw zhN{*zjR46W(rdE4up}hB|7HwG^0u8j>7j>`5+&B<8L(~Kd4o59CHO=Gvo4DY-U$EM z!ng!sX_xrW;zfnu4UBCbQGyGafKBke$cw>23SSVLa#R!F7sOAGEk%Mza-C!N2gYDt zmpmDx#Qezvb5ERBfS8YqdFC?@@%k(EW2rlEk`QKD$U{tsXC)i3;X|Q_=3tchUnf5S zmdcD?MgTl)>GpK*0}&h!bp|toV}DVx_yq(g(JMibQ*%=@bTQzx|K^?s#COeb3JuI! zoP1QO<8;4f4MvbAG_Db?0WM-im{&= zTh{mmT@yr7J)on3l0{E7GYwq zEPuVXQ!;gQ__hgW-R@1#r6eU!ta98|8ywdY7C7Nv0A<*@Kf-XG8FM8XnH8kR;lTK? z!5ZW9=c`TAyNfpv{L<1)WZoY+Asjj|o3*xbyLaJ=YZCx1nVBO~GjOcUlXo!S(2lAn zPx5MOd0{F%he@2z`}VM!P2YUV96D%xTH1Qa)GIh1B`4n+r2`}(6a(g~zw6d02mr+` z8#2gTSzq4~R7yc%;l}p%yJmkup>=`tAxaQ4DVYczK56?k_j1Hj5xQGls|>}gD`oIW z>nF&lotqx$z0*^S(;XBMn;>rf!0}e5tr{mm58y|DV@IZ|!_98Qc_Ia3wx0cHn&5u9 z__iQJ$X?i6Jh`v0bG?|693#LI)4+qrcWlD2Rhr87gtz37OBiN-k*b}+c@ho1z3J)t zs3W94fXNEKtABm^rav}s5KS@Vh4##%^XiF$g@9Ffq8ae4?&y|{{N2c;&5s9p`On-MU8K{YrvMTho49*TpYl?FC6AXrD{Xmlf} z1CnJ8sEuSM-@3++8BBuQ#4yBu{rD{9a}@X9Y9SgNgOsYwQlht)!ZUalHh#+HA5#}OPGQHF=1 zq8$J9wZBpd-^a|#YCS|N(o6!p$Fm}bL81!dmo<3kD}&}nHed$O{=^9ym=%!v9=u#q zchYt`?IDTsnS-e3m5!_)tPSv5mkuihFCLHvFeJkq(t?E6gtM~)@F*7@zIFW$I_7_Qb zFpq?Uy-4m^9zALV0ayS}|JDE&Eo3iV3wH}h9LW?3UC4y!E`mplv>_sT7Bfs9mfEi~Y{dm<1k%$XQnVp~SP zu&^Moo0&dTVhN+rvKL>zd|BzoOCD8&V%>sy=U^BVFy*PR=bX#mgcmFf{jt=Z)s%RX z8onId(O=9+MkX;~I)+0Ax<=HsynARbjbf9qVbpJ3y#*gxqhY+IMlWkv+dkv~{CAiL<;UniET?0abWLYC_hRKTNC#A73XcWKG&hwfFL9X`GF{cbE|FD2<&%>#Y} zFXi`5vPK->3#6W+BFHmBz{>$@C?Fw0m^RP-_ITT+sZiMD`cF@j**}0^GK>s_K%Sxo zE_3~W!pjyapfQ$%LG^RxO~s6T!H?7mJiaa;w#pBQHNUXm@BLKh7{9m)<;&X}R0{Rm zB1_er8SZxrmIY?~@9k}Pon8zIUKk4a&uah){;&5dzGJIfTU8-(cy4av9vq24o{4g( zc-i-RpHR}Ly*y|l%>Jtg9-u<)h20EvM9R=uwdr=x#*#krjCEwi0dvcCK!EbZEJ6DF z?RR-|F%~d2^1}o`gHTec7S`JSDJ3H4dAEN>`ZAfmCz%Vl9@Z*taAnPnwJqxIx-7_+ z;668Cb&)d|mzF1(UFMvXRh)|)V zXT*di2$5&pbr%@T&W#$82fhJr#}|1Gp*oSlcp>-Hn>Rmw(F`9Q&NJzuy{`>IinIwC z)*&r30&Eq?LzWywL0KbpHLVJdW>nz#+-15-ylbi&OR^UAZ{?aED0TIC1Kf zByLdI=a+l{Dj;^{97&9n(~?4P^yy$qAehc}4+rB(lHeCMxA>{ECr_9V2un;Rj5&uR zS_oQk@0UD`x>dg|F{Iza@YC>|)6#8GQGvqDf%uj^K0UZiY;Q{d3SnHt0xF(Ha61Xx z;J}x9o0Ol6n2JPXz&;F|GSbS*Dycd50OBg;hROvvH)p~X1WOm7gw4qn#@(SyH5_oZ zC`{N9@uV~bq*eIwiA(v#;ytC_f?&K=rZbKQoR*fh{A=AnpKqV$PCM(>2c@Mr2jQn>_#vc z5fPz3vFXjf)(sI6rB#%^8Ll^k{NniKE(fKrn9Kt@W$=D_6NPT=vL(D1WE(DyyT>Lv z+kf}dk>kg=1cI>Do$l_Q9MRfOXX1}}*7_+es9T!B7;ik~%{7+P|1{WfRAt=ZPsMaU z_Vd4LEY(2J=A7x9mFb>$SHIarbDmgSy2-QYHEq{aS9%-ni8xmLsr1sYn&e}Rd5)Cl zqdFNj;Nlg#Ev)?jiA&@a0yK$MnEBm%!Vx;k(Q)JbL6r}0*gZLScGZ*m?w}ot5_j#| zgPY;TV}JTv^|tnBYr9Q~%5UMHwuUZCv1Z}4D-Y%19=&W;;i=SLMyTw{JI!I=64WRE zndH0e=s0 zc1uk0lUsMabM&+e9la|L#+dq!piFEGo!d$iA9K+5J~u_cUH0mg8GE9z3?N9-i%4KE zTZ1$iT$c!mQAP}i%3f78=?U$2DA=zg5?-vUd3^)*Iwp(3pIcAly#ySWTp-Lg#>fQ~ z=cq%gt`07i7aRbMh@A@n30o)rh0XVGijk-scBT9WK?bN5{ZMLP^7YSp;*33$?&?&8 z+TN7Ut1Sjm&8^?ak%xPa5`V@U(_zh;>2Q$fwLQ?+KOt?!!nln+lNDl+&g{y3pBPFNCa@%V2 zcF!fv5s=4W)2+f+J-6OUXDb;6J4_uSp1W@!cGZhu+T6=D;H%_p3DEW6!AT3xFQks` zPD;v+pLGMM4405ZxQzVLue;%FL?$yVbKP_DuGFW2-BQ8G8o66P1;fq52E8pR?NLe79szNC_pf3TbYsi!n~w z%sxHrw=zFA=TcA(d`10W@Pg`G0C~lnNv-{N+~@z%T>KSvVxykMD=-D|Yd}MM;U2Cl zTK_NPr^sMaE-#lvj*4ScGI!RZrC8gcp9;zn4z}aDJv@~`REn-hX#ttn6?hr6;Hc)C z@UL7T%LpDOH!rVsd2a<0+)xk`3gejO;ty@8n097mTZkKg{Gc5>x{x{<{r)Tw90V9l zFV}gyZ0xq_-{_`Cad2@4=X(IvxNS5a#pa$m^Xx?y6uHoUig8tpWRM~Wd82E2%cUeT zK=+7NX%Xt%@K@Rh$0N3H&;OYKLp_n~mX{kYEnLs4l$Fhc&CSg{N5ix2!1!q^#XPMG zRX}N%&4DZ-1AsRTOTGs7rIJK#skFD(Bo#U4V|GGGt9$8q$;8Je#i&^P`89-MZMosT zdJh$^C|G##1+O^(C2pD1NZf8e|M6FIF`1A80aNdVbygC=z@1x9SREEnUs_O*zGdsy z)o@J>C=CKrQy0cL>hb9%hbsDQTP>|cC_Lzbq=f(|Zj00F%IF%7M%XSDNqae7?9;o( zEBbq2l0dnXKNpVtdPVYQMn9x8D`izICv;nONCK=eM#S->I6fr~P3jAJji*>*TyAg0 zWGqreM49^OT~aKzC6u8$`uj?Ji=Yz(<1`;kIXMb$(j-I|WrO&5^sKR33nB;q!R?8b&6MZ*&rj5xc7~nT-lR z)*bqmEB%rZ{+|{g*dZ{?x|iN+aMCAe`$wUOr})ax@ZsFSq@zpVexy-{lCcKg&?w1) z6g)!*Jaty74oJ5gB2@7&zTyEF8_*EaW#i0jTZ11hrx%BwS_4TYvQFTWu?u|Jyns5o zft->Oeu4`-_1mipLxRTI+LlmVRcF0?`t*HK*$Z)4Hweu-4^4%oIj7cA`@-?~!CO$;qnHqjFRG1fsx*r^7uzV=p}KbMig?|)C}Tw+ z57YHRP*X+x_|I6#iVS`YGT3Tubbc=w9V7xmngE=s>|Ox27pwO>7dGQ*P#)OWp6_pfvW) zT8ehHg6b*U6v-bQb?;4PS&cjz~LCTI@ z&@gQL`SW8c-}vov2)fSp%tqjk@POwl`c3|(`STqZ3u#&B|MmE2NR3K;i*!aONaR1s z#h>rqlz?D_L2~fn2GSeQe$kN5V#{GcfUoAi=I_%DwJ-dE=ftTMRq(R-h3&WL1uu?o zYht{sf0zoAv=AjO#_xm zKQ;vb$bc))_n=v@T5~qOy7fOe)|Jr^H0MnGsLR?gUnEmk99`-JWeC0WDXg5|Y?Ei^tvUN2X`I~j*3(+)u z2QAf5K`4UOxA*k)@lT;VquwyC;_!swRR!v`dBK<=g}keqMM8OP5-J48>(0*thQjG3!D41)!C& zDJhQ+WUicitZ?^YLPR4UG?h(-or#mq+B>D3N|azSXOK#2jad$ZIi*UGdD)f={w7{p z>3}(;rMM#4O13Pmt;5?}5dK0t6$nDoZ|`lzLJcc!go}rV0Ddrot2-MD@JijxxC~b) z*CtJxv|8~);I0|swnLYi#R8I)#QDP@8^oZ=0TlwHAwPxIqe02nx;_Y!M};)^M~cUD ziT0mO*Dv;EDn7}G)^rtq<6Ec=2=V*hUp!HtONTH1B1xRZ1?7a7o<3={bwEz}#!s zgnkhk$iw6H=npMfu+kYq7>OwlRa z{bb<2Zqa&Ne}avW;1D_Gj4}wiD&vlt7R%8#rvLLDi7B2fDpJPo3VuGFChJdBTfC=v zvlEQYonG5^`yU>CBs_;5bb!aABDMPfCTDi1O;|0NU@>L$7Z^VJ*c9b6dwJT@0YT12 zz5*euzm}5SB_epdMJ69I|3IJmiWehlZSMYR;k3VHk2^-M>y#1@$8x)T%*V@ezf&#v zDcbhXf`Wq46<@Jn0Zsj}SMw-;Hxz^*Zlo~tP}*(CKwnd2>P|3mH^DsQ-XP8<>Lm>GAUIyJSdhW;yj?eWNg~`VqZafzEdzphlHC z*UiIY7OT$IX`6bnT6S->?8t}+1@9BRST{XA^Q3kB$`1Ik!987|YDttco@);kC=n=Z z!9DlQ}mc*IUcxI^&h3QpE8&=JD-;W-CR_7;mCeMgZ?2SGjk`Il?KCy z?^tmaHU%@XHT7sCKTd7xT#H72n}3{QKCSPT2Mb7wRw}D$DL0(E2R(-a#CqH~^g`eW z1#F)v8bLy+cgi4Al}ZzsdC7n8l(uPRJ$FAW>xmuP+^e#(0uIV#g5U8^DUsm=##6+V z6F~LhF%6F!#%aRySR<&vUCZ6}Wr7SvQjk18;YFf4rJa?TnLqW7jZ%qtT&ru>aa%$dJjCZ$WOq0@iK) zaE_asC8=|e8i+FKRZNIS(bGd1*=6XEAtvRcxL@eCXN~Zs*sfz>hZsA1eFVQmzi?^Q z97$+j^1}ATCw?KxLhDi7g@?JJ+9UaGlv0UY|GCKn6dB9+Cu%hj?v-K+ra;7w z#;IF2Z8{HEk6W!x$F3@s*W#y6@CO1{!5lIFVY7`fHSx1k3{y4}iIsBuT_seVkny-wwE z_oNY0Rxde|SHEEGot!f;s2 z*brV^u#Dj3WcM{~n~1ue?AEySrbh@GXBkQZj^2J!l$WQ*`rcORK`f*!*mR*xmoGnY ze^8io{bu!!&C@rR|vrL=A0nOXbRd!mlwf=ev|;gD_Hw*9l#BxD-b z`+$yHqN8)ae3<9vCWMWoTq}yY9Ac5oqQp=vuM0%RhYMMq-hs=sz`cL}_jKiPT}!@v z16mHG@MPoz9!d+jcJI%F6g!_vK!LKyCKVT4hDj+YsFBVCV-#EaONy_+Bb337&kb7u z_uXM&V$#f-&4#TMQitSM8RSZI0QY2osV-7)w)+LYm6nW}tjl|&Nu7x0d=wQtQYS6- ztSwrZM&pJSXki2vFAv&h4deu~=g!T_$q7FB@EBnn5+B1e1TYdNVadfbJkX;ZJn=ZN z&|Q(5xITQ)`my;akxH?eC^9CLEv4rEM>7?Qj9+Rj!l3}RY!XI_ZkG*}p0c@cHr?m; zlv-R+cb>r*?ui5_;~ND0Q)LhAKN*DE>+$TP-@A_J@1^_iO81rG+>_%(4PKF0tScR|c#j{*l(mHi`}KP9;@ zx2o*h!Pr>=SqS@WbZaFjLVV`NEj=sNsK9&8`4s+|UD$T4F=t#;%Ywwm4Wk55^mg`$cH4z@_lmB|oQx|Q_{-UaT8KAqO8ePLhE zCiS5K&Pitx!_noba} zLr^I~vs@fCNuCUaj8x2cdXRo?_1CUdRaN+jWSBN2dK?{LM~(5@q37ws=WoTHVO414F;?3(IRw|z+9g`e{K`Ge5~07Lq9Hf z1C0x%1j1?rW6=>`63xF7cGXlt>X4IV+w;CVboTXq_s9QFE1*=8S`M*l61$Q<%^I7MGma?oDqqupu2n z)}6~+@AcKyoc2#@XOJ^`=c@(cJ0PecVkHFtP=}q&cVY=^YNtq@c^OswlXbi;~uNmaWsROT(W3hPnPj0InaFL27#sr_ek-t$7k zaBNLll34SnXN1)`F?6wveP*Y{fPpOoTSRD5b_Z!%mS8rZMQ8Wg6!xXp2+ zc>C{m!we4{X4+Rn} z>0Wr=;gMGN;bQw9}sjk;&^G-|8BSlpft!#JiUVuzV0p7e%%sS?a zprWXF-{l`(XuvVveX-U5W8@^KL?Z*Mc0Ew>!EA{wCvHSZ=*2OkMaGUfDy7sTj9FEasHu=C7vH{n_b26>3klPd zU>9KIE;dSd`{1Y=G1YzmGZg<&OZ_Njy0snoZ>s9J^z?QT-2k@1yC&`)p*B5Ff>bVf zID>DMk)5=NOZJZG{4`TdK`}%`TwB0Q>ZBaN_@K4RZnnncg<1eHiHLGRm4aD4GB}i{ z{e(h_X{|$-{NB{^xRLO&(&GX^$yCR%!f}h_ik&#QHYo;NL+4PEe zCvavln|=^YlYBgag&sa~dY}3J^7dq;e~0Jx(x|2Q&_4NVaZkwm{9>K*Ogp&t<)`Z> zgbo*obWq+D}LFt-6cFCZmIS8sRn?A+Zjl3Ld+v;BCc%T_hmD}s8zXRyXWz?M=F!i zI{AgQf4(mv!Gd;jZr+nIM-%t%jUuo|JWF9=?A|tPX4Sy3bCNY1X|^w)>FB6bxRI-o z{d{qFST2=*__UPd zo3@xfnyww^Ldj`Dokca+U2o?#SAlqL|KfkHc=G>5GHj0>IW|w#E9~`T`%6}^#5E)` z0CR``9c(3DEdXZzCRVeX_wMaQKdbk&i#V8>|1&(?b4Bqd-8~y8I5#N}*ZIva++cH{*jw#>9m4 z&(ppqqq?Z5eCNUfk$OY6i1J3pov|mnI6M0RA#ygU5*jWi9OYhRU5$rSzU=zuo-La; zb-AW1`JA-POicQ7#ms4+p4Ls6b~fxOJw`1?-A<~*4>GJ5u1_{S<(zF;Lk%gPw0p*h z`~KPU6`^}L*yLe-JTa}WBu}AaZ1Q-+=63FN6C=cU$(GD=X{;c2t_ilC{C>mc-8SHp z_Vbp(r+@tMS^snSgm@HiilC>qwXv1FA8q!VMoe0#t8NwhZPnKXXAguFD!#qes8N%7 zITX}DiRcS*gYuETKcOQL$sLuM*Q=X7C0!E!PVOq}NTEO*ltltp6=B;nVQP4lT^HBA zk729i%OSvQ0@4V0Q?aJ^Oov@*j{Xw)s2np!23MMIX%UdIPQ|QKTELL_SCdCj4_*W| zkz6Baa_n(0x#_WAKXFfEKb=oh(Knq~_+|5v-QOa8jotBM-O;hcFclnchasYw?;(#Q zjgose?0iM-&5Q+Uvgu3AyM6dhK($ev`;IeQ;(?1tO6Ctk%qskNZi1eRKmjF3r=Aw~ z(7d6F_hJk+D84I!sOvIkPIzupev~#JeNh$Zyxj&5o@`Kgu-ny%x|aJVwF-^*QC*(5 zRx%OLH<`C+Pj)!6pJs2b^Qro;h|2L!9lvRijw6hG)+0l)fN_4aCpHCf6?X>hs$zM^ z`^+p9@lx`gCVL_V-JS^wfi2AWodee;{_&yDb^cSs)E@ATnLEN2q3_X9$Z-!{wCMHS zK3}N6WX$e>+t^L$1(Ji zQ6)cqr`hs@h8I+Ky#K?Rr0~rz-lyB=F?2dVdnfNHIs`uLsI~Tjb>ct2bj0NLi5nS}=?Hc}v{;^cd_PIqxJJB4-AXJgFE9=MI zeqZ&$IHV3ALhB?erJ3W0I4pu~G-W;}CbL@r&=R3@JHe)Xq-UFZsb5Na3>&sh5kWP` zM9u!|(cq2%UJ-;#U&%%%E?l!Nfk8ta)s-jt;<7DUaExj_Q zH03Jw3tQL0vE`cw>SRCO^-*)>^>%4zjE+q@EAbil;LMxpJ561N{?M`aZ@-R3&C7)o z#C@xL>DlY676+=^Jbd3*s|nGCcrBvy^P)DB4=CwuoI@!yK7L-?`D^{Ia0*J}-lbcw zAl5ZgBK{2j@!`b_7jCW=b%_waAgapD)WpQQ&*rLLYWbJ#-{8%mKo-{;+fTY`ZN0j^ z=J2}&3;XNTV!()?olMhi14oC*a5NMoR8#H&o5&#NhpP1pI^==rtS8q@;#mbuKPR^L);NZont1m&kUt1mhpV~A5dDAkgS-4ZzDRwA23C#vV4_Z?wVh^YK;1H z2_HImx+{f;%sW6vDnmz4oH$|Jdy#1)?1#

>jQf1VIEs`k4o6w9{Ax;62umW9UN9)Z3W2mV9`;n!->qBC{h^YcMUWM=tjft(@eRf{FL9SO{`1@h#M$#27{O(=7S*_cu&O5p@j%0wdLfLc%6! zTkfAIGHG$fLgZ2PfeH8eFjfmh3H-G3QX=J=1NG{&gX z%DyzdL@*!O2mqQ9$IUW#`SN9u;=6Z5W*9RYEX-hSD%OExmn=ShJmsILv?@1ToyNuD84OuKLsspOSe6V6I%u} zy)IxBGgR01e*)ewA)kp?|2GhJ)a@!+qTqSsNsM#^HKA5mt76u9!|lc!j;U+Zw{sk5 z>B>ZLEhauIl_XL908Ki_*Rs$Q2uG_!2TQ6|C@W5zaO@Sf%6db+?;)%I7o~UQ*en1> z69NH~3xE8xrEAr;AvOMBVIu0Ha8P8_ihfjsO*e9?C*6{`oguzeN~Ul5Fk$Z?CH2Ao zG7q*;pvU`L=5;)u=MYZu8u_6S%{c{?q~r^ePq9iZuZCCJ{2?eugObM~+C=`^4LRF` zkb}Pcs!q|Yb{(;*iOdN&=hvX2WMh$9Z1W=~tmfcIvR(=Exs`sKIL2;U5)<_S#@6d6MymH2+{47oTZg%geg}@P2JRA>;q9Gt=5&85|U}o6g#ejAaRLow&=&K|Ac0 zVQy<`8i^(X%vQudG@ZGsN);5jfHOntNHYSl`!a%MMK0ei5#PVgqh?!jlbA*F*6Ny4%)B#pAspx7gJAsmv7m+ zoo17ua@o4QA%eOriOj?~0?*i;I3=!uR{z&@&Gy%fngW|4inV+Cy98T6D-ggb>VZ?I zeu~`EL&H63TgmZ0-McsBBbD7t)#0mNVB?7yiHSkfXit8*aLLw?msw;OukJ;o0Qt&LvjQCR(M zJ!W%Y(g6A^S>U#R{p8N4%*Y5(TkU-CQOJqYr)A`mq?op7F-PxD8t20#1;keV1>E(b z{p1LMi6=t3?<5OVleR$Yx)JIVrm-kOXjf1+J>@p9D{?xsav+UcDBmJ6S)zl5sS-^& zVsfjAKBFE7u^xB_WF9H#dMWKGe462a!3vXBgUx!5%<2zx5{x|d z@Y@ZIz2*gOeiQmauXeiA5#L5nb{&SQj~Y4%RiF$ynLg+3=7F9*HbcRhXkbLTy5yB! zN}*T`Sl*!SgB2nxv90wP1&r1T0H>~QCAbKKQbS^bkd2uDUc@Z=ixXpjS|Y?dHygwK zr3^9d=s)kdQ#}n zitOOI%Xh%^UoKHf`|9*2{)$o=V^yLsi2|#w8ghcjcDBPGF2?4t*`O(fe9;1 zX8pS!tJD4#c(lTKwK%N&uRPZ?G+cf1waSw#%6KA-knLS5|Pd3QH>Xn>=8=|86vE7U|BOleDcdy$|KXqc` zg6GYKm=TkD>~$iKU8qRzLs}8;Yz%i#8?YwhR%?bKaY9NOF`$L0SuujPRLFc#8EV9> z7b1n*H+R9U8WdD$3&nv&?<$jwg#CcT7$c+<*)j}UZvh8&p6xoi4t`3cS_lb5oqg}h z9^s5R9iD&zB7SUG@;EkzEN~foD_K0(uC-v-qUaNW7O7}4W;Mu^1Jlw5{u7)KJD`^t zh#E=h0>^+ks;6D$szvn*Do*3t5`MB2D&`VZhj_R|@bZ2xrFS(p9s4hT{+r$^>+)r* zvZ=+7A9q>PuFnN7csIWk(DdTutS5`)l%^t*lv%p`v3=XOpAGaN@eHg47e+N4+jgBs z?8(!oDpc#qdDZYZ6cnATqPJdo_-0q4%uYq9OgM)+dK`%6z?g-N{E${zxV_t#;xfy3 zwk-=C1Gznnfmx0XtLl9ADQR{mXGhcHgLc^l{JuHe1^;~qw71AkuGnS|4nTSdLvc;?LFWe&%WkwVCNR0o&vPVIaW5@Qy)@QAvZmtFwB7d(4* z(j+X(&1TO@mo@>E78&=J{h}!9wBuu+cWVFWu9|=MU2JT**lvYWjoGL(BRvke=BUHg zmr{y)zg#*Uud&DtkX040n7%>OXXxZ{ZWpF6P`By*!790Br*hTWj4O6EMC@c=yy!}e z@8J8wvv9(cDd8wk8OM-%xw(Hz_;>e#>Aq*rf4q5PUZ6F)E`G8|-_e_6qz?BXVss(YCRwvO_ovx;Nr-};N@A60O<*T(r7gO$>u%Stcc}X}#tV>pi*mecpql3$Sr=urXTJ``jF)!(i;`tl>tZw!|&16p2 zux;zUdNX$J!X#i_vtn~PVW1%t1W6}O{PJv6VO7bFI!9O*TOMe9O3GL|PtwoL_`lh% zuI5T5o>LRJYCXM`wUymK25-_fy`pd>3a+o?Bw}+&gKKr;Y+xS9aZ|;n&71o_#8zxG zFbUEn60b_ZAOvB+k})rNJR5iH7^}=Uk2*YZg%R5*Wd^q7|EB5IeQThq)|Qyy*#5YO zM=Hu_V%8OA={Ry#q(K4ywaeSR9K2^92Ax|A6!{8EB|4~F^kf9ax`Dr&7w>19iJ@gp zecG~*x|g%PI-fh+sZrxz$|rWC%q&%{mAc1%WuE1PLCS#pt<`TdI}`4B%;Xp|fYKWI z53y*~!7Qc4lbZ#1n+2Er(qr?Z0Y9(*_~^l><%OT#-~M(5pc&u%^I zaJ0edyo?BQ*r;p{obkgtQd3%=ZF48RUT=KD<~=QMYdzf8cj2wUoz~q<*{0j13?Q3f zf#7{}=FUxMtUUSXL!QsQH!Gg|=#*64EPJ!T_fzqM>*IU0=G~jH{qzmDpyG-#Jz6tb zYHebUeY-WPadB~QBN$}V^diF&JLKBx2Ub;iE&qAv_|Fy39-78vrs}lyj<89cRKsu( zzzyB5>r3nEI=y`Pa&=|w0sh+PUURP7T%Q=3nwt8{j2Rc1>OfeZ$@M10T6F8&qV&z1 z=HG?KsvZ(a`t94n-1nRIC*0ZT=reJb!$HStvjrI=4>~yAx%JAV?(^pagP^;2Cz%W$ zy#L_7F523Gx=n7HyngqtFZi}r_uUS^q)eLKzhjRmt5<3CV?d1uQd6^D{pRZ9)Ad}% zMjx|Q@5iN_p4Jyw_guwCo4Adkp=uWU&pg7*iWp?ks#QNOjk$7Xs?&%~#p}aI*sW>0S1(|i)$QD(d#81Jo2<{jt}#^E{H%H7hWbDJ;N|OURFj!q>P4jW zozmmSk4KK%n{e*UUw{2>G1@vM?fC@Nq~UJ8Hg7KRFif>G=yB@tg0YwCR*mQvWBbC} z*VlJu=Z+oiGd61^^}SeH8s|1>Th89Sd-r%Gzpq|tcO~S)LZY`gqnZ(Ojq&gDAKML9 zV~V$%eLQctsp%{a51YfEChJA|T`KKWHw+cdh1WGcE8C4OcDl1GIbuZqoB_04Oe3$l z9(ts4V7H33lwPR!@t;Czudbku=}QkvllJ0`;eYA z&pbB5wKO%gL)WgG)A#S*72Lh8-p#f~hRXQfj~Dnd19qwQPi^dC_ah4av$7bcJZSD5@Lya- BuE_uZ diff --git a/doc/src_intro/img/class_input.png b/doc/src_intro/img/class_input.png index 987b9e388e2d461197b10d46ca1e7db4d8db3550..42e36655380aab6fec7832348d502105a3dfe301 100644 GIT binary patch literal 15741 zcmZ|02RxR2|2KX}L!~4Yk=@WRvoe#NQBjeVk!;zr8)ir-v&f7RDOnj=QHqR^l~E$u zyNu_3+}HiPpZouRp2zETU0qj>^E{99`~7@BpZ7X~&Z;YJ+rqeoAc$?sN^%+mK_P_y zuA$n9e+&IF&BPy@?UXJ#62$gu@*j!^N4GN(1RJ3&Cv*P#!?7M$?ep!uQp+C02iMbv z8*E7BdTh*jW9KefdCAkcY{qvL__xH|2wDo-Aa61dS#92GBF9#%y@QWov*rFR?s7pv zD_nb6&hETJ#X;44wQPd5hsPI<={qGuG!SjFeyCuB)oRk!>9{Dr)7 zRBXQW*L6Zduhr=_w6toY%<5nL_&Uv7>Zzne<>c&qprP?uR@VKF6vO%`?!xO+9Nj%V z;`)dEjbfr7#K#9uPdn^CbV%jl8D*UXN+BVk!Z&YBR{qTCYfIvayC+K7f9lk!$*EdaN}|{8C-Xij&%&R=AtPU~mQHbZ?rdR^boUJjp{}l}kgcQI^ERn{)FV<-CBp6hbVkgpUL7N(-1*+e{)aMSqZ{^`@FqH#V> z#k+EAt1E8`heAq>Lm6i@1O){jXJ&3Dy33uNox8D3&Kb|1Q4)EtUsDKvBMf84vAF5F z7qqknM_Qf`H!3Sn5q-%f=Pz6!>&CV>fQEJ6bHm=ED)OqshYzzKJ4SuzOhPreK17U| z^AW;uvaf>c@ZpMln=ZS_KAG{n^P*)giBet!F*P-nRbg@^y>*&5O%xw|_QHj+q+fi~ zLyug0Z$?Ja4SkB=WNK>aIaNb%=j^$8$G-BLksJo$RrULc%fpI8hEX6F3CpY0sVo7die+PEGZV&w24;hvUx%zoaDgjnoVT zCnu+`ukYjZ^o_*i@{;4^^%C0&hscqk;d*K$EI>0pYC!W zR%}C|=aPVJPjStUuM77xGPuHduhkc8oj-3_b7yx9zsbh&Z{^>T=BAgHv$K!PFh-8 z;`$_EU|^u6s%ov7j-|rq8d_P^hx*=+j^0E=LlYAlThYd$Lw(GkUtKeyA; zUeeWVY0cEk%*_oC3_Pe7Cuh}`#mKr zyWMekPZJqgSs{!}Oq+?Ga-Z^^VmjIrVqzNB*2idR)gFq5b8vD71(KIIIXMjvH>JqQ z7(Stp1${3LIXX8cfZ~ zQnk0Ymy^4H|GwPqjoWs<`F8vEZHu{IUnKJ{?|438x$1+pOR27wd;07d z=eBLzPOGSJawKPE9n;XzNUjZIrK4?nEOXl&4RUs%CfK&;vg$-sT-<3XDXH`N`rPwh zT3hAh02iIB8AgIq`2EKZBWxUTqqX&Xb#*mi&T`=W z`}aZOLO-UiGl;t!Q&m+Z2$Odq6)B2gk8^Tph!{Z&jrf+1y~nQ-gtd)LQ%47tkB`sz zLiy?+m2~&{S#Mgi-V!$=PBDCXdivDWs|U%hJ>0~pnjo>4;B)z{&2{uBr?fQd$(hyZ znVG?cE$)^+{L`5&ZkA!|vpTwH;A0Tw5uQti6y8uaLP3fEN% z;6|tFdCTA8h@Euw>BuSjv*p5t3un)seOv0WK;D$C8|Lcx&!3HnoJWpqIdS3y#_9E` zfeq`|-Bfa`H2RKS-nGm#>YSd?!P}h2quBA{T}=)9;ln{)gobLspijrG%32dowzZ? zc^Dlf+}i}Vw6neCrHt+Kl9GKbPtGVhI0&Sx#iP?sPw$Kks2#MI&beI9B4XS9HukvL z3tv;J1b+|bZK-sKpM zYWGO(>dN2#zCOan#)g53iIbN%%!+Ga;#(tk3PuL*K6Vq8+x+jnIGg+q-<61yIy#K5 zW?Bzlz7*)_=s1b;{qp5YN12y+TwL6h)BA>xNakK9?7U_^)Ysb&RBtBdDw=(_`Pp?h ziFlD~8^dZno-fe1csMJkL_K`iJ=CiCu*~Z($H9Xek7{Mhp|etN+ZO)dfge`5qPu$^ z;LmMzN5Cul+2JPjFEzEbn=qSi;TY|tqbqu2osf`VXK!DTaV`aId;@0KsPpWsK3naKd4~KlR>Q4H%hn8a8xynHYHtdHl9EzXRP=3A6D`hhjFgwy^2&;lxjB`JiV8KW z)V}=ue5x&5PTAS9Ws?^P851-(Op9zYbT| z@oH&lF)}p#d|Sxa{f^!vZvkq~^4^Y?GyX=s*8hxrC*72b=g+Ul_Za^5Yha>$Z9GZ< zgT?O0huy@WJH>Fd8q+h_mr^8TYo z+oTf1A|iG&FfzKx^V?Lvd*^U@`qHbb{QzO(Q4R+5+yw>VI5tKzL!Wx`z5Pcv>qk6k z6LTLf_~tE(`Lz0Hl((a^ll**t3}S)f$BW!9W@+F2Q6Ei7?BUT1d~j5YgN=>g;o*6a zn=5ni;vSI+G(RI#(+y~ss*l8Wqhc1P>v`?_-cn>;dbJTv9pm+T@iB_G0J27AW}B?6 ztU?(0*O@guq?q(+5<*uYcl!75-+b44OI%pxcWC8*PV`v~N|FsYrKq?m@}OEo=55i$ zMn&9SNN6a(bq601G{foBr}bFht3>lueEqt&t*y<@$>}@Ko%~({<~Qaj~I^NtLs(SxkG-F*nPeJ(5ntpV_g#1K#alzNEb}Yjh|N2nc9-X<8o`X#PIp zz!hWTO8F-1uP^<8_5uUBjvtSlotw*i@#5a1rxdqd;XM>lP+(n6jo4_w(}dxDFif3k*aj zSJKps1Q7dj)#E_;F3SB`e*w%#DsFGOa^*_(%C|>SUU4{*Y1xTJ27c`v?irjVB_(`@ zZwVqf_k^;ta*VJIBajO4wPUlJl zP6>C81BJY=rL9fksPVbcobmzSDvkD|>Z1&gqvp15+a?dN(LQ-Rq+~dkWy1i6tuJkF z1Ww%@L50RdX+`{U<2J_DaRGOCcaD1Elj6b3&oY;kkLoh?Qwo|zT3A`B=s!UVz*i~y zwsp&v!o+RV)P|;}e&~@d83|*w^pyK|F*AosdHpeLczB}FeeOtf?mNCx{V>TVSFNo> zNKi|}m0Leie-vR+gptiAB(xiVa0k`;#owcZG`mdA}6>G`wl8QoHI0PgI{9$dV2Q~67K%`Wl6Pu9k`@@i-d&4Sv|dw z*;yyzq?+0`sl`4@Th)O1`~t}V;~TzN&!0~<`mE9cLJV!JJa_J#46b2hWW2(2+sHsf za*yOLI=b7B#9b?UdYJqB`zL2+A`d4yRr+q$e&fP@Q2ikl`YMT2el|QJ2!M?&3_+Zu zJ(q?s`>OuTjrOCdCBR+YMkKa?Cfm5S1`^#f#WmTgdk3%GE-7(p0%BSjT_#~0KYIe)-*+`=pk)8jD5XamzBDH6C zRFx!X&z|M2Ob%dBDCV(f)t%JiC{d@3wD}#mpt*#20xlmpzoH;V-=d@&bBUqwX=HD24_3 znH=Cdliw<~C*#?RVfG=lR+BKNz+jdLzrw{tkA-n%y>#)E0G+6wSbUaEcIjr5o4zZ8 z;;#}@A8_)xn|I~g#2hzMcU&(}RkwMMWb6BvHyh+>C_afC^N*n}8`~|c)Y&`#&&M6`k_I(SYoJ51fBsA^xa{T2tlr+<0$y%9@77vdTMZW{ z`#TD*vECTsN~o(-T3-5@2(-PkK(&6D9mCdp#y7?0U#Vk*RJtu&h8*W zSR@%UGc&2SZk6@&lEj#(fAj&scrUsg2`eW1tNI59DjzWxboW*T(5P@LGDx03caELk z-F*0S(!WaEtYIIII~TeGsx3R~%^f2HrmP7w8Wkm_w*X#p?^K2@kGThiD`rjnv{L=> zE!;qBdsT@#R+T<-kK}&O)B#g`Nq-AgtJdO<`LV9FhF69ax1x`jtS&E+`&R8{FwYfQ z<957sxA@AH|43+%9ds-#4&P;w{IFtcVsaa2Z~REM{;?ipg4tzFi*1Z}RT3&)O=$pbVNX!6quo5FQ@>qM(4B`2-se&vsdV>YJgV z+W>-!D7YsRna)3avd~_l*C@gVY)?^v*KPCfR3NIq7fTo*Z{Y z+nk=9eEi|VX-ji+Hk2=JA8-QY92pd}S<-XyUSJ^Llp-K@$|f3?9kl08pWXuGaSnwB zOiyAC%xhZOa{y>i;_P$fU0hsd=h`pRopW3thUEZ)d7<_w_|6?F;`!zBg!Stv{vqEu z!_fEWXwR9Ob8T3^eg|z+vGZsh7Qvw8I_A%X?|pqI#a+i!QIL1Z&6wLV=&|ToR_)a$ zHe^P^CPTxMP&?%0W=EbRI*dwQpJdB?_RO(sd3Hpzxw$#{{{3AX9N-t6pwM{dJ^xRM zz-dGy4oGBb$@A&+=OjjYiTiWlSPSd$2wUyP?>j@HDV60YFR<0xX9EVi1v~$;CYCxl@#TYEi z3&Dk?=DM`BWNvL;J=Rq~%fLYO_(XnZSC_7}zOPXTaPy$I`sve^(6kE8BX=LYX!!ZD z45Y=#n-O-~<(0o%eGN?9g+$id~$hVG?GU@T>soQ z?Tgmsq^D0oqqY>fPO!AcmIIM~S~ZI4JryPKx_zj>D~i7js|7+<32m(NqwDgby>(~a z=4jr_{zXM6P^Sgql?qA8$+xW5W44ngyk2h{gR1CVaatR{9I75`c?&uh7CYBt!4^7N zB_y=ln`p-S+Em($6QI}>y3JgTUqTh~d;M`j$9J3>f(qC@i&h@={VAj;S2z8=Ll=JK zD?%2CY>6l@mxlHRU4nSLlw5}YgJ22tyAk3Xt@W$i6F5zDV-D+ zie{eqv$a(9V;ICle9!QNgzW@*^r(eCwB~`D6e%B1YUbTh(+MlW<7z(ujFXc5?YKG?ZLcX7I~X;2YPy zX;G#sKGlNAH0FrRbB?aAW;EXfsAo=ZM&dtrFmssh){Ea3=I$ zykE<`#K!IwF;p=&PF9NHBuEEm zZTY8kuEUSh5Q<&YYW6BLI4OT?ocY;U_2I)75EYG|LYOo5_WTe?gZEIaM>z(DhLVGZ z-*a&?JEQYxd++=mN6=!PgAx$apmyoaVkiiEFZOThE_UAf;ll?z2Zu`D^5x1<-M4(I zuWa{nOh9G&4Bcci>oTdegCW850g_4qtog*}49*~G*GIHvUAm3A3gPNbwKnD3&q=c3 z4pJ zikWon(9zTrr9$y$_D_7#5~}X8%i2x!Ndzz1ayuH3^YK57$K`Y=u|Kxp6eAkYheYT04Tsb) z+IQ{R_4vt?fWw;UY^ZVAicApa3vZr=8qha52*f7{)vjN9ZHdN}Tjj!q-H?N%Fuuj~ zt{DxkHi%EW1@59@mAWsw2ED=%b3f+zhr2$qZG|6Elr;Fi3B8?( zcSF1gjba$fhQ!9&a85-&G#@nUJNjDn{olkma3h-Os-zmocl9HKUa?aUlkl0isP;8d zNXIIJ?;F3pLBTNt0-lnWcb`f5=?|y=yt_N^UfPn!yyeWp=4K6$_#-iqoinP$OftMHjE<| z#nacG|M=|w=g*(B8XA>8Ykx08I=G5AC)k|1L@j*1>M(K8$nQeyH(6es;^O741$>0H z%Alm8QWdiI_~Yl#LjgdHNk$##q4T?|Agt}yE^~rl<|MNKOb1Gjg7u-6!@Fq4n8RPY zuCL|0_L9dfRrb2b%hv#oWGi2q{(;#PWud>ix(dIlnv~K&FHBI6(DD6pbNQjzZ>OiH z2UrMC>Jt+GDI zT6ifpA@#esEm60`=dw?`Z-(gxQyWuml7e76e0Ve1b>(ZTb_4rQ4C!Vs*r&h4`JgUa z9M}pDnFOyIMcw`AvcJ(P4U^i_=<5qTuC)91g_zby$v}RxwY7zL==SA{aZLMmt5)}L zSoS5qj_`f73j2}CPu*hmLV|Q&KUl>+nNOFeQP$AWxdRyJQv9*!jcdWBZ*Yq22H$Nf zEG%R@a3HN^^lD7+Q;bvejQVbUMUB}VwCuvd`S_b&HcrkI%}_>&lxQ@<*LsgldqYo_ z`ZLT4<+%?Xk%UI03Nt@F`Yar!qC`w9rPE{8y6U(@eikm;t-z_fbL=k z6~DX8iwPvF7G5Zcei5bM+`oT4pk)or-89=UNF!(&lki~-A%z462j9-l=5cUzG=k1e z)(u8Fhos2WPjNLra``{T-+}<)IC~FNiACBwWaaMyj^eJ!LucNJeDiGSAM5{*KUK}+ zF*P7x@^}0V$HWP7aq=>tYJo92|L{%6+^Kq)Bn2_op+59g2hl-GuE40Whj*rK6PCKN zKilyQjvbh1hqKU7C`6ObD^0R=2USmk=b(Y^*tKiF@K@QWv2Yi``hg$@f83SF>{)n@ zP*Og(wyr;L;6TUMulAu%^)_R}^BEZ#Brb;^NL1I-VNe37->RYGzqSjS!KZ&|6rvvU z$2M-?M}-&8j<(Z)RIMjqD40N?;p69*0fr06H|uy|#3v}|8y-%pp{d#b`*+Ci-_|5v zn$at{PAeuR21_T};@j~M3Bx8?hXH8MVA)bE64&2KQWjc&6@bTP0>vVy(1m(tT6^|0 z)79S{x#U*|2qFk5#+B%blORrI19AMSjmC$W9rm-cQ$Pi)dNWZLeDB_l-<_|Y)xJAx z7}LJNs`Yyy#(>CnbC0l4zK{|VQhKV}9fib;Y7V0X%F1LG|Bel zmSLYNo10%&jaoA^&k8goNCrb>=Qwa+LyAJ^DK9Ut=;!f92K1E@LiW5y@ioZ-S7yfw zz8QacdO<&5%DzeF5eT3k+RQQ#EP6>zAT4Kco{U*c@AuGP76%uXchDG$zAbr5k+Ug0 z{3boGfg#!vX^`S5^^J{va^8poUK_=&O9;A##YwmcsH&;)!>T4lm9eOTYu}_`Op%BI zWe)fv55^Ne%%*HQ(N#bLw}@)<=9}m^@C|9{>1!Y4+H?t%(V)6}?8FV&je~zD%FVo_ zVnv#n=p_ZO^-Azat~Zym(bUkm1sIKE8A6V4pk;DW<2)S9Z~O%k`WVHqyzF`9>eT_@ z9pics&YFk=Dx~oDcVS|Xq(?{`VPtm7ZBjm>ixUo|Oa|w>AyGOEAsWMx=Cnnq%!OWE z0u(i$Kkopx!Yg80z3LEP!P3NGEPJo5xI!AIFt^?DFBsS1?%nO=pn2muQ3<;gPBy*ABMqIe|EKQu4jL?4 z!z1BbS%|C<;-U(985CGbAyRdAb|Nk$2cilwZwhe92tp9?`JlU!u5P?Xc^b4qa|?^t zu{lB;Hf*?JYT6Gs0Wa_c@q&7F)WyKUl$6=8tfF2W?3DpHY<{t2-xjYb*<3u<-__P6 z8^NPjzf*Gm!za$OXaC10)hkR9ym|9xN2!O%F>Y=nOUn<=4A+EjT#1i@P3s4}(FH=p(@gVhHQ$>7#{bl#l+!)a00nj*c$qirJD|2c>XUL4igM z$V=o}ubiIVKG*vj1zEk`!SD)`{oP$eH&`1M;P3BWH%%TNIEZXJs1Pdh^YvYy`$MnX zn|Y#ifu)`3gbxaQBiDLROiAY}hV>#u5(>d5=nQ)*zkJyZH0WmLbN2SZ`8FzIX55 z4X?lR_LO;f`N%qvqjl5veFU)#*Z9S&SF*OYJcujRZG#kOwtr>pQm*j^^2p;1P!b5y z_|ix%-VieX$P|?3R7Zi{xKGrMz(#4my1I?$a#{EIIp(T5@wSY)bzAowGhetQnzYdC zL8Fypuz|=NJjfR!@$ZiFPyFxSK_aY|`g2ikZnZ0K`^F<;Vz{Q+vQDzSMT?&zT~V+| zFwe2JX?U-sDQwG~@+M2KD1ym8!N{G`C?T#8p%#r_T?IMS4?uU7)yhQSLS8ctEjKv%Bc`?BRF_#d!_^z7Zu_@BoS8#V+loA zgS6_28$K(em!T5Q_%B0a0#7WX!d{}sFY|!MS-9BmWhfGZ8cbb@(kTD_# zX>SSt?aW)QUAvb3R}g=QggF#xz}>3iDw* zdUPvl^6iHQN6%?#Z9*iWwY@zhKYtH8Xa!uAa4;B1f&W(l&PygC z0riRk;>wqXn7R=^TNv+=_4bxRWZ{KH%RxZwdc;F&k-4#lQ;v5x0UhlqaXSu)X$L)h z03=h#6?wE)^4CZ|?$pZGlYyuPb^8uL5CF&4MTkg6(p)X+YE{5}MHIRW=>?-v!%6cW z6C~qRN|=SM8Caw|>(plE=ZDnUSC*IU01AX36{Zy-#}rSM5Cu=Z(8{{Xe;XX7+e&7$ zZZks^1nwG3e!#)0?SgN(Jn}7PjP?Q+i#q?>1-FJIspx2q{HG;YXz*RS4<`e3lR;2W z0!nk18Pr+q)(7iv_$&{yg3E)#+`#L_sdx$`Kid6~iiYjfT9B-50x z3p&y4-S0|DB(n71>_PK~*43wB@269Hyyl-kO|TAx=p8}&mTo;sbIw#`GRCXX_zr{H zbf-jf({x4_vN0ze(_;Xv>O!}`q4F>|X#2#O*|$lG`MIpw2P$f6UntjPpkbu>z_Cj& z<*pP(bvgfA-6Kl`?CT!l3%hqeP;bwi`?EJ)#KVU1HMYopsug260F4ttR3rGOxXtmV z2tZHAdJqhf4h0`^|H^r{qeGkc6#5BWfX{pRI`N5q(QisIj8%G1(1h*Y2m6D;HfZPO z=FrbYAxmp1K<9n<@ZsCRDZ8~*uYD&RQhONENUry<%;>KFWL_ch6&^bLI?af?;dMIS3NB01y!}L{I>rfzM;!8oNOO;CK7g zs~Hu2CILRa8~8T+n3-vJ?0Bmma3?6J0%Csu`1oC%d*~YWPp1Y*9M`8k z_l549&VW-*S@`({1d>R(B{Vb?4pw;QPn|fP_nP8}(^dx3LGIXD2oBYqX#(9MwuLk zKHdZl_%GUe(y{w2lqe7Y(x698YNxJUh1Q2*|M=OnU<`-)+1jMCGBVl?2H_9)4?1sQ z%2yDOWBSGS<3&V8W4da=lmEZ=VD64od12*d=C0MnDHAf@n4X?arp&VS-ypihV=oTZ zo*x2Jc8*Q`S;8LQdlL>X($jBIWypeo0n>?3kXM_T1wcG0lBK=SETuck#l=iK!{|wYeBA;W;`w zssc%6kJ~li7DS9rK}6fnk&M5Jh>F^imYNDD&%l7i!qT$&xo&|H+m3sXNm0!Y0t2%z zm#brw^X&Rhad0pq1Bx`jX=CP>uU;u*>Hv!)q=W|+_U+pjIK0M^ZDVb{Yv}|M#1QgE zAeqX^InDpRq;c_LIyNcz*RNkncoif)yz1!DVB~FvF^=TqzK@TqlfmDcCr`SLcPAC} zx(CCMQ2tN4iPdYC79i#v4mK?x^2zO%${avALK}e;l726ij5-~@*d=hWYB3b$06$2xVUDp znEkemsF#e(<=(S>6_gwtrO9qL3M@dk~X3bMz3$ov^S&IE5b?8t~}===bo!2y)-?%!hAvNI*p7 z2?TBq4xLhWp$!{1emL)++IZ0;QOg2VY60uE`sWNXUyY4nQ9Sym<>W|xb?NTfY|9zJ z>yw5Y$=k=`|F3ar zn%hOS{`{p&?^hBcBV{3+vva%;jl*=Ra|h5Z5dWU?BbMn&T8cZPGmaN_w4aYmoAY920D7T#7kjI z9LWf&oCx@DcRYDu3CZC?xz^XAI`v+9dU~ovMqb|efrVt}l(x^GPXY^aBvNpEWqNHJ z%3`@Unp6a^(FhROPrxp(z>cc?*fEqzaRXEr{h?@1!hKfB*egNW=Ps-Sm`^uq2m1jf zIi4IJvtX9##iI~B+cQe9v-U4}*E6sib#5d`52Za@zY6l*RGaQK`-y^aQ3DMP4q*pn zy&g!|yqdc-AewUgmw$>=_ZA%#3CC0D!$5_kAI#m-JC9%dk1H$k9B3J$RQH;x8Ap7v zNmqS+y?oo(=~m5Vm%QcjNcnmJU*~IkBZZLhhvl0e6dd7~*BF)BXr=h8r?^31Uc*=0 z<6CeW+5nt2KSV>r*JLj_kM=Z1*$cxzLz^c}j)fz5EXVbm*CzP##3zyUzNAB&2%-=O z=M+|(!j%HO|_Lysqz$SC2x#6(_u4`O%6zxw5+JbI5W0y@t!GlTxJY#Hqd_i8clW%#_hkUUprVQmeQ zQ~u}Ri_}MlT!qt2kQ&)VOUpjpi`BOH7{hDs?2fnxXcZ>yUWIANQIApyr zyuix$dabQ2$nAHRxgTf_21wo(29T{|3hKunx-+m^ATq)hNYf!UCI@YR4T5RsD>IsH zdj)(E46s0my<6Tu8Pk`GgX0#Ej(OkPn}Pr%e<0ZeHU5l*xaox_+qz32BM9OF2t1@S zW=lic1i=kT-d!~Ey0*5cF2zc(B4it078G35Y=j{bcfv8f!`-DepMKY_dw7q%OiV54 zLl(G8j`s4-uDck@j1t%RwlVPCK=P3-m%4u~r?64AzHtw26S}tyVxLYcf1JtN$n;rT zy<%;RiKm9X*E;SzFu%&X-^(D4Uq~n|CWe6#ZUy=Nh6nd)C&dSPq z21+MyX#)1X88`FhvBJxdppIwRcXs@REp=EzqU6)xQltg()K7QK7-EpnR`!|H-u0?^ z{YwXb`T@CrY}_-qr&XQdEo51_gy2zI-F)i`tl>HEC8TL!WINTHWt5JMk=z%?fUAtn zmG<3p{yZ8S1}jO0tU-Gvlew{As0H->i%K~62;17d_#fJ4>l z$jY9?PrxX*y4Lee!$loOE&i^VB1vL|urVn{q6WoFSy+@UbW&1MWaK!`>^qKFL>|5< z?5c~Yhcs05#ZHM=@qHY<_0I#mvDukuV(emK#cxI{!IrYSyY(^~AFUJ6)1-`h^&3T8 zqaOJqsRW2Wn$bF%yYXL-^HLZ>JQD!tb~T;;!?di>`J-VZ7ZEBAk_ uV@YiE$=vGq@5hmOkGiD(KOR3`m7bT`btdY0NdcaxCY0sX<+4v1-uhpG)Vo9g literal 14447 zcmZ{L2RxQ<-}jk>%5ETKWwfkhR#H}lsFaNCy(J@5WM?G}tIR}25*Z;Ydqh@}tPmkZ zM#lR+@B6*q=XvkvemP-|_o>*A=XBMwxEYj!gtX(49J|a1MWu<98Vi z75?0mvc`eGHaecvb|wh=D)RTb`}^tH34)6_rEpx+J$~}hHNCL!e`}77=F%kHm6?3f zc5v%`KK~c@lau_<2EQ`P@KQE!tTjx1IUwmP$|}Yin&i@0E8#Da<7ZUe{Z}#O!6|OV z&(dAf5&ENxEK!&UxrRa(+BonE%n`@!!IP3Fpg4c#=n35>k{SI4p&Jc)7|R ze&^CMD*5&*m2a!Lh`gD|Fkzlf8?dvC_I~-D_0dTOS+5XcnpE=i8uz{>c0AXTEPPj7 zymQ~aeNFb1hZ7!sjcn=a=y)G5?HqeqmiYPjsHc+Ju59}+GI|A$>x6`a95k7HXR_|z zyXW_<;bCP{Q|2eLJ%7epQ|hR*a1BQ%r}AePp2uF^=sP3iJU4#f>SRyeS#}e823jR* zAGUqI+|>W$mP|du>kUQvLbYD%C*|hm_KkX#+IF3GRkRamj22yggoDA#%F6DXfsztc z>DuaFiHwk$5fS<8%E6(brUCnuMda_=OA{{( zJm&V{AAkM+{q-~_TTUfy-lOCfFG7F(uuV-%i%_CP%j3*1yQ0=g+SvrW~$alg>BbVsv~dE-t=~@b~w(>pr2RTTXi+ zyso)_cV@>(;_3lQSXeRR7T?i}lO)|4LU%+$T~?#9v3urR0ovUTYh8Refo zv2EJ4X{;x2fB3G$0hNIayLaziuc)X<5Xn0(n2a_*ij0W~mJg&injLE$>&*Q8`Nt;t zO^Zqwt(j|uPFw>J@TmX>?=?cdL|eS39ULnbX#5=!#PlP7a;ScLTn%ih&0c6A+M z3f1Zx6wQ&hD>5O0Vb`u*#i$2z^}o70v!06y;;3fO)*)zO!_wL8l z2W4a%HP~pSy#@K}xG8+RFROhO?cVlpr{T_b4sk(2HETwDoEs6rfo=T1jhS_e4Mk#= zRl37f1L`Rp#aNq0$2*=o=uy2@{!hnB?m63dnp#}h=5D_M+6LdJ8}5sBO^LqMTk(P*DEn`LkygeSI7? z5u6Sk62(Gd=8bX+3JT9V&wA>yIz()5O?iCSEvx*bt1lJZ33BJZ6gaKNYDFJ*6LM?J zwfgwswS{``yPKS-gWB5KvZgpmENthMl6yWuK{UZPYkTa3g@mdH--n1=wejMGYkBqC zHu(#F(G15+O+MwAWnPrkxT&WT*SYg$zM{(5*+t`BdJ!B)cl4UpRTW?RZ62Jc8^+B@ z!^p}SbZm9O_wSGCcWVJpp9)}WDToiPt>sDbf!VH;JyZ=M;^Ob~zuq7#LP|=itgdcj zVPPTRT~;RN7Z6a<(6HH;nxWcz-TFI`k?V+sskhU-cSVnR{-MROSATrOCnAD@q~=U zQ`8of0d%+n|Hw$DACr?#-`n^Iak1OYj}DvEgzqBXiM@Db*0BAB!8;E0HW5)#t86ub zar^cFmx<1jJf{pbb8~)8P0eh)CUl4Rri&LZ(rnx~Ks&uKGnAc|=l|-JXk%kzw&%S4 zlpcs=sjI0uxhYTpWAmrB}Ctf^OZqby8hD;`Z&^K|z)c4+Kr^?9>z# zKIc0;W!kOe_)Yfu(mg`M$cUSK8&Py~?M8~708dU{-jhd%-I$qL3!H}b961sn6trpc z=2I#vA$RZI#dT1krk0i`Q3O0Z$+NRp$NNeSe;XOW>v1CLs;dKnf`0w_MMGR)TbWl- zxVrGu=-jz;$zx-dJUq7}BA((y4@pfOKYl#dYw?!^`@^)_`g$HB7h{Fz*^IvZU2c@eg$PSN;D81A#vF^aix_fw>)6?5o;y#ny zhdt>`T?w}ObJW_{n1_;L9e&-7iW(RlrS_2{&YwR&6}?|8OHNIV&f3~q9d=u|b2C4967o_4QL+)E~)gyM0@{bjNxs+A@sS zg6mULQy)HjAc%#9g?=>71>9TQXEj3Z!i8-&mS>br&CQK_3!DgVbVu%k2bty6DCImo zJ?(WGhh{{)793f3?4Te5XxVOIl#Gpy5kzlq@3>l$fLbgifs#If%XnSCUN|4YdF(;P zBfFzQbWDtl1VP^O^XL29+S)##eVbZXm@F^M5Z(iof%2zLZPeD*CakL)YH9-GO7c3~ z>$Ws?rg(UIR(}4>F4x4uiAE!8QhjpgP=CL72#YWUG1XVH`S9VxjgJnqe0l5kP^!76 zhFVrumhgVJy0p3Bp>W{aw}-O~-t`%N$!i(?y~sQ-p67ci`4`CaoEgVfgV*Udm|&CYrjW~ z%5QCu^89mv;1U*Q!1(b^NZ@qSdv{|c+hfkU`}1eX{n@7PlW1a9D@FD-~9djC{^R7nB>$FU-jTrPR#+M{2WcVIoO_Y9?SdQe>027mEqd1 ziEj3`b3;5TM+ajR&YopDBrfiRN`7(q?RGXcHgpG{le~kpDyp9BFaIdT$tqtiyuycr z;R{?rK`8JrnK#D=pKwObCQi&Wv^;RgjxJHAx~Z|QBf_*!~B`_(HS+$Sw9 z?VXsII<~da>wgQJv3j`ipR?c3$BetLE=yx{i8%Jl5pq|q9L!Jt!iYYeotx|T?Abp3 zVs{_%x*Z)IdJ1K45(TR_5Ux|b8xyNfMqpaErYNUmXEW;P=!hIVcV~14jgPk_L@zLPW;-r^bM6 z-MLm#?J^$oQ(^BzSWEzC#y;l@3tcYqqhpsaL_dLjJfM9Gh@rBrjTy&kVK_?t zXP@V^(TBw2P2(ocmLX2-h|8BRcXxM}b#`vQapT6%U%zg>d?`FTJ8NiePK64-q^->@ zBEpECQh=jeaXt*)Ho+Z}-2$y#2uJ zrg7eYD&=TJS}ASyVTym?XG?MUrluzUCr|i*tY%t{t>vEH^-$<{XtDn`trzyy$gKL_|c&FvuN$_8;G~Z{HQ!SAcGQDJi?rYYlB|8l*MaCxzv2 zByRtZ@+P)%vdm|_se?mHNmplQ+Q+Br&eN3@6_x`P{t60*9QuwNJalN-R2{dJVpJKx z#B^3iXUF%kF^w~4=r{VGh!wZlzPPl+%oG_FwPodJC4+)OE++7mD_1a@+S@g;EXnAw zJUlW^gOo1QeUES$E9z3KuDrN=ml@NF<a4GN%RS3<38YHObYCU~;= zdsI^TjDi9+0|&3Xyu8P+;f)uxv_Ag$^m-%lZFu+tZuOMByf5>XEx|#1#KfZ7+uO%R zn&Re`8t!oRlr&DdIJ&qfVoDJwPv;H}4T(ApDvV7`__mCipz!05S()Hal{YkmoG%Lc z=8R@G6uyy`mXf$S(Me}+Zq9sHM6_-Ev9vRPk;?=XZc8;m_OfyH2UY>~$5m({t-y7A z_Uz%3lDcG^5D-Acul|@evHF5jh2O^b=-8R5He30*KYx^N+>ix%8TkG^xS&7^CAM2k z?6vkcasJl&mX?Qi&bXjuJyy*U+OT0md}~N+d%ME%<38<6*1I$9edNkYrarxXs+#jE zIhiN;pqi>G?|4I9oezLc{>q=v4(`8(gWIpL?TVB5t!jPp3?KcwwynUq%v2Y3bZ+dk)t__WoTlESA-S}u%7{(!=RZB{NJ-;CwL-e3}+w~oOKcK`E(ZGIJ_qSpo|JUT9J z=;gark4#sh-=8L2SyuvL z#eUE5ny2RwPKzSyg6OY}+`VV--bhB*cUE7BpF3&QI5XpFVl;eR$Xp zV;r!T1;Z#PJbdI&7%<(nYuBVaX7><@;Bw9*jRVH2;++OcHBXyN?a?H=i(K}DAp#Oo zadL9T+*>fI4lT#z2nR?zuBF8S1WLYyDC_ECd44go0t1DwnN9i%@5M}=4S=neE?qKg ziWOe~gewf9%W2d6g41GeZ;$2>fJFuPmt9+S&M;g0``7t-5ypj{p(sa0AjeS;E@^2t z^e~^87`COk32HhzIyA#WpKxn|i%X>&{7!HSY-ng`@Xg8+s;{p%E!t*S%h}kaMK293 zgDzQMx%sf`4{u-J^vk=ak-}5(LDp|rb#KM z3Rv5W0(vUEem6;;iwF)1a!=9Rih{4frp8^Dm0vYP3zVlf45&A(U8g$IsT$oF*7`ss zCT?fBsr|H&pmDnD2>;tgyRNLutcP6>fLx2(c8j1*JN2D%o9c}WVr3v!{?03(I6)Cr zSTb?M^G|4O&jUf-YEyf`Jj4nAGItw*C%&QBfw4?yc;H z&peXZU}k1U$`IO{Vv7#u1M#i9b1!yX89o`Kzr$2pt*#fKjG}+e%$}}8@Im1^@d#Da zj_J6~bYIE9*ceSBe^)prW824%(ptxrYLZ=Vv=`+TSujTximQ+C%f68~>M?8i@kJl) zVoDQ7%OOddOY-MlW1fg#J7ZJdYu)u_XAHZy$9&G<3k&15uOp#bQcNmM?VDb(TRv{2 zOV|FeG@1XEAXtR-zN$KAvpwvWGgzYE;yt*}}}6%CUuwE%?qIMqXZC zIb~%MxTU{%anD2FE(17_?Z=NF**0B5gm})&pFbV-N<6lq(t4%y% zsUw}2bw@60Xn5aPS*qi8UhiG*OFi@hdsQX*xw#7H;x-q$ z_MlrN~*U4MT+NdYr5_8vKU zl&^Q$I_my?|E$Yz2LXw10peY8c0POdtPh{cgR+VW3f#oc-@k|2PLUE3FE6E%lF|pr zY|5P1DI-r(Dl01oZ{P)r@{#+Hn!XHWjnsNj+N65);>Ce1dhCUzjSZeWG-_$GuY?`T zP%~T?B}&4?FpKN!y&D@{mnwKsG%?#C4*4EOHEE^!4-A*87*YS3l zPrVO>4bH5tuJ(F@L+$_(K8n)_0jBQLrx+d{o_{BNuPs{c78S`Hb^qxd6olb-%D^B2 zYF~PBaeR^6^qIQ4I&i*`Mz(XBn!~(TIy*Z_%DRQ=?8S@Qt*ouvUTD7_&y$vvd`Nr% z@IJ}Q%=Ay%*xDKiKzm$4ft#Bfb4po30Zc9Rl}Sw-Fh+W6s-LZ`ttC*vEDp$BY=oBm z>C>COfBzn-vB&mGV^vLXjHCm{_wn&IFxQ}Agjo@ zjB8H+9;xj$Z;UR#W=P8}LHp^`C&JoP4x(6KQW7`8B_u@O*Vm_KUI2V%GBfxdygM)? zWHW?E>1_=^2P%{B4A?%+3l|2!7k|#rQ)_Gydcy6%==6wSWMnKW36F@V$uVn?l5WFT zYJIBCsi~#4o11$bxRVBo2hv#c$a-E9zm zU@W3NHJ{Od@7fU#V3PiUfpv-BUpP#c%yZE1lBw!=nUS#(RFo8j5u)NFUrbQg(Tql zC?O%@-o34hn-!fowDS3Gv0SO`!b8?t@B7@>atSv1aN3s7B8FCrA(|7q) zvb`3sOo>5vIMb}9`^`gv*ejut1nCq~NThvkA;AIwr;l zaxr0T%ozO5G^c-P$QKie)RpDJ_V zsUsK{2d)odMky~}*>xke|HqHe^z=RM?(SucjkFvb9HgR(rP^d*V9?Ap`QwM7nVCP9 zm~z900c>1Qa4@b#3#gIpK4VNtMOCl2R>OHSblrL?Ll6N{_ybb^Sx(JK5VC)Nh}m!J z>FwRQo|=Ams`V`-;Eh}O`yU$ID2LKz`pgFJ`0(+gZ)vG4#;k#jS8V-K=UX?21Nz0R zc#8sJ3rAb9gtkNDRAgYd!hrO!x=;?NKs2 za!g%p)J4AQ{S9EV-p?J|1{4%s)in@xj50ogA#8=55Te2Cfk#5Q5xtkd^k6`*ROXDqn7P2k~S3e9J8l z_w;IT%6icN%3D{IZJ)56xaaf4z=SXk!6-h~k1(y~C# z8$sZ3JiNTAW;>eiY}Tpjn(r-i7D4N*E&IYsMMYH$#0PBB0bmP>^sw7h6=Xvr3yUsh zHP4AdonHeW`1YsCp?_rO=Z{vTr9ORXg8C}B_M0EpfuVy##BSwqN2hzNyW%cxWbqiR z+GuHIb&BThyOlq>Qil)k77(D8k&yvY&SJ?C(`ZJIiiuA%Cvx_gypG0AD=R1};wUz0cW*jVFZ5Z(>iHQVAf5Fx7%s2i{ zO2*4x*BO*@x;u#DYgm78FGyTJ?WIOgI;Z)m%e^I@S|dwrzf@k+iQ^+Fd5-g5I;XZ@0L+{ zF2=IT%JuNgq^|wqg{M|vXt=br^mBF=`05~Z-I>4B@0{lY9?7^=G{%U<-A|KW_U(X0 zgKjhc4M~mT=FFfXsLM$Oh9B)2Tc8N&9}e9tFKhKC3EHBw(IIp$CKi^!rgK;B_}i0Otj8}&JuS^?+&t-3}#2e11#`bJSe1JT&vg@<=>MbbUP#@2}96F zPNU@~Rsa~glFfB;W$?P)aTAmF_!t`bRm+YVF|z-^GNI;>_3E~)S}JO%7kl}Ci>{5F=%1fm*bj|$+eb?pZ@_yhz@z*|4Gw^soMymFbi zNQiUjzIB}(Ozz0%#TbLd)+=?$^_%UF(+y+pxwS)VGy7~WFR!c^nVScInjJrN>Qq_| zUv|z62W3MWjX)-GdWj3fj&bXNhxV*Co68YU+N*O|& zx(l5xLRg<2xf2`Pb3h)hS8Y?1qNe7(s!<4u3oSQS*R!*;@04;RpiNo`1?-~aceXK$ ziG!31NDY{1WN%N8@*~Y~950ZCN(dR!fw$9^wrt(%2dp_e(Z#TN`+>4M+{aXUHWLKv zHZlt!e+P~wG;vcivjOlLD3%iDEsyC4kwb_4plX&b|5Aym_H8XSI+%a)LE)3Mv_Vv1 zfy>19sju%Mgi9AFoSdBCtsi%E6yaBm_J(wHY7!35CTL7f!?jGnQ0rS;TR(JmRs#wf z8XMmN;5Ys?T*u5|h)yvu`+{~66ir8aBn>bL@(K&qO8)rqb=47^5%8W$U2j5(2w>o( z2Na-cDRCU22%z7!Zzcx%9V+$C{rh|$qeXgzRYw9k?-$NZer5>{4wiEL!FoVYP}KdW zVf?Y1rP?c2*6};8e9$^~?iRGEx9XDw=CF>zh=h3~E4pbiglTwpbo=a0zenV1Q%6;} z=tVbX-Z!(y6jQ*1p(v8l(`jsMY^DOAx*8bdAA_#3Xa9bAGc!K#fG3W?jeCTI%+D3j z6QG|tB*SEQs-B<(mQKFU#l>ZL_Mc6B{G zJW}DmnZ#vy7*&%N%Xd&osLAb#mc1?m+p+9uihhA3H|AzGjQRZDA~$w^XA?(SPT8Gg z+91z{#XB}W9y>#-*L_zSSOwReZ@J24Y-}uITt!2>OJ-|%d3pC6JKebVSB-Op8Z{0x z!hH_;{keNLSAZ8OC4&Udrqe3z|H$m2S?Zpbfmums4`LMTw!N^i1Wi=g_<=y z$h&lnuC6^+1qKZ|%M3KJ3fMyQ^z;XOG^vLkMHNcR$PC6gln(T5_CEoI82N@l9CmV+ zV^n_t9VvMG)|q}1>h7g{`(55Uy2}5JPi8s*)sQrqG}QzJUpbGSDfU{-d90e5QRFt+ z;}0&!1L_Xm?R)?JHh|Sa840@{N){HDSridL5&|zchK)7(>t~wldMPLy?lCY;XMBh`$}4dP!RafDp_0agX>QP1B9eA zXqa@JPar*lZj#5+ZMx6j$7dZqr)+Qk^>?{N(1qwwf`lAeGkH*91RS}!x)U;emVlG9 ztE+iTpA6%4e52a=^IM=uD?%-U9rP2_$Yg2uJE5UIl9rKCcU?b@6lk{w4GxW0jQ(~4 z_darcX)E3U59d_M-aV-uUmz9-4|&dxm7n^J(K?>zW9Bh&DL1xK{&I}&`4IM;+TN;~ z_WOl=yu5~kRl!8r#?mJP)6)@?pYtIz&_bYy|LBRA!YL-&e@~s&(o%ME5}lV77Jk`U z)Y#NCgMql7xUsh4R!~?7B{8GVscn1}mMCAi@V{s0oX6xTQ|)N*KG+d(oV|{e}7m2suqZiA#f+$CgP3V z=j!XFwx14eWnrnTuBK9;w6U3>3Uh=oOCEJHGnA6z3+Y9Ewl@ zm!-?%V2H3Iupar4#7~$-Wj#GRpo$uuS)3&Jojn6B#}|J>18`cJwIZW41mY7q062kc zR@ApLEMy1_-gq;FMO2JY%KsoxzA>tS3^dos4Ta zZO0qHPyU&FG0=_Z`EXHRzwgDZsHiBuTYCB1@tn-f)L3wcB$a(7o=jV|thcZjy_mVC zCYDp8_CV-zz2d4xE=S&6x=a4QVmP`X!^%h9rgmcgKUaxNK*(7KS)uuf!^+Z}hL#p7 z70--!>~FTo$YUIRVDC}&{}BbG6`08|2M`mLhI8IF_Hh`j z{o~`eF_}YIMJb@(#Ydg^kD(4z4+s*#}*__-vu8~gh1SnroF z(p_c0eqF(W`$qk^=I-wJ*LAut3_Z~Vvo>C!6aQsoW3$=B#DwJakSdr>R-lAcc64lm zFb959hK7jS*(4?=c0fCal1NNX2N|SEyL^9r&kv3ZXw)EL?BP45Z$Sx5M6VztF+}^q zEI%I~c|DR)!06+1xxXd-Y$+kW)I~amNTZN`?~^BHzHulNsa=yvIb@- zBPVA>YASEMloJJViZ!sy3OVaw?F@oZ>1iBN`kQ*e)ILlUYMW3_B^<<`W39XG6Ch1U zUZ0zpDbLi+AD2#6Nl6Md&l8o97@5+hre*c6uRpypa0xLo!W;JsmdKZtEa-oUgSvfT z{`Le7149iyfwXj>6oqme)!~VXi;dkOd2|wV2J)Qfjb(R2T=e?=d-r&A-jpCm)<5G8 z=;{67!S+%8^vp~;5>BA$>S<$Ksxo&qTm5nVmnfDl`l7$z5TrG&&e{5K{_jPvU>e3e zGrhq@k4Z%yZIC<5pVmE>R^*zFCM?vX*t1)&-O1hRGQl`6Dkiptl$}5?V3@Zk-ef$l zwTX4tuCRp#_cNVZ+S+@$XP#d_mYSHTF@1gVmBrnHKk9F<9XbDZd~b6u`u@fZ8~mwW z7m8QMoqRj~=J_ zUR%5Hlif32*_4%5d)hfnPCd)W>wo{0qbJ73#*)G@j>denCFGV~>3_16_ybdFFKP3{ zieZb>!ak$Ycum9mpl1aPk~vAsy5X1U04Ov{fOMp8EPWTq3a_X*fn0_!av%6;3|kw` z9Qa@~7>KNFY{z+-x%chcbc92FMAg;Bhk8N~pED!QPy6<7LuKtvo!3rEU;JUz5@bbM)1VWJo~&^s!tswi2zy(wM|o!jzT{r#{hhmFW%?cw1W3~RWC zXh+8L=O59^4JL{KUnt~|<8bH=NWJt)YH`du-xzv{Xe1*cQ(s^$+g-7O&P$g zKuuSdo%|%1h*%(1DH)k$l;IcxV>@^4;yY)2NO6+ZF|5RXFJfPjpkZUHB*6ifG>S6I z^*@j;B*?wx-UIIJJVuM5hUVq~7@#a(rQ%3JJj=DU&pBdnuR8I#F9N&Gc7v>?Xh+wF za@b8^6GX!}2dfGL2;@F?j1#6pw3tP>pU#t#sK<}P;c$>42Zy(N=T5>jQaS1{Y3mgb z5CB$PLCxv)q5oAog-84Lx`>`Tje>jj(7w3vqQBeVJ?!QMFLLf*w)>xRDCL#qP zA|_UudMb($EFEzR37w~MTylnnTr2`K=`%M`L&8AC13!Kocr}gI2+b)lJe-~kSSf1Y^yT!Y7;y^h>?K^ z^==o`;r+NFS(>>4uA|4N1xOW`{LiVjIOi$cXy5MS{`1eDH0Wi)EhEj3RPd1)qPux` zJeFqnT3K3ZK*MHYGBY>7i>~|y@n`7ba4=gD$AFOoxDP6#glsh2ntw$j>s$US8j06{ zrln?OodF=@;z>rCwRLqp1tBJ{k2B`nOy&9K2RAap`-FuBeB`(W{Q8H770CE8M6cT* zyRa>C>PnRr64Vl(H>n+H1j|1pPh zHcU(rz7%PWAx>I2z5Cd)1RSAsjCPyXK$2uC6OZ?$^m-ifu_s8?9u8g{XeH=ucu>%p z1X(p0Q?r=j{55ht^ODx>dp4m8=aA=RL$8H@hx6x8uB;Y2BcnH9 zz8vOK>kDUuJV}?yZJTvy+OU<{z{p4da-#&9YJXdzHhwb$k9)vM&!0TPuQY%DE< zAn{0kdYD%F4pfRnMVvR6$v_4ykK5ADBT$7ej#w^RaI3IfK8PE zZUA+@|!-6g~JaPi+(&nt5??kxbk86^FKrI>&qjH5LJAvHenXfoCEf zs|P_7xu_mP8amOoVXLsShi$_O>@Y4+RQ9>WP-dauI*uajqdgdixBw-34F-I_?DGjn zVSSbKqa1lrY8`Y>KY}J^T&YYeJ?3;hZ;J`iPAY1S9gO&Nx_WMQYfm%|vj=+d$g)gbueCn?#ZbmSB7aGT5880$rPn&SbJ8uc& zP+R}Yje8Fs41%8Y{zZA3V62cDBX4!ipLs5co}O>Z(`&234+HaD-&Wa0nQN+DzgbjN zM0f-LU-{aA7WhOa@Q}inRTc;U6bnUm51)K7);VqbDK_`hP|VpBC2nL&F)lU`u#$`b znHQjuBtCsgjWD-RZavcQPLL$|8+89$&@=t)J?QYxYg~iu%gFEpT<(Cq*Bf>NOkF8# z$NQD_lJ{J)08bVY))qO*eo7W6nFfF`hNLJD7ngS&TXFc2ObGzw(bc*?Q(qd$^8TMe zCu2nM^B6BFY!eg$17JV&?OOwLX31H(vVZ*ztLZ(L|YJLz4Pdi z;9R8I`L78$O-d0QP1lYGEAYI~%@2>--+6x{jFH0D8r3L%wF-neH7;HZz+)gDdzMG< zj9tti#Oy-dT~>#bjkP7&IX~22IiB2kwguu!1axDbnNRot%i25KrqA;?BbjK;HHP`g3slz-Kdh1A1zC25d5>9e(zgzr23t zJakjd!SBcIbWS(ji;D6kL8`!+c+0%*^OMyY;1Jr+$}XC|zrC$VR%`o4PH)%6l{`gO z&6(u$Hf{EhRH;&&{_!0*Z`Jc(L24Zr^;l`ECn6s`TB$ZWDc*j6zt$~lj-f*Z?~qbJ zOLW*u#6D_io~|9mCdE0YS_u^+2wl?JGm93|m%fg+`fcbX3V}H(p5(M&DW~NRc-z%G zU4C$|d-2Dz+sv{=6HH(c9hQIphFux^TSj!a6MMFnwl+!OYjtZv2?n~3Us-?LCQait aYQB_&VVePWeSCwEIHh<-A?t+Ut^Wfk+XEW_ diff --git a/doc/src_intro/img/class_input_factory.png b/doc/src_intro/img/class_input_factory.png index e8f1e3a43523199a4487c06f00c3177e33180020..53af18ab08674e4caf4426abb16f6362223e9900 100644 GIT binary patch literal 7169 zcma)h2Q-%d-~T0LX53_CW~7Yl6_ReZnWzxTCL>vevMYo_eC@Ky%-)+@S(zEhmc3`$ zJn#GWd!Ff!(DL9oTdKtGm=B|5Zk%e$$oqzUz+vk9G{(IGF z&lsc8oCcibJrQY+q)KSB(ZJ{Wgd)@QOcv())TT4yN)gv%Sh^hF#-6u+Th^x#&DN{1 zInV(^>TD#ird@9>roM^dzoVQyxSUp(Hzy9#{&P*Hi8M7dvbOj8C)5%LCQP!`p z&@rBRdXFh_`ng9)_vVEEo|JP}pinctyN2U@3%!}zvcrFO5&dEQdtt#Ua_aKs%T_U-6 zm{?h5Ixz%?9F2~R6+WA7KZtsdyRogf?Qoh4L*3l}|MvfRCM(h5aNKXOUZ9~FIH*rZ zU}2E3J0G8+k%&IQdzD?EPshcSsnJPsgY4j zkhw@hLxXKFLPn>TML85wgZPbM4j z{WNaf!ehDN<||~@oTL)YRq=9@{i~@Ewy7!X<3|#Nh?uys(TA|mWB=LH@tTW{j*jq? z*BKdCEV|-|k-eks?#*A8iBsR+(`{^QG(__16u53%JRL3}Zfk4X*xEunIu_n77pU7i z0|SC~a1g{|u?W)gft3&$t#zlfwzeiBBFg+(OncEidh-=sdg+(k+`^Zerbt7b=b^*F zjEAVl-oCb{d(52JKEg#-Dt&Y_y~{wI+Kv;Sz3O5BIGJBul(|0 zuH(_3BW@0fiHVU{#ME3?vYHp&HDGy4qICIa>&mTq&&bV&PtE=$?&#?7b)crEM&#`5 z^4hyJ;`jDm`b~(7i(kEV?b~SO^RSqh0Nh$}h2v$`xLl1?#nW<0d*(w(@!+GEqM~AO zm7cCHfaE{iFj<1V-873wsuV3R64pt@v)h_RqTrpE^ zm8L?_SNh9rABozH(j&g89|IZMk7rt8fb$HhP5aXCNP6rE(q4P$`_DgAe*P`rrH4B@ z)TZjGuc#Z3l-XVt5XcYn@+W7$&`yd_u*#lI8e&^oTH^UiN=k~4nu6)Wwc(AAkL#uL zhe?}ZtY)fd>FK6TZ^;UZim=J@{yixQq!pEww{&#qpc9hrfBDqorTmtE=5yS<$%@Ef ztcFXtk;xWTZ;YuayNryC*4*~*Z=?tgyl@q1@~6PhWYQIRHluw0qVQQjIcx~CwDHrY zL9ni=FcC3gHc_EEFz$TUu1!r(`;aqB8MlNmJ3M=aeNQJ)U_T){G&0gOHfB(frxXAF zJ*mFFK5o4tA|p4sHU2hE8%Q@t;HLD+6CN1M9;nmT=4NbbD^cf1u_m}x&lf!rwHQIX zZ{NOcY;WTu5m8at-d>cUp<#vRp?DOZUW$0)uVTy87wh9gMUP3N_zm9S6OuQ4`*seh zC$FkX@^^jWL!nuV>93;4G2*ri9-f{kIy%CnE#)7BgS1K^Ot;k3&ch#vDeSqO#XiER zsj0o4K8>l_S-QK9O)KX`5w6&LsB z8At~)T`y`DtD?};*Jo-DX7s=IsO*xk@Rlu|f1#9!urT`J!;kHUNB^1#tMBs6Y4^Ed zV|-`7N8`33{ECLxh=S=#>2zO0kaguJ347C}{;Zz9K6!opI6?M^LW+y5`$7+bV`F0n znf~Cts;|GPdi(Z-ix9ng>R#&yq2`#usjmO~Vy*Ruo95MTP2OxCZtliXo1c`-%*R~q z-+-D1R9s!J1N0l(#N_4i@BH~A=AOu!bfc;MBG6WSe{Hu$YHz~Y+L}kWv{_K$i{bP; zpZe9CejdTES~IWxuP?!C+qYF!e_yE)1oFy=jE>HUSDe;i*rYbZ(c}6au|SYev+UI) zU%F;`voExx`#^GiQvZ2jsO`>ooNl&HQG*ZZ)@HgVCWaIi3eB)0nFrNNN++^6?_B2O zZ0P9t(na%9yRfkE>eZ{1Uh8Akbc_;q9;^G=|AdG8zyR0(D7km<9?|*p9@Db`hOYs@ z*G4N-@3|Tg^78WPS2#?S&fTkxFQ`&cQEBu(*-j+Tcrk_bixGbOZg|nu)O2!gZg6rx zM>A1e>gkXmj!QN-H_09(z@`RZ*k#;yG7T5iK8h0Gj^@u5Q>*JTH#bkx%urX>(8$*@ zw10Qx={0b(^OJ->D3GRvzek%btYPu-W1%W_MW1g+rz9mIA6RZ+Vd%mV5<+mq7bE?G z9}cLQApmBpur~J73c*H?j z@{57Bv1+5+^SjCIz;r;_4u^kjgBZk?Z0VFZww%*}y>*K%$Yf9Urppb|2zry^C!&qK z0*$=(6=p>N0{0FlPRRuX1a?+_QRn650hpad0C+F4v!CHm43b+PukFo!B%xpL#f%h~ zwUAd-SCcNvxNe2=5bI4AD3j!iH6{-a4`W+fgH$GX&NqpP zti$E@6pW0FE6^yUz_OcV@8H06XQ6jtAcqc_%t-V?Pt>m&q*ci$tKRG#xqXD8_-G>h! z;$RRs@fE-h9A#r~(+rU_HcrB>UcI6o_bN5jEO)ljV_z6b?!&E_-cMvy;lQRC!jyG4 zuc1MXPrrh4!eg6E=Ee;a3ron!@nO^WILn0BVXoj<&R}tsVXfQL*6er0&|5k%I9OYc z*4bGGo*7`mUA|_(0~0&DkctXPoE88niDtYg{xqhb=I`o=KR`4) zl-cv}uU~1Y7{7kSD>zD${Y0IEgF{1p{YkdV_zkZk`ntNhh5jsRDVG(Zn>TOH%*-H& zu!x9|+m6-HuV0Ogjd%dIw039sVcl1L6|>R4@2&H6@AxD^Asnmr*bt{iftCuM{u1s; z1lY$hF`T~<5D*01-qv@4fvAf(mc@h84-E}9bazwi@9(2^t*yD|x)Uj+rKLd+1u;sH zL%U1UiyfyG;Zt(J-AW%=lvPyl5FB(Gd2IR##)A;7ti0Y8FP%}O4{WalL}_AS@fPG4 zhlGR<(cy0WDH$CdU5Rxc!T9(%wn%FZ;Co@DTmWfkYQl%f;fW5+cGJ<)GVY4IUQklv zTU;yxyQnp15ShKIsD19-xq|ZY7AT#~7ZJ0T5Cum^A@u~A{r3I3;>>qfG!jCEd3EyA zXm}r7CA-4TAYyU;csub_Yj3?jOB2V!Q|0mT%w(*xaUgD0Fc>%j?6ojEI|&)t<>$|z zw|946VNU_A@sE!WJ_=* zB*UQJ+BSM)V`J99Go0aV3s8W5psp$)DQ20Mq36lSxY^ilwPtANJaAeW5@Kgp)zHWQ z+V2slKSE{Oy|b?d za~~;TFn)f1=1-oe1_lO#*`a;k_VZ^n4-Zd3z|~8aURiX++`?c01a)-Pp{V_UI1ICF z>>q{92ow|*N$PXnp8g%NPs_+q`t|D<2D5Xt|6Ev5Fv-aKIP&kxFL@~`DW^Y6+U)FA z&daom%gfrM`A*x4Tz znx1oYbGr}2KtoFl@K0?!Qg+AI3&5_!>0&i6{yv<9Tb#iKy|(_FYfiMpqybph{EmR5Gz z`Rp>rTO-iH&V+ZdSC81C$eeqUGxCS#CGBu`wmj*3r^J znES94B>vg6m&C-hR}-|Io12@5YFtHN;{0J;`-!^0f0qXk#+i>W<+Fj9H~ti?X!bBU zPO4;u_q6olPwA0MLP99`8tg)ED&D`W9aye^i>}tCeD7mkqya?F4YwUR!02F^fzO(s zpwq~!urQRA^HQ2%BABD3RL#o0=Aer{;Glx%P>6oD3mHsOj#vjcgj%;hSTH9DGU0uC zgOiGwiHXT~>-(-nwaY4rjg5_dty`)3AFVm(a%$&@fkJ3qYisMP{Cok#xZxEZ$f_n* z?;|_}d>t?sWnQ?Fg2L3%{&vsLpGv8U!IM){$vuj25MOBM8DwR3l`Tx!*v5wU$SZRB zdQ?;t;9Vm~{Y{X`d=E>AK&WHDaPk}01e_zKg)%gPp9OlN3Go2hd#540fA-Et(bw>B z{6=*_1qFh^bDAKvhfA#SfpL*netzeUj*db@Lz9FJEiAb1YigpHn9e6{xqbZb;R7WL z9i6{ku|;D~4<$l*@nRq#-oQ&I?L=A6(6F%A;5zXT*fzg?X|JP~I8Q5KH;N!kvL5ue zZr$n`7|?#02eh+yc-Vx+o`Ibns&eLaSs%aV>+k2+2qN3f%`HaKF{ODqq3Ur;_Bb8C zKCVs=%bpS=F+yf<6skauOaBRpgjq@+zz*B(*Q(D;E-;Sd!q89d5~N=`{ZPrLDKSB(TpwJ#ANz}eS+ z|NiZ(>HGNcW0DNgoU-Jd9Vb4cIwlGhnO7kpB|+L}mwF zx%rKIA~39lmyhp4ySVp>2cKRMhDbtG^ovkl5|~|(iwa;&Fzl#z@8A19HUTr$o2q06 za>2pTu@SsVXiQ9Ikv`yZL2)s)7ZlWrm9tIoNPNvvc2r=I+x+}IXcEJ{ z`X!fT?aX1jm7zlX&!0c*!u+?34wu>T#@+W$9H`#5vC`fhpXK!r3?z1PcBV<-@gXmua%VQ@dSP|dai6yPi znsfv6;U1TJoMg3gZJYu0TjH)ici7*0%*n;YvvU04X8S+UU^mNeEoXInvbxf~^m3`6 z`)JkPyXnvJPZL{PvRJkB9uvHG+hUTE^gaY+=%-KlpcaF92Jb=FNJZa{h3zss*jc>F z$M@CfWQz_bV*p^!-gS-7cC#e!9}S(InMtatVVawp%a6;CjnxYd27zUlE1jU-_Q8;Z zgv2-A4{(s4o*v26w~P`n;$P9{Eq*quI$GsSN+)3Go1DxB%l-D24*~HMSoXcW=?~yt z@xfC=mXxKIe;~un!-KZ4NOur5{8MFq>(=XL=DUY~SMjbIab+)!6+OP~M-C3+c4|$e ztps8WBd=TMaUB)|R5=17S~Im|LSlXN&f0u;BAxp7%1Akdy1KfckkD%gIezr@-MfFE z-M4LVVL=XTx%bKbJnyW@lP4sA>Q8?aofD2dzqq)#FkV}YwHB*{=!b)sm(;Q=4)3n( zdMn5nN66lAft`R+-35YXPEO8A5GRVjhX~|kMpwhLot8{bPmUqiP*6}fN6sQcL_tA; zL}t{_;B$gMaNOH4VN)O2LLzxx2Wl6VrXby*2b~1=Tkz$Eu^){BPvmcZRxjkP>wy+e zB(}5jj_nN%kXWktlKrmKs~A0I5K6u2cNhb{nF2U`(JLlk4^!4%8 zWV}z9AexhOS&11g(z4}cVPR?Q?xrIMlkwQ2gq-JzlGw*jpHcy0vBt%)+jn9nhvaM+n4b=I4C^3Y?c8 z1aCbk8$*ysj~+=%NtwcPfYtm8YT=22Wq-Von~|v1{EMB1d!-pN1Do61O;7}5Gc%u| zAzhOT@sQu?8yIZ%DzP?x|4vFvOAA%Y%*@2W(HVSvA@f#Bzc7RBm5F-RtgI|S35gak zHwB=(C8ec*#&iu0(L*J0i|$~X4w4e$7Br+TC}0Sju7`kxo11&6!jYrQZtNXs%SIq} z_z5n01tl7pu1NznJv+) z9x>nuu!MbE4OtNgcO_+IBDB1`O>M3PC?j1kTtMChplY5@)G1@|r}EW8Cz4CGEWb^hD$Z|@(P-bY za^uD`PRoO2&{Ut`V6q4Kh6c-mhx^;})9sPG@XQ;Vn~j!Y#Q zcm^yM07r52WjyT&TZwEE3JQO)t*|9F29_s(^1Zp4c{dERq|oVgsW+B+MMWbZ={k70 zy+;Y9sdAV?*Y<%7=PK0Y3(EY`2@!K!e}4o_yWc5J%>y_(w{K52`e3bws@$ko(`21J z;%8FHV=Y|PMpdBMB&XIRHBSRp->PwOC@Cqu`|!a&>3%JXy?KeHJcpOjB(HVAz9?WD zxImBXPKnaD(UFmCJUk@e$w4;RhaNctuPE*e3;^J-KYY~D*4B6>(POLZ{pNUEdpi~s zF^Y!f@=-?ac2S+J6ug`ONz@3DFheHBzFS&i(yvwz8bB}UaEahNeUjk26(|KR<@Wa{ zq~+7?G2Rbml*nuRk^LbcfN1LN!4f11r(F@n*`NZjBO`~U^Wh&q^2D)x>CD#7@x?P- z!p*RNVNIr32k=(TgWPP*i$(+QXm|^3N5nl27BfgPOc>n^vu!lCY$o%+=kOID{G<9= zx5Nt7m3TA%S<>hs8l&xUEVex>4^1kX)z=*ri%YKtXH~oeNyRF<0 z|3HoR!7nKi-V4Z5e`6Rfe>=}t!QEZ|xbu-e3CDH03KC5NbL9my1%8@=M=N>Enr}s- z4=1HWC5ly(GKcsY)`x%9876u4+PQl*E*?m9u8W5U2I3KrQ&7mLsi{3ExksNe>);XA z`{&N-7`ahl{~f+IY7=ihaW?ExrvlH}LL{eNC?YH(jJ z;EG>lrpN3W{UReZP15;c0mWakR1)7sMBp$mFhq9-(;mfy z4(03k29{V29&O=F#E8g?nF}_yw*6Tuba4p@PZxWVWIw!qeNH(^l;Y_}Y6ek9pOh4) zWO3KmKYu+noWOy2nWqa-94kgL?xfzU|Ct-%yOOU*9N z%+8WfQ{(CA=yb*N<02cq-lt^VXGc?ijt?BFs;Z_tqB*f26SA8Ojfx_#s;S56cn!ok78yK?0cLNE4;5V1enwKX+0Z5ke~RO(GP{cYP6t40&aCn(rDka-^m z>F@6saatjN`SN97p7xMA-;*X}|LEvEa(sMzm4+sWQ>Q3Zzw$Z3_rbotCinGvTx4mq zobzyZRiCvtVWBrA{4Jd@ij(v5=;&zQ(2!qcrLcyE#=Dr9OP-#dAMQ9@x^Xv*{E{@> zDRe4flBm<`hzJs-X<&dfD=SOn^ZD)74ZKgE@ z2Qf1?g`CX<`*V1~^(Qyya-edVxT8d~9l?;7I zN}|X*+rWGlb^0|~FNRzb6Qct}B0h%oZul7J0X#fBX)P^sXze$!y=m@yYxa(gHjWZB z?)n?^nr$n&Zaz5I2vsj#y42#hmY$BP?&RS2I(CUyOOf;}aosZi($@C$+xwf)TYSV5 z#f&~o5^l`L>wuDOTAZcy?jIe|y{U0xs_7rX~as z0-Ym2R$=?m~4E&M8d+te`jVIkCd8mY{d)PFT}mmsn~-&j+gEOfMt@vB|F ze3@R-gZgN9)wiNT=>7ZmJf`he0f94i-bZxf z#b7YSwIZQ{2}MOkEwO~dUg<qlH(7CodmO+aOtnVH44)S>m19$D?wCZS4y zQvdTHxSag-bR@z&(m`yf{Ea}PNakklcn}md%jhk&#aDq4QSYk!tT?H*h|m9{GO%q zd2_xqQNr6SVL%cjMlP27F^|p967yT%M?P5?KYu>?w?NcT{=z9cFwlDAndH6u_Y#~)39K8G&$;Sy=Q}Xfi|7kosA;ywUp?)Q8w7I;zd}K#dRMfT} zZv5z6G%Fh$9=z#OUcO^}+s?|0Lm`y9KiySpFH$En*E2A8H*aj))_HSI$;H(b1B_o> z%SNQ(a3%n-Afy$@(Y>Oe=cs->+<5Aj;(e;S%x7+Hz7Ili9-sp6<9+rg`kZk$96|p2 z>o2^^mwkbnv7k9UIl3VzNP(09*szFQ2F;RXCdGVt*rF2=|R7!#a?j{5)m1joBQ8xJSIg-oYxIqTwI>CyumN|^yxg}u{Ysd zQdt?0nRydbA|x)3`g&4Vm$HbM*yk@_E+{A{z*^3eT)%UN2AJb3T$R^j-#&VIFe*CQ zPsn!k380Qz(2Cr~#s({>7~ym{HY==oJ<>)k;io| zohi2;<`xzKa4ycX120l4s_ZhZycHMVf$h~XDi#(N9%13HllAU?JfL7`G#V>~f#Kl+ zXjC(}tT&P~%ggL#I*yJ43gL`zOG6AXK66Zyl3W3|q=-FAQDb8>QarAQeq2#!YAl_RAAJ|h^1Xn1lSjZ z&5q1$r>D0UTpKPdoY!UJ$??W#VvZm7(XjQ;EG@5da1iwL^k55L=eji);|XkE^6_JH z5E<*r@5Y#0`u^ZXg-+0+QEXgXTGSO*LmYb5FEdM*=4NN*7JE}-52m0~zBM&T??1P+ zR08{!vAOvYg`(v*C-mI>#)?LR(4i-4oHD=~qENxX!6>*F6l%1=Q|ykYD8cga>CyTH zpUthU+`76Ch`NHpB@z<2WSEDir{&6Et|OqV+RW+Y%XBr#gEt(UoXgNkgB7;=fb$IS zWf5UvS8lSf5F9xE{uu%4cMpw@kB=V&)jd2|ObH5nw!PF}W{;6Yp*nhdv$-GF^nsQI z20jD1BENc7z1UImbl)UF+?9`nWPWb$Dl%GPe4d1af{IEL$Y#04?=l)~YGb3!$jGSm z;DHPp-O$h=;J#~vLcuwu%3?Q}nft(d>12ze(Vr}Ovo<#DG49;MUg?xRP2al9r=;3(1PvgZ?`w4#n|(J?U^uC909GD;-0 zw6p{UvazuE>s3Bi5w@FTPS5j7Ei6>2w3}iBU>E<#x%3kz@APSixNP1N2+ zo;AO|h%L*VJ9n5VL)f{wRn2sNudZ75CQG2v+cT|~2?z+%0Z%!<>4Gbi%&aPxfy*uD z+9O(Oj7m-MA&n`U#ee$rNl8;PvdE}W6^;HH&cy2ELH9a`NLTr-e{db{&xQvn?szHb z)?4%@t4vN#V%OQ5B9#r6EfPAU<2b+5u-^L!K-B)_%bS^*nKvcSxc3wluW4#(c64;0 z(rb=xqtYX8+#LYNwKA8Mks$~7x&4*Nd+N^uRR=_oXl8ZGx8eBkm`A~ z>(r700cLK_6dNoche6tM*_g%wR)WlkwUI7vZs!oJDTMVr1!6#ak|o@qj#s?^-osUQ zVySqws)zVAG)P{$LLUfrP}DW=-rZzCCgKAgpsTyv>_=o{qtxJFUc&dUUva;E`$nX9 zS9*x#q%Tcw-d|TwucfEw3WN^C2hw3vM+bqBkdW-b>gp;E;(56JS8gtQkzxI4jvL3o zzzLc{-pOX7Mi4>*9x*X7(iBK?BQ-7U`iBUJZ2O0YviI*_mL58paain;(bOa>)GL1t z=2n@BS6KKi_-+INN`;*F+Rx8#LqbeU-%OX7Ns^F>iOIM&k;nKP8bt!vB0zpZSgUwG z5uB@;{q#qHF15h3tH^YF#EpI6u(Zs~i;o{aHmGsL2U{pxv$fFen~*^J~ynli)Tqyl?a4hZOdxC zbWbadA1rw*Nl{VEzXL|gEPXA%X9=>cvukD{h@+$9^uhv*=5D@D@zc}e18f)oYpnjF}W4h!jUlg7_8GhmD)tA4;?~ zUVUS)Aui8x&a&Ojs!Jleu1=hqnwpJ}_{tRpQ&VP2Zi7Gw9v3cN{MOxQPQ$^$L2IBU zuUC_jlb#bMJ(St8zwd(4c&Muz-(^;q;K|0%PsaJMpa~LuT2_|-__#rQl4o}SWqyAC z@PT2<{g~?NY7y^K@tzc^+sEq%TZ^(r>yT9I>gq}y7FBfXhTJ=jP|XNk|txR9C-7 zZ#opF|F|N7OcMedd!$Cbyh={~ z25cqP)=W(qRgtDE-Y-*A=@^~coASm@t-@9u21~x1ULa>~+e z-vrV*z&5m%7=OkNM?f=7&CQ=eKzbkwf4TpJ?WOt)n zDNfK27`C>y`ZMoSQPa_7l$MhI`cdc$iZWVX0lJH&A7Fo&iHUgZm$aB^M`xRRS|y0Q zK*8wg#o4JR(ge1e=fw;f@=9u59X*7Iz`#Ihz^#U+=8L&@7~&Y6Zc=%i9xSr4v&$$c z;RDi4U&#*P%0g?3cpjGZ^){THx>rl3uyb;LPL=Vs-&#;Xq${6KKF zs#Wpy@F)Q!Vo2w~b75v?P!2;fjKEdn)eg8*-e(fXG%%3M<{Z9HUQ#2_`vzGt)E&Z^ z%ya!5t6xBUnBOCx0>i>6xsy2bVx?!tvKykxgYw+OL`7%dRItzJ7cV|`Q3M|5=aa}%v``sEKVUPqzMfgBfp`T+V&N=Ek4yqgv?sRoK+Y;DciRRDfP zZhf-;#p!p}8y2>k~V>+YS;9uSC?H@OLVwyz(8^O*W>RMZAthu%Tpq zJ^XR)D;X|I&c{Yb2`tB;&gJ6+r=n%;Z8CW$z&Q$*e#ybX0Xt;{Va2k5y865ElrtyzgmH&$s^ta(L6MFkQJ`RVB?kDwsP{zWh(B&4M2rFMhPi3Pc@5aE zzae?0K`$&#H8u`7;ivYmY8vH@qIK(s3v_*9Rzyup+tS}p0_(HtQ+tQa%huNUCBH>Q zMFWF^n&02Nk3~cEQTEyCUL(PxyjG*y$K7lwf9Y&;sjiGllIN(FjEoFS6gDZlXM3A| z{)~fhRl*0=d-n)v=;$uDryPxe{XJ1d*I3_>Zll(H1?=CJw+fh z?3U7yO{>m)f5zRGf_p!Bm^?OcY)4Av_fLxoJ6CA3ZW}e&Xoy0hA1rz-20Zy7sbpC6 zsH~c#vG}85f{DaiYTk3;4u5{K2p``lE#>1fsJd!wY}_|EXcKchG&F=+TbsW(-| zjJYcZDv9|_Eafo)Pm09hfdHfwuZdQdU;mJv+lEn=U!9#E3ppJfZhu$fHEAP^-V4!o zg;`LEjx_{+7^QvzYxl&~_SW$k7*lAiHz6UHDR1cw+8n4P2;`0oSOr78#>n85)6mj3 z@Xi-tv*0}3UgiSfdQ6%3nU@XRn(;mi)BJ*Xicv{f_5e&6yOh9N@w$I^S95>={vETv zUd(gMbhaPB!(Nh^qc;qL6W7Qs?ED+cY6qM1EZH|vH$OW(c<>;Jy>SReXhf))SVDM) zIm1ZGBc)6Keol2((Yn}~4X?+M69@mtVeky6 YcVKJm3-<;qJk>*#B?&D4r#Zf{2$8cMkLy)4xC@uQ-Bd&Lc+gy$;J2uBMK32bc z!J2vY_6!Ybh(Zh7uOTPWpyQ~dS>fN zc`_x%*3nqa?x_{4O=W+3`m|d1Ezem0-EA!A`|d>Eo*1ohkFAzovu34?jEv$@OUpHS z7j$E9pZRk9-~af!EUJ~KT#gNY#Q7wTZ(V1Q^|*B8%a<<)4l^)NoACi=(suZMsA`d0hu-Mh;lPMGrd z8Shx+*>L8jm6a8Ki@GCwVs^`1g&f;A&24ToToV%$3jJpatetlM{T>geFQ0^DeNFj& zO(S$)G8>YMDwj*U#-4+p;E%q5po9G1A3j%5>NNZNL(5YN-^dROGGez~lA3Todi3aO zY3bs=c6^7dxl7LcmxTNGOM4~~lcrcXIGBU0%5O^_ldv<+JGaJFMdb4DA5Bs()Ev9% zJx><5Vnj*s-O_%Jd@5s#b-a6p$XWpGEc^j?V z)!ltH%l30wc{!7hkB`}0N5O@qv9YlhP3gklfBcYl>f3kZ*fAzb>Od@;NU-0-hpPt$ z225&Ww;66$Q&X#n*~({-ZCB~DgfBiJ;p&qoaw;D4LisLZG27D6kOzzyk!E;~hAGB}gdQogz&YY8%m!KW3#IIz-KiZn>rRqMbe&U2M0|Udu zloST)+-R$S@YeJ6lP4u`6Lt4?vbf=W$jqdW*ZxPzrliteVC(sHvPK2|e}46=MW|d* zFf%u=%$l2>?Jo0KvU~sjm(7{xnHRpDw&^Gmrf_eJRP%GorMhYQ3(uT66JXo?>67WJ zn=4n#$W&Ga@#UTs#Aj9nEahIdOd_i|Ie8Vn)p5LY`)K;{vu72WI{wU07qhal(Zgj= zIE=P#=I7@xX=>ubUNCG62nZNx&b(joV!Oti+n?XldQVIk3=It(dS7v~iK+^9b#*y7 zIqftw6ygw3c{LIj9UW9wwj(h)`92rD}IGMb4*NYd;T5}vJ&(vcXfghillrp+aeLC|bGc%;+ zPC&pSsuM4(^^*9m8+2D!*TUSRd-m)ZpPsHN_v3W@S}$4P_LHaThOk#^s`R>b>$sLK zWuhXK?L~%1M&#|=Ra7p1XZ7P0?HiPnlPhUVGvMap5_@r=sHliv-fY2igwy-@?c);@ zrQg4PV4$+?+IT*D{G9yq`KDJ!&#`AnV#T#_wJQyKQDF}GrB)}(#D33df(8nY$$qQIxujtoiRH*yM=`XMScJN zor-VoIYvqXx9P1ufg2W`H{;@J3#X?$Je<_xwm2`w?(xdVSU)w|7PN#|;ed;GXStjYyOTU*=S-d>8UUBjGgTCHZ!p>2*+!^a;RWbYr| zW^8Pn*`ckiox7;tAj{^8uP^h|SVyg`$3*u+%G54lZ@8@KkHL=zb#zKcK4}A8U9(+FtH|Rjb|LnQ-m}x}r2g33+gn&$Gf^+E33!Qm{Nmo~ zGFriB>~>{l#`W%ICuVth`S*2oA*u5(@pO0W-pzXT>Q!v#MHIiPn``RxO0xdu!l?M? z&yRG!oSZz1_fyo!A)nTRU9rir+q?Oa^B8jgxq_vu_E)s#I@J|>c#wss_rhxV+O=yt zM@FuDdQw6vu3T5HT$vfoA2T_5()&dI`K~Ha51S{y(+sj1xm084#>+V~E$V1F`T5F& z{ESRYnHPUpE#u=eA8yWUo%=mEUG*+zYv$>lD?a)bw7jrp zS+#1_HQ}wiZ{EDYonNoWcdyA0@=ugfO?&vTvuNG!{L62GNEiD#eP1ObG12?^^XC$F zhFLZO{=2Q}_xWBB{nXNu5Ff8@Q>ON9Y;wG7=l9XJe4}`8|J5Jd&;%1tsC_AY^KA0* zuermq+EHgBq#i~$+$JsNq$$(?G$5(B8}^B7U8+I5DwnH&vi1MyN0$;`VJqATeLi*O z#J_vy@5d_AwQrOQ3!gwvQo*u8KPZe^jUpe~)`IKzHd%MiU%w}?dOQ28Yh`#Zz;hxEG;c{o&U9&>U?usx^u$S zP&g_oYT$GB`tu_#A5G@^`ucWjYunbDPfko+2@U0G;=>MM6W+4Scr zR9qIsD}ybtyHLs6+Il-Z$8~}>`(tR;+`iY_kF285nH{UpmjA>%^}i!^5B+|{(KF`L z_Us!sZsgx~Q4y8AIl;Mz!@m5d`TTGH-Gh~QiOJ|C3&noVuBlDEH#uqO5!pE1S;_?D zkQsjG4lg>w&CpPq%QoDVm!BU?LqkL7zyK>X(;c+_efo*5s9$1gYQ--&u2^b3P3Lwt zUQES5cpy0;d4RcbtZ0to`0?Wk(;E~OD{>rr98ju83x}FA%$uK>T71rup-Nu8Vx5~F zt9o=aRig1;aa{1UEStfr&ZY=SgudbkLX84M2M|i$$$kPvB{B!+G%?FG&3p_=_?ePjn{TB=9Ll> z3uI+wpFDY@Ze_JLXzm>BRy+ZEMSQ;^E;bV?QtX;u&rNU!8C`dB4Ni zvt>WO^)s-J-OaN6z^pbuBaUA+wXzCC1@4NrFDmt9U@|c^E!{CM5D6@(sHiAWq_}b8 zy$25#s?Yv79D8i%m*`sz(Uun)8ylOmYz1+RzUzx-7@N{hl)nlQM|l@JhA*fUmyuyd zciy#c9~)Nt6UQD+;ET?Nl*8{oe!QK(ew}jP=beokcMOjeqMjul2R?NN7&?@_lzZZ* z+m^qzx#RMj%#YDFgWy@bycn zi&#R1=WT6lEP7sE4+{_9MOgrw9WgN2OQ*+daZW&uKd7tAo05{EgTBVief#!pooFT7 z0YHMV*x3CoEiLEz-wD%bd-m;hI>|MkVj|OxQJJiz3 zs=lk-FTj5wyW=vTuH?n<1Kix)#|;cVbe4MMng{s%#{)4RLU#p1uZ!RAwOT^L+ut8} zPV4B=+vz9rHR*KhL`i37=h>l*Vt;>&zM4oy+ZM%uIKP+};WXpoSbzV~j^YCsFJAoq zH93xlyY9K=hll1>H@>6oFXgU7M|q7W>F@vR*Ds5S?n=XL*#8M=Ry5jK7nkIlH@N_^ zADpR;)rnJexA@lgmS@Q36|n&b zR}ZiMHvi`BTgjzMm#&qTMxlHBSb~<|n;ti5G5RCi(mi2F_s{(A%687hi)j>j=Jc{Z z;?%**msPpB@rDAa_g5D#0q`_m;Cbn|o}T}24$re^&koc-*xQg{tXBX2y%^q0OP;fI zQ!JRqr{?DOO~xMDC}m-{ZhdQc$8gwKOKXv(rRD1a&4!POn+*YD$bn82F#}loa(t%M+u@o36)T&+6qiv?<=3am&<3HWf zYk@J*JT_gLvhi{bRJk<8hIe$;%ZmvhHU80~K#%#KEO?9ysqaHgoap^I9)DD+uIy9b zFrx<6dV2goH3a2jeF614xV)iC-n?1dmhZwsfpsj*%F23@mDP8-7J#oQ8G8f(nrZv? z?Uc9ECto&!GTZ(M*MX)C(JkkP^)hS@9^^tj$m!_m?v}g!%XQiEDxC%NxQ=)Mwt7R97!aJ`l$&_RCE--Efh*tMZ4}uLHKO%EC9xXR9^;TBieu;CtVdHwqJtP2?Ls=BWL@B)*4iBDjl z2!=#a35kphApHYy(!S8^l)lC--i*F)KRdtuq`ZR%@PNC%eqEDwAj7DT@EWQF?9K=6 z)U4&XC4tzVYinyc(HkgFwLia>;+2%$T)ETX%bVNGb2o3@Vlp>3A9ZnecMq7m4oC*h z&dSQ#$;?dwt~qp9EV{eN@#^Pkv|%pR1%S)9_4<9;1#^zfV--3$J6F#Cp1T(>CX}tI zp|KK8({ScsQC)DAKu^FDSu(|q+$Mf_J3G@Im(E`P@@b;QmS;ey|eR1^u3dfYqZ-8`t|ko zXXeI=8CaV}e${%+d*Q|H*uI@1+rEQ0I_Ow-3<`lMs>CLbc@4 zQF*cW*##4}az)M4r=_MBa#E=FnYN#^F8)c@N_g;~@&tkQT>}HJ-qw9+XrQB-a0vJk}_nPZchfEz`~n={vc0KxkC z^XIEquSy>3+|T))=Q4KVRP~+G*RNAb7u|=llH=6Bzc61p^qRm1X0)?PLhl9}*4P={ z&dij5d0o&CP3ohx_+m!a7w*q9s>hG>Y$-v4g3DdZ{O~vr^{w?I;T8*SkloUIyW`46QvzE z@ZQ6Ruh^~DpU9JNzH#OGmIoJ5++C8<4_Hx+(Y(vh6f*5QRIl;NGg6&jzDT}^d9XLU z8$f>d-o0MnKUl;Q6IG(hk3@k%CkN5ui+=VAQYC0p6F?^>-v{bkf6d6Bu8F7{p4D*j z314^o>X+(pCN5@M?C#*tyLRsMV$W(f&5+@2LWR2yHNzC8h4TJ$Q%XC^+rH>0Gawfe zrE>Wfzo4?6cTiAJ#iIMmmoMLhXMu(={-en_sI4pXWktn;!b{UH!Ie6{etq2*IWaxG z3$>aoLG?{K?HwI)d$sEHAhEn}YT5<3bI`yb$lsq84{WqqVq~nhcLC&;;bEJKs;a$h z$Bd+;q@Fx|+FgITHP3komOyy^FBEG+B_&p^a&jTh9@4-Spch82%XXmhn)~+cyET{V zK6jofD{ag)uj<5quCG6I4w|SpH~7nc{w7UXHZ)Z9ks0!_1?I!Dj?Lt($W;Wov<(!XibC^)QD*&vgZohyI{W&3@yJ{+T`EU$ zZf|b~_snT-i+>4yqMuo1+odTYu*li9ZrTULr)=N;INJjX5Ez0f(40mPuPG6~fB__u z@^A75SM5A^P7$nua1pY^QPa<=sX9Sz(b3^X0b^oeVHy36Rnmjj_2l_;djGqa3GDo) z{J94HmoHxq)ZJ$xx`$Q6>T5!qd1AJ@yd3`YtZR7qnq6C7*RP-7^zzTkK+f`RZf?Hl zOr)|i@9tg!GDgQh^W}|4OPc|ojc#2J(qxHUl8LuR1g8#h@1Q6CH(`AzI*6N_sj`Nh6pu zS8Hg}&$T_8JEW^CwPeW>eaK5kj~wCR)^T){zi{CKfn@}7JjW(uREJJNryC|F3~X>G z2ydXOre@zDxL8VR>aC(8)wi+RqTf_k2khpL%y{tNhkkHONctL`z>HHIeB})q>-?|< z$5`}=dRJNxY*kLi56{n`8d`!(g5T}Y}f30FxgJBM z%Ur+pZM;-+J0zs^)M<}4-t|V;y1UIF*qEW1<^bS}sJi(BckeJ8O-11glv)0vesXe> z3ux`pk0+9rgz@&Z-Cyu){f5z0Je}O(+@|FK^nq)f^=i@aW2m7aOx|K3#=wDu9?2t?)MGfg@>9O_vM6kp}f15jYn@?L{DQ=ll{aL*?hhi zwzUU7=W-q!1c+rI0%<(J$N8=7c^09MYpmaqBFFhpyFM!Aad-v{z zWMztKO?h5nVk!Ihak=Q_nUw_v1twNji_vA#WnjmMiHT7#Iv^74bmF`p3p82&_ANUv zFE4lm0gsdkq|jGy-)cZfmp7|mg`#-#(z35mUBI~_qN2J{?6p-#UpD@8*PqjlHXagE zvWd{MOFwph3OIhvR6bZqh0k@|8bpUxQ|;c1mgeAIfA(ws7($nAtrEOYsxIN`&4a4-d z$jTDoi`avxP!xIFGvHFErp7*Al*m2zl}AWOh}1y53a3(f{f+yNAG1MOq9`mtB~P<< zfwalpnespg9q0H4Q|1OTQ}nGzKcW-KqZ<>8E@Ijbyc{*gC!=U~F&v6=tkF8~=Y7#i zX+|ij^@qrdg5GfO*s&_CMLCB~^+?+S{a}e*H-xrpYBCcYZ)8Mf!|QYT=SOaagfNJU ziyP*h)3WN;^1bl+A7yy#W<>>^f5nP2Flv}9F9GOHEG$^}?yc5rI%Q|ap{%S-m6^o6 zd9$atzrX487ZVyuWl|-HTDOQ;h}vlWYi6QVMc(&k_Fq{# z!i6=i*6$wz`NXuGOH`Eein`eJVnOG^s9yq}dW;q!0vk>fhpn=*lE^b)e)1OY#RBG( zblaR=A*~olzE&(RVAr=T!D?R!0S+2eJUHmUhh)whBHLQ@-!gDX@x*|eV1cuOWnl-I z4K}2>0+yy`eb!sEW(|O`Uux=5^yp%$OZ*7->EPht#m}f%H^aidGheKf+jsc6X4wFo zDHA|7B3y!BN$tPuk47lAYE|+l=b%tkrn1{g`r?1D1voTxnWWQXuhu%fCsbWs9r0kn z)KGC3ii*bZMv6*m0R$0g6|NdSwi8tiw1QBRi&Mitb+x6`0P;1j@n1nr_b=?=>EJcc zx3XFbuefGw;=SIQ$%`8^pBENxgWH;GedN#~9u!E_n3jhZCAcLc)6>!_!G(MGD7=*$ zOE}G$Bcbuyu=uht3ObyuWl9P0p7HTwCr_O!1)c_&hcm`4y_Ac~b9{W9S^NyuMb*B3 zy+~72lNd^}hB*|amu)8uVCvP|d-B{^yD(Avva$gD*&e5*f9UN>83WD~ItZ*)AV=?OFw{ z`sUrcY}f|Ft+`9_774z*8xzAop{RPn)gl6^y?t96|m~4q{jp6Lq^p z?}1SI2L^`bjP<>ZCeR!1H4U=4ABS++E>U-hXV(F6g{P*b0II#Svz2%3*dYg_oU)%U z*icg(l34M9UGmJGrqqB39|Hk^PV&Hg5E;?f-zzUeR9t?wu6a^iguEy%(|WEv>B&V+C+? zL(~qscI_H$u0W6&3y>V1xf$#{9Z)++jG&!nRbhAU?t_CRNlWk8 zkx@}Zuxu;1aEtQ)Xl-wQV9}yQbb9aT=zd5UL`Mbbybn|RJ)WTC)EOXAMVC=S8f_Mi z`EF2FAl!X)`hi%LmB0~1MWrRcbw7l+x<*<$wQi*01^E4;g9qcGE<(@*n%b?Q;X@QY z^tlC|SUIaVZ;pgGwtCenKYxE-8GSl61H?X*chT3@#*O|;DYaYyY(=ke|TD5BO~nUGn;gG?P5W%rabYw&1c5DVD4Dx zZcWIe|Fnj3!U5itX}TRAvToOnVA`r`b4dnsn7P@yu7}6ErBwh#AVKEig6)Qa?Hj6`--B3 zx18(by?Xhmkx{H66YCXqPr&9*n6Isu0O}zOas?%Z9O3Y6mY5kFw6dE_UIzi%%=t@i zZ%J$G-Afq-1wzp2-r6OP<}!Kn&E|1$hZ=bB$dP43!3A`tmOR@5s2UsVerU(I_?kwY zfkXnVTG%iG=<1W1>6kio&%UF`b)ws+!Ztx7W9#|h5-7E~58V0tv@LE|BtyaQ1ER}2 z_mxpS;-Ouc_aXxFVX$<IDS`S>4E5$8>_vZ?Ity#Qv!_0y76%-A|@-`b$HTl=@QAR83ZpU z(c8Y~0vODNc3*nUq(mg>+E{Mfu?(ZOs5Vpn6n#mV3S2oMWJEZmh@kWQx#G!_CrwH` z87OZrIn}sety@y1ZEYvg^La!>M2M*f5J0i6x|Wxp?}bpqyStkKwzjLQQ-ljrWel1K zLOgx?^oc{)4vKwO5d>cGl`F3VB^E%h{`LF!1Y!;R0s`1q0n(Rdzgx;m=tE}1M-!>R zr2sNepGc&VZ+`w(s0q2tR@BC+Rlx{yM9SiH_N`mDyui7bC}?IOw{Deh%UkFjd=WCq zHHfpfs=q%@NT@gQ4)Mpc!tQ)x-6Z=rAe5Wsnf<4L_`dtBt)@Kp9tx{Lhw1F^X910Z zY#_qS%naztO?W5lImbEeD8)rsAGhWNL!nY2pb(4~QC3ny!L~uN#uqLw2ndwrMcAC1 zHgCQM28aH$6ZSdjazH@j*3q(7(rAoOc~JSUqD%O4igI8#5T_GAcT*JwoZEEq`)b1z zCvu;n_`QUHWNK*{fGykusc!iE#p%)OuxZL0 z8+ozT;jkGL?mCZs+Zs~_zDwdgM8gGKX*TiZ`d?~M!$Y0csqEkXdNAF;|LnUIAQ&!V zz)a&=(r>Q?IoKCA{aJ`18af7n!NHtcTt-_ve_fr{g6f3Nyn^o0)Ogy}b(4tN<#kOx zX1*7qRghdGA|k>L5_ZRq9`!+Y+Ov1>O3>e(84sK zz@vGQNC>Le$xqMK=668r>1~C~J7+hPiaWRO;olktQcJN~sBO{|j zho1pcFTz&=Vpb8?P+i0_AOzhr0OmfF9uk~U2)De|-`td8y#D+!G>DnLXnX1j{mnjU zWE?}HnysObteX&lz!lTlYN#MDe-G~_AOoPA#v`R>bED75LsByKyrbhi!3ed zqRO3vjF!2e%9&`*&tJUAy?95)KocATnh$KrXQ$sLz$$yKatCG(qdJNgPqxcoLxAe+ zfcVAP?`w|g>eiQBVfy;4R#iN~cd2;Q%a?$fw`!)M&kn?1L2Wq1o-xmH-AaIg4WhY-rfsp?ry%d z_p1WDGYKiFtXDCys9N^`T=17(g6%ls7f&}GKW2X8H=27X>PaSQ0|?1eJf2i@5^MQC z`9sOuV{Jw5Tk)N8?z8944ZLRnuhlqp>On;wL^hHp#IAH01Nkq!cI<68&ww-lV?z!u4O}pOPgmNhy3F;*pDqC0lWE!2_xqz2Q#zyx zk}E)^K{NcTVYMDg`+^!xERp}F9SU)C8zv)>F~F6qb2I=42r^a?@U<*}+)5Pd9K=Fo zjf<`|G#m*CDMRL%I$aE_TTf-%s!}X+PW&0-AD~0jr z%J*)YlH7X-zT;w)yw*$3OV3I$eSfJMt zVG0Z4DoRCo>(d9=+vTwCa&vPxo$X~sv?mbFh3H%Gmk2e!eO};RqyK(0{v<~jz;&s| z*2{i_1Xsz}ihuo$|RZsC;(r)X9@2|IKXF zBWzy4a6)&`MCZ7N2Zz01QBhIS(y{_OslO#;8M`#KNYA>*kNXS z$0<)Zy{LXH@s4#eFrA5vM&uqlyBjb1>+o?g9udwJix82GI$qC7lAC2|`tWg*-O z{g8oLZ(LLXrGh{WJp%)CRR4cG;yhFE1-gTS9NCn_3x-+pRCNzkwxmP3!;J|XY15`n zCiwLqcNQ>uGquW|$TNY>a8_eg0LZ-JmnV#AAeDN!QSh$0%&=5(w1+bZa!|7`^MgOg3 z6^@XUk&3Gv@;7(@9N1=9i860G z4IrVVMIRSMgSrrehW#iD1BZ&}14nYrw%%cO^&dn{n`K>ifS`J40aE)S z)JfbUe7$ifykHsQqPzYlcdhz}?YRq;J`q*{jTW`x3nMQyBZ9?DBsrv>iK>I0aA|6oLCo-3?Wa$X`A07yHw<07 z?A<#KPdV{Si|cB5;pi7MH8oKP+h}3^b~_=>^8$(bBqY#aZ#s5{>eiq@a?kQb1n!a1yaembLWWK6(YWikxTY{8r%guyfRcX=(9T@BH$^Ll(pO3 zNH*mOOKxAJ!b0#h%Coc61h%Gcbmu34gPa@)5&t4Zxx5z^dX|)^BV%lTdGe=Q=5F$u z$Wq2l8N2_uZTREk?Wm|ggb{WSJ6H}ZG55{JRaYOT#7Td-!L22zWg8XDpuAne|^uL3=txS^zM{GR=R zXo3b*CYNCmCgU8HXZl@N%9E6B>~8eSfWv>O$lvV5~S-9Wdc z|BYNd4B^b;>O7;WdR06K`!_HT1P#}Ypn|kkd~2+Sv0C6dv7^Yw&g?Xl)RO*h@|N`y$m&&ZPad8NN+Y@;joRraG(~6gfDL|7kl=uRQ&^0y|jNVy}m?Rp$;U}bW z#8<6iQ6JLCCUz|ntPj)E39lI*9?sdmFs_zBar6lWim31~;!E3vYhJ%Dg=E6O8lL~^ z_3JK?4{vCJ5|93IJj%9}Eu;wA9cpAJRzCP3mUM66ex9!g72Ocpd=-zap|LTL{c4oc zjp*521+cN2q4&cKO{qExo^p#T5VM(|pSS2J+Q!Dl_5=ZGn@>*{dNH$iPem(Q@?Z_E zn$DJjR5aXCEDEsebL9#HjYcCP9{|+A;2>?ohNVEg2$}4FA4W7glr6&?hb#HtJ{(lM zhIfQthf>WBfgS!k(MTX^`yqgVpW|sG1{8o-0k7q@^yd|IG6=fwfQSLkbB#zU$gj*m zxuPh@oFs+`0>*&*Z7p&agf46N2?)a+2!TujASVo{)!1oXmq!GBXnT5yr)ltfTn;q^ zjy&wp>TCNSNyEJ%!!#)1K>p%)7Upg4&p}loW=sJ`!JjzG^^QGA)2Y+Vx~62l;(d@Y z3OhSlI05?4?XU+xEpkgYv;5J;6#yZyC@3hbIME1y7~%z2e(J|4c)4{++JcDVKi_Sp z;cK~wQ&g1>x6Bc3G2pXtl~DSfqIp%wnd%tfC@BsL1A+ zL_j;@{byv@?{z+$a5Pod^lj9}nc-)(oui{S9D81NVUVFDa>E(@7bp7K5W)_Gr=S(H zRo0TDNzkAr84Vk`LDof!EGJ5N#cBeJAnw`a22E=_NqsKTUg|918?ygUx20uGO%3K1 zI;^~8;+=WKl9Q5XYu2P_424NRI3Yj|6FEdbMVRI)dsYPR4^3u6GRpzNPgG@i7ukCR zRaI3Z&|snV!pJDrwd^_J1f32TXSchsitCe4w%*>}yVE=d-rtjPSSHi&e3#SLQahCA zz!{J-JVM+~2wIkRZtiB>ADI(?=G2A6G%GuMB|6JE z6lVr%w7sxeQfA|Z4Is1rt;ReaGhHkQ1()I*3NQZHp|8J!>b!M8l|)sFeogLW}fViS8REXUce@$Ssm&M9JLA9-BY# zBtu}}AFIU*dsSKKgWU?zxAF0DMT9{jt7y^;Pyg>|sScgK;K#`4a6lO%9g{>T1YbJ+ zIkqgCMfacp!nY`w2zsJqeH|J)eCSYU&HRI;q)_B9e#5;&G&D4H2b9I{GZW_Eo{6gP zD7d+`<5XjSZl#~?2Nw#fNKSLHkAy*L=?I=^Sk{T!l=$Gmc4*EpRY<6TES0dZ1<+QJ z9&jpE3~kIzd-SM`a4e8D*_ky+)M2w4UcLvvu)L)uD(H?~;C}@lHT+2Mk#otC^2f)Y z<$RTd3T3t^e5j?^LoGZ`=fDBZ{rmSDw#52^ftvQd3X$8efr(;Up~#9pidfpi>;|Fo z=f28Heq?6AQU#s;iaG_^lGu={sv?Y6Jfk!6kcT1Y8Uz&UjS2S`1i~HQEQ6SWipYU= zA(`mdV7Ix>%x!ILXlQkh>7@x(e$J~tG-)q9H$6(?qyohJ#V2?nYjyr2S6R>1}79q!dcxRv;D9s07fc9R_=YK`7XRT z$Pdd9@g}J`gBNXmi#a*_dG$6bEAN6gK#4(8B;x9)kH*QMb}6~}@8Z;eL}z+7PWzkk zA4ho252J$JgCA1~iGi*ysmX}-FNDgw)5hj;bBr{Ck-v}(avkqvm|hDvR(DyZ#hQ$~ zrGwuf>&1Cpy-Kd*u9}Ak{FriV1XcWC*U82f@XNx~B7(j?4|QACOMM!Q8Y_#7M^x1&;$zJo_a0}F&_k1R>D zp60jgPh{RrYu?@|u?9u;6GlGT6(A!K9uf>P& zMb}364f%9_=c1e1`}UcD7J@7=P~dizlBb!ynM5(80~my10dcH^zwtXjCI@FQJ47%7 z1y2gAy72@3ewng`ZCM3PEcfJ_gg>kF4le(er}+QNP&1}$RM0)Jx)Dye5+2S6;`JWW zNP5SQ2gsxn6BgeOmGvIJBFCYNkurVy5iu^Y&6@=vh*QUKY`rt(r{xiBw+KVL?e7eK!R7YUor|N8aYpAPt5Xex+u)kg`zhMTFEX|@nUHvU+k)lQEDl78xo?~&TNH5z%_HDY3(K!WO!p3Oenx8-S| zbW3ot`uh*y0~6EJ_XGbX!`B4wO#+;x(EwqD5LF%@&Lb@t9RNhvGBAh+fSvf2Z1eePSI zHlvts20Ua*2?;Ll5XfIX-rfgoZDo*VyoRc^lZ2F-68$NFbQE+dp00%Z&-M7IiTxmSy^8^ z*ot|y#=tg>P$`rSH`TbU9GICzF^OD~#QT5b@Yl-oU4LvLY`G%v3AX@zMXHNuGf|B1 zyBTdf`HIUG|B z;n2WP?joRV*$vJp(DH6G4v3Q}J{tQQTRap-bvZd|0bN4p(jRmGH?0*t=iuN__+uGL zBAJtZ^=davXnffs&q@-IPO_+7__|}0ZilJ>%GI9_6;qCc~1A>K?>qa=CslE zCn=ZgFbSEXQE=+Q3!(Ai*J%)3a?XBPj4{ObFivs@Q}>=LaQ=L=-}TBLjlDAZ&;2hQ zh_zUQet!3^P-gBLG?4Lc->grLMNSKFYsCm2!FYkTV)*&rVaLof{)^?pL%4i>8xJ2g zKV0*G&mf)A%bq&}gF;u>(^lm6^DOXdLfsFAKO&Qc;&h@ARPWW+PSdI`AOpBWZ9}D` zOdDztw<59t8PtU)0D3~)HS9!3L_#8mEEznB?L&F_JN%w?Mn<;;gfufVb7r!7J!0vr zb!AmmV+FZ@)B=SMxBZ#9{+~W$g35Y&#oI4Dx0jzd3B^xB>B-GRyXQB6(J0gBHy-NHxCc(SPU)U%Bi-Vx7F1> zqxxF2Ds-l;KmhBGKlK)DZIT>v`qk;hIZk3!k22VZbKNr^Q#9!O_(5~SkiE5l+GUlO z!J>bX@>d>h%Po?rgm6TJ=821u9-JhX_#Z~4?4hKrEM8dh=rNsAr-?8CBMoZF)%^T? zLocFcF5~6xhUY+eFVzI5f@v;y=A95SiHOU2=0E#3P$!P~DGhQj9_s=z!vn)0@07R8 zJ&Z(Ge;fl*hM^!EI*FJ8nHonIz&Qj&rB5G*%#&+D#y2rxV*+urbpkGa)TNX9;baH) z20YhjgNj%`Rv1$NMV~*T|yDf z>`9xuK&AwdBWlg^O?Uu&>j3-*!QAOLucM30E=)d6U!OvekJ#e8wh1OS(t~YLF_uQl z9vo|ep$QDl07DZ(ygG<0WV+_3rj`1P)8lmQ)3L$X3yK>2M+t0ihZYqbOkh66=4m=>E81EtA5YrT*as|4@0*cU5 zkb;83LLwNTCqOrMa*6wgR%86p7hxPitAn0?D!inu`sbGunJ-LABDAKg_w}tIVXxKt zXTaYOWMm>^9-x!2-PY+Smtp*w88K`_Z*2%2R99yb9we$H$&bmM?cJUGZU|8?In2%i zXx#?_Bi3J`I}+`gXTR)0T(uL!U^8k{?^M$Jp8xKNI~=$!<@w#IFNrq}MkO4|QVe}~ z&u4o?W<`92nVDQ;%{bf3Ewy@n6A^pl!!nnxJt$RoL?9fW!^&-tVvQS{adPE@~Dzs`YB?-_3?xR_n@$sS;ozFjC9se37L$>F~l)_#{V# zJ+6 zryV)?+hWpoI|N}wz+0Zz_%?8EdTa8W&%UyA_Gf<_#(Y_@+SVBrv!N3gUg?Ns*{F1gV@<^i9JYUP}hQ2VFx$L0E`LMHIfixv8E}6^AsK zWBJO-%U=OlfPy%IlU@u9T)ENrNFIa?2F5GBe+JkRuC#jf?sUJGU?pbo--%y{P>E)+ z$Xj9hqa~Z#M0(0h9G;Y1Vq^AN`Oa8!-16|1#Hm$q<*Mx=0V>4Ow+_M(^KoL?7W|3gztzCgZZZIXpqVO^MQ8ByU2;fIP zzP>!%*tpyz7`AWUwVEjzRBfn={{Fiqcy!?IyJKjBE+OKOmsaI7F`X!R<-liq+eotf zZ1=;FC5}|QZv7xYF7aqFzd{HI1|^C6g((+2ToN3m;WI-l_Efuq)TC z+qbUs37$PDgu(EQu;t^Mp|_&u_Gg9T@DM|@&OQV_oF)XoBB1G2`HY14;u#~+N`|1J zotV82mE`$Ql;UXm>zS+dr5t`dxjHaGH!`_@^(rILiQ(eFVd|Vp9R)svzP%IBA6NkB zye#II?JFoCm@lZ{c-yd0DE)&T_8-RhpD0Q!bW2CQX2QOZXJ+H4;9-y~AuZ(L>!;Yl ztOpJpkR3r3STZTC7Use@25-BK|IG5iyg*l6VkAMFj_BWdj%GsWfr(YJGo^b<}t#D$C0GqEH zkynxIsKlfW8AivXmGT9ialp=IR93KETGo#H7=Fi>bV8|ZJ$mR6EnMGEVvq&5qNWx% zcL^yhGCF}Yox_j8qrf9d#{s?NQM+;Qi#Nukd%)=jI*N;1NAQv=Q20r*6wK(X4iD~=hv`=C{4w>?(c zF2VC+@Q9g_kqG9Qq6?1k-MUt4QXmZP*VNv=c3})c`+iADr|*xsK{!GT{;J2HxehZP zJ(^3<%Q2z3lH?~y4}_80w$D(EP&~wzE#?*yS~ul`hf)qkXkux( z2;35b8evOHHaia>luX18$mC|`9MXL| zF~@?B#Sup|-mh+uipf9>Sz$Qi1d2NKBGtQC`ZtX3G;!RR53})0|p_=5;TG~@g0v@{HnV$h=d*y zWx;3=lr?6^SNCeNumw#(?|>GpzYAw9@pOYpJ1{h4j)8eHG<$hTV}@}s>@LErpb}PL z(P8Y02{o$}Cp+QRy53!5B9~sH8I;um@`-doqn#bM&QuVqYt2nd4W3bK7KsXuDt*rEn*g{P}VSG z1TY5Hiu@{90G)=z1|&Cc*;0?s3ivCsB4YP9`btYc6o=$hiFmQfY=r{e;N;X)5-#TA z@7ay)D-`{4vba-qNDmkgT*<|XlPp-M@u{gk?*|xOb)5fo0X-k`Dd&m2bETm9xvui~KVaK^ z6>$Nq3*T_KNb^aL?w%e3rm*&)mn{5{q}?;Bp{ZF`Rplpm3o!FaRZkZVZ9&xg zDpWM|c|=$|AuX6fvLkC6f()WyZq$nqD>Z~CDqg}eoPvNB z5)&iSw+bWdB=MWQ>M`L8g?US5z{^o$mPsE20>r{-W85#5=L9~iyTdSkF-27s$kczj>fQ7A#l#Z8u zd+K`lo4s`;>>xCh$*ky=AzMu6l;7s7%3hn&h~1pPu`vGp!uu(yP>pQsYh_qvj%c`;1}3A(P_%q^OYG3pWNyDSwvEL5;W^=qs0G-{3>2g+ z%%_wirAJPtg9KoRk%_<4%lj{G#{dc>_kJaSy)KV8(6g8N|T=n6U80@f^@%CI&xB2ROQ)42g)C39ipR`OCQrr#^tA+zJOW%bt|B zoDb^{y;GdlXABf|`BjwopmCb&gXZzDeZo)`$Bskv3Nr#M9U%vUEz=fMnoF`pGy&j z0=iy;@iY=hM#`{ND}sz(Y}+Qxc!feu&$;kT3TMz5v`%ldZtMj5BD)B)mz`r{wI9FW zagUEXAZJ|$6BOZEq>I={U>g?fW4%m9a!ez}ilBLJ5+A~YnHkCM!0|Nxa+o+_9s@)-vud19Ms4{^xv)@&%`l zkB*Ab9vkLPzRe1p(2Z2GT>;s!GGSfzaxy7}M<<8OtkU}EQVVHhYP&i+J%K@`#$1M* zxnap8KH`)3^RP(bmowkidrgcU($`-M1tq|0p|ca+J%UvHpueTV<3Q#rT4PyFoo`*4K2-ve1SU59~c4{KiSYs-vS=f6|nmH4xN;1-;QK$beeRlZ1+b1=)X7i$4|iUU;jR`FQ4BK zMF?&~*F4{1pSvn=qb1g@dmLghl)oQI5ezC+m{{3r01pC_p(BpN*~2{LX?x1%6?*hI z5F+L3^xI-FKs2$1>B7hkL#+yir zQvf;YD5rqhc=r_05s43vI&MSRKv+FKDajW;j6a=5siUr-i(sgq5iAP$$1yn~=|J2K zjQ^J+(*c=)Yq1YfI|~k4Hy}$;j-fg@24*^gf@gv05l1hrujj!}kh=7*nX+qs!a!#3 zK+=g)_e>Ou6FD>i!*yhc5HhL++q+NL#`$cKSWl;MMbp2@~TiH|zLL6MRFyWP7ElY_BT zRgKc03U+_}x(GQuq!ifH)3Pg(8H5AmgOD|VjlmIFuR1A+bvGq2f2w8dHsMn-N2jB_ zBJ8j^vx%rjQOJW#7sFjA01G$+8RJk)bV298=I;-G2@PKJd++O|IGkzE9vZ&spYxV9 zcI~=_cZjqiIg}~o(W67434m5oQiq^54?x?a(=p1XL7WF#0*(!+Z)ixwPnE5lpu91} z;}98~fCOD!3m;1k8=%o3+S4#N1B(U6|3pSdAO0KQ1DvYE=?JjXKRrFAXwxh=3pfkh z2d2?GJdB|yG#g1Y?X|M9QZzFBjnK~RhRnwuS$M-bkc1#LhX4U$J_Khs`E!e}R#Xi0 z2Sy3p4Fd*Jh`;}8Ik}ri-{(vasn-%`Qqt+mxVg9Ejp1084K&(fc6LcBEG9-9dfwkz zslVRPy?fh%+F-wjgltE_#Q@&6NL!cl=aT?Ksz1U9U$SEJSqbIy7`CLr&A5m&8M(RN z#;L_&ZUd)R0VpLRJAkQtLw!h4G#WC8E77jLA) zbpbz{*01#z1vQ%!RAuzL0&m=4j;m#ftKEeck6SA3{|0a=(ML)(i30*;!`=74w55B( zmBdf+fGG;v0j3(e-mFlz6GCl6{l5y(L)2riwZ8`%@nbn48v>Rk0wbJ+wx|~ew4O5B zG-_-egQpDL45D4tZ)3h~L^#KoG|7ArrxC$zEpc1|9k`f7R1Bg(b zets+nl2a6dkT^ha`BI-dFQKsz^oUcYz7Kv363hS^FozCJSyd*E3=fZ^6w1b-v7)h1 z4R6K?Fi}s7c7f0YV8ucK#3aAIxbz=b{#7|DGSU=ZOXeI?+a{+l&4W?Oa6ybCtR``G zs16IMf6bkea2TvmZ0SwhW1z)n-S@*8gIfa@PL+KA9KCey8M*mU#qV-d2|SC69a_Z5 z07GLqnBRgK&4uy0nl*^6A>hETaFUgj+?(>aFIN~0c*n??Ujd9TMO}r2#7vQ4Pe909 zpNeL`{6B>Kd0fx=+y0Ng?EBcVkG)9QvyYvkEG=4;?6PF+Ye{8y zLYs&Rl~j{dwo3KApUmg;zTUsNKDXa>d;c-l4E1_FpO4469LI4UCxZSZ=)gy9{k!Ar z)8ku!?^Aw^I95WbAbwTAr$c~(*Jin=UZb%P96~V|x=Nx82Tc^v*Id$3@K8g2FATo0 z>?#SkrP;Fe72m&$UL9CQ+WTI;f4b2bxnKXdubTo0{lVAb)Ry6EaobWCntAO#TY3W*M!>@%i|!~$Xdw|5m(p0z1KigFQM`C^qm7s`tn1LLvG{QmQujxy+)~$4la%x`Ixvu41jqxf)C3lapR_Ug~rGdPkZ` z8Lj%}u6E)3RiNCXm%PxGEgLg#+&DtyoUrrh&yzpxTnNn$R@m9US(7GriGtEwZpN+# z4n};L?H^XxefFVMqur(3dhsr4j2kF;hQjCn19hGq|9Qk7iim6H6980rERUW(-Nz}P zdxOl;8_^o{#Rv4_fQs|Np9XQr#e^ArphrY#_nn_x%cQf<2%n7*N>_?>w6*WTSi~&Y zgou&O2^dEuENn=};yrcsx(ta33g0|_)Bz9>ImjI;#RS4f3H>mOzPMTSbB zJ%7FzAZco^*0iXR&+4J&5x9mntffL`Nf9B;OWj*3boD=@Nqiy&P}SNwS0QOBzIIa= zDDDvHL?c6vfe{W;?&jr@YK~=+u*bXO{KT0tEXO1Tnp<43}3cqa?cxEi=DX0 zi$rA%{7%;{mo}>5nekH{P^OHq;*tB(CQl5VC*! zno75Z+QZCSH#$Ck_>Z{0r+rY2ZvXmsr&AN`4)NueK5%TEIDYZp)L~Ruh(~oYqn_rM zM@H}X{GsQy6+Yvsb#bF;y+e2>=IQ?SJ(#roXE)SUG2Jk@BsI|OaodGdoNGQGCraaa z)0C#{W9q3WBqu!(P11Xy_pt{w6J-ui-1mx#w>ZTJ-p_L*lO3Yin|X3fJ76U-d=?KC z3K$Bkz zo=zq)3Wml|KR24sd>1kN@+wTiT6OO1B*tREf{BH%fSvT|PpDyqqM|5yr3={e7eiN* zRFx(JSm3oMLNcO|Jx4>{CDhj*Kt@jRn|JT-O`bK_tOaqv_*s`^bYPHGQnP=^yg5<| zU0|~N4*l%p(v3vb>JATUfHup1k~PM?hG`wSJ`km@;6O}!3>Xj^SH&reB>`TvtF>+3X=r@~ zCV;#7ijMQq$?ipUj<9NU@5d0>93e?QYqM`VQ%er%od6XA;rSQU@#BhgwB_79nXmk2 zMibv{oV5e&K3=Vz(QZ77kH5zd<$3^8xuP&C_YmJX+Eo`Vl>S%Y!ylvQz<8o3sI%CQ z{W3I?c~a?zNuAAz0-}^=ghY$#b&0O%6N_?!>Soemny+owByav<&Sx#k1=6sH^t&n$t&)?G zU4F;tRGb@;${;*hMAqFHknN-PyA~AO}c?@a^`%hHl=v@BPlGc$P46+NOjscKp?&+AvX0N7+{2 zh}*$yoXhL(vbJ^3g~|8Zg`vb-3@0IvmU-grze`qPqChVtUd0Hd)>m}7p;UDLefIMs z=so()IroMab7Cg%kn$1uApq&@-!uLB)oSK5j31OO~gr`O=Y ztpK)}MR`CH%-)*Pu~zTs-540YHo_KtdVAk{z`Yv&F0En@9CpN*0?smX_5hokQAO%s zX$9{9!pOH5>WBM~d+#ghzVq_+PzZbLQ%Q?LMfNVxt8_#lOiVu;X1KF7ro)RUD~;PV zm8<2Qt-Bbp?$oxOF{hs9=b(vH+-VT9d~jC#;>)XUU%c1~1NYapbgA&+#rhtGMAlKJ zjZCFf+SlDy(PQ8#YhZa^9s0V+%#6_tgTl95oma6XwYv-E*o*1LLI-YwNO+ySu4pIq z*)ZzR?CrM>Mo*9{2HUjo?Afz|q{&nX_y3s;3*EfAl;-0)wHfKOrnuJ&VO8JOLMy9SE`NA<28#Mk{ z*2dthapJ<(t=m9-Fa0(p@l}r(Jvx9UTMz=~6nsX!z6-#0}$~W7C{Do6kv_PSOZ*oW7Xp2e-T{m@A=x*)`J zeCgvw;o|Er2IxY4k&NG<)D{zq>{Uyp+Q4ROX!NU4hWsZlG5lV6YWI6F76)ZQVIwoy zyt30fzjl%sjUzT#J$%{Tw&Cl7Z2^B}gdwHG`Ou-YMpn%m63(Z$0Tw+gHhu4Q_UZ*= zfNt}|i`9&_j>eB*e^qvJvMU8uAVHfFFb>VWOk)2W!KQoZEnV;blPC%R9i)*EUl>P6 zNR>cXvd@SVdiA2ElPx5u^_MU2BTm%-V_hOf)4YQh7vS9j+r=1`3@Y+>TDLwzU73EK ziMggtn)K}Dhk3Es!i0qM{{?~ot0Y61Px^^F$e04{I3e%Y(W81(r#hsT1_w{k)pbcu zPDZXOGvVNIy?Wh1h9`Io9dzr~p=J?IB+>njs(7@7JfVc*Px~RsI+im83bhh1;r)(} zkP`vCAyAMp^*Gi#Z2kDU-<3@Aes7SKkG1ckp31lMmRa8|0^|V%d|{ zUsfeGHG!jqI^lmff-}e^GlVE5hdd=SJ-fAI8wp}DVU?>0FT(>x#l3%A{YOdwnxq;8u7Z*So#7F}h7)q;|cwS5_PI2G2Z<^a0?VsKKn-RCI zckD>m;!4RN?A(cqMLfD^XQs8B?ceR^J{@9IGl?RqmKf)WVW)(&gYfm zl(By83gk=T@ry=9Vfm$?aLG}QDYK=AingH)!ab`oJv>oj5fYpMmg>7pP0su7tE1?U zmU-{qUvBk+X(9lSXuxEykK_*DzTSj`5@{8IcQmsrg461$Iz&fDn^&Iw4=ADXq&sr> z$v6~>jU_do*y}4S{bLJbyZmAMW0VYJ@EM7{GD#;RI!p=FRAtvLfwq1R)V{t>jTuHKIA_ZTlg7igrB)wSW26YV>h4`{7x zWMWcVtJ7uWceFX1>=;OpYKXt+FT`aW z0+~kJ!?c8&x3SMxpCk+%yl1vW?!(_8tWH*L6W6?O41KBS8>D9-Krj~E62+ZOdE!VJ zN)yp6fV2p1>hAJ6q9yL6@n1I4hoFbZoo&>xe*HVZ<`kpIG#WBeYERu$FCg>A5?1T@ z>OJxpjz3=e364WM-ua_Vd%qg5ssDqL+ze&?fX4l&`_u8`e4Y*Wj%=Cm8B`|6_674T z-mmB27M=B|mFu)|lrjf8nM^FU^{d=49}k51(05oqUCZb=H*%v2;}HkA0#Z>R7QKs@ zaoKyfZDR|KztYI5Ebo7{QH$*S|M02*fi*hZ%F4_tc;HI+nBt+C5PR z3%9@ciBl*}Ajid@4-!fyJ!tOf)=xLP2bPwjWkEgvRu+gLL+RU^4r&i_fwgO;U!rCP z;~6j~ep>tg02F6slhTz0DY4Nb+^+ig$IR2?yHYYjjKr`RgC%G7eab=47vmH-%I5oE zg4MOlcFcia@~DQuTS9P^Z%71;iI)-0U+BiMVXe++hR>KQq$g{)qBO0lX*KERX8lG2 zfdajcActD3KDo1Fmo8J3+w`QlhU>@bzyXN@^;;=jMm+^5U_GcspCTFjq0|+}B?X`3 zqWO&X|AU%M9Un@gxS0ECe*8wtL4f-2=m;YdzYg$6enV*q<_TUsNSs_z0Wt_P*>b#9 z?37=mt%#lLq^?z}26NxQ5aO{lbFdeYPiSiT@^4$%2pMpvH6RS19EzGArl|`;Po}Nj zJy=Uwvw@8f1Hb1|DT|dg9X2Ue`(WYIML)V8$y@y5%8HiMQ~SuR+*o#mOntX)Gc~K2 zd9vZ?n;AqKCH!@d6%G)r`fxV2y(C4JoV3P%ZsKvNB~>m)R5X#-M%%E~EI|e0g|?lv{Szkq>WHLCYj-zMMTSa>pi5qORU?Du`))(OwXhqt>D;X z7)aJ>SzJv7uM=F1HD8o+-f0&IivrkD=1qmBqu2-bkm(>IwxHmm5v6q$4ju~-;rAr; zFfh5BZfzprK|n@y27o~sA(fq)n<7MLTrNTcOBaaU1!fwxBQ!}UvLq&C{>}Cbp~&Qx zY!sRndhxteB!C;w91< z+^d-XfgJD2FAY0^IyVXKKoy5RN5`5U<+>SI?`$c_I!V-2d;XMED-|54P^-Apc$-nO z+Qs}8ssvs9NH7n?j{F&_qF$c2FJE>A3ID(y@EYBo=5F2J?!BfAH7x1p46mKx2F|i^ z#|3+{k+tAnA`XI25aSXG6KAE7w`*&5@EsN>`Dvb*u?9jyVNXO5hb=?^XaeLaj{os# z%CR+UuMw_8EZsrwhTT}mC8J89r)ofomRk$B{A*;FjZqDM`@JzDAA!=_jQfpI>PeI! z0`-gE1ByBX!CLe~XQs@mtxS(5qQu2~))+EG6dv{&9@VHw5Yu6X@RpMN^#c8W&e#ibv8?i|v81Z* zSkg!01S^+*nv0L#SpUBf2)o6<5Qyf-kR-K&ly%)+i}rbAgTpn!Vh=z;;H%kTsILt)sbFV>*>b~5VM|+YNTed%V)o1>Q#F0u}*0e-dxEC*#1`5H~ zz-z;2jGL8Y(E9mvz3Aux78H^2C#GE@0z4@osGIlO{`pG~v1ZYF8iA2b>u<}8Z$~^5 zq>76d8tSM0Q?1YgmLnE@WQPB#ZF?%K`G!arO4E_cnoKE8J@-JX!shl-$8wlqvD#4F zq0tidg-9j?fg~TEl6eLh$QL{gU7c{~aK41Yh9V83&zVNF14A3tq@zN{{fPsjFx|0Z zhs@C`4xc>Pf^hTusPziWg#;4<5>Q#YbzRWMG0OWd>PR$&K1E{ZfP=s7kJ4!}984Ih zqmThKKsPCbfiTe#*Ht)Isvn@~5Td5})auF~WJ@vgLAV1BQ3oz=;Pg=Co-g<5#W9K7JqCfD*jLiWT|BR)Jamwh_;Rukhp^pPmq% zn33{+U9$y*+a$pYi}_lZz{$tq2Qs#lb}ZN!Lz9s$y58h26r z9Vt5w_&00WQs8s&!rfea264%l6PI^KA5n@y>svAv%TEp&-rY#>zCA2&@ydQkd0V;l zTdfPA)VViXpbp!j*-+gFlXG zZ44O?ys7zT1Kl>5m~dn!iw8UIQ{eaqGE<&CyF=x!5J{L=NWFHO)fFZM-s}Ca-zm=z z0zposVeCI2S0Fa0?81$rjzTOQxJH}WXeP&Z$FZUBp>YJ_BB1*JHlHTi*&*>*I&FvnyLg|FU=={3$!?zAB&`R-CgW0v~(%L-ic zNi)n4?uA&5oBWZedtU7a z+1*96%X5_Iix>Mo{`rPI9WS=;(BXiG>4YU4sB4j0MXr3rhiCm&h`C=za)wY55H4Dk z3tPkn&Q1xb8Kqswwj8Z9Hq9I66z9Bu-;lcOQX^Rw)f%m+kbB^!GEXgA{kY;3MDyL& zJ^=cZRZff`++k`)#nS&F`fyh_VSd&gZX=u9K*|oO`kC@{T#C74J;90;|3IbZ`7Z#p-L(D z)&$?yo{~`&y)3Q`PD0(JH{+yc_8*k?>Z4cq(?vTe$EB@iT9qp)?r&hQUWN1PTJCn6 zK=dK19e&x~G^+Kg?pAxWyAVryFIUJeTuf^X%0E^7(9&XSjQ*9J^N)h&xi$_SR(Qa? zUPMws5scClT3ej>mVQ)IRh7p$FKulvVW_0Q^bC7DDs5I9s$YZbL5Qt}4+9DQ=NW&J>Rgpj5Qq zjzE%Y2X+UM;w`^eb{m^aiS6_&@@F8Mp7?uQ)ybyKp=;eRIh!UG`y+!hMx(5f&%pvv zTbNgZZi?9e(@?yI*CIuw61i#zFg4v=G&7IIX>i23zI_!`S+`9E;sWF3!Na!X4}5! zG#?$ksSgKZKtyy4DU+!nK9Mu(1Z0kUUs#y2a!&$-#NrzRv2LHSyCJYWjC9b8DkFp) zpWmfZsXNnK!E&jP;ddU)YpYJBmBC-`zv#>O~H?`gS*3^Nyf4Z%Yy5jh8!_mew^#Oq~=G3=tO`AWvmZ9&#?+25$V2U3_+yd(noXF z>jr#@g)Ml8?nrP>uN6$I3WkGxNq^3qdYt@!bj*pJ2d~NADiP#w`yrBE+cyf`YcN2@7Jp6B>U*(2H zr{)j6W64tdcvL`B8Qr~BJ2fk<_J+r4D$hyS+)XUj*-A@)JcMn5Ehr`tVmuV@074UU zC9U`%(%Xn|Chy2u{g;P%!e<~j$y+!){aZ&f*R4Y4{ukfhD}KnpH<0N0v!iFs^Pj+U zBo9<<$YqgkuOp80d{;Y;T~##UgHAAYw#S;}k*mTzzMb#MJGIXx%85`MiJiFOkP{y? z|J>mJXaU|YxKKW@8g|B@XytWEE}>MC+qG}6g^0Alkc>l|xsN5pn7R{rtJVhw&?(3f z=}Cx*2Sh8YM6aa$#Cy$_IE`9vKIC71=Uca_3Cq5H>pNh;fM5G5c|xMitcHeQAd{FV zDp9Nkd-WPRV#GNaodNErbj@IvxpnKzXuH#B_*Q}yI~U6IGh0a+9BKzqqpWYD-;~qV76m#V^`=^RA|4;AUaHa?7 z4LhWzrm`xvMX2eOy^v6kol9v#u5UQvadly|tx~5>abF5}R()t^aewn=>Tcua&C0tb zK08Nr4EZ(zZ7P)y1P_ss!R*+)TV!Ro(^t0n%C)5I^oJWg;pixR-(_})kKeQfQI#I` z9kbn(IAV9n*q#qf+MXF2?C6kPY-emhXxBaeT{bB1?`q1$)3}~-n6rHZH*AX)E86N8 zH@cIRRWsn46Os)!%>74vx<%_?ILi8r)isHa9`)$vG7W&V!;W!0WhTYrAPH!sKA;-O z`Iy$pd}_odpp|wcMR77|(5O)gEKBFKIc8=$1bby7`q1IS{b?Os)XzYw@kIkT5)961 z0f4`DSq<>Y8d`4@m>(#l!>!7fqb5xy%@kq)12~n$Ln(lnH=hq-uP%R-W-1PtotQm~ z3%zX38bA@Ib9>RZXTXhDlLBO1j4Bj(aRM5#p2Xeb6YR!|w=yjC^l8)fvFt+|iFRL@ z5Nmb?@(qq4Ejf1lxGVi!*KyYFb?epBhIpfHSw%Qah1l*q!8Yn~I3@tTASdgKx#|As z0o{0-zyvP11x=+KTaz);bo!23|4!y$`NMD#>62jdGxde6TaTs8VTO7-b?LGxo!o{f zSw&@!h7uoc6_n2Fchf~>9T1>L;WYQwmWEy-sBoidEi5;FS^ZOM6S-vO5PLA8k8`(7 z0q|PS?nc4Im|!7mj9v#%k4$A_dTChGN2mh-ug=1(|EK}GO9#6B0x9-09^3Vg$uwF3 zt%rx%#qSRP@n=o-YPbKWD4efu{*gw973;OowqJX#+|!fcsd1&j~?p~F>{P>}7&Z=kC zPoBEq)q(d;=SFC*-ZPec0rxKaoYnX-XBFeE?%NB!Tip&B)N2ftC~3)Wexa4g%CMDc zza~4j?KAFT-XdlWO5n~-7UFt3WX%N*!6GnCg*_zKQot{)FZQ8xb(ris_u`d*ffAkf zJHk9Wp0t1UFC1cG=wlfw5U)ycJ~TC5T$UTRWax-5tH2?kHTHn>Nsa+4cAv3K7NTuu zLSP7L4Y5|^l)v*!JP-8LG=zE334%atCmF8dLf=PJMU_can_quSQTe}yEJkTNHEG+& z@#I0iw2*W4CSLud&XE7MRfk6Q=+*15W-CpZSOZbIu zv^ra1)*jfx^``le=?)l_zCrRMs{vqa2W?x>@Qg}$_A-WQm8l^t~O*_0fEan0B2<@ZH<`t&;l*A0kN1Px#~zaw@%c;5uIQOE@-0=3^9<5?m!);v|Clgm`$VJ9B&8J-h;}MyvhzChuqS>LaU3Meq?3Zga zFe=PRK4eG*7eyB?mq>k`Kg*<|P;hj`J;sge3X%yOd-!FeRdQ-_5|iEcP3oLj+OR(p z6dLX_h6|jLL&CpLRV@3x_qR%z2RB7Wkb8}QSqu~v0`M%3*2*VLs!f)kcz zc-z5S)lo39HIcl4%J{K=phkaD%aU8eZdX1Es^Wo9rdtyc8wk8(=o{_(XeIfW3VWI= zrj)~HO&wAMXtR%2<9snj49jQ>8&ME1DPV{~%p!yzR1D_mncucCooPPLpu*K*p_E7d zFvy2*PoAIMMcgI@JV8D)WpDFcSU7gbc!+wBPle+Q{#3ozGe&_#Q;DLTrr&Uxw(qe1 zeGy3s97tSTkNX~2CFM=H{wd%gu}x#RhT`RYc-LLEOG~nHtfOjUT_$9COjWiH-mEuu z-QwAKHXSFc9?!cNYP#mnW^KLi|9N1v;ohfvpS~D>-ZyKLtB7T*g|sC>y=^RWtW! zpu1C#{7`G+(`G{j>>E>xb3D@m=S*9XdD&29;tH!*>VcQn%ri4nD@lC(c=Pec>IOq~ z?J>eI9KFWq^}@9jT})J%2i+{I$uazWefZ^x=R6wNdMFpX)C)EqfXesrj6t^^0H=#Q zjAB4^@B7nlAZL@wcXAso436ywz?Sg4j{yi)&(w;up$m_D`qZRu^ZfVk)kfN=Ao71x zR5Syrow{)d!d!FHtD6f9n6Q}13QNWV81QVXq%;*bHdaf@<~+!%ln_%5*~vxp<9>0s z_R>45T%ZM5vSP(~jRFyPuzD?d>5d@1%6zN-DU+GLEjsAN`}ZThd7Qg)@#3>U1&ac` zkW~QpB+QyKzs?x-S6kz5hCyGbnT-9|y~qPavstLInU6y&oje--qFwRk#*uqk2~O#( zb>>P|b!^~v8#4-l_^}IP)S4QqX&WRmp)+UiNQ#Y(oJuap5S*socrO3}wwP%Gycn05 zmhE9k}Z|P_K!@OJ#yIL+Y zbF6xqk+G5S0-u0;=nikI`FBA%MVM1&!V2{Pi0lK(6$JovE*OG;GGOB+Hm9;@(cbTp zF_{!ZJfFvqbhVC@AH*9#S8x>5f_uR;v0D2P`l%SQbC=J;=ag^4_H_g)O?Vb+&$k`rc zyhwH45xpa8IYc=eyjiy)azdoFd_9~1{U~qa8-(W8c!nr4FQAdb-KqR;qwb%c{854c zJqDU>p_*qpZx&?3hf1Mw&y|@sBFY|!)lMfyYnXB&__;$sUA9b9^I2*0h^V+S<(#;m z+klGZZB5W|{ruf1b#nDZG)txtmLAC(G~)@dJzUYd6!k~S2N{nYF^suqqQ6f-yG&$y z3VbX$>(g)*QuA=asHAXg+JgRMH}ojvWZ#3P{Mi)K{2K3P@#DSDPBWg9ROp}lJZ!$Y z^_RjgXAkt$Hc-L6OPnxc(Ab&2XEm5fC|v9)NB;w30p7PW17!`COAH z{{?cj`|<<`)7HFI=If?$vzkr>Gvl|Q9>6@~Vyn|OW&2xAb_5|3uMW=)TM8_h%?>g& zE;v1aC_QZDGoR$uQ?(oFDSf%oALoeFu=!O(jB8KX`JEUYt*mW*qj68{b=MwCK&Rtw zoKqHd+USdFdiG`Oj%t>^VQNI~1y*_OkoMnUooUUAqZ&JzP}FxkRs%fxo}`|RDH~=Gsw7? z@N;hVNgbg{hYz=4Vnf{Ir12s+i0q9)g@7x?z@3mqi5%RjiLpABD}v*P`yDN;O;3)W zDKwiyE2HB}b?WkiS>b5*ekd{+gv+xa(g>G3KCBrVH}O3XCdSgFUKoOb1VXMNY^3+6jJ#AIEjGf|Q zFCfcBQF}CF9S(D}ZIqNgpFPlLT@bpXuAWo&iscE&wCuet{q$*j za*XS#rI+uiXuB$pb3Y#ub4!i6OOJlm$^{#?_b*@1zvh3{ZbljRAZ|h*c=P{P_C+li zlx)6>f5yjTpyp_gUCP?YR|YVP%_s^7-K1diZ!OgsJmuaNK2}%QRB$1TJW+OOnYL?%icw;rm^Q-Jc1`r{9i zz6mNW z7num20eMDH4E_yd{~+>m-=vi*(}LPbT}N~2;c0)m zP<2CF-<7T=G6RKIT|`6-VlE)CR$aR$vNuJ9KvWwIo!<3hRA8ZLdUp20f<2M=_~J_G z!~L0<^dMN|n6SRg;VJ~80YvX!&=JeKPgqGAoS)s5sS9d+EDwF+^Ji7AaBVkG+x2Yz zBftz1amikQsO?8kCL4HMhECkX;5fk$yVK^B3(_SkrSR}&0P`Me zuZ?zLmSNmnnO3=q374@`&LVn{nv0?ft^;W0ci~Jtv5YMIgf>^uXqmP1+kA_eDU>3|7%2Zzm{w0_koZ}QtkpiVm_2J&9aJ=WT2u_LkaJZ80L-@djTJ2tjA3w`+VrK#yPrnq^yt*OdnH4>kSuS*#d`TFv> z4?|==?o85$&E909E~uXmu@&N3>~!mzxTZhP;Ddw&*}+Fi&C-WO_-S*kuIE7iPnuW(jN~j+4(ryrU`xe)I8UnQFOS=N?7+>IGmH&V zEhEat1A1M{vOa*}r&v7St}ImN$|O8iXSxxwjz#A6>!VI?VX=xShJz^C#CSuv%O5{B zo27Qk>$oz)431tWPl}i6@~P9N?@35czou1rrMS3wzmt>NmkQ!NR@x^11r!wefrjxX zGtw8@gCvmaA?7d6sp{Ay;fbx0vd`XtrYZKvmTMPn+W-*61)+!2)H= zh}^!~$>n`Vj^xdDAVfD(iuf9kR%kG%iYJ$~J*S0G>fHG)p3c9IcI9t4!2s0Jd~4+t zJHkjbrij-80_R&Ei-;J`ZC}K5QP7hVJub7Qv?XluM5)A&ku*2pVx^!7@EBWyCo>*j z260Y~j&FE`@i%0<7x;$$*Jz%)==R&TodOpToY&Dk-PLG8f|qhXSV>JQI8Jrwg_Mn6 z)E@u0;^A5^!KrHrqH=^$lcPS}YsQpQ+xRksz+!XEc!??>B?dUm!vfia= z{pXrBm~8BNwsM&07dwz`TVuANB=3rfhD;)aQ0d2;B~F~|{l=kYQU?b%hp@hQA@O;z)n^H|44KVzV?}{et0t4hZ1lJ317L z+Z-;Vk6W(XSYQ-cqob?EM8N~(9`4cCpjY8GYU|HX9=A58U09zVeTW0va ze>vwUzV~Hf-S1;IH|7iDedjSm3rOxE)wVrJUx;Q)gGt4~ZG+*Kb)j&Ni{GeyR zAS9i93A#*tYQP2D#_$nhCv_ z*#5SG0xMzaB9D!K^AF;4>Aq#hm%H;5;%*X7U)@Xw|XfbUnRiZUa3(*EihitXklE?)R^V$*{~mw<-p1{FD~u^T=09HC!v^=;BslI?rcCqa?WB74O>E(0YzAZg_KxJH>W&ej$;!GV5sQ0sspnOR%Xtx)vkU!WKuc(CiUq`*puDcZn@srUh zDJlBFX+-&b^c%>UG`VS5A@ny&7;wxB+?0$VU?q(gJ=SQfF%pX%m9-6q@5pf;8T4hB z--=BB?&-~~&#sv1oOnM1#!o~>N|~K_1HVO>IfKZO@{G+w>BZxKw0P&t%Hb;fgwIfiAE}?9gfhIoL%v>x5;(7b^V|}E}<``iq#a-Rgpzoy0Hu8jj+Z(%E@0ekzihA3O`14YB@!m5Y?;9NyVTs%Ip&d5t#)2srP! z9c^A`sVNvy#LZvF>Tx7}Dwat@AlBitH@~;d+;v&SbNJXxju1q2W_qCyfXleeD z>f599>ORs_C8x~#QadffD{?)&N#mYJ0oQW|q_sWF1}+LPDiFfT<+Yh(SaT5ipv1Z} zxJY_fS32G|{$2~LlVgsY&411_$9_#6>6*nryWe-e&rkH824xUfafYi=hAOIp7AxW8 zzVM8Oi4$B1l%no9ZClxonyAk9!c(n8BTdDQ8e@Ec-*i{Q`yv)_XqC5MALj=2$mo=< zZO5UvW)4c3U~cW9qe+KV&;Llfur`R|?jrTT2`a~JpbnR!pUvl_X~;=*_qrTDYv<@> z-GS+p1W4C}o&9gAEweth;GA9f=a!R=uj}B2mfmC}5KUEX(@oux`*oV8&jWEir9b?u zyC46+{|u)ZU;p(_mUEpAuiNb0*`#sffUh>c%0z3QVSQ(xcoSV)T{2}2-Q;DAdrm%; zmGDGx5=I+ppTn6p@`IF(3XiCp(>UafZ(lJCeSy`RrY2~CCO1a#v{}s@+>jdm3Pak~ zWi9`Y7NF0t&MnZoMpYIDr_EpX^8=mIa2dPOmXZTogMtUM9sJghN7-;<+>Z9(M0B-3 zE%%wgT!!iZEstKb?M^nU&P0w{N7k33uLFtr16U^qGatG%wf^_X9%%DaSZ~bhR+5|B2f~SS<}6G%SEP);RljLF3O&pgla7`sY^_ zN~Y!!W{Gsx_O1SUI=<>4qr*d(Xp#96NCc=2%D{cB;Qd5D@)k0Io4WyQ6{A*0QEMuT z261?1SX++)niCoyB{8T?{X2BVbQZps=M$bVaTlUB>U_Ys0g;U?xo8^Pl|0! zJ=p<+R2iy9Eo40ybsIDx5O;i~JUAq^O}7{|E=MQ?5K~un?gjw$06Y#`lc8i!>vHR{ zRT$;zeN14D)k0cu@DrQ$$g2v)|_2I?8r$^Vs zs9%V>2ggzIExMK^4zmKcfVbYKcIt-*j??nv18iI3bFkq3h;Xw3NYbhPPCi9`^vp7% zou@8Q)`i~Y+RZl`9KIeYu&_Q>Q=zkPY06|!Z}k$5p+oKc;@$lHEdray6S7y4bM_>t zl~ZPKWJpO+88}&SSJw$;NTnP2oKP}^Hyoa#Qp0ODw%_*ieg(~QHo7h=6o_dGaq=g8 zPYE>!NRFYT@GuTWG{&&;2V`Qb_~3V6A@wNm)0&I`37#)t{X98VY=2U9+W&&$!{6e` zvuB5K5~-)@F_Jq9oJO8g9yO|?hmO(OYm?%_$++B9@k&0qg>TOP+j0}Rj;K+&Z+mW2 z0o8T3^ySaU7(2sT`@p8~<`I>FJuI}8PiVd9H)x<`0B|WQZ3H%tSS{upT4$1EnJAg7 zfd96~LTKuj80WFhWf*l5YLJU)F?~L0-y=blQThoWPbIo4$*%#pIX=?+0lL9XuxOeb zXd}DEKx9{Dg!cn$xX*v(>lTGu{x$!Gh>KIr^@m$%1Jg~2o-#tZ8tulyJJ{nWe zld5($d=)nT4^V|Wuw$PcX7trI*b=$5xHG7`%J}iOALjvN{XBoVi5M1iU#l?3ID8I)ch?R9D)*N^6(L*1?52~endAp z@u9x^&ws76tl7{1u5Hl5O)w??<=M_(4UMkT)k^=r=_O16aQBaTdFRtCW!>r)C1=8; z?4f{`7NZ(q@i0#tfh)DGYsPKdqt0zbFH@-648%d|jWpK|6IpT?VRT(0FmJ?)+GQ?? z1VyR}^G9Z7p7L1=D!x8y7lwv#6Lff93HKS(bnGa1mAwRxl677RuyS8CS!CjOxw#L3 z<~_drgO=49h5tkGt81|c6$uU}^(LvH6%*4P4hi9pCSwoq7u1cI$AW6>_nCc*;)hRj zpYq#T>prtT*SD2)Q&1AbV9N;Y04Jmatc=sQl7h5E|9O;tt`0QSM7*x(xLmBi%Lmu4 zY!vWyU`(BQ4H;Y2-Ml%x>?MJ*6KVjUFNw+2x$u)nJ$e8zJYG8$GXN4OL)pu4$fFDO zio`BlRYo|Nyne(JIEEaEOmPM{mGm|Q&p}!x#dcuzRctHd?TQ&NYF04w#`X+OQmZWE zej*L|i#~!(-b`svKgx|W3=hR`MQQqk0S)r7!SJr5f4<{WCM|~#n948`2x#3N8X9hZ z3UpSExBF$(to@OOT?eUg42m$M}^4teR_-+){f1%;wuBu&Yu6zW=l?q8cr+HFktf|rXFnkgw> zDs0yx5qMR;{uQl#0+zhX&p$tBu{BSz6TqR=20UZL0K^F=<6wc|##jZWS*je~a_Qa2 z`|sj)ORahB{_)8e7XzF~<#>$qjxfvyqZ6?mTQM%wxS7wDoe^fCHoq-ezWiL&pi^NJ z;I%@HgHvu8J-&C(FXQ0_ZP(A6TTgcH@?t!L<@I*^Riz0DW3-@BGBJmex?tYg3_fgc zhwUHMBz)E#Url5=3W^C*urpw+Wnop{6can^dOok`VkWB9@{5Hyg2UbY&TeTQrbP$= z-+y+4Mowm@U>g0(O*z)P{NfKm7b_U4i^W;-adC@|gJB*Uq9l20S5w}70py0kD}dno zPHGFV7qwVh#Z!;3dZ%;REVQBOwh>mN6QY#Ioi`x`H!ymUsy&w{hO(f3n8TgTJojihr`k<{NDfSW#56yivF=poa!Z5$0T& z11NLOB&~$fQ>DC&pW_h2x1~{7ih=;$t_I_-j12{s=PtcOMI;)fW zPPO+NVoK%fL!CwH5+cX8`ilu70U-ylBx0<3ep~{>k&FoBym>Pb@B-Cz10P^Q@~!!b zo2((5-96lg#5FxZu0ZmpLH5*q>(sbRi3j6 z!-z86ZBtorULmrHjvWKWW~%=DQ-()6uYPNt_5Wn2eg^AKJ=D!>vjLUV%)>5RSorbI zPWijmbHOR{W>11+?|*u)-RwsLHAyIT*HNniI*a`*){P{81pBjXY^5+(?LO>%IRbTYNEe^?}ZB&e%zw3 zw9H&PE5$Mb^Sdh#%T5!w*WLQko|alv13)C5UwJBzYcjbp()+yxYBi6hJ)uw<=zM!h zfQ=;Ij9izMOSS-qnQ?4zh3O_%eb1aVs{+%5?Zpx4=n|Kag8DDKeS!j*|AQV77HUp1 zuQnNMgCM^uD{3@^$P$nO;L)T2{oV{lg@#n|-SO_w0i^{b?8C&Fl~ZPR_GzkHI`q3F zZ}wL7894AaWPRXg_xKlz?FIf`{D$}wj=;bHhH8Aj21;8J5;1`SO@&SoZ*I&>8!UpB zNo~MdCo+pSOuN9(Mg9N{G{o z3gTsQ;P!3XJw-~5z6>0FY4w)8omkVLS9^-p5RCV4g0+xlA&PT%T~*Q6)u7`A{$xmu z6KitA7PkW$e>8>eJi!Tj+Zf9rz$bd46lUldF43g8XRDcsnP(Ok0|12jrLV?{C%F`0 zg1SSUG^4)(bQegB`RgTEL&-=ljO{xV6O<09KBuzS4`6K*RzpNTGR}RI6gFN7{6^_*d1VK41z%R>IRif9^?Dd>MZOPNsl4 z;#Q9la93xoDU^spo+?lUEytD?CogYeh0%3qWK0Bq3wmmP(R;qR@xXhGspatCVxgw9})w4dw3tizJoYKU>kTfu(#f`rir#d`!;mx>S zl&&2|u04_5U<||g@JvvCBpwaS+}d>OHk)#yw7h&NWg=LIp|vRL*r6c9(@`{G|0`=f zQQstwbiBo^hW2d3)~&{0^<7W(jj&7;c%H7vXjL`$PF8=N{1|-xBzCTdv)Nm@pV8RM zj9>FBkVEH-!&>Lg2<8%DjI?LXq7`XFfD#txG9d|oqKp+Qo^xi#ZxTY+5#voz8 zz{;EZI4n{RydLX2>eLzwMEDiNS`c+#h%B3$iu}esH}^>m+aK;~Xw=f^EsU&KC_-X$ z2E?40m^EfwKY)MZ+xLq2lsHg@r4AScA{%H zC$$Yc-dNFHvpy-PxrT!M(Bhsk2*fKN zg~R-~z6dan*%$!|{QdW1x|ZOmg;GDE1UIai@)9JI=E9)vH;$bLQtYzw^8G)_a@D*+ z&v_FDZ(WoNtn{hxp>qPbjvmh^@Zw?qmJqgvn_r&h)~zd1YjN({)vFEl%&s`JvO#kowjsPnft0y_IuVCE=-yAcy>o}p zhud}nG;vc^b$5A zH4#k4AXMb>G=?B&wZ$P0107Ja@)8 zSZaEyu1F(G0hB;ljje8I&|%So2r0)34p~k)Y0@OFpLlR62-)@S5O*l=qYWnYKh&xW zS14EX$NaMEKpcRR7Ld?P4fb1Q0$56-`_5#{kYU3@3c@#D+5jN?;nmGbLoZi;aa z=|3*SHK(qViyL|l{s1{lEvJtTdad9mqe8eNO!U8G>VXT@NYAWciOJZ;3mW_8B9->P zGCM9RG$cf{n#lVs-kW48+icu8zQC%NgX*TC@c^L>+O~Bwi1xiKwyMll6X%_W+NJAh zq-Qr;jLH<+4pB_cp+jA%9|Vm8*%S_fI(W|WodCLmMNkKx=aw18XQQeF^eCnFEzeke zK_4{|WyLuM9dC3h%pbgArfH7Z6`v0ehcRr-2^Y(@$21l%udeAr1H2fM9MRQSO}1u^ z>@~};i0GbtEIP|rT9?^0Jjj+>!hDEyimbGoG~23e+d2N>E>mo6Z6n*BeotMsea(Q9 zsyRkOt8-?oQ`Dx%Z=|6;voWWc@p3vj+2evpX~dr|CUR5tg40m_4q5)VBX^hun1oPQ z26e?st(9!b5&RG>YveDM$z%39*{dTeBE(s1OSDE)@AC7(9(J)WPkhl7u;8@Z!^ z;VOnREe>^84Mbo9VRad7PW~dn)HG`QrR2{wJ`@MBCY4XFLeS|m)K+Gg#-a& zW%;oyZ?Ypd?W1tEQ0xSiMEPn|Gca-?BHz0#+#*NFreGi;j}7fCIxz%_Ut2rjW69j8 zM0bJ7Fw=H`zA}Dw1+c4!NJ@qW6Xb>MW`Tuh>lOnZkYQNu#lFn5sXNH#a8sQIFS379 zZ>ZkqKf?AGmF(WQe*Gfujz^e@P5HdBAH!c%w>=A=b&8j#Znuras(3rNqdZ(DdF`KP_QlC?pYJ~f=^sM*QsMi z_g5Rul4h2-+i4dx`J7!;L3b-N$9H`*br|-RRVW9$j68&-YYv16nx$qFp|1sarwpZo zeRgs26i9*4=9eMaIw0;?ik+`ewZH#9lee$le>dnN_2{HCNjM86P-n=@ESUj3uvP2U zcV$qO~r{aF>zm?IpLqiS(FJj<>XEBauz0kmot`QBhHx zN8vyOr#bI^tiar}LYMgg@~1Yv@B<6%87=bPC^HC6V}m81C_ut}V5#pOZBO z*2WJ8K~6WoAo%Qk(B*kMjg39aYB+(&C!Qf|K-n6Po4)(%tSdbjnH1OF-vikf;z;Y- zmto8W?-8|ce03Obs;BqYNzrygtKDYRnjdWZ1IuYTOXE}Ze~=zA$_1yxIMr0L8(F@^q%|C(EO-xDaH~?gL+E6w8R4NgohhjE zJ7*e0u;U=n->$ZL+p$e!b&{_XMh2`$rtK!WVaz$0;1KujU##czO~C-lNLU6lP)xH2 zZtFgD+#VFM5>7AS@GTqa0VaSA789b#k>d*dpf>BB@^PWQ%2xXd&8ej?~CFh%1b&eB4}c|7_JNJ*H}IZ9DGE0CR8+OjKJ^DN~pRm|W^u z(ta+tZte8H)X{fkx4^3WDgvL_opK_VE?F`eB7Do_x&Rf%J4PiXMV!0+`!oyk#F+9<;|?AlmF|Jg z&Y?|t`Qo(CC94_AK>!kIR(=8KqQd&n!sH3Dy|1lj*5Vl@#m3biVkVvKu1S}I{IOmS z9KHY{0BCD2?A#KTq=JYWklTooR#nBT0Lx6?ZclJ+<_JcH~V8b9p@170|77@o36i`Vh&1rl|x+{3@ z@s&bRQ1yhbO!|v%YcNu_jp}VkJ>s#?S){9Ke1{YE;dP`2xG&0rg2#RMMJte>H&seJ z7lp9^RS1V)T%JTy_+Oge_uOHbi4eS)xQiZR7RaI%z|ISP#xaj5KDTtA0ES5`hs``X zSp44Ve1d%XU_R{r{reslI|3HT1Rh*3(xM9*0k?zlnDResS6hP|dgYSpY;N1L=AH&)n`an%&toD-TAcxw?zid1Qk~RdXWE)lM0I`ld zOV#+(I12Uz_#Wk*h!w{ai2Dvu8Id)#tamwLJi_xXI_q*MaNwn&T<_z@n;BQXl#;=z-F>hU90HKu3&*!;m~ zW)HkIR`E53vmqsn>3LagPLfr>67#410-gVl7Qkc~a5RuaD>_pw=bT9tZDM@=s^?-o zM)q7zuog9KaUrHG+{b5Y&sldqyvV2^YU*RBfgwmmh!=2dJeelUAg&*N&yAXm+GSrOc z&Ycb#Ck8bsDQ-|3I8n()2oiwBR$q}@5rW%7-BF66f_OWjwxT6fUkvCsDIQ_xeY(*K z!g%S|uLC`%p;t)wyG%HXe=$FE3oa29mZBmMHVB5Zu)gAg<>-ISx^dCeGq=K!^Xn+z zguTm~5DFo*kqtI{I*h-WL>JY9Pr$~Tbj_mMz)lDL)xY6)vP>DG6$BZ5SiSexf8^Vy zE1)_B*#qEf&G$i3>fuzyhnE_Y{A9sllM~H0y{gF*i7q2jbnfH7DAnw`r-a(Oc5AL)a5q!55v1@{=~Ly)0WS!tX|J*;TQnJ)7)?hBTE|hi$UaosN1v3;`JMvH;9n-hD|PXLw>J>w z5tT0EB8JoGAqp7iScAZ@mlP7h$N_#Z?JH7!qo%<|NhQsk-g~Ky_X6)8UcmGu(gvWU zC977kF}6Mf0}tu;G2HV}ZD@-8Kp0}Z&)xN)x7-JMbNe*7@K@JmKcOcO0>!<3D0Pz2 zsJ$!=b>W(!4u6E~Vbu0dJt$Ii-Ylomr|$<^RMn_PIPll5N&32$fIn2#I)Pi9?mt($ z_R#P>KNxClW~Y`0REOY6i5nC2@QqL+xEbBcb#J~@KW!s$k$U+eC@xSK(YpJ;vZV!4xss72~tLCtW=zP;}G77+LRPoGZ z!GSa7o}SW&D)J?0Ra@qdU?ZsDw!Ga??MOLTy|go7z!k5~(-s z{U*lJMaA2N#emp&d_!O>`v=yoyI|va@?;{Qx5v$zceMxW$S($F^#4J&S*7yvC^o2Q zeWz+^A$dtap@FdR(vz!cmRln49-B3Dru#SKi53sr4jVbLZ|~l_QS*6r(F<1==5Y=g zCDdlY5n3&{hRw<2R*vS`S72s>)Ne8d5tM&aI&%uH&Ny@vg$gxBJylEJ<8-v(sx;pK z2j>j;GMymU&kgeI2gAlhd{IdnytGf=6?$OzLhob8JR-Bdxiso;dbJFkqbT=0+!!_lnTDz%!ZUhS%HJ9%_CJRilvm^3s{DzV#y)VORh zgJB~N6RfLm6$LCaKMT;0>r1o3n#8V(R#! zIe%r4KutJfiZ%KAmNT|&GyZ(C z|JulYMOAvQo6gDl_I6VImRiY$Chu!5Ex^wN#h-4cH6Cq@&ESIz>$&ygrF;a~zMV4kFDWzd(k)%?HP?8W*6iEnWOBBPDtx|m- zuQB)c{(gV=+~;@B@BHQ*f6Po>uIqEXm)GmLz2vzFlR-z197j@tmE@&Hj5w9!MZyy* z(WGe|WdjRxIdoB0)6iT0)bKp|MuJTx*U2W$y+27P9oirCokfOd( z@wa^|no0L4W@ml%6FbJNp5H`pR=yD!;wddIkmV6KFu~M-?fk#254f&R7pyN~#uh{= z*2-kB>LoFA%h|?w$Eae@tgF$3#GhUDx8CFs!{HjOg^#1FDMQxX#PqZlsVBeEIV2;7 z;Pym=agdA0R8=xua=uN6jVDAW&@|RxX4n9_D0Wn{T|-tHu}HF*QUGG2H0fERKoQzs zW?x%1e-CBjyBi}*B{l$I)K%Q%EnBs^Z6izyoX>#7BN&o-Hn(DDYQoL?;)pQM6OZ#4 z9y*Lc)Hm-*3tP%PZ<>K>vux{;_}A$nKP3&opLQVRyZ_eTT0ZeMx)T^jgfGi_F_*s4 ztT0!8%gk~EXAe5c?+_Ol?Fo96mGwNzXa42iS8N>Ack^T3k|PPa$syhRMRee08IqBf zbiUyB5JKG^zAe7w?bGwaS9O7|zi0iiTNS0)sD`>0>+jEJI)MZnZ{D z)$(1SsDW1kHE~u*c`vbG>dW79+=-6_n$n+YaT`E$|6JBs7W@T@ zdk+2MsLvelOT;gtfi3MOP>Y%qh})7%H^z=bt}{Bz&fJk*s6Yo;eP_oOak};581+?#Gj!~2YDQUKIzS(>MQ0U z4&c7jDa<(CYW@ObL1sT=e(Nvj@v6=YcqM39hq^^eUn791lrAK39DVntOC2ggnSWvo z2$w|!tuYJYGVg>(ONlofJ@*7eZFbb&ExDX46n^vR zgIgLg)UoAvn*noTh;#2it0Q0IQ>ru5p74jA`41N<1&{ZzGN!^;$cLTlC^TTRySoB+635Y+865q`4J=B z?-Q)Q50@MYqq=)#tt!UF?0J!UXqc`U#puZyUUy&A^?U77l3~AiuO^Jsw$6i;O^fCT zE|yeuV8w+K6S2X;)Fh=i1tXOJz}B5P=<4OmE8i3kXTYlcfDdC@qd!QvUO4~u)clow z|G`C%*(Uwc>5N`?HvQw})82YFT7~ah6BTm?2!ae}8QKF$OLcdmWQliY!=8Muz92=^ z<5r`CoNTz_yTTL}RddHnmV7$b6TMsjdtGW55dVZ#VPDRT6!Il-Y1)51vCgzUDh?8lX+94sA_aLJAM56n>bl4MS@aHf8HK ze&J1?|DmvzU+#qqPg28AwF^N88hrJXhnrh`QPM>+w8nY%$ZQoF_==wFXw_bnSz~AQ zAfIgkmb#f1lU-+}{W5{kN)^6qhQ{a+nWwzb=$&Ej?t=-G<==d557`^ou}njqwUkAd zN`rKFO))_;^jN8hbkC{~B<6QXX`4s`a1b{4RnqL)!}bGNKB=f!vx=dJxb&#>97 z9Fo6$J2-j{*gLf?$}#5sedd#&0xOZI zwR~{9!ag%!|0wzFVy15B*|Fm$uKTU4PH@{B%w7%O%b|D@w+X|*10MF~U#gPgL?w>C z9)Kbj$%t51$v_lUc?t>@F>ClUQO=iBKNulf&5cv6y0Yit*%IHUnLT%t@n|SEV87{0B zfYjT_-33w8uzCOJ;X}!z-MZl;q9eft^bcB}44r?c8nvo`Qx|F2anj1f9h-P*O$cup z-*fo7vQTSmKJ8QUReYEJJf-Do!UI#i>qqHYaz@*xuU@&|!0t|z{$Y$BePF!t+`u#u zL&u}e29*AEo?NbroTL$+yHxXs4j&tH4>3fDsWvcrP~e-AbH5>Y!culwDhCufbK+r9%Nyb=y`B8_cyfVhj5*?gwj4@T$DwzLFVsJva4oa`U>ItujROX7=V#O(3jrQh z3@yb64#$C%W`5FDdUc+S#V6}Q?OKHEl{K}$*)ww9xiz71cL%Hzq$Fc=RFz|^5i6MF zO-qUd6UacG*x1Zz3DA9@hX!1x^XL)#Zd%uVUX#d(h=|Fx+aPVg!6K`@O>4L#xs^Mj z>FKSdwSffG$VCbpb>IM&nbGb&9a=c=z3O&`(pGvu))rNnq!9t35mTTOYAPm|wr!i6 zp1jA&vI&&~U0_F|Is|;$Kv6Rcc7}FqcuxNH>wOFiy88I|L@sumfQqmO;H3KRmUCqTP<5rV;>&UYXEh>hlDa(qsyaJuk6%n|+ zK5(tkFAr~_#Tcrmr!2{QXf_M8i-)*2i5wiC79l#+*jSM`u5@>Q&ZHzI-L|?37YVf3 zl5@G=;knL^VFw7Xf&}XaR3<0OY)|SX^?eD*`9y8E@;VthMwgt@m{yrL%FORjRMx@) zl_x{)MCq1pEf{Vq5_r1gXLj&doZfDIUjvNerk}B9jZo`uz4EwZI|8YZdY{9)5u*XP zi_x`CE`VAzUz`-*yFJfVbB#ckEFuj+q0qj23$468!k2nPnAx1{(WQmT%!qhpd)Fqm zj)>*IW!=+Nl{xVJ@^G(RaD-}P{$zZR(KPD?M*`x1kA2^$x`7%z-TQQMWU_8fV_WXJ zU|X|ROhwCQ3(y;e#WuxWo$6J6=*UkpsDb^~b?BnaTNAl3xSz_X6PpR+MsE15rR!tb z*y$%E>@?IWF@r3o5I*Fe@;rW`Xm7SxZg8xD8L2@PA$Rrg&IP9_ zTX3M|TyW$o!DoGP`J>uj9vm8^WT6|XvHlrwRL>f3-H9rJzO|dxOgkMN(3|N*NDud` z0*D?hcm}PHseL!s=e1QY@m4V|Rxn*60k)aO^n$`dOuX!#ZYMRQ>^R4Dsjs3zH2Gea zx%LZj?|^(>!jLI9Cnsd((o--su`~a1LU120+2@lg!L66FU(&IIiMW6(>zY$H0Wxuj z2-iv;JJCvgF-pNaDG@77gLp-sNY+CnDxwi1cs?0%HxHqelp%CT zMrJQ;9+Xr?G=2QKaMBcX>F-FKl_VG@HmZdjc|y`Su=|vZ5wvDdn*2)i2ZL5BL)3!% zI88S|+N;%=SWyuce`(kI^JTcH4&uK12O(}W4NfY{9EFmgY!mYh-FLt$z}h8jPm(Hs z<}8x50I=^PvpaS)ogBsu?Nk3DtjGld{ud5^D7M~8QYi>xujr*~pSB}D?bGb8p{k*l zfBX==XgJ7MQEd|F>i!)LuIGF%W^{gy(plS8A{5p@9HfLFZHwyEM!8RlZT-pL%-=H8 zBbdL>?o}#Q4gfpTHJ{%_t$U4tG?;H~uJw(MEh+}FIfLmQ-Fc9v!mHDH1Sd6|7*#mA zv0MB0-=(Z5wNE~EYBx`!_jE`%qL0Jsav*d~DcpAh*Y=^ns;Op~nev+ixR@&xJ9(!4 z?%%sN72_5-cx=4oY2pD3F(*6Grm5$#Urk_nf>FOMrWHleZGtUtr~Jissl6m6i^e5P zpEBtc)paOfzI#bNow~MB8f2cGAFbef!qP+!4sWuPjcn~S8voisB2d(>Qqc|OeOOl7 zyZ8gDOa*?qQ=6pTrHe~S;*C!;@7+ybf3Drpq?QMrjSYwNDh}V~=hvKc2|AxGkkafK zpJVhMQMN)qN_5(pbY{BOyF=_-=*$f6L!&jk=tN7E z;U?#TKejKFK`Ek{|AI;fj&L`Cz2&`3sq}|Wn%C@#U!Xh zp#jAzdj&W(T(Nw49?3XObPpy-Z;*^sZC?4PB+7*B(P@>fcx|z`$|#(dFAsl66TKqt zWdxL26V{GT{Nws)J81|Gua~!pU#aJVjCiGEBXqi1RFHsb{!&NHxyOGuA&T6>0e-o~ z#cAgACh3@zE9Olu4kt8FNKZH?r-8N80O1&u*ERecV-MJuD2>)Wt$p_N zskmqnvm+asm}l1a&+aDjh1Vj#%2|aK3BCIFr#=eQ=%1ixI;`E@E<_2AXP5$CE|}t0 zWHLh;AZ+6Yx*SZ^FK8W}APKxB>EY;3osYAii`#H)A$;70kn9O6LL@CNPj{;*Uzq)z zK8=o~CYmNGs zM~$kwzck|7-PAK@etiFOmJ;A<7fFC30}ri8&ob$g!<+s=Lfzw~>~D+gCuK z-3`~SUtdga0&MIvJZWGS{Q?c0W}g@`crfFH4M==Lq#)6|C|cEjA0MTl-oAz~&L(4> z0p&5L=Ffc11pwS)vxTQu4Ov{-h_%GMFJ&cCBcw4gGrI)eN6HIbL=B2YUM~iyBDu(ch7nk}582=pB4?Js2!T)p05pY?nhL`}p>t zG{~z{=!Q}}> z-JodB?O+JTD9LBi+|p}`$DSf}L-5#@e6uiO`>4bU&?oS=pSz*ry*{qtkG7Iw^mFD6 zt92Td=A%%9bu!LWi{-`caX5 zDk1&K0xwY2|Nngic@fQTCM_vNu`grUFoTRoL4v{&Bdt~WdWw3sYW9sAcf9r|)hRI= zCuquLQB8r2a{WF=^h9605oLo*2;zbn1R3UyQdPcC?Png>hvJmxRV1NkStKG*QE=1~ zMJe5+cio$jtVyvRFFs3oFEfPbg}g)tNsFuK6|{<-N}AuGySpaBm;owt4$|E$#pDHx>T8e^&VW)b8KFC*DMV-ysgt$|JLXQya5P z_e$7`iLW#gIV31C53PiS4CFE2uaV{qeuxWaS5S~ha+Dr9f24TpM}`620*$(E=wY2) zp8t>T?njcV3;+CVj`;`mj4zJc7}+q}GPCXni_XV(e;iWQ^lWnd46o5frxK^B*s6H? zcG>gy)p=jB>L`-OLLjGIOd8D&D?a6#i#npU5!eFOiRipq(;oY1*xcC7Hd`_bK_IE8 zElLKRz%=)NFU`S-ni~CkalYx;k-h6N)p0~lNwi|!f?gNwRUd~W34?+Jlwv2EUsip` zLsOv_I=A*Z&1)(#6x%(;!NaE1>7*uEo|qeGd$h230f_#Gr2np8~)Uc<18%4lQyb6*|%(zu!jbYsZF;!hALrBv z&-uXl0kmu~L3?Uf=X;ffs-4ZwUF7VX!-+Sb`^aI#kc@3YOf;0w8kzOWnDwZqEc)0s>_E^|&`nTB`WQW<49_ znf97Oz~zI_s27Q9+~v_L2U3oJ{i0zWkLdKd zo&8^L!w=*=C*e+50Szh+7O!`Yn*hcVCuotHbT|Zg1${o*s~6FeQ^mhS|7<;VXZ*GU z2YPX0U1EuuaL^GwHJXy=$f^3P5uB8k0T`T2A`IjxKPn z#ib`Qx%J=c<1h9q%HtocLOTL7@C9IBqcoyVxAh*W>+43aW`sw5wi{-~P;65PSGHQW2wb}LzVmV+@}%}O2nthTg@emXay&+2)AJ{U!2Gv zOX@^PBuF2jKVsXXN|lh_vQZ~PYi>=^JnnLL@a};&6Obz_^lCp-U|);&h7x;WbrOk}ZRc)@GK9X>ATCp@rfb%KbPu*D#I; z(MfCw&KS%D=x6Kjgo>mIK6SWz^E)!ut=9r|!ww$FTS2lKWG`phAHXSYWUxYTBg=ip(vm!P)H9Zc zXU17zZ8PI9M>ocZf^&lK^Jw|@B=HDv2-yo}-W=>!j*l)vNO0C&;iUacn=968-5(<0 z1(?>Jj714lfh^ig+B$4bQu*_@LFqnCxohvh6PLIL-cC?Rh%wI|MU;9mO!bkVX^Odf zNIwzhr4SJ_$JVGwN{h?lkkiMGi6b7w>U>UV01fVZi++z2)o{#>t$o>>;y_?p_=nxv zYsJk(TjE6Y77I~6hA3vW>)FJszGXfd(C9(h3^?s3kITv?O`Epe?kcfInGk?Z9Dol? zP(O;Z_2b9B+*FWxi(Fj;DE&Et+`7r!R~e1u(>RvP5zz)Vg-ncX222!#BwK)*Rq0E0 zMB{Tl>8?sP$fPKROpOOfgu-mYwG83TwLGxV=azc*#A}E5{;N@J(9}}4x)A+tP8(~F z!U`YyQE-OI*c(=(`;o+IoI+ktoB8?q4I`Mzzyv32H9)ix_n|^Z^cUTSj#>A4Cjlhl z+?24}#L94<>tcib6c+`DrguYsgg5;$;Bh9ji4r~J^3(a?+uea1YwppQmz84| z0XnYj9qNUWpI8DT7S-?_XYp<9-1$!Dd^1XgeUTQrVlU5m`YJP5mMzjnH37Ot5Yz>AUw zBX1r}F8f1-tcA`VTdr54+w8#lx_tfmcGf1K*d+uoSbGi*)QsKsx4op&sHRMnSZ$SL zXJTj99b%EX@LIWXrta!aJ#(ML@31{b?+zTx+6OwzM8+&1HDY!67{*nAuc8?_e(KaA zC{3(y*V=F8ldVexU!e_BHQnk%yFABfkE8nAsKryiaKbBrMyhjEh>^gQDxFx0xNtFwJ(1vl;eNX$a{`vc@mhHlP2#OpWZKCt46ZGm;s(U)M zNr_hD%=d7v>xAa0>1h_b=W|2UM~`aqHd>GTJtTGwJ;aX#1II|oONbu#5VWTVp4Z5U zcr)9Od6EkVwP+&)P{o}KGj))Y2LyUA&uli6Z{a-z{>|LbB>9p$8fCTQT>#YsLJFK_4yjEw{xsgbzOK|{6 zF(ryU-NleCVS4sngU z!sU6IQ}M~ThqrdG?|Em?>@E`$%(PaII6Nb>?r=!!?q*H%3NjM8L#hlYM*_wkP4A)A zJR#<`KeZDJM`EjS$0LtL1MhOA)YQyO{E}3tO_>WvWSTM1M(7*wPD5YA8i-*EoMGjU zKSm;r`GRV5!|z682MjQKHkM^G6@vQtTW$x7uu&_|2%P}-X@C)(GqbsAQR^?vfoo#g zJv_O(K22Q3wCBN7yopcEMCDX%{06`w{&fqMl^fzhyf#237nsQh9L#aWI|Pc_85TB$ z8}7$ds~iA+QKtZkO=f+``JhPdABnUI(BwBXZ!#nq8vwDSi=k7M_)*dSCo|bXiD#_U z_QJ?zH#bO}4RfbBL7RC!sl+mT5q&myR5?CV?}K_bu3y*D)h(Fwn^Itr6D4MOVDk8- zPMJ0u_d-36L7?a#^vZeAq^d>QSBsfQ-$YuhT{#mSNB;SS4?~FW%|{xoB<}4{Yx^fO zIegJigR&BHn{BgHt@>Y0?&8qa^ERflp|1=hhOal4Dwl35%C6vsVCG|MKfRs*jr> z;duIzhXxK!yr~q893}!FIyhXCr^%+<82qG04oMs$3Yu3=Q<9m$sR zDjGh@yoc5zLD<{HZ zq`8&(BmN!48Ee8;*;V3Q=lY7h%l|TGYK=ZYK~4l@F`h3#hVi}Pj?{2m3vt3>R=|cW za}c$Mk`sAfRmb_7P2nN@pOd@I-7}R^F_=I4;6<1`TnY014X(uFwgEk;ooq zT_SGn-3aWWdRn7JkA4sa54>L!D;2RrT-uwP^#`O}P z8@pFg%iSb)5)stk3_rY`>z_z(W2AvsEGnb_oT0JLVD>`mCH?6a7v)qLj8|< z|E5v>#CK@~u-`Fi{4e$Oa>a6Bq?2q+}9Hjd_F`3vkAvX~bcjI(YNMzbXL&G!%4B#X}-DegOF z4Eql*(tGiPWYdp6bq`8O^l@ABje~;&?Q?vOfc+%r<4#@HeJ;TYTr$e;Gh=$kPs< z<=Wdtz8KWoMoeRHG6`0B$1w-C_8UN~Djkk(-nQy9;H8`X>XwHs%4&h-XD(|s3sx~< z-ee{-L(yDdgeFYcxLIp?WVd4vH7%i5FS0G&xqtt3)Cb}o;$(f((eZwl78U+qn{@8> z1G|KJC9UJOlyswua48#{|<&{I)*30H5@6Z++GMB z8Sv&g`RWqM06&v6;SnVkUU)Z7EIAfokv4Xy&t`kG&o)qdr)PR|euyKVrkK<`B^h;y z5-(=wDU?>qL(DVh+Sv{K^au^QNGk#F=ozZAt{qkNO^dt|+X<0ppm`i*R`06g99kVg zENRT8t%44gI-4GPGkBYW6K=j`t)cNI({U=-fi$oy z(*M|Mw*(%Lilz*CQ}Pd|23yv|Qya;AP<i2@?+m5Eq1FX(pQW;XBU%aitq;`CCF} z#5wom<=8fSNJr9PC`y#Ioq7YAQb=-mQo&d)TuS@5Ry9>?qmklMp+_dSST0~!&CBS( zGca|uw@+61)Xm+}pqLw}rd^xDk|F|cAGp}}FpkKl)k2>4I!o(K%^)#O6h|Zxh;6DY z(lSc%_}Me*uTES&9P2Phb+Sw@e(bC+Km4gINY{LRAb$Ud-dFc>=YxbMe=7PTt*$|=caw>SWS zbvtTm=2KmQwGi?OsI%kXN<*2EvUGoF+@sQTuU%ZS5;#DGcA0bXdCC+c zRrSwE=DEya8>6!Az$R%+zo2;mbw8Uiw32pJRt-ESGU!A0+ zlENl*0*W8Ig@au08y!u4d}7^vgv3*v2MyW`zX=b-JvDE~4zL}xU4ODiN|3GJjT*HV zKh3gxwsYo4Hb+K7t&5V7hO|B&MO`#B)I!`lV*|}XsY|6({qD)c``7$;?0CWR4YhnZ z1q(W#PGa@gz>+CdRXjuq=2mVOydim1`AU!CtI9%OCx~wZeL(|oj*@otO3VbI`O?Hl z(Amwg{wJY1K*yM1y@Wc&?I56U|F8tBgoH5f1Nx~+bAFk@IHI~wEG;sua+N0lR4dD{&>7o7(J0yC5-b3b;5|zdWN_gDvm72vW zH&Rx9%*@XInY*&8raS_jUdoG42?IZO8Xxg^4=DxK1y``<9YlRHzp|!QfIV#^rb^5_ z+doBO$YQv5s+>kn6ks%tv(tRZk{7p^`x_}7&;m_`^^rn;Ks_!rky54A=2s}@)~~R& z-Fr}>a}WZ=r8`EhuzmaY$G}qoqs-8#|Aooj+}__&eZQht<6ZB<0X{%lg#t9PG3-?< zTWi44LIU@$aRgNq#B6g%jKnYW|NeUgidUJd5E2nF1X9j~sA}mjo>x@p!l%i*050EG zn6ZBCHJD@!PP@o#8$i5;3HACe_xf6omOBYah!*Pj;^wMyhld&$9BJIaA1*91X*P!81=UIbq0SJ8Yr-NBpUV6KOv;e7g0oLjHS9IEcHDWiMt9+03&} zf#~-C67abcIak(q{5X8YQQu(q7NOjtbKXwb0n}HyzMBiVGrJAn^vwpOvd+Gy-Og|b zH=sel_L@Om56l6Yu?F8{BVV;Kx3X`$A~Jd&8QwptZhw`;FC$c ziB>-dxJWFIp=Z<0=ZjKl9001__xP3F*)ren8j%f zGoz+3daCHM_nqvI*HqR>&%wlu$-?%Z%(*$;e7ZMj06u8QByv zG7|sS=en-@d7l4sKfmAac&_8RkE>gJea8EJp09Pj167sfcI}|uK_ZcM$)A%}Cy_P^ zlSmu%$+qGvZ+21B;y>H3ozrzBktnK(|80okpg2S#9VW?3pVf4E^8Kr~e(>V@($6|I zwq+$YcJ}OWBVF2OHobnV8EovDj~=?HoDT}N31XJGvt01weby=Kqmq*0jQI!d1n=wQ zOO(7IB@&r4%{c0wqas(~ZSt$6&-SZrs-rWcabb9Ydp|A4^^5 z?p{y7e~!ED-u%(BzyI^+qe5Rotq_^-Vf-sPC@m$od-K`dw@0Hb#{T-+OwXQO^k<2$ z#p&HGEiK)_!bJYp_pWNNRcmPf>tl#dlgJ&f$>#Xydy^8Gh@Y==ROEBQ4{tu}VjFlT zg!m<7&77?*RK(W?ic<_eQ&3S+jg60Y6p>QY+5WyTBj#7HUM;PxbQX!?QtGrmwLBEL z!NtbLHb2>wTf1d!VnV%s@ArRxHL2;rsZECt9s2&`hqeB*!(@{3Q6Xda#!w;05z(6& zWWFEgaYwgV(i0MV+!v=d%q;eKKTS#5 z;`8d&_3X}hs?7s^@*)xv6+OWUDSHeIzOv}hCmwTjbX;2+40Y%_l3!53EF$t4&yA;$ zgL;SC!bHu_!MaR?>$0+2_wCy^J6%#z;xyK>ft#EA%KJw$FRr|AP&%|{PgRVOSN%g? z^9c{J$an9~`QEy56p*Z*T8tPQBVlHjN2ByF{yF@@*Dlq*-fDPEH0< z7u6r493{1Z#QR-eP3^MnEp;sxA)c>Q{>enIY{N3z6m{Lv<$e42H|C05|NgGquHt>X z_gekhpWnJKEvW46?UR#}BR_u%I~KTo@9~osEr)~es2l8Fzt=3`Cwa5HTwLi9-v-TK zx`oL{L1S1{8m;`w$@|A;Rz@Yt9z30+{MEO<7Nho5c0-12r5vN@?XWN^Sy|cDY43HZ zL{*FLj0_CQzkmH`?dqy~^XBGLxzLT*7ACZ)cWkjMUp{VYYwI-8F0X8AWz~SYdw`c- z7ea43Kh~Q3?Ah~6H9JVXE`z)9%~%GhTA3HFet8+#EV2Hi%g8&HLp$fB3(inM-k0spwJl2Y1vmUCND2fy80<^gP-J^EZrAl-G$u2wERihxrX|sF8LJe?8NGR zA z9oo2i?_Mc91FUJ=hi0tQJF2RxNaxOuduMN69y%bc+z(wSX5?59@|}*)F(FcI^89nS;wPXTogW` z;wxn4=H?~We>9A|e?0sHujI0sS?hB%MJH$H@sFvLA~&Xvv9QSX*1dZdz+JwyQT2T* z+r7ZR?IiED<<#2WyjPkko11gn*S?lGKgG3F*VSq0=$unf*dbuod$}`97x#PGw&&bn zZLsU&*Bh2C2^((SyeTa$eQj>!Jz5 zzRqVcr;j&Vh&)xW~JI}|}wPxw^;=x#U zWJIn0e(O)k|4ZQX>1d-v2M&;~O?GDQXe0{f+QaJX%+cE`I>?;18 z_NQb#&c+sq7uo;)yFNSRf@$e6wq4D={hRuyrVNLPYa!tQzQDS4`}I9AJDW3s_K4M& zmu%+Eal_v~ztAtbcC#^t`(uH17kgJ`NseI|d&P&Qrp*aTk54;ayn|vpb9Fb9@H$B` z`b6u}*H52x7^u`xoCY&<%P)O+B1BC?^Rq+S$nv}_7b`1C(`c6X+|hXNt^NLtUX}Ir z={?VRd3kl8U*5hr-N$m|$W2DCr48G*ZR>TL%x3TEtE%$tEpwlHFVJ`Y@neqWha0q* zEbyt)GBQ6WGIO81{Jg{6vmhH$CJn_Ffma?#f{n6@6m+wdCh`YJBJ9iqhG$XR~zj zeLtqE%r$W2=3W2s#f?L8Y4p*5X-BSTN1ax>o5KuI1{;-gHQC4eDkN@9_h$1k`e~l! z9QhD?@0h%E`N_wJMR!eX*$~5R^kJwzBL2GbZ5~v%TOFC&AG7rY`p0vgGUa&t&U|lZ zZcdf*rx@mXkl8Dj^^|FqBhYUfmiC(1fA*&b__FoV@^VyhXDIQSSNAaedlM^iX8x-M zOSF}_FE)5o4DDh5vb?-Jd<9zo#f?qi-BYwngO#~v2{u;NmLivQBWp{``bkMGIhn4a zyR1>(}wHwrOj3u@5^=_lk*%i3wf*ejrxZ`5V4o zI`=^&ORtbZKD@|d*&)5^v?Z!T95D=L6MT-6ITjG@A$H(FJ0< zKDa)b97BT&wC>}r{_^Fbq3FVw0_zior3X}0RM18#gMxzCmAt=IZx0U-pZWQ7;AyCM zQeNJD8jcIbCMIV!HL0`p3UeF`&<1r}4PD&YyZr0Mfe=(x&!D7mR5*9!8cF0EM;|6r zsScqRiMvj7+g!8zm5nPF?r@*??;irEZN5~eD8`)R;i+nDyhkr`{eD!GUw-~6e+v3< z66?#9sA&mC6<%l^2Ym3m99HHnh0fT!xe0TZ&F?{B?$q$9|5RbDH+9&p;&+ae${JboF#-& zA|x^K$k*35a`|lH#XWUiT|GzwbYVVz{0?f%ri_jv4Rv*kPkBdja&j)4n>&uR9FYy7 zlSea<_%pwkgkLtavM`DMJ@eT-zBNha-inA$qHKv_fM~E4sF^-QH?i?3fV5dCScn`>VHcqkt`o^ z`~WSjy1srB$^h5&$7K1vt?!n%{k?Fjcym$Uchd5mTf*eO-6l(n5TIihR$6q zw0)1pSnNExk3}VJXmxq+e4MB*Q*LRgXruyj#rm2EI{X#1+uL{UM6sIvQS-{Oa2Z_cDY6ebBoLCWkvdz)=zY?(b|)~xwo1I(YtGKh!orVGu6Y5%eAsi#+5s7^ zPxmU}!QtbL0Yi(5iuwl!HSFq+i5|o)di?rq{zSsNyzLKO?shV=e$<#Y6OUBz>7_a3wLEczu*foPzc z^3Y03ZcK+17YkjuaKYoxLf7mXy|9z<&u=vk9z4i1YutyYYFZogrl*Gv9kJ)@*J9VX z<0Jsd%l(x%@r>J2RTxntf#QbH4wF^l#Xo)iY(G%t$J5-3$2HblCW5+h8Fw}`GSblP z>+AdAv<)rLiP`K>{ng&mgOrq%vvYHn?P*jJ>#Hwn`(%xb;sNLG;a8l*+PHf4YTk<% zgMSwLQq$7XnnXFmt3Q8!s2nSN%ChZP@c{AV7cX9TC`(F74a;899Y!5} zfU4J)D7B4_j!w}2+vWsXwyXFxMqbOzA3l6|@aWNVpiY!6=?bqud3kxpCaldc&wD*KAb^ba^i{GnT6XNv6!0O((GLSZegq$rKVei(=Yz(5L_WM! z|E^nXayZjzEb5U@`KCRuZ-hR1LI=Kbyl;=9q9PMF_jDk`YgK``PnRz*sLrl#h=fdiT)OBz6UdC#98Wn}+|kpczbwvCIoA60^9%FP zQipH&6#=24EQb&K0OmhadW=sIIj5*-I?4hY!Nfq=TW zyAwF%^>n!+AT6FB&_Pm@@RluGPF-m_(Dw18E_Qf+e*WxfT=T1|pR2HIhfNGr#llWr zezzN6I9jovhQ=>7l?C;e>F{9^R#RJB8?iM3126yhQb04JyKkZ46+ZD8Gqe5dko>oA z-vR;yHyD4b4n#4&9~Slo#PCz8>kIw$x<<5dleN`l0s>2{Ep0-_bbYBRC$}v{UH;bA zU4Y%+?s1nNK5=5Fl#~?eOEv1(^2}RGj;u@qHF%_{NwFM1z7^XHdob|cJ=5v{sso1( zeattNbB)(XRYngXzxdMPY{YRTmjS>1dHMMR01GjTy4Zx+H=}sLJLv@Pqw3Ao9+YHE7d*chRmii>hek75U5z=!Vwu_RU3*0!NlU@-@Tgw%F->*dVlnY>kHrC!A~ z(Tt>{UWkD+`IVK4fgA%@IiNoE^z@Ki7CN*+>%#V@sIyXIU%%sct^D|Ou;=ezt$8L= zFAECr>0xqrNLg7~V_yn5NPr_%ot^uvt*w_A0qUYMJ_5p@Q&KW(PgC>BU`aMSrfA@= zZR8pC>qmEtf{0Z+Yw(>9sAb!C?mQ+S5R;sItk-kV09+D3b_G>$HsG9$YqUAwn$N`c zt=ih!#d0)<4mG0eZs-_`y>;uBhcW|qDli|)xt7<)ODzd!X-6sh7rKmMnzc<#j-Y$z z&a7@n8*YxL6>}cOt|=@ONGPG9-m^z?eeDnbukp_>Sn5IO1Rjs z@Mq=cDwZ*^Nb29cOTeb49rhi0-g)uj#S|}Y>$tlsr_rdhhZcA4+_^NFTfr`-0*YAr zv-Z&H>RdDUk;CGY!Bz^obHMo|yq~B=PImUH%F2W`(MAo2^aVWRMin_aVW$98?nt7- zZQVtCZM=;+n5r^-n5Y)m+>QWyc=+Dye+p}h@2rdXPp~j6tZ|Jj1J16Bh=$cQ+FZSQ zK*CFOFN^XJfV|Jdg$oW2JWR4d_ZKJe{!y4}-n=<$*pz+(dv^6#w_S=XN5i-2>EpDf_|Yb zeS*~xXzVupEt((Oi4&2GG{N`oMZ~vrG@>@6W2XQ$_LRBD0PL%3YHB_m>m;D;TxRF4 zSbRftiH%k?Rur%In#VJhcx6LF2HYK;xW@w^0fHP5sO{RdGjekNPy;NJZCaDI02;ou z{rafbar8MbnfOxwE%q*Zlm*;NqfswOSy>s>a&T%YBr1w#YHDgHK$+?MQ{g+5j9dbI zh8{moS)uyFhY*y-pUb21j(`n3jE{5K{Upy`zI+U_ z3qZt4vj*yo8#iWnJg%*;55()H<+r+BR#vvU21%&MX?zdxK{Zwgs%{jmO?n8ZW-DkR zP|1e?DyEtFdEzhGG@kX3jhzFUAv*cJ{oGfE8=}CsqZ*h_oCpHqG_kgB?0<9X;VILt zu_8A{Qeq4t=q>4-df^k_>*2Tg0EpD-@$rk~#y85x;Nerk#5fBpJ( zLihP?E=WXQo`JhaD6Ad>JrB@J@|_7%XOGI#FAneX`kmeMLs(eY!aDQHs0B2g(w?C9 z$(^8)d)751U9l-vR#s+LUjZW2=XP*JXv=wdiPIPivL|sVu2$@*dNKL4IL`{ICp9&7 zOR1|P)uck2$f46$jmO(khHckT=;DoS*tK;%2L}f;`6$o3cr8qJsRUV&SMjn+NEn$G zKe`)mCq&hJk=c)G`5Ki!vwOj?C6g! za>{Gf1*Nh0Z#_-

@|2QCD@QBj3$0GevM-!o2z!6& z=O7@#o7&ntiBkS(X&qLhb46dA)&L_dKR;*gF0{+NR#DjJbqGzm#A&<=K-d-C)&ku( zxPkiiqcmr!(HG6)gJ?H2Q$%mRkbTiFGm}Hi{Z}$7Ir`HkAJj2GzMu2+$q*Sz?p1Uj=@7wSBDhuyuT`b6Gb7Uf`icq^Cms|Q_cbcqrdwvhJ z&j39BkI$3_3%U&7HZZ+jVjKS-)ao2*!b$zAjlTLLO};kZ3L(j#%i|}Pi>s?W9v~s3;HseI(b5ZntmzvV z5N*`^&%%E6gG*56b{;sH(8j~ioOn!KNg9B^7`_?yRbdLio^IiRPzc%<#L|mLHrC*W zEJfth)w7=|>CQh948v6cwa~Av&Z(e-9uT}{94q=nb$0t_VCyc$ROQ`q&&-n&U)c4D z=NP=+nl`0(W3qD>h%eCgITaPTbj^nDc3M6QT**EN@#bai<1luHv3Nz@<^!h7e^X$o zoZ(knuJR)%VcpkDz5Porg6ji%m#1JBd84P}y&PDdoTpO@!Q0W|u*RX*W8X+wS+PUs zD)^xHwSHqqfP<&g1o4WTrOcsmNA8OTK-(gte)eq8xj8HKJWHEAxod9Sc#1htbi`@;$+xXe$b_{F;1136L8{ zO}1l4xDj;0!j24WS=l?QD?cA7LKEp&Dg(d=4A0bLK-nBcRi~XUgW&076>ex2`XvSx zKq9WWk-I{FSai!-7l&82UoTFS1@2|xxl~O?+zOb~8`wchaLBZ?Jru7GK^kscUt5$o zt`ZkiP{6;#kJz+m{LB*lY8@WW&Oc1b{{vkHvKSd2kAs5)$W5kfYR;>=BV^4Re}J(% z2(U*fz<`)6+taL`AXmVmmTLa9Xv=^lEMH)M)Crb~RIlumlo}A=j97C**KMC)(N;6J zfNeTEd(g|v3o>&3ZwqiG{k;s+@1i==GVb0LzCEF56e{48@NMwq>C^kVxCb7p&R$e& z`%fj;X5pi_S?kA-d)J%z=h3z`R8>_+PA>@4^5>hp-3lA+;?yrdKuEdTgR8h85I2ZA zgz9(3nM$Lgv$HejnrGJYza7M!qu*9o$eP6$76$D90~^e(6gz9tqX((H-jNbnTBD`0 zz+ZU$o3=dwCd17P4GrDL_dqk7ne7bZs`ytHU^XLSncEDol)`gmegKc{ zdvDoef**m5LVSYqnncI>N0%_Auq6bqe}7Q>+d03%(m?V2d1~Bi+9n!j)(OJ2Yc%-$ zsi&t@)`W>r#b6r2f90Rz6Av`qe|xsQBvIqSd@uQaEYW9|Smjhef-QAbNn*UAM;+~T#10pB72)6 zn9G|yyRvj|#m3S@ez**c4Fu?(wxMfE8xMgI(4UD?1$+*jbqZ`#CdI4ZsW|PDKnm`ox3s5gKtxSbXT1ZQN0fX;#X)#TbfPZz z;r&H_nTF{37I3b=-Bo` z@b(N}=s5dQ&f*>z@_%5(4Dz330YrP9mL9)+M$ zqECPmr1tdQ!P}P=jhRJDAN=uyld!D#D#q1~NyoxP0Js4?C) z8%nSZ{N5l2Fgt+8D>c#m9l)DONa!F0 z$!E&3J1T(yfP@Bs)RI$DOs-x%A*YxdAT0g1-19dSQclNs_)if}o-~1Xv2k&ATJ%Ih zlJz6h8aM(G(a{(Fe&WDdv-!C?`5AN%Bl-m4%y+n*4&t#4mvTRNfrk7`*jg_8TiD`1x*8ot(eglFAL4-RvDvx;%a5{5xv(<#*-&crl}vUOm)WdI}UeY=#Csjg#RB> z40-tQAnd}oA3jjX$;r89=RF@`!FwUpBtU>+>oKT558wxt?*4+zO5Uqi&!EtE7J5OA zv4mBhKs!!BNtvtV6`J`W-w1Ax{a|gr<;UaDM2ABf@$&hExd{GSb$h$>MU{cR6hm7B z=3~cZQ2ZJy1Z=)Uf<8TojU5)^FE1~@eEIS<&@*C>S5$bXEW?PaFMNHbKp)g_6#7ZB z_xc(k2M8q!2n$~<5749zD}>3gdGluI#z)qB$~_MeB4MA}tPqzU1ziNt%ZxOV&%Ri&vBg3# z>IrG>MBI(DY1{t?l&b`nlmw9YwzoG9_1hE;R!2vtxX=VigJ8)-!WNo!|NQwgmad7d zE#bdFQ|Gg6OKxzy$*%r(9!DjM`8Lu2^t_A|l%9`=`ErtHLS+*58(J z_s_TQ--B>1SkdtN21ZBWZLMxdEB^%XkDz3(>wgw+-esDlU=)ACsrTw#StyY;@>sey z)mNc{mC=gW&qoGfr*k2DKf?3^pV2`;$fFdLYBsxg;@b7=$2m9@y{G|re-ri@#G>|+ zCs?B}1W6rb^Z3*9z9VV2Y&p6w?!cDu1J5C~ppxuhV$4K&r{Lh=C|@2qMDqHxpj~{z ze@pKu9o0MOQ=gt}9C1Md+2DK9cC*lRxe5-S_vl*Tu#V45U z2KtH}<;tfnv{R*rWH9_jZ#!pVl2{uMK2}7wkn$h8TEXS|Jsut&2gE%DIWNAfMA+va zaf|m_{~6Z`G#W2F7WUllpHaflE^rMLz!^j=!}IrbDDswHOZXwaqOB2nA#!6VrT}|$ zfCp`W5@%?_76EcfS7#g1Von-Yl3c0ZK^Q}t1I;S``SYr;Ut=Mcv=!N#f^ti`xCnv{ zLXC(As6>{8BlT;Z$tDP4Nl?9XE?#t)XlDcA%=8oo|4>G~2d^dAHP})ct`N)U!lVP@ zcQPn=2p1w;6;5={68?4|(xjv$7qrkNXmm_?049bu*6RVb=-DdjF#*Y3NA7>*-h;!VuL^owrw~XU!nY(sFLqoU`-d4D~y zg1a?%{_~xa|Ba!OD0cmlClc*DZ_RKTCm1Bl1-G zd+N1woP-Y=A6~{=xLIh_sODjAY@@nVw6qtePQ9}3QXV|5u7tEB4`eupLhsd|bq>kj z%+H#QJ}rM6M#j%1zX#4BY!VeOl|L7O-r!_tiZtKNv8PGTos2(B=A1fIkd%zCCS+$T zL3&lOkw&0*!2XhSs>grGtf8TyF)Z_)F^CU71oq=8baiog$I;Tok1o!jolOp6OSqnpf0$cHTd%sa+<+y`SJVXI;KbWGB7=AtIb}ge~sexigO*-|N30 zs&IXE;9ep`2{s4D&I9m6E7wEA7krTSSx?{~jf@fzfVrJY6rATtiwwYY2YIjTK6p@G zS(ySa5?Q_NSeiUB8*|BTO!b5f*8Mvjs%0;e{F)h>R_{9_3a{!+qH4SK{e}rA!7Cr0 z=%#43I662WjiP6hc_CdzeEBwv#ZyQufLq96%kfpcCX-a^_}{Ui2-tz&CMFtyM~OxV zce<@e;_;IwLAP#gf&!I-rsi-ikXbRhB~6V9=7%z%S8GQ{4dhJxBsdbMN;n6%Lhcu& zbbwgNQHY=u+mAFIBtb>wljJ8s=6iusmEfj!g9zush_-ijCPZrRj~C|63@CA^jYnbV zs&YP{p`}&8QX;hCG1!Nwwxm_;>e4^Ix<7sTWDH71NVE>aJ4i;J3pAUy?mT?#*lmy? zKTx22bj60XNFS?#Jehm@2EKjsh3SfI#ziB%QFB)#zJqWwwArkle}TLBK-87z%9Sfl zlbylXdB{J@pw?%9uvc2o@l`!!<~-kEdgY2Nq7&JJT3X5C!gPUwfhx&~dueEDPy}>} zt{s6}S@rhqEfnhx_u{I#T%erd;^MGJkM34fNPwe7O1MB0fB?Ijj_$mNM=4!l1`-BE zMS@s@aDM+snUUz$i<_d#VVkzB;OHO zlKJ%MTfp0DWEqzc`}_3Vj2vCvw6ENgPULz}vpCVTZSOyL@DA}Nc*w&rzC5rmf%!Kf zpQ;R~jmk2JS4GI~;AdwR4%niM!ytm9xtE^){q6008)9P(k;mPK!gB>U;E9-fG~%t1 zZWGe!n%@Qn-T;<9JZT~sm2^C_rn-7Jyk+E?n~47*ItBwSr>&;qSy-_3+zp!BcOyGm z73JmMAX@~{2JxMTJZ3vkD=%NULUdN*3E*$r+cnpSl=b`fyHv&Y9oo0=4orBW^Bp+l z3*N4MF{VM7E>$@;34GJ(`=>BM6T5v&l|3rxAn#UWM8Ptz-MBFdJ%KQ5LAYK(c`$Sx zrXj%tvA=#jdU4mTU7Q6g_O2Il4TC|nL7wKne~tj1BpG`Dapp2AZ*re5lS8V6;8ysR zG1|8KZh!edL=GCs=X7;-iS+;sNc8ScpAH~t3N>JJ+9h^q{0)lk(>=v|K^DJ%|4u@h zJI3_n0vU-0=HYf}9i0PvkDu?y z(n3cFkBQOFIF(%f-V2C5JR$-3@;SwwZH3^PHR+zRc z$VMfabQ92jk;~7c@VQFYRwki*KL^l*WV-~58h5rE^knn4ZH~x8Da_H_ZfH+S)X<$b zRIL%x1^)w-CV~}!El{_ID5bAmJ89(ohd*J(XX}?(V;N=Gaf1sP5~F z$5$IqZ7M|E$9w&^(efk0>jjy#;x8Np^C!AFasy{N9zw6lEA@n}{=K^}6x1&%I~#U4 zIU+|~yt#lNNcK~viC5qi3{UA{FLx8RZ&TAwAIOJoCC=8x8<>I7|F;CuXei;L%mNr9 zpc-NM1MN2K6g@~!&uJvhez&bV$3O(eG+)wIRJ{M7hm*V$wkTAn;{$jXAdo}~jRexl z|KYFL)KGs)XmcijT(-m0q|0CGJ}v;7LoS{9S;y!ICS}E_0{X~DtIW(2*fm1eH9yTx z)}f^1SMJcLu$Wk^K(EU!cnX0i*Rc9%!SfoMCZSIiy?)*Jn?b^>w8vA?t<>>Zj#T~R z1BiNVmSa%k1}7&u{snW5W(H4{+mK9f?GYcs#)k{JFb|HX@liYAl<-9p>g(qn5A9hr~`!{pvVE<>D`r0KX7 ze;V$-8KovC=mqB6=eZbL>*;`cPnfLI(wiaAA{SAppcc_#=((UpI5t4;P-@`PtM^`b z?5O`&2`TtDns|b@R}YFK$`dm?yMk%RMRaDJGPeTRx1s=C3QyaH)%w`EKG&nAh8u;_ z^4|quBJwy0Cx3w6(b&WyAg~|B5pMG`-nEd|s$fV+h*rki!B}2Z=a%+Z-m_`kh<76Q zqQ$_erUw}j8VvDZAbc8MzFdu28lq$z6ug#DYJ@savA*UWrTzOV^008pfws57R0US} zT<$6I<;xc$tbqde^5x5GNOBk%5pFcXBE;_=ru+z$S$zEmEfL*CZU+A18HO$JNsc0~ za^uDg#KF+R%u(EksOaDGBq7iNVC6z8h(kqduoSrZsS@GuG04GCEuRQG??ATwVr(}R zlk7D_nTR2wmoG1aop_*8_)N665R4MRjI8YJVx%^p=sSEdEOVnebm$%wL*!0~5Fcbm z?ew01v$axwK~a4JDTL6#VAjRQGvZRr5zL|)`2pPlajUVOVqSDoTB(%+p*sFQuXjiq zxGl{bfz=-=;tG8p*~rL8S&t(kq=0RR3@21f+HNp)J7Bsiy=qa5uOujM!Xs`Qp2@MV9h`>90I+n^4J&Odx|xt zO4DLCxFUSVp~OK}pssdc9z%8K7(M6J#5U__7rXpSx@=*=D&{hi@L}%P{Cs4u>u9WS z^J08I)T`(xPo7vszJjc&j#^0HmFD4%JlE!PFcMX=&JTPxv$NxdynVjJeKE%gPnwMo zNdRBHwM8m0FGt&z@~o=@_H8C;2AV(1)-!RZpf}f|ODX0S>CBq(81h@{zpc161V+6yEL;#x;cOnnm)dtz`81w<+ zLfcTvQV_>Fhj?d1IT)Y9WTD%F6~b1^;ROW+?dV41V3o6{F|cR}c0h1h?5Y$5Z`tWz z%uGkd#IW$&_3D?4i>}Q(!~+uId=G2Z@G`bLqBo+X_d^9kl2wn} zjBxM)U+C!RK}!^i!|c|T)HO5?3OQUZ?w&k4J0ro?a82ujzrTOo-mEY=IwQ9E+Tj z?Cse!IVU1L(UXJdw#sZ*j)ji4ib`$+hv5#G=FyUg*zQK<1`B+424dD-6|nu-C5nFX zMegj-&;|&cxcrb}U|GvyS4p@+Z%Ibs*gvM8ie4GN6A}7`%X11d9W5>Q(JQ)suLeOH zB1Q_n6xxO6(pA!y~DP`Pu;k6l_g* z%1Hgc(p7HP)>kFh;o=K<1-W_N0TTYlxU1b!+WZ`WoQ6pS(MBqdu53LP%$%z3!cZD; z=tVz=v?k!}OuC7b%iA&`Sqd#Ml$BoIrm}nDV)h|nGnwhKYXcjxnem3Dw9ehy8icYu zH`)w0ipUE6oSkhuH;D3qKYuQ=XM%S^SVu(lfpQq^UI8x%$>DztJU0JG9n@ruGG2nH z;q>DR4Tcd=%!r=^1Do9|gVsVDK@MAl|G0RLQAHeN3S(>Qdl39b4+;# zBH0&pkYdn&!-fqo;l7QJ%M&AgF!_NMPZY!-lZP)o0FfPj#b*!*Mvs{dCMG6P(Q30U zU%!6E?3Nh-u8&ngd-z$YR7i8kJM7Y=t64_i`M&n&t;ir_;PhR0D5C_xu_vO-iC{X= zMYS%foK4I5PpePSlxC>pwEM5`>;g_1?59rU_Z|{v7IDEE|9?4rjg2?=Q&aEWzh4fu z7$GFUyWOCm(21MSb|1iSQ%DJi`-WgAF##{O(-uj$cgjV^@@uBng6KJ2=)M*PgT4Z_EnC;{@;&e z?LRa&zJ($S0~YB<8E6|H(0Ye=Q~9cD|8Jc?&7R6!w&EoP2k+ix&7HNExp=~KE?3p6~igiGe;+tTiw z>Tr~Dn;(0Fw01oN1!TZLKi@IYK>!(n-v=q%9-A9#Z$nlt47ghV5>b!=M3frqP5~XG zvr4SaNcoLBI6A_5`1bWipG=}^3j}PC0PT^QXU|!yhSL>>`k>`(%FrFdKBZ-1rh(#| zNB6y1bhqfne`Nvc>ij|9gDc|*&W83tBwFa{W7&t(pNShfe+B6pBG)#vqODo3ytxU( z%L)`eRv6p^2!_b2STMmw#!t0xUoCV8B3Oz`g;Ek_wKLuBh0*Kl!9c&*i9;tT`EB|$ z2VcW?r8F|?Q}5=OFb1^>LayHtd2F;;Nvu;M1pQ}afq<^yM-5$%kY@pRJ%g|ws(}fZ zy4m$khC)pH5rOa@g?&gPr6QCFhLhXdeD83(#m?f$xtTDzCI&fmWwk=~uW{d<19BZ& z%-B;S1damJCis9PX8su&6e>^+G%9R+XNk)miZfK|tXCBnQ(&;G4;+a4Bi3;5o4#(zenXeDOa}iLjo1Hd z8L$WJM9Ko`xc3N@VMgRQo-`gJf@^*M%|NX9uLk18)^fCNVnUv9_ih@6%?j&SjgOBL zW?|`kn<8XsC=8vdu;#890x7~=L5ZVnq54@&R~rQQbnG>Z3ACH_~G6 zD0_H_LfCNF+=mbu=1-yiM6=vSS)j&>hGPIBET=8zIY@k=?N=h==)>+%^5O+AJbz$5 zNH+d>TB6~Ec7%}Ezud$PTDg*9+E3Hc&M{1FAuKkmf-rYO%%GcqPWDuI$AkMr9N9@}Q?ja0^1POh!_F zwhuDe1ANvjaP{1qZH(_CUMR})<($JS;|p1Yfzlz^8}1znTx7M=Oq;sqGu9QJH*6h! zJAM%0=g*%H4ex}5)r{=ZPzkxDCoz2v=rM|Vh)BT2ob7rN^Ig-}W-C2jRm(&~JJ zd^1jU?tFW<|K-;^NQ-XW;`ntS;FLg}Z76F-pWidUp7;vTizE`Zh_h zt76^Yk&l8M7yX4t3RH)*woq&O%59malRnRPX^U9GDHe;9pL~TLShPfZ3Q*YnW{-?1 zrOuh4<7#_NrOw`Gm%e-M>+e6eZj9D#eEr?mxZWejI>-9P$oLD9xhB!YKV|Vr80Mvy zHJg5KZ?f#(@*@xuuGMR^Oz1#F5QmJ6%;(V~T7>F;*0aPL6rNaq1$7r&v< zLI3nemjpbcu(O-K?%97$5VH3fya&{+e5Y}Bs2VpWj_@M@44wKdDlmu;RIxWe7YWav z)g})(6l1)?54tS`cA~`w)^>Dt?FWVN!&ZX4n2!y1-4ZYxL+=-fBUbqN`SEDZI63iM zfw}nVd&mk-Ie15hj=~8qjTnD}`TG`X*ui^nN#YRnVDU4a@y?w7Qt7_YcNRL+uKRI zz0%UNvZPH-nRtuk6&2sUe=P9u6W=c2+~yhoed2Mc?K)srJQ8e zUMl2ZLZQ{9mzS?a#SpU3Ma)TYa4#wiVJ&aQ8hMob0cW+KOR9;ru(x{5x61LMCmLo) z4F9M^xgt7fM@NUIfq@cOV$&#Sw}L@0HqYyx=p4g!IEK=g(L0K6$ivT{;yO2?W?(=+ zCxOwXWa3a0+}Jzp-p`2MD@jW`J3CWTQJuwT^)X11#NI-#Ln*1`7NT1+GJeo%d!{~N zBDlV`_D+#L7yM8SSmy8J#2yC({F?4lfnRgk#zqNMJQ8X-p5{v!{5a)<*3!x<95c~) zyRG18@)$csK35v|^b&Ic>S}6!4;@N5-SAk<{WKs2apVGnm4Q2kv;wgrotK2;ho^(# zw_(ja#NY&PrMd(yW8+_EDAV3o$XRmDeDKKbXb24^CawZ5oO@#thnv6Kg5dq* z1DghJ9K@>%^EHUIBss_ANbm0jvZE|`=IG`os-xp}7dsOts3;Hp1kvMRNXWef88eJB zQlG1^?h<|Z_+ZuSN?2xA7PV_$P7aar9IqJx>tBsMa%*s*JSn+va9UtjMXriE2Wf z{@zznq38ce(9b1iXA1OlR z_i)Dg5&xtJjK4ZHiy)^TfXKa|Ej0tzp!x^k9UhpSoh75BtV00u2nWYK91L;^5ElU} z9|);f6ZK?OG}P3_2yriATp}Sk`8M({yg&1>I;a>KLvbm@01I?QoDD)EL7dr!P#}`Z zK81yaElOoL0|rA>wM5;CL-@u=aOydi#4OswpBuM8#{WFesKU9^JI3!p}7nZ0lfC+eUA5FH*+Z5NgrfVc^! z!-{T9GYHaAAjnIM=p+DD8RSf(svJQ2MEv)6Ug8W59Kf*eAc@8zuo^@m1T>O*|Nf_m zi5oD2#fdF?8`4f9=K4W#aC#Ucnh__TZLFW}fzwwHzyJ?~rg>MXu4?x9eT;+y{FF{z z!E$?y-vqz1UmY3g7Tq*W0J&?Gd`^_#(V7ms}=QH zJ+QE_AgS;U29G2X8br+N!Q;n+nDd^Qo0Ebs2e^W>m2N@XzS%f@3E46o&~6F_(Evm^ zsxb710b4mwPcf*aNLOvmGI;%}aRFxm@obG79v(&uz0@3mGaSI*g8-h+N=a=ZJgO^5 zsu8o*c)_(;K=zO-NfrXOu~2+D)P%9kwsb1{`wer-J(*2lHERKJYwPG>1~8aFSUEj2 zGXhc*ltL=1R%krLObvZB8w-mZvbf3k-fur$BB2)aGf)K|}(OFS{IqUC|Q7 zp&igXssVK4?+Lm6Ff$7ad6c=Wt+KQ>HFw1uAFXxag1V(8 z+lB-zeV#fVo}JL`umU z-k}PL178_Z3790!jF~C*cCVfUlwwC zFNT&?TBkUlsq8$b!G*d+POfOzmZ_)>HRvW{%m|Ub8Fn~@#9L3f=WBx!ycH5>1nt?& zU$D-J^?_m1rr-+al?|J=CZO?seXn!!4HcQ}*CKnVvE#juK14fxNy6*rp*_{9IfeK@4TMc!Hm7V=kJC9MR%S}p&)!mpD-~eDD!W_Ujx0*+p2;0-2 zLI#mmw6Hq}UmU?1Jfv%|b2PQI-hBN^k7`hagO7-rBH{?L%hV50uZU0uEA!m42L^Si zfPW_)DgZ))f%RvWJ@A7^a1xZzzTLZh;L8vbP$al+K?pvSy8PUz@$CE?VB;`^-^JrY zi3$$0`8JXdNcA0jom5gHj3hoeKe?#W!Inbmm(PIUgUNQ+f~D z6^138*tq|CG520NxhF+Ddh})Bc?a-xLRuObmL#%8-ynMmy8k*cSeBfTaTn)>@CjbFhTVJ!Mp=E2o?_&ss^6UStX@i@K}fh z$m*XzCO9nyC-W4Qlqo_V~GFo&T)pBvyetTarV zfL6-9g&;Q2@R}CE>@LmpzabGviO7yQ;(g8h`X!4lLmU9d5L&mnb{^0b;E_1-1mCl| z_IvsO@0Fccu_ThAp&`An!^;$BA%Gr2_eH7p#Tqw3sQV;8|BsV>01p_MrKG2)Cr+jL zusvzzf`I`s^G5Q)Ss=u>qauF;?5_r~-arCc2iGF7Q?KP~T^&Q_vI*y!*()s?YIi=f zR-HHzj$>3pVN7g?$6mGH$m1rlPG7$^MavVs)=vV;u*V@)GcKY4ibsze*?0ie)vt1x48 zZLoG1PS&IZldUEY88>%x@?+dC2;ogs97PG^6DJIAdp>=O6Ah1UfzaZMNfc;}7-6}C zTr37Eae$8g#B)ff{Sy;A5^7p15);p!J1toWEg=D?YU25zH{evIO(<~@CE{9ITGcf* zCeZj$F84kpI5;skh+iCvIPwuOF@p&d<>xp)@5IYyAW&vzW|!5a{PyAeJSUpsh6aVO zZIcrdEm%&5S1HKJ8~Y9(y;K!Nw%a2bB*@dVtljMH>)Jr6_J!O`-*o!Kq@*g3=rBvy zsqd_UQ}7*H3+;>`9-cu5fkN{Jf{{IrMSwG|px;L%wwgD3=7d<#zsALBB`@T(DQ)v_O`UNu|?Q=%gyiKC2y*6!iF zf%2tqbC5D-4+#8>~f17~z~A1=QKGd>wVJT#R2YC0n; z>voa#6TuR5UjtxCsD;co8?r2hs%gMb)Y{@YqiHiLz%6+8mCV z;q|BG=5C8`#%W$hpL!ox>Vs0#{q+!7BS>rOloBPmqDmV?9lhLJkg|xw9Pr+*IXasD zl5m+JA(!k6kO3u7RY!*`q2>=xecOYX!B7%keFM|^9 zvv12V2qEyQDH2iyNXNP*k+_Y@i8FajEG<#C$WbbgTVk%c)!422>nRs|u2I1;LQ z&T!VX31HoFL1x{ z(B+UjL9;Y5GxNi4mhGS=5%D}^1rc{Zo|y`wds99-O(h~rpe5jK=1-Mg%+u0uf5xR> zv>O;6vk-R>dVto?vT)fD7lxzth(I)vm?xGRaiR?R!3K0r$QuKAak1q$ZS+EpK`DA$ zSGNt#_2j8j8=&tXF_SWd7=(t1S}T?ef}?qj7fzJj6FkfC|B?14P(810+y5_Q-Uww3 zrIM1!oGGa&k|rrblnfb*5K<8uNTosBR1poR3=x@9N})lCA~YL988g)Tx!CvnJooe5 z?^^%0{(C*^S$n(5@Av&)*Et-=aUQ2(tMgPlk7mt(eZXW=B;zyHR}tkQan7SHiH(dD zpj)pgSI9XeTbY5|T_Ci~tgMzPuI`W0k+&Cf{rXYbT7j!T#CdzG4jj0XN+brYxwkjm z0r%S9+nb_iCOC?Kd^WC@)2nF0X2!?6me0&ciisF-SB#=SI+vI@Krsr(x^DY3k5m3A zDr#fhp@GSUw>Rzka_W%10Z)X$&f9aBmsbEeeqiB6&d<4|B$@G{XG)XdRvg!?IZ6J4 zlRpkZM=QbKG8o$5+eYyU=840~=fj8r7^Uycph|_AYIvCLT81lChGNT zM@2;&*kkF|t-H#Y(&5F%#LPyQaRBBx)Y~TNo;p5~#3!BuU9%F34pBZ{xHe>MzxP)b zy?E|JO{X<_^vOGS43<78zz&`;;peDi->Lu8av;rSdGYcki>OuPA8l>==}OWa_QeuWwP0@of`SxHuPWEI*>l?yYG}kp zE}ZCH&zB+hGDCpd*4WrsgmUp+dzyUbrMNxF%JKlJrN@?%2(!Nym(L|`*hS-d&2ppL zS~Un%L5xz_OC%;oC)@%Nt^zfS-8ch-dXRGYdQ$56zGK%(;ALBKu@@~}dM7=B`rSS?Oz91pa%+uNPOq8gsuJkQD zH;QucLqmfu6;0FE8_kPROOic2DV0XVN_mJLv$-bu$@jW_ixeLnIke8zb(}~AU<^y778MoU{f`x}?Or&nC4(B|tv4gPjAwa;v^ z{JEy&bo$Tn4^VgCe7UYm_wHW2+j1_zSU_03LA>Z_ZviTVf1;To%ZM0Gvy3rHWL`Sn zN|Snyb5>$Z*Av=N3{N=?wncrp^4*G>)K`i}=z|5MB@v}eLdvKi?p9m$hRsF+@2Kt$ zjD{u$NO%Qm7Bf{5wb)b?s zIN5y?nEL>FTEtU#9=pI1KTcUc=y)ASpBSvJK9h|+AzV2T-PWx~kCNwgJ3^&4a`b57 za3%4eGel8fe!^d8rRZk4krA9Ty~3AzT_pfnW4utAuDw0{ z^k#n5BXm$c>fYxP8F!!~OIuXPoM4;2JZ$QiJ$+a1%Q1d%-kWP&9=4OFWP)e zm-L8qA{yciPux3yW$}<9?*}~Feq8j&Yo5bs3d>4jrr{Y6tZ;or#aM8{kQBa$xmf|F z!!RkLDq+y|Mg8X4rlz+r3TN_SFT%vb<2Q9eopO-gP^9IKy|h|UZY+@N(5*|)p5CJA zAZTG>u#LwlmEtSlY8vbxKf|yE|Y`E>L>TX)OMaxqay+z9*ob z&&N7YZ@%d|XXiBT$F98}Y)4U%`J#*K0)q0)tpEGH0O~_`t?VK&+rJMTGMzuaqnn!> zIEqjkWZk=`2bGDaWwE1UdkBaRjX$j(<)T51iI1g`NtEa0Uju}qEOP<` zrqr`%+;QU5>@PcFb^KJzz;^*iZVeeTX4EKwUx_}5*h&42_0G*zG_ZSD87wOgj}qk4 zpAP+g+oQ=cDF74sDib2*rKFFLkVMqgE%Q?2M|Ln;X<>g-A5vcm{ttC3t7h;kgH&X)Ti^(`d6PF|xyh1^( z9Xh7%+q<_5;26#PeBbl8(;Av(zB+m@xMH_>@hjt2GpzW8g8+LdxucNv2a)d2EVvp< z)|f>zSJxn3J_u?pPhR)OR-0jo18-S?6NpzXBXezAV-N!rwJ`UxDJMPx(~H72TV~MF z!Twym7CN2#O{o2F851Z3v!+n1qehNIfK;)ZvO`aAq}%rmk=Oen%M%oz9uU4^Wo>O% zUszQ|QngKzowUP}B^SCmcQ48XHVhOeQkIJpNK*q#BXcbG6vVjT9vOVu=WWw!R$X1) zu7+hxmgE5rXv?<=z0u}vfh>LYy!#;6>u|ir??)^u@S^A^TGr#bCWs;)7ktc3hH^#I zPiZ4~1-g}qWyud(nFIC;JE{5Cw#dT%Kx=ylILBes=+WiJntu)gBI>1qj5GXM)qj8k zv;-DGl}Xz!hGywSGYE%0b2I%#H7P>7&~fKId^nZ7N>}0mSM728rJ!KG;dvQ8#uWHU zoKm&hfA9pe@s|@5Q)RTZ1^5w7^){OOpJK28>;1@-TeSYr>2e zog2tJ8ZUG+DkcnZc6Z7l`?uJ0dkSp$d6UDNmu}MUD4k=h;}@~Qs?HU6!3SCMMerfp z+~%(AvM7<}B2-lK1UA>6=6-@DmnG^!mM7_2%{G1o!49Q6P(eL`yBpU;1X)iF6Q&M5KW29=q`*Tv zQ&YE%->Mvu5tB-%go?Mv>w$T8Ba~|G!4bD(>#kzFa!URq?~>exuX^j;mS1hR{WzgL zfNQZU#`wc0C4c|aPQ0u^Bl81;$LRm4q+nZ`riNCfFACVxam(5;FVlWOs#2BlxLg_- z8V*8@$ouCv4E%;j$33uE&9sjs_T%*RzgEtG4Pc^YH}$vF^6*wjr!IcHiTkKn9rA%= z-*(qLsdT?(zEf#>`9^m7<5{V&|NHkXKEt+<3O+HS>V7tnLHk|;6Oclb z!aLqup$FFrt0{FMy?CX#U5S8mqO|3T+}lopESPSHY6)ffelctc+$WK+kY?l85F!KD zVfw1W4;sGe{C*N%TS3;YzIQ2l^k%@siSo>Jjb)AllJDRzB8ad9iinME2i99{0;s%$ zGDDOB{5FYAxiwSTf_235Th^>!gWaLdTen~(PBzJOf04MXNt$Ueih$a2x16(bVGqhj{GIb%FPv>9sj(js*CV{|%@m_UU>O;w56xJA6zy?)!Yob#X&8MF8D};^LlUJt0Dizt zgr4#f^nFLs$?+HAyYGX_YWm1KaPNOpoJTsS18|7S<<^a+&zcYufS@hl(4QTu68>ut z#)51G`s7*dK-o#>`95jpQLi{ z`TjO9KPnZ{bzS$-np;gzq2y0hm(;^0Rfg#z#JOm;C0Ki4%>Qhj41e zF;rqRVfK4OUFn0bVrJQ`07uexG}F5L1cxcprtMjfY!}$iY0muxpS8bXzs~Lx@5VJN zRv7XgK0!e_E?+(XM>m6+%z3*KF!az7>*;Oy1EZXRcj#*B7k%B+Qwl|qImcFj1Pmw2 zT%7wd=k8ro8gChyCyyT^$Lq_lHL-IdAN;rEVhZOSJiV5-jvq&sX0S7wVqPXNF>wxa zCi;4MU1ahJV$=DIbi&L*k+oIGQTQ-nqAC;;-rgrr{i zwf^Z&@E`@n#mla9RGNV&>4zgokuox-(9Q^K^TlctJv}s?r?@PNilDp$>29>a6l7#H z<|ca3!p-DeTFjd_17ri2g|Zb}t;@ERv~Mj(dvL6D%h&0;CR-OIed9=C>#AYU0y=y$|*@^rrwHH~O(A?SqO zKgx^vVIb;gg0(@P_FTzT)DZrQV&UTQ!U%;G8 z=apY{LGC3qSP3Z(L)H#l&~WATy*Cj9Tjgg+UGPg%@*dsk!rY2u|D7CubMYT|gBIN* zbd;08H*y3l(@4jlJu*&RQ?rNBpy{Q(1dOrdgv<3uGWX_fbr)y@lX4H8rSdDl{dZzS z26nLX_RAN*t}~xYw|%5IuO?)}1nrO81LRgbSigPy^#C_rt^t&y)P*6QqUYDAG~?ok z6%=>Y#ML#vnH6Cn7kX*ef7cKheY*K2IT7#=R9K3JOqkUGJKUM@At`bC?LIFTmX-J( z&8fnh^78H45~K}c@x%uhv)hG*-M39THhgaPr;Dgj4)$?G$Bku5>Dj(6E}u892??6+ z_vY2BcE*k#a$5r*v4Nq$ton>Tm-y1!G{~^aER_(I5gHvdHyz+b>qZ_sQITKrBl6UO z4W&nGNKOJds4EBw3$y2(FciOw0#7n*FynBE!o>=1r^`+pY_x3c&Ef8g1ZIz1?(`D9t2&VAO#AGi~a5odbN2&^{)Y) z2kczVGH5($3qZDXizG1~y_K01x<>ytV4@YkJV zu}OdM?~IL2;! zZbxEk9srJkY&2gu3_wl>T~0+AIos7WrLax_fKs)?c3aP5AC?j8X96z2r9$qF0OlE{ zZO@XZu}tmO-aq@rxHmQz`k-7e*)xH-l+Z@h~)So5K8CnO`+p8Ch`jhb#@GCaadrT+~sdK3{zLvIk^5soC=^jsrT6;v{_0LOkr(6JY{;fOr)%fW0 zb;i@R!^@`ZhpW>|5)uH7w7 z-cU4W*hO*|WHb}D>+emXwiO`FG_(-NMvNHqga(1fD|qy1X~U(3SAr~leuB?Tuc(hf zeFq(Ocomch`%n zs*(9tMPr;cY;2n6_fSPyIq>*#`%@0r+x_bLwNLkp8!p00^q#n7B-5Xp)cVb{vYJM! z+#7LLvhkI#&{yv1GUy;Bi68jSh@6SErQ)0p0}fyTPe0P^-pCu2YZ!8uN~eVw{0z>i zin?&2JB{B|IA)buhrPLZEhRt}iOcg94R+WwB|3IP?d(%87uXy>b*c@O@&xy$`HJ;s zQox&IF>R!b6F@Dftir8aVS(GVCsMyf4L;p=t)8)L#rfZy{k;=C295k4_g$rvVeX9! zsqeP?{P=5QI*1#N7G9{0U|BY(^(#fMiZW)V2`keMt`AVO;Gg?7ZAL2ERSI@Fzl|D8XdH_&z)Yk+2cC)XJ| zm|O5mf7DU~Bn2 zUEx(@SZMJxO{W{TlKJv1oSd{M)zkAqhP|i%&QznR`&09IRy2Kl~1Nks7( zNjCyAd+)$-kTf0w2wiv`Dm%Q$0xoO*mxOIs`V3YA3GBuD9`lN=$UPJ+6)>o6|N2Yz z^|6@i?erE?F*~trg<)YV+#_#mD;bvBoUoXGEg^1gdBCTiGjiU%>oMT_n8$x3sbwll z%q-y+>F}jPy8XQ7SxAfOfml0Kt#un3t$&iV7?q6k)2t4)S#Ki747oFJ-gDxsJW1(I z;FhxPCq9o}wAi)JZ{>5;$&O9Y`VXoK@_D_IYR zDo#x2O9B|G0n5i2SG zy0q29zz)oHb#NPU)rf zXJqF0FIlr=Oayg(!lW&Yv@hN{RYCL{fWBrx6#(=F!hYyPyUv|Y;l%{Ii!qE27pZ%f zE;@91OX$29W|~<7>L#;4Q{c-DpFc-awSC7&fz0|lsu9e_fb{O+WFMR$bgS0$<{f~* z#X3hTKlK>h5&+Z%ETkGfeNtl94A@g~(y`}@pKHe*ipf}xv}YfuVw%W?b#=zvBD+kV zn2g!OiBm9VS1GaFYPQR4TS2xd8s(%kKs$>;4#_rNxT7 z#i;P72umSG3bitA`V6$azAaoV4&vFN+1s^e&qKtxrA6k})`rdBi*IDXU4faeK=v}T z7m4_P4@*FaLpCmFHO~pG(cpJw3i64Eo$1~JnMQS3x>U;r=d86OS$T`CoRY{8oawtT z+r!uV#nYnCEFsDxCp^YV!YoX^uuTyUf_6cCbjE_j#zFCZM6n@W1~tAam==F8k{mxi z9~SWbFztg!jtmx!DT^g2=?%b@z-B+qdYC-QU^{ex>y|A+$VTz)!yUgb>s3+UY$wMWuI9z(gc;^2fRUvf-o?ak%5bS2!P9ejbotyD~PM&UNo5hjMR=A)PQZa;P61Z!zKw{G29EYQNyCVZ}0)Y$)5bK7cVHCoR$`!nAROWVB6 zErO<`4pA_lwAAf9;~o!IjnYHnv^|O?919&RK0 z>vjuCy0>YH*TxskLvjJ&H7v*Lo7&j4 z=dheSgS2Mva4X7>3Rf|XKwsWgTE#(3=JWu)zs+ac5{+T%(!~tQTr;y;+o1ge^WT$J zX0sC7wnls>$Q((Yb4!|q3wn)WHUWvJA~ngjN&Uq~?>6T6#m{al|ItMcFKH#hy`^PH z;qWEtMSn>UB#2P~paHBu5kx;(5e`8iIzV`gTQwh(*fvrM}OMZ+%Rt;7(p+C4%q_o6fBckZ5jR8W#^`zk9d19Q=XPe81r^0`k3Cl}zLe^W^XsxGyh zJ-bV{T)}1FY$BBx)ft`o{}M^lww-z09~4uK5BA!IQy zD{bQe$5sD)6}ho`QMXqoSf6jL=Y;@k;i`hG#_+GK(xCDm@02p123j{NdV--Sp^!pw zR}OBOJGV@ZMiM`h+?gL%IyxTg(wb)k`yL#Z3SCdvyfIc|qSG&oY;S_jJ5jUEdZ;pJ zkUhFp;36?{1R~b!R2v~P$;=#)^Drp1r38N@c{+|H;1ZvbR2CW{89r@3t&0Rv%GGp( z^SpGxsDtCytE^#ynMOsySYA%f3Bn`|qd9tg`F`)o1&%9M($;1hXudaQdaniFyE3Tq{J=$VV^7G8+2`wPcepSAquAf|6#FbtyPYIm)X{@1$MIvS zu=GI)k4|#)Wrp`9oM7jf%6f<`{sv^BD654Jcd^+h}Ov|-(-QJ!Z3EF}ZKq?PgtdQyVr!VY7 zbu?_`$aFRzfCl@r=~vj8`0W4mt=^te`zG#?hS(I|nczVXQQ*PQXiDWZBo9T}0}&O} zX<`Sz^u#F>Z54L-1&_V*V_9f=i-jeZ#=VcbBJMC?^)k_N`ge_jE z{9dA0r)U(*18!B+&$hPqA1!XMAxwxza7z9iv>i2HDgPNbY9f{YOL^);kkZtjCTPy-GiL0BtrbcWbZJAS<>pvgij5dNSM60R z|4R>d(rw4w1rlslg-PkKwV^nZ==(+^|LLx!rQz3_n9FEaIyJCF@(&Ga^!!iz)e(N+ zt=^uhkhEDF#PvV%!m|CzWLZt=yvS*<|DRIn*u$M{I^?>X&`_CsvTM(wEj12wpW=~@ z+E9oTpr}d4i$mkI72%+of4z5ynv@;&deIyPnuvd~ur4=pw=fA*(+@^58!RmkoTwRD8lVA%Ngt9kcy@u#$fvfMez zfD@kqIlY8~*Tq@>B78j@&n!m8qo!f43gOW5YiTuo8JK1%x z;o;~}ZXg3XtXUy&x9 zwD0XRE&S3PP(z4F?}7 zB^*#$T9=~3?9fegN1&VdK-`nw$B>7I_w0G|{HQ^yPpW#-!-HESa92wGbA6o0h@Y?u??7(XY z|G!d-?3 z>eEnL)qPj@htufrIqAxkzlnOPm?L?6i(OPehcvDx?oEw@P~<%1;f~h`V}uy3&naPS z3Z8FiWyN5>%*RF;8MCmj6z4-P=?A^(Kcg5o1|_;f9IN}Cf6sHL<^9@wUPi;{dU#DU zOG}5domXGly}NaF^YiHFctDmZCMKOJrU|eDE(bm&t(8Uh3MW~j&62vXxnEm5O%|X0 zdv`J3vPQ^>i6QqkYhZ8DkJ3k2@f=WL3RWUSaUV9PcCw%7GUqFnS^F_`5ZYw~m0e%C z=E)&Y#THshvb$ri769TKO-3i|5N(A7Vzdp&G7U%tSp}z^Od{_spjoad=`Zk(m%!5} zdZMzOb9$~Ps6uz0oUYH&4ka;0U;I=nbW`9^*9F&%5?V%FtMPm>YK4z!>F?q8>!(!`Gt|C;(qXku1vo7n5Q(3Xp$)uiL5RY!c^E#fFrkO_w8KUypsLe z;Gfz>sohpFHZyVx9m*7v72iRx8hhK7r#j7_Gv`sHy2GZ|YtG2on3^iodqtknFd;nC zbNB3Fs%W>$^tXa9*?#LQ^y&ZEfhQ@58bO)?>$DNJ1^ z7kV_xN>}H?7hP2ijSMORapBokAgtDyxm*2sf@@=HMVCYJgcREt8Ob4>}o{nDlU#mo2h2 zZ5#R|J13_e=My3K0BI417?g^%6JqF%$>@!jH)Q@Mj2edK)s4~Sc^o-ujdUh-i1iLM z2KZY_fVPPFwIh!)HX)psQPftD2YPC6P~{yTUseb`2TNhI#Qw=(f;|@(0ErbVw8;Qgj!h zghTAjkZIbG_>1onl-|YtVU*Ai>TpE{zP!%n;URMq#rilAsOhkGFbtLn(lC^r1&{`SbG`Ldbco1gFLr>>@G)=Emsba4Bm$YOtKWnVjm$NM(# zo37Zq+lqlo7#LM+ukk9ny5wtp}3qI@m#&*5?#skM5kW@_a zBq`>1isCF=I(NfB;ZW>Y)QPb)nc=HqYroo-HQ$F03AsEZ^)zLI*knD*p(09{2T}5A zIC)OP3YU78ox9tp85z%K)LC;0O^XJ5R=6g^wExZSX25Bg%^LhbA# zCJIOyRdFT_O9PqMN7)Z`rTXbII1n=pC*e`Gq|!G-jgW5PBXnl#Dp%(tLR`~e(mW#RZkmKuX^AsjER*LdNd`k|w*!7ERoLFMQs14oa zw(ujl6W}*)5uwFyO%CRT<@q}pdU4qXH#iEN1B%KM1EXIzMOZ*KZ6th;)(8>N~xA>v8lVJc5_ImlciQ#+cU-46V`tvV}UTKlDjNV=UuC&2mZ0`r`M3kZO2!v11@Kt+e#2 z-d26?$MQN=miu~j(M36FiO6p%dvc}=7uOTf(XxrRSqZ0e z?ArAH97r)ua`6g4Yx?;2sRQwMw6L3OSk_5x!LZqifzz8}gOv_C@>Ci3LIjIf$a&ln zkf*ml^MMwHJLLcMy=ppGKY5YT;R5Kil?1~R4UakW5{s9^j<@8zEljBir*OQN_!9V1#4l0Jy?PQfA?|YqP8YR> zvE3jz;}R!ro+RbmProkg=lQ|Ie@;dW&HKF3ah_7wyOR(1kjdC4?+W^ikG^PWiH1U{ z=IJ@b(=vce#3t-uo&k?Ha^q>Pr+64*5g(HS=dcQb>h?AMEJ^XaL2}vkB@!_LZxjcC zK<>LR6eI%aAWHO{|M?pgX@ptqm^3Hv%u||;n|131XYfda+rf@Qi(f~l@_IPtO z#7G(;EZANx#Fx7M11@TbtDa~P!FMMlXu``#$aNm5?X)(%n~!r}_L%3}rZPNKj~E^0 zJ_tOFLrcc6447FU*oY;Vj1`04+#^Cy$MWkN+cR0LXU9MpW|hJd9_xwc+dlrqOE5ow z>9kuO3yj1%1z4Tvy%rD^4M?7nSZ37Y+O8mXNgP;Zk5?H2V}^Pd+*37h`oi|CT-?S6 z;gP(|o5Q*83`H#bTLT}s?**~ugV+KL&TjAV^hFgIEMp4cR;$7*9RdgS+zhp=yPvK~ z{b8g{M!PY5!Mpi=ee@a%c$OBiX8P8vKdOZUR{ePY*@1)1q390CBjP3VB1Ba8qNRol zrCi_dsR_)^>dK$njRfSRUB!kk@18O7P(R~BZBagpjLE-upuuAoTpbMzdi(b63d=*v zuEzh|Xen{nsE4jQj#$_SMR$FiaX_j0kqA|0qn451YtpvO(UtN^%vY+Z#oZK5 z*Nf`vId+XmfsdQTcHfo1_Ijg1-Dco79;7|srL6rr=>|vz7O|Z14l+~{KWuQgv&n*M z)4!Bu+cB3*TXQP?W5cq}JU$gvk03*XGkefKvFl82!)ELS`xqPFcP@U&D`jyGBA0cM zY4f`JoG2f+i+-Mv@Ayd8ZWYu5ZCBNfDcCjyG} z0JaJb&z){hu>IT1HcXe@CX@!x9}J)1Kq_Llv(w8oY2-vXK)iT7 zD+%~MS>E#);reM2+N0->KQG;Q?62@;ti%reY85?|j0U)u2k*X*N+2;m^#b+XU z^Lb1d7Nlla%3p(q*OTrNtd?zV?U>nE1d>cP>Skh++fb(Mqi5Ffn0wPW;2!<6scLFx zZhx!^US^m&L^CI+VON+{tOY(H@fM#gY=$)eJ|L+Q`_qXFBUq-3I_)N>;~+c7M3)Pn z=&N0W0@L3pn#%eBQ!luUq_8HD$8!pV&gk5wpu9(qs$s`C_B(Nl4`Qe-#!uUyx`%{{l9=fr&5%NPfxkYXwNzdLv+nfn>Mw%iD0mE z=gxq?wpo*a)s>fKK6w(3v^Fj_NbU~dn;X2ZWD>O;uIGR0(56DrDhR&B$|`Jf^UnjY zTrKjhyKSW-7H<3jZ&qMAXPf_1b?^w(wWIJtZyCW=;*1P-E5n?hlfI|n;b8{1Jde3NzJnkoJeA zz82s%%CT^E@~Dx{ZYfwFTs+~F%M@JP-s%Z!H}%8!$|9(owCNAzrMwb|-=s+E8^K*o zoG76Q7r_E(WM+6(;B)(;!ondR(CN%;oS(2z;7xuhTYd)|C0C1*LQ5N)zt0`1>5B#b zq9sc#Uif|INE9a69^*;LxxRJyu&uh3H8=5YY*oE|^QH%7=m<9S0gJ8RaZ!0o?=EgA zuBxb*N=Jo%wSKf&5({r}p|^4EK~&>Ow2IM_KLRW*{6Ys<QQtbBWoKDYBWc`w)_ElsN&osbj03IjGd(iOLZ91>H} z1Rwx1su(c?Y80*J{NQ@xy_?bD&ow)SM_P%G5maElX4*0aQKV0vAvm!zXDQVrVFMSm zY-)HZu`7W?Am~dRSj5aU=`F9g_!QOw-0%YoT45MIgV#h_ivrZE8g*XC)e*U{0X7>{ zb~)$J^Klp+F6S5lfh_2$wWKY9;|_ZU@lq0Xhd4LfUXBfp7+MSk3|*KyH-fG0H$e@B zzd6x;H`qeO`}fUh8~d~OLuW{!NDfLtX{J7Q=N{pG*he9Kvf|eF;Mo*-13=vw1Q2HQ z6z;r!*P@ey+bSTU6p<;F@Rm^0*XKkUrho#aq2zc`r1Ckq%E8sTsZLeXT<2$hPTHdE z;KAFP8f&tz7i+9{LZAjXCnn}hSJ&&x^1x$I4yTO^wOEwSi_}Dt2-21KOH|SG_1;@@zRadIZn5A z`3n-B#TYn5aSK}YpStG3*NJkSKWS0_(2(Ds;=~TsOUKVc z%Yi%FE^3CLVk1XpR#sb{FM%k!Z--8u?v$1F<4=M&!^kH(zh$5v(HRP)KnbG$kxP;$}Ai#^8B{;Y;S z!ofQSN28y(j+6!|>q(|-Ay!WwWvZULoKxoc=Xt5^GsM^4useN>&kIU;qwy5t0`=q1vW*kxi{72IbYh-MEkU+xxPK1BzGBeX70aNgKL{aMxq&X(h``xFf+ZF&+QsYEOqA{W0Rmn5y;*KZ<)-y=!NxOmFD7*%cTK0Yx1DU~wo z!2by4W(N-CnlzmQQy7SCHnRB_Tv`N+aKQnWN8=wm#~nO*Vp@^EItz)JRlJ#~+{L}27BhVwJ_$!fpf`Ob!sC*>Dl-&Bf2kw8*Gw}vKYvs0ZuSx`J~qxlh*487j8@hZz4~G-TOi(SFAfee z(v82|s0rNe+wP_K?(HcLOesv2ht^o$sfBoBKiQ|Q^LqVD3(%%<>U)hrv=FrUa^DZ9 z4jry?Zd+q^PEYwi70X(UgplL*0DK6CA~TVUWfNv>W3F?TF21d(QeagrHI&fj3zhWCd?6n3Xrps#DFG^EA}AM2#Z0iV;VO*5Be%hz|{Fu#`@vd@K6 zCH3OX8$SlCVK&+H)0Gp!w~!K7jV{ZMXs)y7^i6ub@JVi4T(6plv)0v6+3cmc)q*P< zrkI-_U~*_weorv^7WBdTV>uFkA zxZ_0=sJ{Psi|oo;IM%?RAYFP!5;_~e#eV>}1&nuQ9%Tx90cgd@h8>XMP>aXTyL8rO z0jXSCE40SgylR}hYmKY{k5Z&MVeo=(iMJhuxGU+VtLy5@watymZwh0Nud2~l!C_e# z=rjHe_}k)oLvCoZSeWB0t1i46SqIBT)xA*n4Rl_DmZ$ch>+6U|>$akkbJ|j91L=tc z<+OA-ZEGbt2lQmhcn29s5c<0fsx$(yi5kmQP#}+R;O!~enfVg5 zJe2Gp^f($CgQGNE*T-IHo=D|KpXy5=rT%ahk5ENJV;>!iRLZSeNSHs>m0F!ywQzSm zcfEzM_yq-=y?i{e{8n!6e!d^b5yY+4?%pmNHVF4GkNJDV$S3yoEmI0!09iz1gm1I} zh^q#ALP8<^0#_wK$-seQ^!I(@Y@It!?SZ$55ZsA9xBMBjwWBbUsGQX-QY;;~;2?m`r*JVPLVZN1$g9mz2{F=#{x%w- z9vB?5>r1#*XSK4LDs^gJs;|>(S$jbbxHh+4}>j0KMcM!g{^fB zDGbSFG@Zg^V+r?G`U^CmJP;XqLTFtiY}qgijh&$s8V@st^uec1LkEa zCx^|cc{9!>mZNxY3Ax3lALGV)%Tu%DCpG_EuQKzX4p1`SGLyzKV&cJd|24$OM)I_n zr{|}1B{GU#l*AixxY4xZ;~xS@_K|WZ|NJr&F*s{_Y0UzM!u0IyI1ghGc?pwB=Pio6 z;1$bf7OR5=)(zas=Zo9bDmZ%8!f!kD%;qdqcc`>7HqHP1-(G_}VoW#rq)Q@z#OUtXCGs+@jtWXb?2!B7Rj!huG%DcR})V3;K=nhoLc4 zSz8%bud;3a9%dsCWh}|Q!I#4oLQ1vXo6#iEm|s|3I>-8O;FyeK#|Q*1^)*|$9))HS z4t(q}i89(zd-YWdCvR6L&}@I5HE+9Dsu+1a?U_?k zDu7-jT`!r075FGMLIM5|&LJVwv;8_oH%|tfnEloXh*_~^lyXJB$ppNLP)Z}pVF|EySEN|nBP?(Lxr zPIS!Z7Dm|4HfVc`ad}q^#?EQ3-Aa*!94eU1R9;=Zo6d$WR(NJ!4;YzIjqRx5#5#4p z-dMVl@KvtX?{Dx0kY?ZJQF7orbM^HYi^Y~eD7ujrI==(MK1iL&I}j|0#b?aI&m&C` zJqz@ZZit#C5g|xRwm)l3IQ-ve;zRQLWbKn-_->D4=J3U7t;EzH9Vr0cQo4SeaF5{~ zFkno514ZoIYg*#^f@9B{}@?*abQ3o`pdnlL4ZT^wG=bl zGP4^rPo)}lANT{`>Q!D{?)^O~e*RzZ5r!*pp7{rS8c=*UmV+H|wJSQG{S?yO=t{`1 zyx-)8gf6=G>qS_wjI&@+>@U1Vd~*CSaC{PP#!QKLif#eRtJ)9g^8Bf zPfn3Z@1u5MUvVJZ!}edFtc24z5cd2q3$kK>dFSoC__VnJ`|*- zMdhW=tx~}Gk~voCtY1|ufftV5Y9XT3toq1EmD+`8*(#$(T};!u)Z-3ansAJx1P~!2 zTXTfZiF07hVmIa6vTKKE6~#u8ev`Ik@tuT#82yFV#z=PrxT;4Pf$<%GIDj*1 z;Iu(lXw8`;hYX00lnyU$8%9W#>dBv)%?}>U`^cXUxtl-O_!+SFB3e-jkcyWtJsE7f zS2@(R3g%0iyiDMKMUJBO9l(S()wB~98zNy6>zn}Sm6R$i5B<c+ogsfJrMT;#2H-l1uT^^s43tOpQyIvqB=^H z)T3GJ6I5?tc`Z`nhlAx4siXmr zkTDGO5>{OQ0CK>wnG|sCJ6_WsH%^#NOE5&SPTf2lwio|iQB8pFQOjgt&4Q3=)Wj%J zWn%&P;lcR#l3^?vU|(zLn39(vslNo@3!zSa6TKSUP&qQrZAD8%e8t!}KZ@7!3d|}x zxd<8(N-hVCw!PaW(Ad6FJ)zZ<$-E!SXUQNcC`Tda_yej^1*Rl}_A6w|TO6;t=yF=x z5t-^C6Wc3z;ihy0wq-Zl?9Ng>bOWyuv$NfF+k)~a3FNA9?V2?UBQ*G}5IKyXd5YhP zDyA#1Q_cg$XIJ-MpTlBUNb#6?g)X|@Out4#FO%Fgy}CqEeb@o(NWUJ*=rpQ}>>8lc zcDw{+V*|NEsw5rd>rLNRA{(I(m8Ik<=gSMpI89hvT52&uBYrc$jEXSri(ZSSQV+d;joMGQt*}@f$YarG zjGG_A+i!<5fe%2_)IImPBY$btcf<^O9P11oF~5miKaX|JHb0p};0I9M44`4SJf@jOK=hjsift-QjPwBh zpT3ciZ%KVYYO~VXNwfhW-x$FSt{Kw&oRUK5G;_U^04r zs@6!}30~ZBhI@pKFlSnQ+!@BSUOl@yhF2DSy^Nt%u^JTbLqVmVu?ZnWh(L7sVf2h1 zaaIX}y`)Y=b1)m+2ayV|(WsL~R+04GoO@+xMx)n)CLp9X`<}$LqG=#Kc^XCQLckkW zZwI{dT^dOF!$#10!Q&jeya&K)C^!sOe6sx>QdNJ@wYQJI%9Wni)-pMY6e>8E0LLgFOig z46N5Rlzcq7q$GKD{9C5S%*;F9U*CR!)%u#o+(vubhVLzBD`vlcc9l`~_T&JI4hOek z?OxFI(X5u1NifpVA&89YzS9Bt&Rk*xmq&AvU6`!b z5ZA6_M z%=DegqYhMW^ZBqf!;WK^H9E0Iis_JzgpC|r zu{&1!KkY8JVZM<1G^hy8rNg|o3e9EZlkb+Aq)gk;Fy~z*c8X%bC;)B-!ClnY^lWV+ zh=f#D9S~j!i3O0Q=*NQc>R>3*1Po^pG~h$qKMZ9?$%~4L+kDj|vJ6WQflj(%hiViZ zMMl5^qyg(>+7}Z#d!!7rTitC?$`jZR3teoM^r2cQ2RWk0@`Zwi$I4Eve9Al%Kd(n^ zABa~-G11!+O%cHjb9rqsDx-J;!J!>qxa=jOjl-WOha#d8XBnZF0H;`l0)Sa$5AX~b zs9IPOVi8@+VVX#}l;CX;kwOTLbqPor6_7AN^?-q8V$MN0=<}MQgE71rOEw&0?mk^9 zL0w*Z!{#%sS}Mz$99MkG+%xj{ILevr-Yq`Kn`BPKS8@m;q z3=Su@iFq;bj+Qr}Ws@#lssXoFo;AWqDZ{k4LuHT13E6RL3x1fGZ9JjXP-@$BCTn36 zGzk@O)XX+0Qrh?E5mx-*?%fLG{zH$@dy9^QK2L(z_A%n%^g$p6d_?)R`d=FOf(tFG6eT|Z~$fw`oSRQI&4|0!A0jqONs^t+ z_$@C=bN(`?_m|5NdAN5XU^?c`-;Pc!Ct7CCqZ*UYgqsafJs0kouSuOPs}^De-`gJX zmFY!C%Y2AGv1lVWZkuUi($PW6%KCTrgkV@bX9HadShx-ZR* zQgPjO-$-q%Tr`d*VYpqox7{0xs%y)kZ+4YfcHQ;tN3kbo zqn!@w(6`aahr({3(R$3VjPT{-$?ods9-ea6sN7|9v!Po5@HemPSoYRa;QBOX7AMXv zX>xe(psd+v>`gc_Xv=89V{-FERC|1`zP>)%=BS*ktQe4ss7!C)sZ%v=v;*oez;HA2 z6XPMbkdO)c7s_GP;!z=?#Tot$&Mb`pAp2&sbn5n|vgQMZ|5r$5Y4i)chzWr(iZ}HZ zhZ9Da^=hn}rZ(`#ui)_p%OC=zucuOL86YADZxg~N32CYT>5V9WH*8n}5|-V_CqvY^ z7)ptVM>HSO&|&_xX>AD1qOvAsNra;{i~?Ad*u9J+`PswoU%$=0;QtvNRrN_K&vF;Vdr zC4R_vu&wCO&we{RvaqhFt;1H(hsUY*e7sPUBjq(U(+JJWpI%P-Tg}zfZTLU+ysm7r?X>ij5oPMl zC$!F;=<98#dOz<>SeTXPE8#M#LvYmj$=jfm6!FgV>c-U$TLxePhQ!hjDWV_bQ9dU? zjI~jhl6z#qm+a^qb-ka)#v?wFTV9->Zz}pjxK|%)V_%Xa)vqYXfm$qAWlugrnWPTE zbY`Zscuk^vYO9bAbm_H!|9qIo6)Bs%{`#vef>8feP9iY9spg z8M`jRW^&Ve_vUV3C^EWj(b1^U;bc&1P!;2ZrDkpweepQ1L1ODVKb~jjg(wLpCe=k1 zAI+`Equog1U4U?80kUN2PiZd53Q7bHp`gzI!qH<4!0X118+<6}D^th?(S4BmGU!dx z5s?*s{|+nA4L0BC27U;l;tmWAJ^A=)ck=Vi07MCW@|**c2qt zZCPFj5Vp_m$AH0u4bg=A@hy2&IG2YIMr9#Zc@G?NCHOi5H0-!&1GTf z$dJA0$DK6<^-IU8{KeQw=xCw{VdZ37(XX)TWD0$^y17+ws3nAFP~oo!!=-i9V)i^pk(ReKLYAtTQ37=#j)egr2=vk)TwDC#c?bNEAg%-fC*zrN^m-o!CzyQfa`YbHhAamgzutR z*j5?Jf)&rMjFONhjst%YZKKk!v*M=$oK$wre%R3oCgFA)XjOvmJ)%?0%*{1vG|Rz= zZ1xix1O?P^fH@AfSW5E0TAkZefqavt5z;w-d+1Ie9^MF$%U0Qegictwrn3y{oj6xo#tLDZBo+dIq&rA zP_8cpW1heQB4nWO1G?Y?GgggnPTc_f96aRX|4<`3=)Ake)w9gL_VK}ZNB_q>5n&Tg zO3A)n(`|dTv2~?|iw6U?SorHrvB+(8toaI?6m!?kGbNJ67M(JS4X)8hxHe&mVb%hN zz#I2_D7cSzt+%D9R!>^%i##|wPy6HMrb)8Zhr{kX2>PBlq;l;*_wmY~^*I#qJMrtb zQaDw*B8?c->^uPuOu)Gm>mfIY-~t@a@VtA&Yl!C7P5l_h5EI)V^Xrk%2z0#4?`c+6 zjK@^QQjR!B56qeo%*4m*7MU>b<^u*9mGv;)KE9z8i{aSOJ$_=4=5Up|)zMamTeU@D z{QsI}*y|Xqcl1EJ6x%{q+n?}_qACVJgrx1o3k4v#;luGR-yNeIpzn5#ga*4o)VsNv`h^5{AsUb{C#e1Fy( zxhD7S*)#a@82$QfDYStMRa-~=rMkejyTh`DDdk5qdnmj2X)GOVY#Y4n?pcmoaA=rf z&&LSsDWo$<*`7}aloC?c(KUjzAdj)q+H-8O`%!R^&@1n_><2`J~EI5_K9&`O|Y08^cJ%Zq5SLSnTM1R{!- zRQfAb<_0w-xc~A4d=qQey6h0}PNtFlG?d|-W%I*__zQu(=ABT{+b#kYbGW2(0S(d~ z_R4Z8u(_}tRH2-l4qi9-^XIzKFe)1cYA_<}ghXR7k>Bz)$J2pjrh;)N8B4N$DdzUy zj6Qe)RaFkX0kSKF;ll%=iq!q@QZJxG=`LZ3UnO|jYta<*S*wLHlE(J)wZ|jD=RHKuxt0X7`@a_enRKv0lx(H#QoplYD z8AD`gA>R&9n4CR`mLfzS1q`5@?7`$MM=1-sGLi!OnUtJ-l3_q0ctE|#l1kxf&MRWj zZMR_1Nnv5%ix<-Eh`l6qAUE-j0t@Ndy}L!6?8wGf`N!J;Epvefpk5fTewbuGjlnd&q&-zM&JS18|4(6O0+w^$_Wi49WKSw<)}m-Zb|RNZ z2^Er(C0mRv$r2$=p^dbVwT)CL+t^x&QiN1?V{1Y7YK$7&^Eu7D?{Pox`W*Lt+|SH3 zx|ZMn{GI3b{4NzSY$5>;!g%FnuU?Iz3#XP(+@An`v8>{nHVh!VZOS2GIh3B?e}T62 z`SWZT6cB;v1tO_K^|T%hfF2^|ECF{vKbRj=MCZ+I<$gP<1Y-M^AH^rAm zD=xSDp+oZn`zuphzQd@By~&;TOO_QTAPEF%#<6=xk4=f#v~bTRT+HlIIY_2wR!4?+ zR%93>8r6-mIXLiH)CexogSPfMl8n?ND&>C1$rLiC4RNwW++S2&tQ1WJr~HlCyv@4BQ#rdj?01gd?q3bEvqO=?+T68#5LCZ_Ms~a5eL#x)eI4x+Imy3Y zdS}$|+-oMrAI|0HUvpI0-`4Y-J&6!&*OZygSNB}b@UD?9I!u$K$iE?9hwyLq3GjwG zL#?!iWz{3Y*#4Jyp{y5A7F*T^#T%{63hDo%Fs6{1@tU^P=ks>aTkq5NX}hLnw73Tm z1nYvN85f2zYD1FK1YE611B#&iY3a+(jW|_*RuxcuaI{^{HKyrN`SikY_KfZ1Eu+F(6{|od!cp~JBY(z*XgdXBXNqY9h_aMmp3eEnH+PP)Dfo4JrVooT znv`Ftpp>*W&=0R~`L^RfBuZnA711%6JkW$VlvhCuI=1-nU|Ett3LQ(+!oMH<@b!h_ zhr2f9&cMB`vPQY0;txEnuxVOA0*aW=ju&e6&M^ZeT%Swy$JpO(QZh{Q z2aI@hu~U0eUmA6M$%2L<;<$#ZZz08A&sd>%rMsQqphqqv$+lD!~rkC zYM|hhy?&jNv~T!@-CCY2vPGK4mloxe$BBd$lQPBzg27BkICu}nt2jFDzvtK^bmFwz zpURDU<(GJ;aA@e$UU03{_q6gu{CBd|i9$ea+u{Ct;iapM6H}#=8J7+3mevJG7;a%F z=wAGVe%MON&i|?r&F%mH(TE;ZI?Rh4<&u2h&DEAe)K++$IC132+UYwix+JR~Na)J_ zp*@Cku?v)onX`h6iFJ{7O4vHI7%28{(45>Jy%4*;hRvEemguJQ!B8nGP9HUTXmc=g z|D`Zz>+pLjN594|E{q@$Gd1=7ShFjaF8Rq?>HM^H6lt7c&fNZyJ$;q*IaVFl!{GliT8kGZN9-qW*{d?cvigLE@*}oOzv~xxKSHhvQ7LQb zzTC{Rpai227ua?evl?T4xS8RG%81}aOa0;aapUH)rHAa5;%hSHUz}F%5k#SLVX5#Y zt73k9J#-%}PG4fsjT~Dp_N;3QRRw+6Rf{Di3!Wa|`UelQNqX=}TD0A(qDpqhk zKdnRadkN>R+lQx2fKIc8JsE;@Xz_`!9-T=;D$#;RQHLHeIb7`C3B|2O-I?LAfg>73 zgQfI(ecPIgJczC#n6{iLUp5PLK!S`+zWD=ZePg9D_><;XEgCR__e+H znn`H-dVWX=CwIFAO@_9#T|FN3S#e8IcSR_hc>A+sv$t4w|#SoC{UI z!Q>~^1;8dOt;BUqm|g$_U)dDUZ7s#KitcPAQ1b3~vYK%0t&n6DZohu}g5qDBCJ(PM z?QRa4l@;#9Q+*n_{5@#tvx|M^|G5LWeR!$9d(Vm@qf|3*(LZfh zzjwBQyM@Z}*lzZIzM6SST84h{@xAtbXr6V>w4T{WZLPv3#&^kXU-$mpz31m&{_$<- z7d4vZT{SwL7JofGt?-4XL-vYubmPJLGPWe(vkl}Dwfd-`md)qo+}K3W1bs8?(c^Wc z;b{a`jcC-&Y31~nU0}kV&9_*~^}j&H>|jBqU3|&zjN*a<*Wf#>wzD7r_aE%E z;^1ia-LZSObK^mAu`V^>fBt_(`0G8GGqL3Ci{%<2F8msCuwI7!QtW{PIa;^HuXnqT z2xuyI7>{2MGtrJCSjMz9^W*~=Q6NeAzc9xe#-K-!E|3E#6M0EzJm|g z4W=R6$rcn3JC%VPbGAp(RwHqxGY;R)g`wm4QFX?q#H%(X%3=0fBF3p+(#(6Y9J{`H z3T~NW0h>qS|BbJ4bh~`WxvkH=?g0P>e!Beg-j@+gA@A;l|^+ks-PFiK{P|EAdD3+n&5BAOMqki4tc#83XwO zqa&D?$MCv^o;!j-5d7VMfYlV-CNsG>#RiZbO2Ug|=-ZWUv7UZuBVR(Ft%)R7x2OyG zgRdSsAs*R_gRQ*6uPiC}B(_u2vwRv3i!s&fuC4#=$l=2y@xR-aKg5vtrS#VIIYYW*IkCxGh{BBa&l9!{y97Ml3*B~N*n3bJr}JKh z@BlBqtidksH!fe>_^(LicS4;Jbt(_IL`%@Wo{o;dI+CdtzqDJIN?nUmdkmOEU{lwkYH~_y2o$zcZ&K{Av4k`!hG@^LlY@!!QNy)O}xm>EchL z6YQSUcd}Hr`40VQgnEnD3%?{{3rUoqFWZ3u*SfwOC;1xG@Geu%u<`5731;@+Y@G^G zPL;(PEdG_BCmCufeDU;w%Yb8vO6>e~UJpHgM3i@3i4%*23-XyCz1upg8OQb+b0@0^ zQj}&g4E_ud>oaZvwj)g#+b)7KyJSqk&<~*abwbUKywAIJG#(r7@!6xX%60eH;jrLl z2wQ`D1#E< z%f6!v8bcR?40I6+75Fyb`n)TycrejQG{mP=aS^yj)Mq{V$7U@5bGPN@;`Q~53lR*s zffbYFy~Mut_&B@irr}>xfmN}zwG)?njtGXvmsu+mKg;^K-C zl(-qKqhL50>6Cm9DyUHMTvH}L{8?2}TrA&GZS88&)@3QR8Xf%7qGHuS?C)uKx^fy6 z;#LSa*SVyK?VMo6ilxX+!DxtlANTfJ=-H?ajSddzYJ7E1BGjPCg=*H-*ZvCMx9_o` z;nZLIem?bTfgnJLEa>h*Rq-xp4e<%7uOBK-Sf3;wG=bw1xpQY3-`Hh(iMYduA0?L! zBSMN=NA=2PZ6TfBY%bbKD{U&5sdrxe{p%odMx#Cao~kwVc@%tL?Or{Oddrtx?@rID zbA?i%&Xc$ayBFRwp62XZZ|0z(7jtabC8HS>M1-yoKZ3BBm~DI-X5(uVF!3ai)9dQq zwJix9QO2B0oHS+1s)gD|5@Lq8eHu^|?z|U}Edo}vvs*haI24{QuD5ydiPIEFQAkcp zn}7NpL{bcJc4#Q`#Z@25eH+3aW}SSX2S)UOEyalIPMCz|Fgvk}(KOjP7O&fU9%h&J zKj`aWg>8i*6AXh_qyL_9J4{@!wdZMj+FhiDMR)IZ6K=FOZ(k(DB6Wkv-EjON55}4w>Fgf{)T%LLNV?8T;SKe{bJJnQj0u=^j8%kTk1Ri{fQZ&IJS?nJ z)lguyE$}<19-FBGC8PVI{(IPB^~n?Rr3g7|{sxjH<}*;MRjaXI&m`JSAFyM`j&g(y z<$R9v-vejQM%R7AKki+JG<+H_FJDmbEv=^vGr~GZFN5cv&oGjc_2Jnw3rba9hR)Z0 zt+cgQxbM%55{Q|L!7S!v;_%$u+yh`hmuIhfQDaq>Zjx2d(Us@{#9cv^;Y}4h|ENqx z<5UVe25u&V7*#03zc6BH)t$YTm)8J}lYx;@4sfZ2JXWvvTjE_9Gh8gynElvf`t#%{ zBu*VEnD{3{l#;wdtfg~jZ1@(ypNG7;cjj3rliRQc_=ST`n1jO`8V#-)d97mfzFL21b$Tj^JQvnbBeDm=r1KL^}c%$*d^Ky$=OSprSz0d;8>=xbFKOmLST zJeWGhq@jXLDzVmvrs#X+;l3B0s446wO%l?7g!^$PBcQ{5%O;`Y^QEt@S%U_Z z8mr1zt%3XrGJ$f+6p`FyGg1M@h;t;$dN-&?GmksTRRw;(8P13zbkhu)O!2S;q@p8G zV~Ar5Tt*8kjS971GOj^RN0xdMemMeaX=R8>GwYYwSZ>#Xba9c9_q{9 z+%*zclq-7r+ecx>S^ z^W?XY%E~s*HR+mGNNx`Y7O{w7&xm# zG9TCPV;1f%&{ye|yL?(;5TBX#WwhfpZsaQSn+-C9e6f;1B0TiKg$ z%q!zR&w0jciG5S)JIuKeYZ7@H7@+DgYtB8N%n|G|Y*+`{5uQIC2iq;B+|j+v%znM& zV_WRq_dnncJ&K@b6j za3XHo3JZKo!PN9RObB!0ZHv8imv&QCLl4{YxrVHfdyPMYqyqlUQS8PWHEvvV>z1$B z1{)Zta}J4p59yH{7pEe@EYNp8zP{5_WM;G$*Z)BDVxf);ZG8giwh)#|izqt;x0vK9 zlPAw&^uB*~Syxc$$FDy{d3CTT>pC*KUpj$Vko}uOoQICr_4ahX32q) zz?)EkEKSmBpSqZsG{ctBpJ&|hkDcJx+xE5Ci9E>!9KIXpg zWLY8|2;Tyii`?MU#hh*nJj|Ob7}-YhiQiw;pCxuEE4UU+Qg)7xn|AG*8oXvNJRO}C zLuf$8A2BpLTF{ZAz;VyPDA0ncpK;N0M@d=@Y` zuD|KHzIMc`Z#-crDxUE$?c3}91?o(EhnbP5J6rF*<63>~W~Z>31ENk|c*Ca67pOOQ z-3HjSb3nIAiC8ZZ7eD(Oy5fv4g!@q}mj(*?d zz;D&pp9CFv(}G}b_VS}Ijh}l+%O+3ubj%ck`)vZP5ib#Z!kNF_2sN|~B{uZ)NBBjT zb8_nQ>gLmb0Q0q; z{g6nE=wxf`A^UNaTLoxo1^(>xS5nqQ^$fF5$nV$28%B1pq-5J|yKwDxkDz-7m0`T`$yLI2>1xVNGueH5>uUO`>yXCZW zj!@uUr{n@)x?_DZWa*c`JYQ_;;YL!U;(b8jZME@p^-g3-ZS3) zMTlEc>=rZ#_sJQ2ji-zjzUx2EC{B60Jl6*emF0a$ipkuF%>nxXFIFfi;^G2EPj|ZOW9cIj(KYt_) za;g}AI(0({q)LQNc7>;kf_RzQwEbDw5w$&f-xnQC5*n2~p)y8-m>@3Ko%VwhxgltFE zeNq-#L1lPcj9~g0UjGXcI+5*4o1kOlbnC^r0iT|-*wajD?nAiEt*la?T zDc43;tsY8>?FbZmM=tC-JIK!9hPUz0bRt%0^=Q<%=9qh$%7X=$eNQRg3K!>{1bYkw zRwb(Be~ebQd>}qOj61uvc-qznjxu!88lN)e(xXU8Y!B>;#w-nFRh)GA@UJD&J56U? zVTBxUn!7t2(KD3NN&BtiGE`(@GM$lCKc+B`z6N9M*ng%oGo4m6Y+FJ?wEF0dBaLm% zeHnWw@wV}1s04{!ki=10K}1LM;kbe8i}>y25)KrdeYV?iIp|FBL2q9e6BxzGc@BF^ z;hdU?EH>`gv9QXt72+&p&bLDWv0}EE=>82U&huc?EQR8K9*e>IUeSJSnbx0AaTMP- z0cRUgQ;?<8JHYd(uqcRiE4~Es=fDAK9h{wjY7npbdP;jTtk*_3am@#o62$Q(;)5fro@~S&$ zXYfI_)FB&H|sM2%uX4 zCh4qyo5g`dF`#!2c<>kbUtQ=F0KBq+D1=zu34?7`pURq3CrhJ z2-q7k>jq$v@JPvA>!#jWa%Py)x3(YT$03pUfek;t4WL?mgcm#$uq^-j^&Iw<_EV-v zypF`}VdMmHGl+G*wm7v+nYgA^i(n^(S|Jl4M}fjVeFBn zIWKvyveFQ`o~Zh^A3jE>h#22s$lzTeZPQg?+HIc{{^IE+@vp_smH{l>Al+A|q0 zr5<-^;jjLF2A_@Y={&*{F7w7*lCIaM>X%r}UNWfIPqn{2f3YfX_zm<;Ef`8xt@`Zv zxnk)+Q8}^R+l2Bm{=k9ybk7ph7n_u{1@OODA6Av45FyT{{&E848UwZFyKHK*voQ}4 zA150lEz~dC-j^v~vOy61kP}wMJj9wSo26@gaseH8Snf$f{^-M0_mT||m> zj?Kj2MR0BpkES@P##Q0vN5n}09lAC%*G6Qz6C+6{ST5ugK)W2Qb%goEQIJZ+1j~b+ zjlkLE`qZ#z>KX%Hu)6z*oDm7;&Z=`lDlAX-JvQ{Dd0~ZN=;?Sw!TUq}(F+3t{3}mIm+(f2yHQZ=dOu=7 z$e*?f?JL0wD?_Kcx`u+K|L*kSV6`o9zCBI&N1&ZmYa4H2x^!sX%Vy83Th0l@-%-jG zTh@E2^EiY4M=rP2$=856b7N70OzELKsKO$DCUSwRyQY3GT@r=wh0TLmxdfe5=$2@PYtTka|PPEq8{6Fs&r{R+=bKxE{k;LljWy8M~Tg!Z@| znRIs3N}jAV5Bz6`lKzcma%Y{x*tjwAE*(+`*6=N;a0C8h7TAc4WlWp+PMyR2f$M)x zyUsT%^EGEr4D9xCxc5u2wIDDEnY9@nn3-ofhS#6`om&w`x0(V`+wc(Yo#dzRboAn$ z11xJy;T4OKTlZ_zygl#ig}W>FFhwS$angwsp22f7{t7W{_;-`tKL^U~i>r#B*VOS^ zq)V818J_QEsbUth=gInN{dtVRmn*+rh)HVqTu z8BKII;s%CkD7Oj|%?LI!uiw0p3kRXHFt;#bot}P$tZe##RS_QQQSkpi&X(DYdbc{`aYrhq~JhNt~b)THAZu94FMgu}W zjs~`!tT&OKJ$wJYnXay`Y+)dAGm}dK7ln2y$cQ}um>5Vp4)`ALA_#hG<4|*-+NJ!S znQVNeG%)$w+u11)u!3(2VN(F2TkbE{BLU06Cxo3Ka#1Bf1{+AWZJYRfXXBXyA$7iH zcZFu2*Q!-g#YyF92tokQ`S+x}IG&h;FEPHzLpeAqi^SL*^+pea($YTsdU7kN8391O zqTT0puezqaTj~Ay*cSg2-zd(%X;eR~h%&c^>4|?G8CT;ZC)^(M zP#tqJ;y<>#`!;0$l8H>PHtrTy^asaoEqTlW>N!&c^?z;fXJBhM#@3UkEb$)dp|WxR zPWP4FC2pQ97vj8pQzPa(7<}l06B9^qvl_JLZNS)+hf8G6bv(gfwvFR0%?nVjOo}I; zVj#>)qgkx|?}Pa!TDNJF4fMO!SJinD1hcb@evV5s4DN4`; zM3GEamNYa%S*c{|=&Y|F0C%hRBRT}K6GEva?07oq>9JB&6T3*HSO(S0q5#(56$oq! zW-Ahz@+yH|N=yAdWPNGIC_;REoI{jt<`z4IxXgPMF<_P~~PMoIrwYB()A)Is0}YIl17T zZ2+N^WgyU<2MlOMH>zm+>naQwj66+fs-^6frMv~G<>qZnv!VQAUEQ%=zlB=g*`m#x zyb5Ko_@ns#Nba4PkrDmWbb7{^%(Dhdv_JU7kEFi7%VrW}JR*B+Bdkyk7r7{xw940b zd-DmXkRphS(=*R=T!utU8{WQiC*TTrbj#P*n|@7eeC}e3@>q-kV3+?QeVJlbtoWqU zPha&%Z^}8%&TP^jLVh^$U2|KClOlczVuMxHwB@baF}9I5C%rc>Yg94LuiIeRK?eYX z{l_MpHDc4)BF}j5K43U^dPyXzF6MCt4<|171Tr~{?d0c8}B3>K< z(Z-fc9g9`!yo_!#p~KZO-dZwrS$vjD0@mFyEAr1qw1 zlG&3%Yo&WLK(}1-ZbVGHEpK**ANU6sw=VapxDN)be_9V;@3S-HPD}b$Nw8EtVg}hN9HzT>OTpCx0NJH_{~>wi#rz@uumu_>X~cPJlT{Ne1+xBATHl2{`LrC`?T%bqg}< zct49Co@&UpY)O&zwD2EJtSW@z4@SfQB8@*q9QTf+`OA^m^_BPSs?iYj)X$Asu}KcW zTeQ)eylFHS#HXf?=Z@Ru0ld_W=}6yS!xQ5Yj`v9DmbM^-2teol)sD4~nImdq@ze*k z_b;f>#LfyM&_8tYE-Zi9OcY{#zwcft%TTd47KHs_M(LgA@)OPFJeyfsBm3d>`S$qGx2%0J|!E|9(7o zK|a(0F;YjV)(sG@oK^}G8k0GE0Lq%9DJfkP`BY5#@0gkmeq53f)DL)YI`Ofw7F@FV zaArp!slz4|>FJbLYshch)uiLFy+8pi0bCuNoo&=R&!N&Nf2`!w?k?uoe8M^KhZLQl z7v^BeAWj{qd*Sh0s(04w(tGc$8u)EsuJuKg_$lbjY zSew4AkDu>aAugN$xox}tqm^!)ne0keR29?ZyG6uusN>#0@Q6#!aEPt%Zju(lYy%pF zfs}8HuA?vh@kd7PnJ$=g;AQxH_>a2g?5Rg@ZQl@OwoYC|c=#oXgT$a6AcTThfN}6L zp1PtgrANO^SRflNF6GVO!PM|)5DA%;yE2T|)z$H7{sxy=tULNVzNW$z(*m9HNQNSu z$jrrcZul1W;xseuGfPNB zNBps48Wc2G>lO&*N^B?a@F7GPxU953a8;+j&T84Xbn@@zIZuUU_l7s`MirZn*VH}t zBeSt&xGn16j$h=&t`#?lPFP`7fB$;gZpIALKX?6V!!USgVff&`e@;%O##dL^0a_i{ zHJ#q8ESm}%0AG<~6pwKSYtA|4QSF;;-aZ9~cJTsptB4xca^GM1J=L(pRB?Yh=RLMv z-0RtwFV{mE_NwGiRl|Ms;b2K^D$AK4j?KH#HgQuokYe~Hw##OKGD^?M4Vt)YKFdSa ztNwF#b9y~eUh=I8ax!bdf`-hW04=B5c6|oDQ0!eC+!PlPSp?A+)>BZlN=l2St_=(g z4PY?hV^b(7m?K$u@LMjrk+&6J96$S*g|kgdU7Pu{SP(usV_Nh1PQ=ap()Sx8M_bj2 z5{Pqu1$tlD-o0NPTN$t>l>IQ>w8hk^y9Rf?P*J6uQsf;`9;Le5#waQ(s!i@CV8x3S zp0oY|E1&byLcC6#>r1kG8^~POC3C2r#tuiD@C8ALKeYatMP&gc7j1aj=`N}F(~>`Z zmErWj?N{nt-w4=d-<$x8haPVJ&9utjH9DmX+z!8EIu$`k2(VCNISX*Nh;C~%%80ex zoqg3dDrkw^)~6*U`SM}&d+2pkq0P`-s-bAPMEAGr+wQSuyeGU&N4{7A;4h1c&cE-} z+m&bl^HjcQsy=vnC-6r~qN?J`?ZcI4t{{BcVs2&sw8w7e%TpX3`!tMWu-lX85yW67 z9ymACGBVn;iP9R3mN0Z@lNVEPZ|3knIE{i3HY^){D7f#Rs}~ zp&OOyIQFJ8L?ZCI%mz-9K|&Tln}kA--CsoV+U7rIZ0(k(0Jt<`0liO9)n=MVD@mg7VzE?C!mLXCCZ-Omm0M2x66@?b^p@ z)6>mf_H5L{_@JEumtc_BoAfb>-ph{s2f@s^Jc?e}>GYyDEJO6K^<=NG4JoFq$)MwD z28V-YG7oH|du3g5F*jF@OH1}_Qk~d8GM5RYD!egd(^a_b#>L00@;Gt>b3iYL>yPyh zmzF?$SfYE)QpKd{IH?+ZR+kwy_$m5&iSG2haJs;GF_-`*`vV7_ZFlJQFse1mQtHjq_zPo~NG~aH9&_!zl8Lic|BJZ+ zWj$2cSG)lJlZKAYFMxOoa~FsT=(RKtXDlqZ_6|r4NaoS=vXa{Ofz1gE1Tu12l*V)o zRl<1m`hv0{nejD=A5D_FinBNDHxxG)dWQ~#thNPtL6P3(;-2I>Xs%7r?rya>Ynws8 z2`+I}=Itg_>Sov*cQOcv*3*PBw)KJy6P8QKoOKiDG!GsQ zi+&{uR7ppVYP-}MSrOHD|CN&3)R5-Qn$0^zQw!Bt6~~|{wO1+hka{8M#tGb8K-yJ zSE1+9tHf%`&tLLB=tH26#?Sxv%<%oZFkUQw+^_#|$m|Rvr;k14Y+>iEA9|>&@Aq+A t5An~>{~RxP-S?C~H!Qrt%pE`K9jh`Aiap+VjDr8O9yQ)FRXNk|zW~vPRo(yq diff --git a/doc/src_intro/rs_driver_intro.md b/doc/src_intro/rs_driver_intro.md index 8353a444..7dacca5b 100644 --- a/doc/src_intro/rs_driver_intro.md +++ b/doc/src_intro/rs_driver_intro.md @@ -1,4 +1,4 @@ -# rs_driver 源代码解析 +# rs_driver v1.5.1 源代码解析 ## 1 基本概念 @@ -61,8 +61,8 @@ Input部分负责接收MSOP/DIFOP Packet,包括: Input定义接收MSOP/DIFOP Packet的接口。 + 成员`input_param_`是用户配置参数RSInputParam,其中包括从哪个port接收Packet等信息。 + Input自己不分配接收Packet的缓存。 - + Input的使用者调用Input::regRecvCallback(),提供两个回调函数cb_get和cb_put, 它们分别保存在成员变量`cb_get_`和`cb_put_`中。 - + Input的派生类调用`cb_get_`可以得到空闲的缓存;在缓存中填充好Packet后,可以调用`cb_put_`将它返回。 + + Input的使用者调用Input::regCallback(),提供两个回调函数cb_get_pkt和cb_put_pkt, 它们分别保存在成员变量`cb_get_pkt_`和`cb_put_pkt_`中。 + + Input的派生类调用`cb_get_pkt_`可以得到空闲的缓存;在缓存中填充好Packet后,可以调用`cb_put_pkt_`将它返回。 + Input有自己的线程`recv_thread_`。 + Input的派生类启动这个线程读取Packet。 @@ -78,7 +78,7 @@ InputSockt类从UDP Socket接收MSOP/DIFOP Packet。雷达将MSOP/DIFOP Packet + 一般情况下,雷达将MSOP/DIFOP Packet发送到不同的目的Port,所以InputSock创建两个Socket来分别接收它们。 + 成员变量`fds_[2]`保存这两个Socket的描述符。`fds_[0]`是MSOP socket, `fds_[1]`是DIFOP socket。但也可以配置雷达将MSOP/DIFOP Packet发到同一个Port,这时一个Socket就够了,`fds_[1]`就是为无效值`-1`。 + MSOP/DIFOP对应的Port值可以在RSInputParam中设置,分别对应于`RSInputParam::msop_port`和`RSInputParam::difop_port`。 -+ 一般情况下,MSOP/DIFOP Packet直接构建在UDP协议上。但在某些客户的场景下(如车联网),MSOP/DIFOP Packet可能构建在客户的协议上,客户协议再构建在UDP协议。这时,InputSock派发MSOP/DIFOP Packet之前,会先丢弃`USER_LAYER`的部分。成员变量`sock_offset_`保存了`USER_LAYER`部分的字节数。 ++ 一般情况下,MSOP/DIFOP Packet直接构建在UDP协议上。但在某些客户的场景下(如车联网),MSOP/DIFOP Packet可能构建在客户的协议上,客户协议再构建在UDP协议上。这时,InputSock派发MSOP/DIFOP Packet之前,会先丢弃`USER_LAYER`的部分。成员变量`sock_offset_`保存了`USER_LAYER`部分的字节数。 + `USER_LAYER`部分的字节数可以在RSInputParam中设置,对应于`RSInputParam::user_layer_bytes`。 + 有的场景下,客户的协议会在MSOP/DIFOP Packet尾部附加额外的字节。这时,InputSock派发MSOP/DIFOP Packet之前,会先丢弃`TAIL_LAYER`的部分。成员变量`sock_tail_`保存了`TAIL_LAYER`部分的字节数。 + `TAIL_LAYER`部分的字节数可以在RSInputParam中设置,对应于`RSInputParam::tail_layer_bytes`。 @@ -118,9 +118,9 @@ recvPacket() 接收MSOP/DIFOP Packet。 + 调用FD_ZERO()初始化本地变量`rfds`,调用FD_SET()将`fds_[2]`中的两个fd加入`rfds`。当然,如果MSOP/DIFOP Packet共用一个socket, 无效的`fds_[1]`就不必加入了。 + 调用select()在`rfds`上等待Packet, 超时值设置为`0.5`秒。 如果select()的返回值提示`rfds`上有信号,调用FD_ISSET()检查是`fds_[]`中的哪一个fd可读。对这个fd, -+ 调用回调函数`cb_get_`, 得到大小为`MAX_PKT_LEN`的缓存。`MAX_PKT_LEN` = `1500`,对当前Robosense雷达来说,够大了。 ++ 调用回调函数`cb_get_pkt_`, 得到大小为`MAX_PKT_LEN`的缓存。`MAX_PKT_LEN` = `1500`,对当前Robosense雷达来说,够大了。 + 调用recvfrom()接收Packet,保存到这个缓存中 -+ 调用回调函数`cb_put_`,将Packet派发给InputSock的使用者。 ++ 调用回调函数`cb_put_pkt_`,将Packet派发给InputSock的使用者。 + 注意在派发之前,调用Buffer::setData()设置了MSOP Packet在Buffer的中偏移量及长度,以便剥除`USER_LAYER`和`TAIL_LAYER`(如果有的话)。 #### 3.2.5 InputSock::higherThreadPrioty() @@ -188,9 +188,9 @@ recvPacket()解析PCAP文件。 + 调用pcap_offline_filter(),使用PCAP过滤器校验Packet(检查端口、协议等是否匹配)。 如果是MSOP Packet, - + 调用`cb_get_`得到大小为`MAX_PKT_LEN`的缓存。`MAX_PKT_LEN` = `1500`,对当前的RoboSense雷达来说,够大了。 + + 调用`cb_get_pkt_`得到大小为`MAX_PKT_LEN`的缓存。`MAX_PKT_LEN` = `1500`,对当前的RoboSense雷达来说,够大了。 + 调用memcpy()将Packet数据复制到缓存中,并调用Buffer::setData()设置Packet的长度。复制时剥除了不需要的层,包括`USER_LAYER`和`TAIL_LAYER`(如果有的话)。 - + 调用回调函数`cb_put_`,将Packet派发给InputSock的使用者。 + + 调用回调函数`cb_put_pkt_`,将Packet派发给InputSock的使用者。 如果是DIFOP Packet,处理与MSOP Packet一样。 @@ -393,7 +393,7 @@ enum RSEchoMode 如前面MSOP格式的章节所说,理论上从distance、垂直角、水平角就可以计算点的直角坐标系的坐标。 -但实践中装配雷达总是无可避免地有细微的误差,导致雷达的角度不精确,需要进行修正。雷达装配后的参数标定过程,会找出相关的修正值,写入雷达的寄存器。标定后,使用修正值调整点,就可以使其精度达到要求。 +但在实践中,装配雷达总是无可避免地有细微的误差,导致雷达的角度不精确,需要进行修正。雷达装配后的参数标定过程,会找出相关的修正值,写入雷达的寄存器。标定后,使用修正值调整点,就可以使其精度达到要求。 MEMS雷达的角度修正,在雷达内部完成,所以驱动不需要做什么;机械式雷达的角度修正,由驱动在电脑主机端完成。 @@ -481,12 +481,10 @@ typedef struct typedef struct { ... - uint8_t pitch_cali[48]; - ... } RS16DifopPkt; - + ``` 为了像其他雷达一样处理RS16,将RS16DifopPkt适配到一个能兼容RSCalibrationAngle的结构 AdapterDifopPkt, @@ -501,23 +499,25 @@ typedef struct RSCalibrationAngle horiz_angle_cali[32]; } AdapterDifopPkt; ``` - + RS16使用了转换函数RS16DifopPkt2Adapter(),从RS16DifopPkt构造一个AdapterDifopPkt。 ``` void RS16DifopPkt2Adapter (const RS16DifopPkt& src, AdapterDifopPkt& dst); ``` - + + RS32也有类似的情况。虽然它的修正值也保存在RSCalibrationAngle数组中,但角度值的含义不同。 ``` typedef struct { + ... RSCalibrationAngle vert_angle_cali[32]; RSCalibrationAngle horiz_angle_cali[32]; + ... } RS32DifopPkt; ``` - + 与RS16类似,也将RS32DifopPkt适配到AdapterDifopPkt。RS32使用的转换函数是RS32DifopPkt2Adapter()。 #### 4.2.5 ChanAngles::loadFromFile() @@ -630,7 +630,7 @@ cos()查表返回角度的cos值。 对于机械式雷达,雷达持续旋转,垂直方向上的每一轮激光发射,在MSOP Packet中对应一个Block。 以RSBP雷达为例, + 一轮就是`32`次激光发射,对应`32`个channel。所以`RSDecoderConstParam::CHANNELS_PER_BLOCK` = `32`。 -+ MSOP的设计初衷,当然是向每个Packet多塞几个Block,这样就有`RSDecoderConstParam::BLOCKS_PER_PKT` = `12`。 ++ MSOP的设计初衷,当然是向每个Packet尽可能多塞几个Block,这样就有`RSDecoderConstParam::BLOCKS_PER_PKT` = `12`。 ![msop single return](./img/msop_single_return.png) @@ -1022,6 +1022,7 @@ RSDecoderConstParam是雷达配置参数,这些参数都是特定于雷达的 + `MSOP_ID[]`是MSOP Packet的标志字节。各雷达的标志字节不同,用`MSOP_ID_LEN`指定其长度。 + `DIFOP_ID[]`是DIFOP Packet的标志字节。各雷达的标志字节不同,用`DIFOP_ID_LEN`指定其长度。 + `BLOCK_ID[]`是MSOP Packet中Block的标志字节。所有雷达都是两个字节。 ++ `LASER_NUM`是雷达的通道数。如RS16是16, RS32是32,RS128是128。 + `BLOCKS_PER_PKT`、`CHANNELS_PER_BLOCK`分别指定每个MSOP Packet中有几个Block,和每个Block中有几个Channel。 + `DISTANCE_MIN`、`DISTANCE_MAX`指定雷达测距范围 + `DISTANCE_RES`指定MSOP格式中`distance`的解析度。 @@ -1042,6 +1043,7 @@ struct RSDecoderConstParam uint8_t BLOCK_ID[2]; // packet structure + uint16_t LASER_NUM; uint16_t BLOCKS_PER_PKT; uint16_t CHANNELS_PER_BLOCK; @@ -1136,7 +1138,6 @@ decodeDifopCommon()解析DIFOP Packet。 ``` uint16_t rpm; - ``` + 计算单回波模式下,每帧Block数,也就是`blks_per_frame_`。 @@ -1364,23 +1365,24 @@ typedef struct RSDriverParam + 函数packetGet()和packetPut()用来向input_ptr_注册。`input_ptr_`调用前者得到空闲的Buffer,和调用后者派发填充好Packet的Buffer。 组合Decoder, -+ 成员`cb_get_pc_`和`cb_put_pc_`是回调函数,由驱动的使用者提供。它们的作用类似于Input类的`cb_get_`和`cb_put_`。驱动调用`cb_get_pc_`得到空闲的点云,调用`cb_put_pc_`派发填充好的点云。 - + 驱动的使用者调用成员函数regPointCloudCallback(),设置`cb_get_pc_`和`cb_put_pc_`。 -+ 成员函数splitFrame()用来向`decoder_ptr_`注册。`decoder_ptr_`在需要分帧时,调用split_Frame()。这样LidarDriverImpl可以调用`cb_put_pc_`将点云传给使用者,同时调用`cb_get_pc_`得到空闲的点云,用于下一帧的累积。 ++ 成员`cb_get_cloud_`和`cb_put_cloud_`是回调函数,由驱动的使用者提供。它们的作用类似于Input类的`cb_get_pkt_`和`cb_put_pkt_`。驱动调用`cb_get_cloud_`得到空闲的点云,调用`cb_put_cloud_`派发填充好的点云。 + + 驱动的使用者调用成员函数regPointCloudCallback(),设置`cb_get_cloud_`和`cb_put_cloud_`。 ++ 成员函数splitFrame()用来向`decoder_ptr_`注册。`decoder_ptr_`在需要分帧时,调用split_Frame()。这样LidarDriverImpl可以调用`cb_put_cloud_`将点云传给使用者,同时调用`cb_get_cloud_`得到空闲的点云,用于下一帧的累积。 #### 4.9.1 LidarDriverImpl::getPointCloud() -LidarriverImpl的成员`cb_get_pc_`是rs_driver的使用者提供的。getPointCloud(对它加了一层包装,以便较验它是否合乎要求。 +LidarriverImpl的成员`cb_get_cloud_`是rs_driver的使用者提供的。getPointCloud(对它加了一层包装,以便较验它是否合乎要求。 在循环中, -+ 调用`cb_get_pc_`,得到点云, + ++ 调用`cb_get_cloud_`,得到点云, 如果点云有效, + 将点云大小设置为`0`。 如果点云无效, -+ 睡眠一小会。由于getPointCloud()运行在LidarDriverImpl的处理线程中,睡眠可能导致`msop_pkt_queue_`和`difop_pkt_queue_`中的Packet无法及时得到处理。 ++ 调用runExceptionCallback()报告错误。 #### 4.9.2 LidarDriverImpl::init() -init()初始话LidarDriverImpl实例。 +init()初始化LidarDriverImpl实例。 初始化Decoder部分, + 调用DecoderFactory::createDecoder(),创建Decoder实例。 @@ -1479,7 +1481,7 @@ getTemperature()调用Decoder::getTemperature(), 得到雷达温度。 InputRaw回放MOSP/DIFOP Packet。 + 使用者从某种源(比如文件)中解析MSOP/DIFOP Packet,调用InputRaw的成员函数feedPacket(),将Packet喂给它。 - + 在feedPacket()中,InputRaw简单地调用成员`cb_put_`,将Packet推送给调用者。这样,它的后端处理就与InputSock/InputPcap一样了。 + + 在feedPacket()中,InputRaw简单地调用成员`cb_put_pkt_`,将Packet推送给调用者。这样,它的后端处理就与InputSock/InputPcap一样了。 所以除了输出点云之外,驱动还可以直接输出Packet,以后再重新导入进行播放。 From 7f2e660f4a690568c4bd539de0a7ea94d0761969 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 28 Apr 2022 11:48:55 +0800 Subject: [PATCH 241/379] feat: add option to usleep in case of no packets --- src/rs_driver/driver/lidar_driver_impl.hpp | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 5b6e46ca..7165c7b0 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -350,11 +350,24 @@ inline void LidarDriverImpl::processMsop() { while (!to_exit_handle_) { + // + // Low latency, or low CPU usage, that is the question. + // -- Hamlet + // +#if 1 std::shared_ptr pkt = msop_pkt_queue_.popWait(1000); if (pkt.get() == NULL) { continue; } +#else + std::shared_ptr pkt = msop_pkt_queue_.pop(); + if (pkt.get() == NULL) + { + usleep(1000); + continue; + } +#endif bool pkt_to_split = decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); runPacketCallBack(pkt, decoder_ptr_->prevPktTs(), false, pkt_to_split); // msop packet From 032efcea6ff5180faab08425c876b448f64b1ab1 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 28 Apr 2022 11:49:58 +0800 Subject: [PATCH 242/379] format: format --- CHANGELOG.md | 2 +- demo/CMakeLists.txt | 20 ++++++++++---------- tool/CMakeLists.txt | 22 ++++++++++++++++------ 3 files changed, 27 insertions(+), 17 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 55e86420..64568496 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,6 +1,6 @@ # Changelog -## v1.5.0 - 2022-04-21 +## v1.5.1 - 2022-04-21 ### Changed - refactory the decoder part diff --git a/demo/CMakeLists.txt b/demo/CMakeLists.txt index 6f4b9b86..fccf85fb 100644 --- a/demo/CMakeLists.txt +++ b/demo/CMakeLists.txt @@ -1,37 +1,37 @@ cmake_minimum_required(VERSION 3.5) + project(rs_driver_demos) + message(=============================================================) message("-- Ready to compile demos") message(=============================================================) -if(${ENABLE_PCL_POINTCLOUD}) +if (${ENABLE_PCL_POINTCLOUD}) find_package(PCL REQUIRED) include_directories(${PCL_INCLUDE_DIRS}) link_directories(${PCL_LIBRARY_DIRS}) add_definitions(${PCL_DEFINITIONS}) -endif(${ENABLE_PCL_POINTCLOUD}) +endif (${ENABLE_PCL_POINTCLOUD}) include_directories(${DRIVER_INCLUDE_DIRS}) add_executable(demo_online - demo_online.cpp - ) + demo_online.cpp) + target_link_libraries(demo_online pthread - ${EXTERNAL_LIBS} -) + ${EXTERNAL_LIBS}) if(${ENABLE_PCAP_PARSE}) add_executable(demo_pcap - demo_pcap.cpp - ) + demo_pcap.cpp) + target_link_libraries(demo_pcap pthread - ${EXTERNAL_LIBS} -) + ${EXTERNAL_LIBS}) endif(${ENABLE_PCAP_PARSE}) diff --git a/tool/CMakeLists.txt b/tool/CMakeLists.txt index fe35e749..031a0d36 100644 --- a/tool/CMakeLists.txt +++ b/tool/CMakeLists.txt @@ -1,10 +1,16 @@ + cmake_minimum_required(VERSION 3.5) + project(rs_driver_viewer) + message(=============================================================) message("-- Ready to compile tools") message(=============================================================) + include_directories(${DRIVER_INCLUDE_DIRS}) + set(CMAKE_BUILD_TYPE Release) + if(WIN32) cmake_policy(SET CMP0074 NEW) set(OPENNI_ROOT "C:\\Program Files\\OpenNI2") @@ -13,22 +19,26 @@ if(WIN32) file(COPY ${OPENNI_ROOT}\\Redist\\OpenNI2.dll DESTINATION ${PROJECT_BINARY_DIR}\\Release) file(COPY ${OPENNI_ROOT}\\Redist\\OpenNI2.dll DESTINATION ${PROJECT_BINARY_DIR}\\Debug) endif(WIN32) + find_package(PCL COMPONENTS common visualization io QUIET REQUIRED) add_definitions(${PCL_DEFINITIONS}) include_directories(${PCL_INCLUDE_DIRS}) link_directories(${PCL_LIBRARY_DIRS}) + if(PCL_FOUND) + add_executable(rs_driver_viewer - rs_driver_viewer.cpp - ) + rs_driver_viewer.cpp) + target_link_libraries(rs_driver_viewer ${EXTERNAL_LIBS} - ${PCL_LIBRARIES} -) + ${PCL_LIBRARIES}) + else() + message("PCL Not found! Can not compile rs_driver_viewer!") + endif() install(TARGETS rs_driver_viewer - RUNTIME DESTINATION /usr/bin -) + RUNTIME DESTINATION /usr/bin) From 71de982c13ba90ee7ce93d7a3ec15747ff09838b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 28 Apr 2022 14:18:22 +0800 Subject: [PATCH 243/379] feat: limit error info of NODIFOPRECV --- src/rs_driver/common/error_code.hpp | 11 +++++++++++ src/rs_driver/driver/decoder/decoder.hpp | 2 +- 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/src/rs_driver/common/error_code.hpp b/src/rs_driver/common/error_code.hpp index 648adb12..ff46c01a 100644 --- a/src/rs_driver/common/error_code.hpp +++ b/src/rs_driver/common/error_code.hpp @@ -145,5 +145,16 @@ struct Error } \ } +#define DELAY_LIMIT_CALL(func, sec) \ +{ \ + static time_t prev_tm = time(NULL); \ + time_t cur_tm = time(NULL); \ + if ((cur_tm - prev_tm) > sec) \ + { \ + func; \ + prev_tm = cur_tm; \ + } \ +} + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 92148b97..aefcdc75 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -390,7 +390,7 @@ inline bool Decoder::processMsopPkt(const uint8_t* pkt, size_t siz { if (param_.wait_for_difop && !angles_ready_) { - LIMIT_CALL(cb_excep_(Error(ERRCODE_NODIFOPRECV)), 1); + DELAY_LIMIT_CALL(cb_excep_(Error(ERRCODE_NODIFOPRECV)), 1); return false; } From 79dd719d29b9572f9435c1cde60a0ebce6f1aa98 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 28 Apr 2022 14:35:33 +0800 Subject: [PATCH 244/379] feat: update CHANGELOG --- CHANGELOG.md | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 64568496..37177949 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,9 +1,16 @@ # Changelog -## v1.5.1 - 2022-04-21 +## v1.5.1 - 2022-04-28 ### Changed -- refactory the decoder part +- When replay MSOP/DIFOP file, use the timestamp when it is recording. +For Mechanical LiDARs, +- Split frame by block instead of by packet +- Let every point has its own timestamp, instead of using the block's one. +- + +## v1.5.0 - 2022-04-21 +-- Refactory the coder part ## v1.4.6 - 2022-04-21 From 82f4edc7d11345f26b65d42866cc885334b94d7c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 28 Apr 2022 14:49:56 +0800 Subject: [PATCH 245/379] format: format --- doc/test_cases/rs_driver_test_case.md | 106 -------------------------- 1 file changed, 106 deletions(-) delete mode 100644 doc/test_cases/rs_driver_test_case.md diff --git a/doc/test_cases/rs_driver_test_case.md b/doc/test_cases/rs_driver_test_case.md deleted file mode 100644 index d199afb6..00000000 --- a/doc/test_cases/rs_driver_test_case.md +++ /dev/null @@ -1,106 +0,0 @@ -**rs_driver 测试用例** - -## 1 简介 - -这里的测试都在Linux系统下进行。 - -测试用例级别: -+ P1 基本功能。失败将导致多数重要功能无法运行。 -+ P2 重要功能。系统中主要特性,失败则无法使用该特性。 -+ P3 可选功能。系统中次要特性,失败无法使用该特性。 - -## 2 功能测试 - -## 2.1 编译运行rs_driver - -| 级别 | 功能步骤简要说明 | 期望结果 | -|:------:|:--------------------------------------------------------|:--------------:| -| P1 | 安装libpcap/PCL/eigen库时,编译rs_driver | 编译成功 | -| P3 | ENALBE_PCAP_PARSE=OFF,不安装libpcap库时,编译rs_driver | 编译成功 | -| P3 | ENABLE_TRANSFORM=OFF,不安装eigen库时,编译rs_driver | 编译成功 | -| P3 | COMPILE_TOOLS=OFF,不安装PCL库时,编译rs_driver | 编译成功 | -| P1 | 用rs_driver_viewer连接在线雷达 | rs_driver_viewer显示点云 | -| P1 | 用demo_online连接在线雷达,点为XYZI/XYZIRT,打印点。 | 点属性正常 | - -## 2.2 rs_driver输出点云的正确性 - -这里需要测试点云正确性的雷达包括:RS16/RS32/RSBP/RSHELIOS/RS80/RS128/RSM1。 - -| 级别 | 功能步骤简要说明 | 期望结果 | -|:------:|:--------------------------------------------------------|:------------------------------:| -| P2 | 用rs_driver_viewer依次连接每种雷达,雷达工作在单回波模式下 | rs_driver_viewer正常显示点云 | -| P2 | 用rs_driver_viewer依次连接每种雷达,雷达工作在双回波模式下 | rs_driver_viewer正常显示点云 | - -## 2.3 rs_driver连接在线雷达 - -| 级别 | 功能步骤简要说明 | 期望结果 | -|:------:|:--------------------------------------------------------|:------------------------------:| -| P1 | 用demo_online连接在线雷达,雷达工作在广播模式下, | demo_online正常打印点云 | -| P2 | 用demo_online连接在线雷达,雷达工作在组播模式下 | demo_online正常打印点云 | -| P2 | 用demo_online连接在线雷达,雷达工作在单播模式下 | demo_online正常打印点云 | -| P2 | 用demo_online连接在线雷达,雷达包带USER_LAYER | demo_online正常打印点云 | -| P2 | 用demo_online连接在线雷达,雷达包带TAIL_LAYER | demo_online正常打印点云 | -| P2 | 启动demo_online两个实例,连接两台雷达,雷达指定不同目标端口、相同目标IP | demo_online正常打印点云 | -| P2 | 启动demo_online两个实例,连接两台雷达,雷达指定相同目标端口、不同目标IP | demo_online正常打印点云 | -| P2 | 用demo_online连接在线雷达,雷达不做时间同步,user_lidar_clock=true(或false),打印点的时间戳 | 时间戳是雷达时间(或主机时间) | -| P2 | 用demo_online连接在线雷达,dense_points = true(或false),打印点云大小 | 点云大小是(或不是)雷达线数的整数倍 | -| P3 | 用rs_driver_viewer连接在线雷达,设置错误的DIFOP端口,wait_for_difop=false | 显示扁平点云 | -| P3 | 用rs_driver_viewer接在线雷达,设置错误的DIFOP端口,wait_for_difop=true | 不显示点云 | -| P2 | 用rs_driver_viewer连接在线雷达,config_from_file=true,angle_path=angle.csv | 正常显示(非扁平的)点云 | -| P2 | 用rs_driver_viewer连接在线雷达,split_frame_mode=by_angle,split_angle=0/90/180/270 | 正常显示点云 | -| P3 | 用rs_driver_viewer连接在线雷达,split_frame_mode=by_fixed_pkts,num_pkts_split=N | 显示点云 | -| P3 | 用rs_driver_viewer连接在线雷达,split_frame_mode=by_custome_pkts | 显示点云 | -| P3 | 用rs_driver_viewer连接在线雷达,start_angle=90, end_angle=180 | 显示半圈的点云 | -| P3 | 用rs_driver_viewer连接在线雷达,min_distance=1, end_angle=10 | 显示被裁剪的点云 | - -## 2.4 rs_driver解析PCAP文件 -| 级别 | 功能步骤简要说明 | 期望结果 | -|:------:|:--------------------------------------------------------|:------------------------------:| -| P3 | 用demo_pcap解析PCAP文件,雷达工作在广播模式下 | 正常打印点云 | -| P2 | 用rs_driver_viewer解析PCAP文件 | rs_driver_viewer正常显示点云 | -| P3 | 用rs_driver_viewer解析PCAP文件, pcap_repeat=true(或false) | 循环播放PCAP中的点云(或播放一遍退出) | -| P3 | 用rs_driver_viewer解析PCAP文件, pcap_rate=0.5/1/2 | 点云播放速度变慢(或正常播放、加快) | -| P3 | 用rs_driver_viewer解析PCAP文件, PCAP的包带VLAN层 | demo_pcap正常打印点云 | - -## 2.5 rs_driver错误输出 - -| 级别 | 功能步骤简要说明 | 期望结果 | -|:------:|:--------------------------------------------------------|:------------------------------:| -| P1 | 用demo_online连接在线雷达,网络设置错误。 | 驱动打印错误提示无法收到MSOP/DIFOP包 | -| P1 | 用demo_online连接在线雷达,雷达类型设置错误。 | 驱动打印错误提示包的大小或格式错误 | -| P1 | 用demo_pcap连接在线雷达,指定不存在的PCAP文件。 | 驱动打印错误提示文件路径无误 | - -## 2.6 其他功能 - -| 级别 | 功能步骤简要说明 | 期望结果 | -|:------:|:--------------------------------------------------------|:------------------------------:| -| P1 | 用demo_online连接在线雷达,ENABLE_TRASFORM=TRUE,设置转换参数。 | 点云坐标变换正确 | - -## 3 性能测试 - -### 3.1 针对工控机 - -在当下主流性能的工控机上,做如下测试。 - -| 级别 | 功能步骤简要说明 | 期望结果 | -|:------:|:--------------------------------------------------------|:------------------------------:| -| P1 | 用demo_online连接在线的RSHELIOS/RS128/RSM1雷达,测试demo_online的CPU占用率 | 低于期望值(值待定) | -| P1 | 用demo_online连接在线的RSHELIOS/RS128/RSM1雷达,测试输出的点云大小 | 丢包率低于期望值(值待定) | -| P1 | 启动demo_online两个实例,连接两个在线的RSHELIOS/RS128/RSM1雷达,测试demo_online的CPU占用率 | 低于期望值(值待定) | -| P1 | 用demo_online两个实例,连接两个在线的RSHELIOS/RS128/RSM1雷达,测试输出的点云大小 | 丢包率低于期望值(值待定) | - -### 3.2 针对ARM板 - -在当下主流性能的ARM板上,做如下测试。 - -| 级别 | 功能步骤简要说明 | 期望结果 | -|:------:|:--------------------------------------------------------|:------------------------------:| -| P1 | 用demo_online连接在线的RSM1雷达,测试demo_online的CPU占用率 | 低于期望值(值待定) | -| P1 | 用demo_online连接在线的RSM1雷达,测试输出的点云大小 | 丢包率低于期望值(值待定) | -| P1 | 启动demo_online两个实例,连接两个在线的RSM1雷达,测试demo_online的CPU占用率 | 低于期望值(值待定) | -| P1 | 用demo_online两个实例,连接两个在线的RSM1雷达,测试输出的点云大小 | 丢包率低于期望值(值待定) | - - - - - From 50c8053f3959e1cb80e2d4034e54f9947565fe23 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 29 Apr 2022 16:01:44 +0800 Subject: [PATCH 246/379] format: format --- src/rs_driver/driver/lidar_driver_impl.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 7165c7b0..d972dc1a 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -352,7 +352,7 @@ inline void LidarDriverImpl::processMsop() { // // Low latency, or low CPU usage, that is the question. - // -- Hamlet + // - Hamlet // #if 1 std::shared_ptr pkt = msop_pkt_queue_.popWait(1000); From 527ae3cddd814ab9166babaa5a2b42c49d1ebc0b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 6 May 2022 09:31:13 +0800 Subject: [PATCH 247/379] feat: use raw buffer to packet callback --- src/rs_driver/driver/decoder/decoder.hpp | 2 +- src/rs_driver/driver/lidar_driver_impl.hpp | 12 ++++++------ 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index aefcdc75..662a471d 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -400,7 +400,7 @@ inline bool Decoder::processMsopPkt(const uint8_t* pkt, size_t siz return false; } - if (memcmp(pkt, this->const_param_.MSOP_ID, const_param_.MSOP_ID_LEN) != 0) + if (memcmp(pkt, this->const_param_.MSOP_ID, this->const_param_.MSOP_ID_LEN) != 0) { LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)), 1); return false; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 7165c7b0..c7a28754 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -81,7 +81,7 @@ class LidarDriverImpl private: - void runPacketCallBack(std::shared_ptr buf, double timestamp, uint8_t is_difop, uint8_t is_frame_begin); + void runPacketCallBack(uint8_t* data, size_t data_size, double timestamp, uint8_t is_difop, uint8_t is_frame_begin); void runExceptionCallback(const Error& error); std::shared_ptr packetGet(size_t size); @@ -277,7 +277,7 @@ inline bool LidarDriverImpl::getTemperature(float& temp) } template -inline void LidarDriverImpl::runPacketCallBack(std::shared_ptr buf, +inline void LidarDriverImpl::runPacketCallBack(uint8_t* data, size_t data_size, double timestamp, uint8_t is_difop, uint8_t is_frame_begin) { if (cb_put_pkt_) @@ -288,8 +288,8 @@ inline void LidarDriverImpl::runPacketCallBack(std::shared_ptrdataSize()); - memcpy (pkt.buf_.data(), buf->data(), buf->dataSize()); + pkt.buf_.resize(data_size); + memcpy (pkt.buf_.data(), data, data_size); cb_put_pkt_(pkt); } } @@ -370,7 +370,7 @@ inline void LidarDriverImpl::processMsop() #endif bool pkt_to_split = decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); - runPacketCallBack(pkt, decoder_ptr_->prevPktTs(), false, pkt_to_split); // msop packet + runPacketCallBack(pkt->data(), pkt->dataSize(), decoder_ptr_->prevPktTs(), false, pkt_to_split); // msop packet free_pkt_queue_.push(pkt); } @@ -388,7 +388,7 @@ inline void LidarDriverImpl::processDifop() } decoder_ptr_->processDifopPkt(pkt->data(), pkt->dataSize()); - runPacketCallBack(pkt, 0, true, false); // difop packet + runPacketCallBack(pkt->data(), pkt->dataSize(), 0, true, false); // difop packet free_pkt_queue_.push(pkt); } From a56cd56a165e3d1bcc6836802dfc2d4823d44646 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 6 May 2022 12:14:32 +0800 Subject: [PATCH 248/379] feat: support rsp128 --- .../driver/decoder/decoder_RS128.hpp | 10 --- ...der_RSRUBY_PLUS.hpp => decoder_RSP128.hpp} | 85 +++++++++++++------ .../driver/decoder/decoder_factory.hpp | 12 +-- src/rs_driver/driver/driver_param.hpp | 26 +++--- 4 files changed, 80 insertions(+), 53 deletions(-) rename src/rs_driver/driver/decoder/{decoder_RSRUBY_PLUS.hpp => decoder_RSP128.hpp} (80%) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 0da36742..51373848 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -89,9 +89,6 @@ class DecoderRS128 : public DecoderMech explicit DecoderRS128(const RSDecoderParam& param); - explicit DecoderRS128(const RSDecoderMechConstParam& const_param, - const RSDecoderParam& param); - #ifndef UNIT_TEST protected: #endif @@ -183,13 +180,6 @@ inline DecoderRS128::DecoderRS128(const RSDecoderParam& param) { } -template -inline DecoderRS128::DecoderRS128(const RSDecoderMechConstParam& const_param, - const RSDecoderParam& param) - : DecoderMech(const_param, param) -{ -} - template inline void DecoderRS128::decodeDifopPkt(const uint8_t* packet, size_t size) { diff --git a/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp b/src/rs_driver/driver/decoder/decoder_RSP128.hpp similarity index 80% rename from src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp rename to src/rs_driver/driver/decoder/decoder_RSP128.hpp index 3a5a9027..86c4732f 100644 --- a/src/rs_driver/driver/decoder/decoder_RSRUBY_PLUS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP128.hpp @@ -32,22 +32,62 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include -#include namespace robosense { namespace lidar { +#pragma pack(push, 1) +typedef struct +{ + uint8_t id[1]; + uint8_t ret_id; + uint16_t azimuth; + RSChannel channels[128]; +} RSP128MsopBlock; + +typedef struct +{ + RSMsopHeaderV2 header; + RSP128MsopBlock blocks[3]; + unsigned int index; +} RSP128MsopPkt; + +typedef struct +{ + uint8_t id[8]; + uint16_t rpm; + RSEthNetV2 eth; + RSFOV fov; + uint8_t reserved1[2]; + uint16_t phase_lock_angle; + RSVersionV2 version; + uint8_t reserved2[229]; + RSSN sn; + uint16_t zero_cali; + uint8_t return_mode; + RSTimeInfo time_info; + RSStatusV1 status; + uint8_t reserved3[5]; + RSDiagnoV1 diagno; + uint8_t gprmc[86]; + RSCalibrationAngle vert_angle_cali[128]; + RSCalibrationAngle horiz_angle_cali[128]; + uint8_t reserved4[10]; + uint16_t tail; +} RSP128DifopPkt; + +#pragma pack(pop) template -class DecoderRSRUBY_PLUS : public DecoderRS128 +class DecoderRSP128 : public DecoderMech { public: virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); - //virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); - virtual ~DecoderRSRUBY_PLUS() = default; + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRSP128() = default; - explicit DecoderRSRUBY_PLUS(const RSDecoderParam& param); + explicit DecoderRSP128(const RSDecoderParam& param); #ifndef UNIT_TEST protected: @@ -61,7 +101,7 @@ class DecoderRSRUBY_PLUS : public DecoderRS128 }; template -inline RSDecoderMechConstParam& DecoderRSRUBY_PLUS::getConstParam() +inline RSDecoderMechConstParam& DecoderRSP128::getConstParam() { static RSDecoderMechConstParam param = { @@ -123,7 +163,7 @@ inline RSDecoderMechConstParam& DecoderRSRUBY_PLUS::getConstParam( } template -inline RSEchoMode DecoderRSRUBY_PLUS::getEchoMode(uint8_t mode) +inline RSEchoMode DecoderRSP128::getEchoMode(uint8_t mode) { switch (mode) { @@ -140,42 +180,40 @@ inline RSEchoMode DecoderRSRUBY_PLUS::getEchoMode(uint8_t mode) } template -inline void DecoderRSRUBY_PLUS::decodeDifopPkt(const uint8_t* packet, size_t size) +inline void DecoderRSP128::decodeDifopPkt(const uint8_t* packet, size_t size) { - const RS128DifopPkt& pkt = *(const RS128DifopPkt*)(packet); - this->template decodeDifopCommon(pkt); + const RSP128DifopPkt& pkt = *(const RSP128DifopPkt*)(packet); + this->template decodeDifopCommon(pkt); this->echo_mode_ = getEchoMode (pkt.return_mode); this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? (this->blks_per_frame_ << 1) : this->blks_per_frame_; } - template -inline DecoderRSRUBY_PLUS::DecoderRSRUBY_PLUS(const RSDecoderParam& param) - : DecoderRS128(getConstParam(), param) +inline DecoderRSP128::DecoderRSP128(const RSDecoderParam& param) + : DecoderMech(getConstParam(), param) { } -#if 0 template -inline bool DecoderRSRUBY_PLUS::decodeMsopPkt(const uint8_t* pkt, size_t size) +inline bool DecoderRSP128::decodeMsopPkt(const uint8_t* pkt, size_t size) { if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } else { - return internDecodeMsopPkt>(pkt, size); + return internDecodeMsopPkt>(pkt, size); } } template template -inline bool DecoderRSRUBY_PLUS::internDecodeMsopPkt(const uint8_t* packet, size_t size) +inline bool DecoderRSP128::internDecodeMsopPkt(const uint8_t* packet, size_t size) { - const RS128MsopPkt& pkt = *(const RS128MsopPkt*)(packet); + const RSP128MsopPkt& pkt = *(const RSP128MsopPkt*)(packet); bool ret = false; this->temperature_ = parseTempInBe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; @@ -204,23 +242,23 @@ inline bool DecoderRSRUBY_PLUS::internDecodeMsopPkt(const uint8_t* double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { - const RS128MsopBlock& block = pkt.blocks[blk]; + const RSP128MsopBlock& block = pkt.blocks[blk]; if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { - this->excb_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); break; } int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->height_, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); ret = true; } int32_t block_az_diff; - float block_ts_off; + double block_ts_off; iter.get(blk, block_az_diff, block_ts_off); for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) @@ -272,7 +310,6 @@ inline bool DecoderRSRUBY_PLUS::internDecodeMsopPkt(const uint8_t* this->prev_pkt_ts_ = pkt_ts; return ret; } -#endif } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index b02d33a6..dde94158 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -38,7 +38,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include +#include #include #include @@ -79,14 +79,14 @@ inline std::shared_ptr> DecoderFactory::crea case LidarType::RSHELIOS_16P: ret_ptr = std::make_shared>(param); break; - case LidarType::RS80: - ret_ptr = std::make_shared>(param); - break; case LidarType::RS128: ret_ptr = std::make_shared>(param); break; - case LidarType::RSRUBY_PLUS: - ret_ptr = std::make_shared>(param); + case LidarType::RS80: + ret_ptr = std::make_shared>(param); + break; + case LidarType::RSP128: + ret_ptr = std::make_shared>(param); break; case LidarType::RSM1: ret_ptr = std::make_shared>(param); diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index a5552ed8..f91669f0 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -47,7 +47,7 @@ enum LidarType ///< LiDAR type RSBP, RS128, RS80, - RSRUBY_PLUS, + RSP128, RSHELIOS, RSHELIOS_16P, RSROCK, @@ -75,14 +75,14 @@ inline std::string lidarTypeToStr(const LidarType& type) case LidarType::RSHELIOS_16P: str = "RSHELIOS_16P"; break; - case LidarType::RS80: - str = "RS80"; - break; case LidarType::RS128: str = "RS128"; break; - case LidarType::RSRUBY_PLUS: - str = "RSRUBY_PLUS"; + case LidarType::RS80: + str = "RS80"; + break; + case LidarType::RSP128: + str = "RSP128"; break; case LidarType::RSM1: str = "RSM1"; @@ -119,17 +119,17 @@ inline LidarType strToLidarType(const std::string& type) { return lidar::LidarType::RSHELIOS_16P; } - else if (type == "RS80") - { - return lidar::LidarType::RS80; - } else if (type == "RS128") { return lidar::LidarType::RS128; } - else if (type == "RSRUBY_PLUS") + else if (type == "RS80") + { + return lidar::LidarType::RS80; + } + else if (type == "RSP128") { - return lidar::LidarType::RSRUBY_PLUS; + return lidar::LidarType::RSP128; } else if (type == "RSM1") { @@ -142,7 +142,7 @@ inline LidarType strToLidarType(const std::string& type) else { RS_ERROR << "Wrong lidar type: " << type << RS_REND; - RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS80, RS128, RSRUBY_PLUS, RSM1, RSM2." + RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS80, RS128, RSP128, RSM1, RSM2." << RS_REND; exit(-1); } From d260d4ab4ca6cd9494e40d8a509795ecf0bbe00c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 6 May 2022 16:03:03 +0800 Subject: [PATCH 249/379] feat: support rsp80 --- .../driver/decoder/decoder_RSP80.hpp | 350 ++++++++++++++++++ .../driver/decoder/decoder_factory.hpp | 4 + src/rs_driver/driver/driver_param.hpp | 10 +- 3 files changed, 363 insertions(+), 1 deletion(-) create mode 100644 src/rs_driver/driver/decoder/decoder_RSP80.hpp diff --git a/src/rs_driver/driver/decoder/decoder_RSP80.hpp b/src/rs_driver/driver/decoder/decoder_RSP80.hpp new file mode 100644 index 00000000..1e7553f5 --- /dev/null +++ b/src/rs_driver/driver/decoder/decoder_RSP80.hpp @@ -0,0 +1,350 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include + +namespace robosense +{ +namespace lidar +{ +#pragma pack(push, 1) +typedef struct +{ + uint8_t id[1]; + uint8_t ret_id; + uint16_t azimuth; + RSChannel channels[80]; +} RSP80MsopBlock; + +typedef struct +{ + RSMsopHeaderV2 header; + RSP80MsopBlock blocks[4]; + unsigned int index; + unsigned char tail[188]; +} RSP80MsopPkt; + +typedef struct +{ + uint8_t id[8]; + uint16_t rpm; + RSEthNetV2 eth; + RSFOV fov; + uint8_t reserved1[2]; + uint16_t phase_lock_angle; + RSVersionV2 version; + uint8_t reserved2[229]; + RSSN sn; + uint16_t zero_cali; + uint8_t return_mode; + RSTimeInfo time_info; + RSStatusV1 status; + uint8_t reserved3[5]; + RSDiagnoV1 diagno; + uint8_t gprmc[86]; + RSCalibrationAngle vert_angle_cali[128]; + RSCalibrationAngle horiz_angle_cali[128]; + uint8_t reserved4[10]; + uint16_t tail; +} RSP80DifopPkt; + +#pragma pack(pop) + +template +class DecoderRSP80 : public DecoderMech +{ +public: + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRSP80() = default; + + explicit DecoderRSP80(const RSDecoderParam& param); + +#ifndef UNIT_TEST +protected: +#endif + + static RSDecoderMechConstParam& getConstParam(); + static RSEchoMode getEchoMode(uint8_t mode); + + void calcParam(); + template + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); + + uint8_t lidar_type_; +}; + +template +inline RSDecoderMechConstParam& DecoderRSP80::getConstParam() +{ + static RSDecoderMechConstParam param = + { + 1248 // msop len + , 1248 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x5A} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFE} // block id + , 80 // laser number + , 4 // blocks per packet + , 80 // channels per block + , 1.0f // distance min + , 250.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.02892f // RX + , -0.013f // RY + , 0.0f // RZ + }; + + float blk_ts = 55.56f; + param.BLOCK_DURATION = blk_ts / 1000000; + + return param; +} + +template +inline void DecoderRSP80::calcParam() +{ + float blk_ts = 55.56f; + + float firing_tss_80[80] = + { + 0.0f, 0.0f, 0.0f, 0.0f, 1.217f, 1.217f, 1.217f, 1.217f, + 2.434f, 2.434f, 3.652f, 3.652f, 3.652f, 4.869f, 4.869f, 6.086f, + 6.086f, 7.304f, 7.304f, 8.521f, 8.521f, 9.739f, 9.739f, 11.323f, + 11.323f, 12.907f, 12.907f, 14.924f, 14.924f, 16.941f, 16.941f, 16.941f, + + 16.941f, 18.959f, 18.959f, 18.959f, 18.959f, 20.976f, 20.976f, 20.976f, + 20.976f, 23.127f, 23.127f, 23.127f, 23.127f, 25.278f, 25.278f, 25.278f, + 25.278f, 27.428f, 27.428f, 27.428f, 27.428f, 29.579f, 29.579f, 29.579f, + 29.579f, 31.963f, 31.963f, 31.963f, 31.963f, 34.347f, 34.347f, 34.347f, + + 34.347f, 36.498f, 36.498f, 36.498f, 36.498f, 38.648f, 38.648f, 40.666f, + 40.666f, 42.683f, 50.603f, 52.187f, 52.187f, 52.187f, 53.771f, 53.771f, + }; + + float firing_tss_80v[80] = + { + 0.0f, 0.0f, 0.0f, 0.0f, 1.217f, 1.217f, 1.217f, 1.217f, + 2.434f, 2.434f, 2.434f, 2.434f, 3.652f, 3.652f, 3.652f, 3.652f, + 4.869f, 4.869f, 4.869f, 4.869f, 6.086f, 6.086f, 6.086f, 6.086f, + 7.304f, 7.304f, 7.304f, 7.304f, 8.521f, 8.521f, 8.521f, 8.521f, + + 9.739f, 9.739f, 9.739f, 9.739f, 11.323f, 11.323f, 11.323f, 11.323f, + 12.907f, 12.907f, 12.907f, 12.907f, 14.924f, 14.924f, 14.924f, 14.924f, + 16.941f, 16.941f, 16.941f, 16.941f, 18.959f, 18.959f, 18.959f, 18.959f, + 20.976f, 20.976f, 20.976f, 20.976f, 23.127f, 23.127f, 23.127f, 23.127f, + + 25.278f, 25.278f, 25.278f, 25.278f, 27.428f, 27.428f, 27.428f, 27.428f, + 29.579f, 29.579f, 29.579f, 29.579f, 31.963f, 31.963f, 31.963f, 31.963f, + }; + + float* firing_tss = firing_tss_80; // 80 - lidar_type = 0x07 + if (lidar_type_ == 0x08) // 80v - lidar_type = 0x08 + { + firing_tss = firing_tss_80v; + } + + RSDecoderMechConstParam& param = this->mech_const_param_; + param.BLOCK_DURATION = blk_ts / 1000000; + for (uint16_t i = 0; i < 80; i++) + { + param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; + param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; + } +} + +template +inline RSEchoMode DecoderRSP80::getEchoMode(uint8_t mode) +{ + switch (mode) + { + case 0x00: + case 0x01: + case 0x02: + return RSEchoMode::ECHO_SINGLE; + case 0x03: + case 0x04: + case 0x05: + default: + return RSEchoMode::ECHO_DUAL; + } +} + +template +inline void DecoderRSP80::decodeDifopPkt(const uint8_t* packet, size_t size) +{ + const RSP80DifopPkt& pkt = *(const RSP80DifopPkt*)(packet); + this->template decodeDifopCommon(pkt); + + this->echo_mode_ = getEchoMode (pkt.return_mode); + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; +} + +template +inline DecoderRSP80::DecoderRSP80(const RSDecoderParam& param) + : DecoderMech(getConstParam(), param), + lidar_type_(0) +{ +} + +template +inline bool DecoderRSP80::decodeMsopPkt(const uint8_t* pkt, size_t size) +{ + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) + { + return internDecodeMsopPkt>(pkt, size); + } + else + { + return internDecodeMsopPkt>(pkt, size); + } +} + +template +template +inline bool DecoderRSP80::internDecodeMsopPkt(const uint8_t* packet, size_t size) +{ + const RSP80MsopPkt& pkt = *(const RSP80MsopPkt*)(packet); + bool ret = false; + + uint8_t lidar_type = pkt.header.lidar_type; + if (lidar_type_ != lidar_type) + { + lidar_type_ = lidar_type; + calcParam(); + } + + this->temperature_ = parseTempInBe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) + { + pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 1e-6; + } + else + { + uint64_t ts = getTimeHost(); + + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = ts * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeUTCWithNs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + } + } + + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + this->block_az_diff_, this->fov_blind_ts_diff_); + + double block_ts = pkt_ts; + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + { + const RSP80MsopBlock& block = pkt.blocks[blk]; + + if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) + { + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + break; + } + + int32_t block_az = ntohs(block.azimuth); + if (this->split_strategy_->newBlock(block_az)) + { + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + ret = true; + } + + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) + { + const RSChannel& channel = block.channels[chan]; + + double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + int32_t angle_horiz = block_az + + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); + + int32_t angle_vert = this->chan_angles_.vertAdjust(chan); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + + if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) + { + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); + } + else if (!this->param_.dense_points) + { + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); + } + + this->prev_point_ts_ = chan_ts; + } + } + + this->prev_pkt_ts_ = pkt_ts; + return ret; +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index dde94158..70d5bc0b 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -39,6 +39,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include #include @@ -88,6 +89,9 @@ inline std::shared_ptr> DecoderFactory::crea case LidarType::RSP128: ret_ptr = std::make_shared>(param); break; + case LidarType::RSP80: + ret_ptr = std::make_shared>(param); + break; case LidarType::RSM1: ret_ptr = std::make_shared>(param); break; diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index f91669f0..6ce281c9 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -48,6 +48,7 @@ enum LidarType ///< LiDAR type RS128, RS80, RSP128, + RSP80, RSHELIOS, RSHELIOS_16P, RSROCK, @@ -84,6 +85,9 @@ inline std::string lidarTypeToStr(const LidarType& type) case LidarType::RSP128: str = "RSP128"; break; + case LidarType::RSP80: + str = "RSP80"; + break; case LidarType::RSM1: str = "RSM1"; break; @@ -131,6 +135,10 @@ inline LidarType strToLidarType(const std::string& type) { return lidar::LidarType::RSP128; } + else if (type == "RSP80") + { + return lidar::LidarType::RSP80; + } else if (type == "RSM1") { return lidar::LidarType::RSM1; @@ -142,7 +150,7 @@ inline LidarType strToLidarType(const std::string& type) else { RS_ERROR << "Wrong lidar type: " << type << RS_REND; - RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS80, RS128, RSP128, RSM1, RSM2." + RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS80, RS128, RSP128, RSP80, RSM1, RSM2." << RS_REND; exit(-1); } From 81e51b261a3a73b08aa61dcf847a77119c8b247d Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 6 May 2022 17:07:56 +0800 Subject: [PATCH 250/379] feat: support rsp48 --- .../driver/decoder/decoder_RSP48.hpp | 304 ++++++++++++++++++ .../driver/decoder/decoder_RSP80.hpp | 1 - .../driver/decoder/decoder_factory.hpp | 4 + src/rs_driver/driver/driver_param.hpp | 10 +- 4 files changed, 317 insertions(+), 2 deletions(-) create mode 100644 src/rs_driver/driver/decoder/decoder_RSP48.hpp diff --git a/src/rs_driver/driver/decoder/decoder_RSP48.hpp b/src/rs_driver/driver/decoder/decoder_RSP48.hpp new file mode 100644 index 00000000..014e2f4b --- /dev/null +++ b/src/rs_driver/driver/decoder/decoder_RSP48.hpp @@ -0,0 +1,304 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include + +namespace robosense +{ +namespace lidar +{ +#pragma pack(push, 1) +typedef struct +{ + uint8_t id[1]; + uint8_t ret_id; + uint16_t azimuth; + RSChannel channels[48]; +} RSP48MsopBlock; + +typedef struct +{ + RSMsopHeaderV2 header; + RSP48MsopBlock blocks[8]; + unsigned int index; +} RSP48MsopPkt; + +typedef struct +{ + uint8_t id[8]; + uint16_t rpm; + RSEthNetV2 eth; + RSFOV fov; + uint8_t reserved1[2]; + uint16_t phase_lock_angle; + RSVersionV2 version; + uint8_t reserved2[229]; + RSSN sn; + uint16_t zero_cali; + uint8_t return_mode; + RSTimeInfo time_info; + RSStatusV1 status; + uint8_t reserved3[5]; + RSDiagnoV1 diagno; + uint8_t gprmc[86]; + RSCalibrationAngle vert_angle_cali[128]; + RSCalibrationAngle horiz_angle_cali[128]; + uint8_t reserved4[10]; + uint16_t tail; +} RSP48DifopPkt; + +#pragma pack(pop) + +template +class DecoderRSP48 : public DecoderMech +{ +public: + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRSP48() = default; + + explicit DecoderRSP48(const RSDecoderParam& param); + +#ifndef UNIT_TEST +protected: +#endif + + static RSDecoderMechConstParam& getConstParam(); + static RSEchoMode getEchoMode(uint8_t mode); + + template + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); +}; + +template +inline RSDecoderMechConstParam& DecoderRSP48::getConstParam() +{ + static RSDecoderMechConstParam param = + { + 1268 // msop len + , 1248 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x5A} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFE} // block id + , 48 // laser number + , 8 // blocks per packet + , 48 // channels per block + , 1.0f // distance min + , 250.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.02892f // RX + , -0.013f // RY + , 0.0f // RZ + }; + + INIT_ONLY_ONCE(); + + float blk_ts = 55.56f; + float firing_tss[48] = + { + 0.0f, 0.0f, 1.217f, 1.217f, 2.434f, 2.434f, 3.652f, 3.652f, + 4.869f, 4.869f, 6.086f, 6.086f, 7.304f, 7.304f, 8.521f, 8.521f, + 9.739f, 9.739f, 11.323f, 11.323f, 12.907f, 12.907f, 14.924f, 14.924f, + 16.941f, 16.941f, 18.959f, 18.959f, 20.976f, 20.976f, 23.127f, 23.127f, + + 25.278f, 25.278f, 27.428f, 27.428f, 29.579f, 29.579f, 31.963f, 31.963f, + 34.347f, 34.347f, 36.498f, 36.498f, 38.648f, 38.648f, 40.666f, 40.666f, + }; + + param.BLOCK_DURATION = blk_ts / 1000000; + for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) + { + param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; + param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; + } + + return param; +} + +template +inline RSEchoMode DecoderRSP48::getEchoMode(uint8_t mode) +{ + switch (mode) + { + case 0x00: + case 0x01: + case 0x02: + return RSEchoMode::ECHO_SINGLE; + case 0x03: + case 0x04: + case 0x05: + default: + return RSEchoMode::ECHO_DUAL; + } +} + +template +inline void DecoderRSP48::decodeDifopPkt(const uint8_t* packet, size_t size) +{ + const RSP48DifopPkt& pkt = *(const RSP48DifopPkt*)(packet); + this->template decodeDifopCommon(pkt); + + this->echo_mode_ = getEchoMode (pkt.return_mode); + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; +} + +template +inline DecoderRSP48::DecoderRSP48(const RSDecoderParam& param) + : DecoderMech(getConstParam(), param) +{ +} + +template +inline bool DecoderRSP48::decodeMsopPkt(const uint8_t* pkt, size_t size) +{ + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) + { + return internDecodeMsopPkt>(pkt, size); + } + else + { + return internDecodeMsopPkt>(pkt, size); + } +} + +template +template +inline bool DecoderRSP48::internDecodeMsopPkt(const uint8_t* packet, size_t size) +{ + const RSP48MsopPkt& pkt = *(const RSP48MsopPkt*)(packet); + bool ret = false; + + this->temperature_ = parseTempInBe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) + { + pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 1e-6; + } + else + { + uint64_t ts = getTimeHost(); + + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = ts * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeUTCWithNs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + } + } + + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + this->block_az_diff_, this->fov_blind_ts_diff_); + + double block_ts = pkt_ts; + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + { + const RSP48MsopBlock& block = pkt.blocks[blk]; + + if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) + { + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + break; + } + + int32_t block_az = ntohs(block.azimuth); + if (this->split_strategy_->newBlock(block_az)) + { + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + ret = true; + } + + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) + { + const RSChannel& channel = block.channels[chan]; + + double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + int32_t angle_horiz = block_az + + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); + + int32_t angle_vert = this->chan_angles_.vertAdjust(chan); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + + if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) + { + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); + } + else if (!this->param_.dense_points) + { + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); + } + + this->prev_point_ts_ = chan_ts; + } + } + + this->prev_pkt_ts_ = pkt_ts; + return ret; +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_RSP80.hpp b/src/rs_driver/driver/decoder/decoder_RSP80.hpp index 1e7553f5..a44151e5 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP80.hpp @@ -181,7 +181,6 @@ inline void DecoderRSP80::calcParam() } RSDecoderMechConstParam& param = this->mech_const_param_; - param.BLOCK_DURATION = blk_ts / 1000000; for (uint16_t i = 0; i < 80; i++) { param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 70d5bc0b..ba2a45c9 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -40,6 +40,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include #include @@ -92,6 +93,9 @@ inline std::shared_ptr> DecoderFactory::crea case LidarType::RSP80: ret_ptr = std::make_shared>(param); break; + case LidarType::RSP48: + ret_ptr = std::make_shared>(param); + break; case LidarType::RSM1: ret_ptr = std::make_shared>(param); break; diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 6ce281c9..94725217 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -49,6 +49,7 @@ enum LidarType ///< LiDAR type RS80, RSP128, RSP80, + RSP48, RSHELIOS, RSHELIOS_16P, RSROCK, @@ -88,6 +89,9 @@ inline std::string lidarTypeToStr(const LidarType& type) case LidarType::RSP80: str = "RSP80"; break; + case LidarType::RSP48: + str = "RSP48"; + break; case LidarType::RSM1: str = "RSM1"; break; @@ -139,6 +143,10 @@ inline LidarType strToLidarType(const std::string& type) { return lidar::LidarType::RSP80; } + else if (type == "RSP48") + { + return lidar::LidarType::RSP48; + } else if (type == "RSM1") { return lidar::LidarType::RSM1; @@ -150,7 +158,7 @@ inline LidarType strToLidarType(const std::string& type) else { RS_ERROR << "Wrong lidar type: " << type << RS_REND; - RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS80, RS128, RSP128, RSP80, RSM1, RSM2." + RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS80, RS128, RSP128, RSP80, RSP48, RSM1, RSM2." << RS_REND; exit(-1); } From 8a35426b8789600b679f354af68bee088edb39bb Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 6 May 2022 17:22:28 +0800 Subject: [PATCH 251/379] feat: format rs ruby --- src/rs_driver/driver/decoder/decoder_RS128.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 3 +-- src/rs_driver/driver/decoder/decoder_RSP128.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSP48.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSP80.hpp | 3 +-- 5 files changed, 5 insertions(+), 7 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 51373848..d60341b6 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -50,7 +50,7 @@ typedef struct { RSMsopHeaderV2 header; RS128MsopBlock blocks[3]; - unsigned int index; + uint8_t reserved[4]; } RS128MsopPkt; typedef struct diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 0c2d0760..05026602 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -51,8 +51,7 @@ typedef struct { RSMsopHeaderV2 header; RS80MsopBlock blocks[4]; - uint8_t reserved[188]; - unsigned int index; + uint8_t reserved[192]; } RS80MsopPkt; typedef struct diff --git a/src/rs_driver/driver/decoder/decoder_RSP128.hpp b/src/rs_driver/driver/decoder/decoder_RSP128.hpp index 86c4732f..a286446b 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP128.hpp @@ -50,7 +50,7 @@ typedef struct { RSMsopHeaderV2 header; RSP128MsopBlock blocks[3]; - unsigned int index; + uint8_t reserved[4]; } RSP128MsopPkt; typedef struct diff --git a/src/rs_driver/driver/decoder/decoder_RSP48.hpp b/src/rs_driver/driver/decoder/decoder_RSP48.hpp index 014e2f4b..75968a6b 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP48.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP48.hpp @@ -51,7 +51,7 @@ typedef struct { RSMsopHeaderV2 header; RSP48MsopBlock blocks[8]; - unsigned int index; + uint8_t reserved[4]; } RSP48MsopPkt; typedef struct diff --git a/src/rs_driver/driver/decoder/decoder_RSP80.hpp b/src/rs_driver/driver/decoder/decoder_RSP80.hpp index a44151e5..1e668469 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP80.hpp @@ -51,8 +51,7 @@ typedef struct { RSMsopHeaderV2 header; RSP80MsopBlock blocks[4]; - unsigned int index; - unsigned char tail[188]; + uint8_t reserved[192]; } RSP80MsopPkt; typedef struct From 46021c161ce8c0078381dedde021c9e1b79250ba Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sat, 7 May 2022 16:16:26 +0800 Subject: [PATCH 252/379] fix: fix compiling error --- src/rs_driver/driver/decoder/trigon.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/rs_driver/driver/decoder/trigon.hpp b/src/rs_driver/driver/decoder/trigon.hpp index b2eda826..996d1767 100644 --- a/src/rs_driver/driver/decoder/trigon.hpp +++ b/src/rs_driver/driver/decoder/trigon.hpp @@ -34,6 +34,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include +#include + namespace robosense { namespace lidar From 8722cecd088198335675d4d94374ce75e25ab72c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sat, 7 May 2022 17:07:11 +0800 Subject: [PATCH 253/379] fix: fix splitting frame for m1/m2 --- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 17 ++++++++--------- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 17 ++++++++--------- 2 files changed, 16 insertions(+), 18 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 7b432afc..cf6e2ae3 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -240,7 +240,14 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); } } - + + uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); + if (split_strategy_.newPacket(pkt_seq)) + { + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + ret = true; + } + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSM1Block& block = pkt.blocks[blk]; @@ -291,14 +298,6 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size } this->prev_pkt_ts_ = pkt_ts; - - uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); - if (split_strategy_.newPacket(pkt_seq)) - { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); - ret = true; - } - return ret; } diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index 3d1cea1a..93832a6e 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -197,7 +197,14 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); } } - + + uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); + if (split_strategy_.newPacket(pkt_seq)) + { + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + ret = true; + } + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSM2Block& block = pkt.blocks[blk]; @@ -245,14 +252,6 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size } this->prev_pkt_ts_ = pkt_ts; - - uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); - if (split_strategy_.newPacket(pkt_seq)) - { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); - ret = true; - } - return ret; } From b7f0f5fe16735335d9b0d0f3339de74cb6a9a7b4 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 9 May 2022 11:47:02 +0800 Subject: [PATCH 254/379] Revert "fix: fix splitting frame for m1/m2" This reverts commit 8722cecd088198335675d4d94374ce75e25ab72c. --- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 17 +++++++++-------- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 17 +++++++++-------- 2 files changed, 18 insertions(+), 16 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index cf6e2ae3..7b432afc 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -240,14 +240,7 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); } } - - uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); - if (split_strategy_.newPacket(pkt_seq)) - { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); - ret = true; - } - + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSM1Block& block = pkt.blocks[blk]; @@ -298,6 +291,14 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size } this->prev_pkt_ts_ = pkt_ts; + + uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); + if (split_strategy_.newPacket(pkt_seq)) + { + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + ret = true; + } + return ret; } diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index 93832a6e..3d1cea1a 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -197,14 +197,7 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); } } - - uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); - if (split_strategy_.newPacket(pkt_seq)) - { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); - ret = true; - } - + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSM2Block& block = pkt.blocks[blk]; @@ -252,6 +245,14 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size } this->prev_pkt_ts_ = pkt_ts; + + uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); + if (split_strategy_.newPacket(pkt_seq)) + { + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + ret = true; + } + return ret; } From d52877cca9e882c9f2e10d6a47b11b06833c5898 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 9 May 2022 11:45:44 +0800 Subject: [PATCH 255/379] feat: split frame by rewinded seq --- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 22 +++++------- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 22 +++++------- .../driver/decoder/split_strategy.hpp | 34 ++++++++----------- test/decoder_test.cpp | 9 ++++- test/split_strategy_test.cpp | 20 +++++++---- 5 files changed, 51 insertions(+), 56 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index 7b432afc..af81d18b 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -140,7 +140,6 @@ class DecoderRSM1 : public Decoder constexpr static double FRAME_DURATION = 0.1; constexpr static uint32_t SINGLE_PKT_NUM = 630; - constexpr static uint32_t DUAL_PKT_NUM = 1260; constexpr static int ANGLE_OFFSET = 32768; virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); @@ -154,7 +153,6 @@ class DecoderRSM1 : public Decoder static RSDecoderConstParam& getConstParam(); RSEchoMode getEchoMode(uint8_t mode); - uint16_t max_seq_; SplitStrategyBySeq split_strategy_; }; @@ -185,8 +183,6 @@ inline RSDecoderConstParam& DecoderRSM1::getConstParam() template inline DecoderRSM1::DecoderRSM1(const RSDecoderParam& param) : Decoder(getConstParam(), param) - , max_seq_(SINGLE_PKT_NUM) - , split_strategy_(&max_seq_) { this->packet_duration_ = FRAME_DURATION / SINGLE_PKT_NUM; this->angles_ready_ = true; @@ -212,7 +208,6 @@ inline void DecoderRSM1::decodeDifopPkt(const uint8_t* packet, siz { const RSM1DifopPkt& pkt = *(RSM1DifopPkt*)packet; this->echo_mode_ = this->getEchoMode(pkt.return_mode); - max_seq_ = (this->echo_mode_ == ECHO_SINGLE) ? SINGLE_PKT_NUM : DUAL_PKT_NUM; } template @@ -240,7 +235,14 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); } } - + + uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); + if (split_strategy_.newPacket(pkt_seq)) + { + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + ret = true; + } + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSM1Block& block = pkt.blocks[blk]; @@ -291,14 +293,6 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size } this->prev_pkt_ts_ = pkt_ts; - - uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); - if (split_strategy_.newPacket(pkt_seq)) - { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); - ret = true; - } - return ret; } diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index 3d1cea1a..a2802c07 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -85,7 +85,6 @@ class DecoderRSM2 : public Decoder constexpr static double FRAME_DURATION = 0.1; constexpr static uint32_t SINGLE_PKT_NUM = 1260; - constexpr static uint32_t DUAL_PKT_NUM = 2520; constexpr static int VECTOR_BASE = 32768; virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); @@ -99,7 +98,6 @@ class DecoderRSM2 : public Decoder static RSDecoderConstParam& getConstParam(); RSEchoMode getEchoMode(uint8_t mode); - uint16_t max_seq_; SplitStrategyBySeq split_strategy_; }; @@ -130,8 +128,6 @@ inline RSDecoderConstParam& DecoderRSM2::getConstParam() template inline DecoderRSM2::DecoderRSM2(const RSDecoderParam& param) : Decoder(getConstParam(), param) - , max_seq_(SINGLE_PKT_NUM) - , split_strategy_(&max_seq_) { this->packet_duration_ = FRAME_DURATION / SINGLE_PKT_NUM; this->angles_ready_ = true; @@ -157,7 +153,6 @@ inline void DecoderRSM2::decodeDifopPkt(const uint8_t* packet, siz { const RSM1DifopPkt& pkt = *(RSM1DifopPkt*)packet; this->echo_mode_ = this->getEchoMode(pkt.return_mode); - max_seq_ = (this->echo_mode_ == ECHO_SINGLE) ? SINGLE_PKT_NUM : DUAL_PKT_NUM; } inline int16_t RS_SWAP_INT16(int16_t value) @@ -197,7 +192,14 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); } } - + + uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); + if (split_strategy_.newPacket(pkt_seq)) + { + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + ret = true; + } + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSM2Block& block = pkt.blocks[blk]; @@ -245,14 +247,6 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size } this->prev_pkt_ts_ = pkt_ts; - - uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); - if (split_strategy_.newPacket(pkt_seq)) - { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); - ret = true; - } - return ret; } diff --git a/src/rs_driver/driver/decoder/split_strategy.hpp b/src/rs_driver/driver/decoder/split_strategy.hpp index 1bf36c07..e8200f5d 100644 --- a/src/rs_driver/driver/decoder/split_strategy.hpp +++ b/src/rs_driver/driver/decoder/split_strategy.hpp @@ -113,8 +113,8 @@ class SplitStrategyBySeq { public: - SplitStrategyBySeq(uint16_t* max_seq) - : max_seq_(max_seq), prev_seq_(0) + SplitStrategyBySeq() + : prev_seq_(0) { setSafeRange(); } @@ -123,30 +123,25 @@ class SplitStrategyBySeq { bool split = false; - if (seq > safe_seq_max_) + if (seq < safe_seq_min_) // rewind { - // do nothing. drop it. + prev_seq_ = seq; + split = true; } - else if (seq > prev_seq_) + else if (seq < prev_seq_) { - if (seq == *max_seq_) // reach end - { - prev_seq_ = 0; - split = true; - } - else - { - prev_seq_ = seq; - } + // do nothing. } - else if (seq > safe_seq_min_) + else if (seq <= safe_seq_max_) { - // do nothing. save it. + prev_seq_ = seq; } - else // rewind + else { - prev_seq_ = seq; - split = true; + if (prev_seq_ == 0) + prev_seq_ = seq; + + //do nothing. } setSafeRange(); @@ -165,7 +160,6 @@ class SplitStrategyBySeq safe_seq_max_ = prev_seq_ + RANGE; } - uint16_t* max_seq_; uint16_t prev_seq_; uint16_t safe_seq_min_; uint16_t safe_seq_max_; diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 7604b9fa..78b174c9 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -162,7 +162,7 @@ TEST(TestDecoder, processDifopPkt) ASSERT_EQ(decoder.blks_per_frame_, 1801); ASSERT_EQ(decoder.block_az_diff_, 20); ASSERT_EQ(decoder.split_blks_per_frame_, 1801); - ASSERT_EQ(decoder.fov_blind_ts_diff_, 0.075f); // 0.1 * 3/4 + ASSERT_EQ(decoder.fov_blind_ts_diff_, 0.075); // 0.1 * 3/4 ASSERT_FALSE(decoder.angles_ready_); ASSERT_EQ(decoder.chan_angles_.vert_angles_.size(), 2); ASSERT_EQ(decoder.chan_angles_.vert_angles_[0], 0); @@ -253,7 +253,14 @@ TEST(TestDecoder, processMsopPkt) decoder.angles_ready_ = false; errCode = ERRCODE_SUCCESS; decoder.processMsopPkt((const uint8_t*)&pkt, 2); + ASSERT_EQ(errCode, 0); + +#if 0 + sleep(2); + errCode = ERRCODE_SUCCESS; + decoder.processMsopPkt((const uint8_t*)&pkt, 2); ASSERT_EQ(errCode, ERRCODE_NODIFOPRECV); +#endif decoder.param_.wait_for_difop = true; decoder.angles_ready_ = true; diff --git a/test/split_strategy_test.cpp b/test/split_strategy_test.cpp index a345c520..cc290649 100644 --- a/test/split_strategy_test.cpp +++ b/test/split_strategy_test.cpp @@ -65,10 +65,9 @@ TEST(TestSplitStrategyByNum, newBlock) ASSERT_TRUE(sn.newBlock(0)); } -TEST(TestSplitStrategyBySeq, newPacket_max_seq) +TEST(TestSplitStrategyBySeq, newPacket_by_seq) { - uint16_t max_seq = 15; - SplitStrategyBySeq sn(&max_seq); + SplitStrategyBySeq sn; ASSERT_EQ(sn.prev_seq_, 0); ASSERT_EQ(sn.safe_seq_min_, 0); ASSERT_EQ(sn.safe_seq_max_, 10); @@ -96,17 +95,25 @@ TEST(TestSplitStrategyBySeq, newPacket_max_seq) ASSERT_EQ(sn.prev_seq_, 12); ASSERT_EQ(sn.safe_seq_min_, 2); ASSERT_EQ(sn.safe_seq_max_, 22); +} - ASSERT_TRUE(sn.newPacket(15)); +TEST(TestSplitStrategyBySeq, newPacket_prev_seq) +{ + SplitStrategyBySeq sn; ASSERT_EQ(sn.prev_seq_, 0); ASSERT_EQ(sn.safe_seq_min_, 0); ASSERT_EQ(sn.safe_seq_max_, 10); + + // init value + ASSERT_FALSE(sn.newPacket(15)); + ASSERT_EQ(sn.prev_seq_, 15); + ASSERT_EQ(sn.safe_seq_min_, 5); + ASSERT_EQ(sn.safe_seq_max_, 25); } TEST(TestSplitStrategyBySeq, newPacket_rewind) { - uint16_t max_seq = 15; - SplitStrategyBySeq sn(&max_seq); + SplitStrategyBySeq sn; ASSERT_EQ(sn.prev_seq_, 0); ASSERT_EQ(sn.safe_seq_min_, 0); ASSERT_EQ(sn.safe_seq_max_, 10); @@ -128,4 +135,3 @@ TEST(TestSplitStrategyBySeq, newPacket_rewind) ASSERT_EQ(sn.safe_seq_min_, 0); ASSERT_EQ(sn.safe_seq_max_, 11); } - From 09acdecc666e5e7aeb8f155a8a9929f718b94370 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 10 May 2022 18:21:42 +0800 Subject: [PATCH 256/379] feat: support eos --- src/rs_driver/common/rs_common.hpp | 13 + .../driver/decoder/decoder_RSEOS.hpp | 240 ++++++++++++++++++ src/rs_driver/driver/decoder/decoder_RSM2.hpp | 13 +- .../driver/decoder/decoder_factory.hpp | 4 + src/rs_driver/driver/driver_param.hpp | 12 +- 5 files changed, 268 insertions(+), 14 deletions(-) create mode 100644 src/rs_driver/driver/decoder/decoder_RSEOS.hpp diff --git a/src/rs_driver/common/rs_common.hpp b/src/rs_driver/common/rs_common.hpp index 2fb93a11..e58df913 100644 --- a/src/rs_driver/common/rs_common.hpp +++ b/src/rs_driver/common/rs_common.hpp @@ -41,6 +41,19 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #endif +inline int16_t RS_SWAP_INT16(int16_t value) +{ + uint8_t* v = (uint8_t*)&value; + + uint8_t temp; + temp = v[0]; + v[0] = v[1]; + v[1] = temp; + + return value; +} + + // // define M_PI // diff --git a/src/rs_driver/driver/decoder/decoder_RSEOS.hpp b/src/rs_driver/driver/decoder/decoder_RSEOS.hpp new file mode 100644 index 00000000..529cc379 --- /dev/null +++ b/src/rs_driver/driver/decoder/decoder_RSEOS.hpp @@ -0,0 +1,240 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include + +namespace robosense +{ +namespace lidar +{ +#pragma pack(push, 1) + +typedef struct +{ + uint8_t id[4]; + uint16_t pkt_seq; + uint16_t protocol_version; + uint8_t return_mode; + uint8_t time_mode; + RSTimestampUTC timestamp; + uint8_t reserved[10]; + uint8_t lidar_type; + int8_t temperature; +} RSEOSMsopHeader; + +typedef struct +{ + uint16_t distance; + int16_t x; + int16_t y; + int16_t z; + uint8_t intensity; + uint8_t point_attribute; +} RSEOSChannel; + +typedef struct +{ + uint16_t time_offset; + RSEOSChannel channel[1]; +} RSEOSBlock; + +typedef struct +{ + RSEOSMsopHeader header; + RSEOSBlock blocks[96]; + uint8_t reserved[16]; +} RSEOSMsopPkt; + +#pragma pack(pop) + +template +class DecoderRSEOS : public Decoder +{ +public: + + constexpr static double FRAME_DURATION = 0.1; + constexpr static uint32_t SINGLE_PKT_NUM = 112; //126 + constexpr static int VECTOR_BASE = 32768; + + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRSEOS() = default; + + explicit DecoderRSEOS(const RSDecoderParam& param); + +private: + + static RSDecoderConstParam& getConstParam(); + RSEchoMode getEchoMode(uint8_t mode); + + SplitStrategyBySeq split_strategy_; +}; + +template +inline RSDecoderConstParam& DecoderRSEOS::getConstParam() +{ + static RSDecoderConstParam param = + { + 1200 // msop len + , 256 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x5A, 0xA5} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0x00, 0x00} + , 1 // laser number + , 96 // blocks per packet + , 1 // channels per block + , 0.2f // distance min + , 200.0f // distance max + , 0.005f // distance resolution + , 80.0f // initial value of temperature + }; + + return param; +} + +template +inline DecoderRSEOS::DecoderRSEOS(const RSDecoderParam& param) + : Decoder(getConstParam(), param) +{ + this->packet_duration_ = FRAME_DURATION / SINGLE_PKT_NUM; + this->angles_ready_ = true; +} + +template +inline RSEchoMode DecoderRSEOS::getEchoMode(uint8_t mode) +{ + switch (mode) + { + case 0x00: // dual return + return RSEchoMode::ECHO_DUAL; + case 0x04: // strongest return + case 0x05: // last return + case 0x06: // nearest return + default: + return RSEchoMode::ECHO_SINGLE; + } +} + +template +inline void DecoderRSEOS::decodeDifopPkt(const uint8_t* packet, size_t size) +{ +} + +template +inline bool DecoderRSEOS::decodeMsopPkt(const uint8_t* packet, size_t size) +{ + const RSEOSMsopPkt& pkt = *(RSEOSMsopPkt*)packet; + bool ret = false; + + this->temperature_ = static_cast(pkt.header.temperature - this->const_param_.TEMPERATURE_RES); + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) + { + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 1e-6; + } + else + { + uint64_t ts = getTimeHost(); + + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = getTimeHost() * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + } + } + + uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); + if (split_strategy_.newPacket(pkt_seq)) + { + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + ret = true; + } + + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + { + const RSEOSBlock& block = pkt.blocks[blk]; + + double point_time = pkt_ts + ntohs(block.time_offset) * 1e-6; + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) + { + const RSEOSChannel& channel = block.channel[chan]; + + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + + if (this->distance_section_.in(distance)) + { + float x = RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; + float y = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; + float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, point_time); + setRing(point, chan); + + this->point_cloud_->points.emplace_back(point); + } + else if (!this->param_.dense_points) + { + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, point_time); + setRing(point, chan); + + this->point_cloud_->points.emplace_back(point); + } + } + + this->prev_point_ts_ = point_time; + } + + this->prev_pkt_ts_ = pkt_ts; + return ret; +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index a2802c07..94d538a7 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -31,6 +31,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once + #include namespace robosense @@ -155,18 +156,6 @@ inline void DecoderRSM2::decodeDifopPkt(const uint8_t* packet, siz this->echo_mode_ = this->getEchoMode(pkt.return_mode); } -inline int16_t RS_SWAP_INT16(int16_t value) -{ - uint8_t* v = (uint8_t*)&value; - - uint8_t temp; - temp = v[0]; - v[0] = v[1]; - v[1] = temp; - - return value; -} - template inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size_t size) { diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index ba2a45c9..c35bd3b3 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -43,6 +43,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include namespace robosense { @@ -102,6 +103,9 @@ inline std::shared_ptr> DecoderFactory::crea case LidarType::RSM2: ret_ptr = std::make_shared>(param); break; + case LidarType::RSEOS: + ret_ptr = std::make_shared>(param); + break; default: RS_ERROR << "Wrong LiDAR Type. Please check your LiDAR Version! " << RS_REND; exit(-1); diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 94725217..d4a804be 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -54,7 +54,8 @@ enum LidarType ///< LiDAR type RSHELIOS_16P, RSROCK, RSM1 = 0x20, - RSM2 + RSM2, + RSEOS }; inline std::string lidarTypeToStr(const LidarType& type) @@ -98,6 +99,9 @@ inline std::string lidarTypeToStr(const LidarType& type) case LidarType::RSM2: str = "RSM2"; break; + case LidarType::RSEOS: + str = "RSEOS"; + break; default: str = "ERROR"; RS_ERROR << "RS_ERROR" << RS_REND; @@ -155,10 +159,14 @@ inline LidarType strToLidarType(const std::string& type) { return lidar::LidarType::RSM2; } + else if (type == "RSEOS") + { + return lidar::LidarType::RSEOS; + } else { RS_ERROR << "Wrong lidar type: " << type << RS_REND; - RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS80, RS128, RSP128, RSP80, RSP48, RSM1, RSM2." + RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS80, RS128, RSP128, RSP80, RSP48, RSM1, RSM2, RSEOS." << RS_REND; exit(-1); } From c2ecc8063e28fe2a52b9daf2c2e748e438caab64 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 19 Apr 2022 09:31:51 +0800 Subject: [PATCH 257/379] feat: remove difop handle thread --- src/rs_driver/driver/lidar_driver_impl.hpp | 59 +++++----------------- 1 file changed, 12 insertions(+), 47 deletions(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index c7a28754..500b7dec 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -88,7 +88,6 @@ class LidarDriverImpl void packetPut(std::shared_ptr pkt); void processMsop(); - void processDifop(); std::shared_ptr getPointCloud(); void splitFrame(uint16_t height, double ts); @@ -105,9 +104,7 @@ class LidarDriverImpl std::shared_ptr> decoder_ptr_; SyncQueue> free_pkt_queue_; SyncQueue> msop_pkt_queue_; - SyncQueue> difop_pkt_queue_; std::thread msop_handle_thread_; - std::thread difop_handle_thread_; uint32_t pkt_seq_; uint32_t point_cloud_seq_; bool to_exit_handle_; @@ -193,7 +190,6 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) // // input // - input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, packet_duration, cb_feed_pkt_); input_ptr_->regCallback( @@ -230,10 +226,7 @@ inline bool LidarDriverImpl::start() } to_exit_handle_ = false; - msop_handle_thread_ = - std::thread(std::bind(&LidarDriverImpl::processMsop, this)); - difop_handle_thread_ = - std::thread(std::bind(&LidarDriverImpl::processDifop, this)); + msop_handle_thread_ = std::thread(std::bind(&LidarDriverImpl::processMsop, this)); input_ptr_->start(); @@ -253,7 +246,6 @@ inline void LidarDriverImpl::stop() to_exit_handle_ = true; msop_handle_thread_.join(); - difop_handle_thread_.join(); start_flag_ = false; } @@ -318,30 +310,12 @@ inline std::shared_ptr LidarDriverImpl::packetGet(size_t s template inline void LidarDriverImpl::packetPut(std::shared_ptr pkt) { - SyncQueue>* queue; - - uint8_t* id = pkt->data(); - if (*id == 0x55) - { - queue = &msop_pkt_queue_; - } - else if (*id == 0xA5) - { - queue = &difop_pkt_queue_; - } - else - { - free_pkt_queue_.push(pkt); - return; - } - constexpr static int PACKET_POOL_MAX = 1024; - - size_t sz = queue->push(pkt); + size_t sz = msop_pkt_queue_.push(pkt); if (sz > PACKET_POOL_MAX) { LIMIT_CALL(runExceptionCallback(Error(ERRCODE_PKTBUFOVERFLOW)), 1); - queue->clear(); + msop_pkt_queue_.clear(); } } @@ -369,26 +343,17 @@ inline void LidarDriverImpl::processMsop() } #endif - bool pkt_to_split = decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); - runPacketCallBack(pkt->data(), pkt->dataSize(), decoder_ptr_->prevPktTs(), false, pkt_to_split); // msop packet - - free_pkt_queue_.push(pkt); - } -} - -template -inline void LidarDriverImpl::processDifop() -{ - while (!to_exit_handle_) - { - std::shared_ptr pkt = difop_pkt_queue_.popWait(500000); - if (pkt.get() == NULL) + uint8_t* id = pkt->data(); + if (*id == 0x55) { - continue; + bool pkt_to_split = decoder_ptr_->processMsopPkt(pkt->data(), pkt->dataSize()); + runPacketCallBack(pkt->data(), pkt->dataSize(), decoder_ptr_->prevPktTs(), false, pkt_to_split); // msop packet + } + else if (*id == 0xA5) + { + decoder_ptr_->processDifopPkt(pkt->data(), pkt->dataSize()); + runPacketCallBack(pkt->data(), pkt->dataSize(), 0, true, false); // difop packet } - - decoder_ptr_->processDifopPkt(pkt->data(), pkt->dataSize()); - runPacketCallBack(pkt->data(), pkt->dataSize(), 0, true, false); // difop packet free_pkt_queue_.push(pkt); } From 02035dca42662f76a7416c970631b2c26c2f4485 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 11 May 2022 11:47:28 +0800 Subject: [PATCH 258/379] feat: rename handle thread --- src/rs_driver/driver/lidar_driver_impl.hpp | 23 +++++++++++----------- 1 file changed, 12 insertions(+), 11 deletions(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 500b7dec..b0fadd12 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -87,7 +87,7 @@ class LidarDriverImpl std::shared_ptr packetGet(size_t size); void packetPut(std::shared_ptr pkt); - void processMsop(); + void processPacket(); std::shared_ptr getPointCloud(); void splitFrame(uint16_t height, double ts); @@ -103,8 +103,8 @@ class LidarDriverImpl std::shared_ptr input_ptr_; std::shared_ptr> decoder_ptr_; SyncQueue> free_pkt_queue_; - SyncQueue> msop_pkt_queue_; - std::thread msop_handle_thread_; + SyncQueue> pkt_queue_; + std::thread handle_thread_; uint32_t pkt_seq_; uint32_t point_cloud_seq_; bool to_exit_handle_; @@ -226,7 +226,7 @@ inline bool LidarDriverImpl::start() } to_exit_handle_ = false; - msop_handle_thread_ = std::thread(std::bind(&LidarDriverImpl::processMsop, this)); + handle_thread_ = std::thread(std::bind(&LidarDriverImpl::processPacket, this)); input_ptr_->start(); @@ -245,7 +245,7 @@ inline void LidarDriverImpl::stop() input_ptr_->stop(); to_exit_handle_ = true; - msop_handle_thread_.join(); + handle_thread_.join(); start_flag_ = false; } @@ -311,31 +311,32 @@ template inline void LidarDriverImpl::packetPut(std::shared_ptr pkt) { constexpr static int PACKET_POOL_MAX = 1024; - size_t sz = msop_pkt_queue_.push(pkt); + + size_t sz = pkt_queue_.push(pkt); if (sz > PACKET_POOL_MAX) { LIMIT_CALL(runExceptionCallback(Error(ERRCODE_PKTBUFOVERFLOW)), 1); - msop_pkt_queue_.clear(); + pkt_queue_.clear(); } } template -inline void LidarDriverImpl::processMsop() +inline void LidarDriverImpl::processPacket() { while (!to_exit_handle_) { // // Low latency, or low CPU usage, that is the question. // -- Hamlet - // + #if 1 - std::shared_ptr pkt = msop_pkt_queue_.popWait(1000); + std::shared_ptr pkt = pkt_queue_.popWait(1000); if (pkt.get() == NULL) { continue; } #else - std::shared_ptr pkt = msop_pkt_queue_.pop(); + std::shared_ptr pkt = pkt_queue_.pop(); if (pkt.get() == NULL) { usleep(1000); From a73dc74190bea3ae2adb83ba43fe6379835076c5 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 11 May 2022 12:02:07 +0800 Subject: [PATCH 259/379] feat: update CHANGELOG --- CHANGELOG.md | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 37177949..d7ba5da9 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,18 @@ # Changelog +## Unreleased + +### Added +- Support RSP128/RSP80/RSP48 lidars +- Support EOS lidar +- Add option to usleep() when no packets to be handled + +### Changed +- Limit error information when error happens +- Use raw buffer for packet callback +- Split frame by seq 1 (for MEMS lidars) +- Remove difop handle thread + ## v1.5.1 - 2022-04-28 ### Changed From e7a217d29057de741f499a148fd633fca186d4a6 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 12 May 2022 10:19:24 +0800 Subject: [PATCH 260/379] feat: move what hamlet said --- src/rs_driver/driver/lidar_driver_impl.hpp | 13 ----------- src/rs_driver/utility/sync_queue.hpp | 27 +++++++++++++++++++--- 2 files changed, 24 insertions(+), 16 deletions(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index b0fadd12..df2c4c66 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -325,24 +325,11 @@ inline void LidarDriverImpl::processPacket() { while (!to_exit_handle_) { - // - // Low latency, or low CPU usage, that is the question. - // -- Hamlet - -#if 1 std::shared_ptr pkt = pkt_queue_.popWait(1000); if (pkt.get() == NULL) { continue; } -#else - std::shared_ptr pkt = pkt_queue_.pop(); - if (pkt.get() == NULL) - { - usleep(1000); - continue; - } -#endif uint8_t* id = pkt->data(); if (*id == 0x55) diff --git a/src/rs_driver/utility/sync_queue.hpp b/src/rs_driver/utility/sync_queue.hpp index d7647cb4..c622c280 100644 --- a/src/rs_driver/utility/sync_queue.hpp +++ b/src/rs_driver/utility/sync_queue.hpp @@ -35,6 +35,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include namespace robosense { @@ -74,11 +75,15 @@ class SyncQueue inline T popWait(unsigned int usec) { - T value; + // + // Low latency, or low CPU usage, that is the question. + // -- Hamlet - std::unique_lock lck(mtx_); +#if 1 + T value; - cv_.wait_for(lck, std::chrono::microseconds(usec), [this] { return (!queue_.empty()); }); + std::unique_lock ul(mtx_); + cv_.wait_for(ul, std::chrono::microseconds(usec), [this] { return (!queue_.empty()); }); if (!queue_.empty()) { @@ -87,6 +92,22 @@ class SyncQueue } return value; +#else + T value; + + { + std::lock_guard lg(mtx_); + if (!queue_.empty()) + { + value = queue_.front(); + queue_.pop(); + return value; + } + } + + std::this_thread::sleep_for(std::chrono::microseconds(1000)); + return value; +#endif } inline void clear() From 74d9f774dfbfe101d8cab2e8f35a277a7da3bfbc Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 12 May 2022 10:29:16 +0800 Subject: [PATCH 261/379] feat: support user layer for input_raw --- src/rs_driver/driver/input/input_raw.hpp | 20 ++++++++++++++------ 1 file changed, 14 insertions(+), 6 deletions(-) diff --git a/src/rs_driver/driver/input/input_raw.hpp b/src/rs_driver/driver/input/input_raw.hpp index acd4bdd9..a589e322 100644 --- a/src/rs_driver/driver/input/input_raw.hpp +++ b/src/rs_driver/driver/input/input_raw.hpp @@ -49,17 +49,25 @@ class InputRaw : public Input void feedPacket(const uint8_t* data, size_t size); - InputRaw(const RSInputParam& input_param) - : Input(input_param) - { - } + InputRaw(const RSInputParam& input_param); + +private: + size_t raw_offset_; + size_t raw_tail_; }; +InputRaw::InputRaw(const RSInputParam& input_param) + : Input(input_param), raw_offset_(0), raw_tail_(0) +{ + raw_offset_ += input_param.user_layer_bytes; + raw_tail_ += input_param.tail_layer_bytes; +} + inline void InputRaw::feedPacket(const uint8_t* data, size_t size) { std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); - memcpy(pkt->data(), data, size); - pkt->setData(0, size); + memcpy(pkt->data(), data + raw_offset_, size - raw_offset_ - raw_tail_); + pkt->setData(0, size - raw_offset_ - raw_tail_); pushPacket(pkt); } From 900c8d576140d8f29c31a3649603f303d12d0372 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 18 May 2022 10:47:53 +0800 Subject: [PATCH 262/379] fix: fix sock_recv 0 byte --- src/rs_driver/driver/input/unix/input_sock.hpp | 2 +- src/rs_driver/driver/input/win/input_sock.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/input/unix/input_sock.hpp b/src/rs_driver/driver/input/unix/input_sock.hpp index c23a335c..de989d2f 100644 --- a/src/rs_driver/driver/input/unix/input_sock.hpp +++ b/src/rs_driver/driver/input/unix/input_sock.hpp @@ -289,7 +289,7 @@ inline void InputSock::recvPacket() std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); ssize_t ret = recvfrom(fds_[0], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); - if (ret <= 0) + if (ret < 0) { perror("recvfrom: "); break; diff --git a/src/rs_driver/driver/input/win/input_sock.hpp b/src/rs_driver/driver/input/win/input_sock.hpp index 5e5a8878..b4a2db49 100644 --- a/src/rs_driver/driver/input/win/input_sock.hpp +++ b/src/rs_driver/driver/input/win/input_sock.hpp @@ -248,7 +248,7 @@ inline void InputSock::recvPacket() { std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); int ret = recvfrom(fds_[0], (char*)pkt->buf(), (int)pkt->bufSize(), 0, NULL, NULL); - if (ret <= 0) + if (ret < 0) { perror("recvfrom: "); break; From cfc3e16659c063c3259c3944ed4395b0f68425e0 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 19 May 2022 17:04:04 +0800 Subject: [PATCH 263/379] feat: update docs --- doc/src_intro/img/class_decoder_rsm1.png | Bin 14074 -> 14507 bytes doc/src_intro/img/class_lidar_driver_impl.png | Bin 66141 -> 57777 bytes .../img/classes_split_strategy_by_seq.png | Bin 9567 -> 8964 bytes doc/src_intro/img/components.png | Bin 18552 -> 14314 bytes doc/src_intro/rs_driver_intro.md | 80 ++++++++---------- 5 files changed, 37 insertions(+), 43 deletions(-) diff --git a/doc/src_intro/img/class_decoder_rsm1.png b/doc/src_intro/img/class_decoder_rsm1.png index 646ab63f499501a6dc7475b5788327469cbd8667..c63a85342c767ae06e4e7398d88621e050547fd8 100644 GIT binary patch literal 14507 zcmaKTcRZJE|MxekBt@b`lA^50mYrlPTV$3!GNO>xpc2_68D)=Xc2`{o6$!A%E6J-x&YEz^fqoJ6ltDf9Wep5U^ zLH%$`l1yde?CPrbkI!%P9S0c8r`&%G?En3><@!h0?c`*qo`r>l`LC_~?d8au z?A${^?oMewkH1ckW01l$MSqu;|XSFW*eKR zIEkWnp)8v@BCR!x#wR8!U&-w-d0bm7|K38twzIwch7s?(`KiwEgoHJP#;%ep*6%F} z_f_0+aCD5$Q#Lkcj){q(prn-3)7$G`$mG)y!S3wter9d?kGYM_-K#VGBNIt}d10Zk zv9Vg~-1>P@a}{n=w4~vN$YYCRk>`@r(*yS&H!K^D-Z4l{nUZ1G^x;E{!=u0(H%>)+ z>4=Mq9}4&|DYIqUwry$;Pi*pA`?GHsi*&GMQw;0Tqg$<869XzL*5i3iLO6~e4|vqS z;bl^>zHCpD)zsYmfLS8Y{aeq-RA)xtD@P{1JfnMYg4R!+hAJKk+wT<+6nyUS>*D;k zUh3X_(>sxodq}d{+I#l#8dcreMr~$pzKKLEx{$E2rj8DI^7qi8&!3t9Om}OGR}LrL zP&;}nF)^|6M4D)MuK~xYnM<~|_s+?z(fyuieTVD)db^Efc=^vaik&;RXjqATZI0V~ z;lhQ<>FKBX`6fzd&&G5pDk|30)NKCqt@ln&4)@g`1DpY$D}0zXZQ67~L?rO}bAB>1 zGUsnS$2q-Q6Q!J8U2i5P9=v($7Wb;bkG|)dTOJAD%FE*&`25*rdES;(Ret^Np~!~W zU+-8_uKgUu^6RRIx=-tJbfl{ABZ?%FYAkQv%`H1<4jc$Zfs7Up`JQ%mK0z9;4%opUWJAL!;&69z z(&qg6^JaYo=3>_ucwDbs8Tt0@erLwH(N9j5b#voQyP25oAC&Ss#K%WX%_3bJ#(Fv| zGV+$=r&n*Ao7Du=NY2w;oK(!>ba{DsV%L5gP*YPoVOB*No0vGQs=7lq?rqVlS9t|J z68!wT@7=ri+Gj6u`ND2-KVON&+ znDv)go8RL!Sl00Vy%O1Q<@z5!&Y$=89HS-u{W;W%N8L@DXpTD)AaU~KZqo0$IkBtX z&yx)={hm;c*hYPjjijKUAi&NZK;npPif+7o>C$Nuy@;u)=}~s}a5hy{)uqqZhMu3f zzgI_F`v}R--u}w>zUR$NO_6i9pI#l0u|B`B@U_>}Pn}fe@#|?v zNl{VJ)X2!M!j{7x>H`%%@e2zJ-g9I38lPomDg|*5&JVici8qr@2nuc{u^l^hL{xO& z^73+9XJ-vI?i4K+TuDVmE6D!x*nIKR4FTaVBlryfryBm3(9UZ>0-%m5Sj+a$pgMM?4MlJ|}**v{U}l zKFcH$4-ZdRM8wUF)d?9Dm*YGMg5L};-Zh0BoS<>jmD>duG{W@;Xx+q;*H)YaXsYjUSrwsG9`^_w@BzSQ1( z?e&MtLSX;bmiRm0zdPIx46LrIB9(jnxmi&m-Cyh!`l;B7d;F5U{rzi$p4;y4JuY|l z?5?d;4E}(DX>P4qJytBRKtx2uY>ViS8QQV(wRvsZp!#hr-lSv)jp6sJ07Dw)|(CpuT zPd#459M4De2k=4b~(7rd<_|TQm=?*H5GYVKxkPb;o9>~hdLdU8betRqY z(IdlA`z!A5b$!n-xu6g6m{uHk^ym@stVChWfB(3LTQ9e&BTbe6@_-o0KPkyHK$3W> z+qcPI+O(5hy?Rx}Jd{O7K}UxU52Imd$ThPu*TmP_OL4POGmF4fJDb9Ba_sbuAUMdP4DjJ)|al%lql(`MLAUABM~p+r~Gnl&J({SeTq`s<=_cv6hfM&;@4=lwcG(182@ABOPHM^7|O&Yh!2$3>TPDB4xI1;j%A*JS$W@v^0D6Xs5h>dhS0k|No=|nYt)+#rAwF2 z8yX%K6Jt1e@+8Us;_2xrcI7J-uSwb6 zEj#w=#Q)Ikad8y%m^J(U`OUtnoSfc|FRXKfyt<3HHGWCcb}^gWYrjxrN1ta>p6&L% zzsTO%&8=4AXPNfZ!@|N;Od?dcYIJJNv)tSQhmQh_%gax3y~*yJST+fh#IP_L9)m)1 z)M3pl$4@7$KOAUi>MgSG9sc<<)a%dmCXV0j1=g(xd5m7u96S417B{~z^XbkmW^ocn zq{zndw|uPs4Il=v?$X%%@PeYE0F=k_{M0Rg&tddpY@w36dcghrJJ6-gyr`2L zXo>52+DO!8gk47z`x-+5RTP{btVH7_eKPhMS9L)<;_V9zcTZzUZNb0!@; zc#v3&l$0a*bd&735BhVURm-Edb#+^2J{1Ev%5(w?3QmZLiB+|?7zKV z&`L>bfpXAq!)J=xa8@+H+jD%Zs!H~twD@C z{c+s$E2Eh6Ap+DR4)9+jw{Cf)J5mh(;J5lqku%g~w7$K%`sR@D%5e}?eNMhDFRWU= z6qwhf`dC|AFMR)~Jr`AE(|*|N`t=vd$^K`~oSFaqdo)!!QYivknH~@j5cSHwH}A2K zEiHlP^HbVho}Mlsdu$EE!)9B_$qQ0bZ-*X~x`?whH9RaEaR8kgXNF^3@Y)ZfU5r9^ z**+FKnVwCOHl}<73N-F|^2p)CN)h;-mJkeSv%u5N=H_4&qj2_UcH{T2U+bMJmIB$9 zfWw8j`&H09uCegQ$kXV{N7>lI*nWO~qv+@7_jP=nUsCe1ot>Q|%0_vvF`B!pqvN8M zRz&JoBORSu^w;IZ#mwB^Y@6OZW>JSe*$7aN(Yw2kFtD(+K7D$aY#7U`6vHX~ZEA}D z=+QunIJuV<6%{X8n3z;|?%XNuy%?4{=R>z|-@Cw_OmipzwgxapLqo$tER?dca#vT^ zSip{bsS6-%Ut^A6@c8{z9d{!jEUcTI0jB*MMJZe=@-}C*$m8_=2M+?XvN+Y$)pzgN zbL;Qmb?Wr=bZ2L05=l&4{0qK~b5o~p>a#^#Tl=M5H|3{Sj@pgZ=p_-NOE?CP#azCW zG(NX#Vazouq0Km#6quC6!YFz<7($HuWF}{*+R+-+L0a@tKtBdlLzQ;og(ecjSzX%lpOivYQ(k z8eaRZm5%MJ`S4*E)PSCWHGtBlBXxUEp7H%5zYS(RJw5Q-B%M1Tcf=m~3uN>YAT8}= zx|N%o`}<%y6DY#1^z@@5mj^P(k}nV%=gE^NVJ#hM1xP?@3?Wf7>*RN54GtowGlCOH0 zr|e^3xQpMCnx0-gG{o}e>WrM7UG}`e)+o;^!!i$kq9=p$t349h{`T!#Xs}Sa3>?i4 zr_Gyh?VEmh5cLN_5e9I0{aVbz!XlaIz4cBVsrTk3(6F#n3ZM!^+Y+|#Nq+hAr5xj# zq%_nh^r|^n7+=Mr+_HR2bF)rq%-mUPZyz7cN?#wM?^muba}!iEQR=$N2+@bo9%siI z_DFipk)zqzbf)j5q@*-6Gs8n~CHNBR=6V)}Z<;wc1aoSqD-Cugrg^_1 zvrI~pmX@BKo4XksyN`0m4sOR!X#H6aaP#5u@%K>%lrvnB4QBTC+%ut!!Ya!SgC$pv zDFie8qRcbYi0|s3oWZ$p9+G6n4NtK z7G6ud2ZFCTNrpu~&*+q|Z$+bB#8o9HyC8S})~6X6cL3>NY3o%j@uHie zq|S$jhl@E6lX#9FANlcPSMoA(a6=e{$w=&@sk7=il*f)8%e_#%3umnc6+ZjXI%x#8 zO44}3vf%mYITy;oA7DKU&2cw0^c{p}>Uym;=TP3t!b}a6=5xnSB9A4m?Xv#xIDD`z zv2I}C06;Hxngg0}|Ni|R8*6{LUvejZ?{|gxQ&LltH!?c#;Gh(jr_Y{MpDf{&V!sVv zs)LdYSc^>>J)8W#_whfL^rTIYxEAxp@pCEtmMvR2I62>7{)=rmReoP#0}& zG!Gs;Ao=GRzj?nSYEyQazoV`hC_t1DNoput@PfhPGgiC!KCcjIbugKT%3>Nq11 z#>>l#?inM`0aldy65h!f^zV-OC~HpBd|l1+=PAyeJ2$lq!DMD(K^~!@t$nMs)GN&~ zJ~8pZQT0bv_4Ql90nWd)*=->Zr}c@e1As$;J?&uW#u}ZlX*)zbnDLvdudmK9;^wv{ zf1lChry-BpKaQpv%qUEW&wMQFO*HO@6^)V=W@g@nU6S$Qh2TyqDjN$6c|JZq5E$(s zaLpQQH1uU8x)v%^R8T-bNl!YAXvsY}`k|05N0m*=Ji>jJ=bwa!??&&nb#!duzf`Z3 z&;$p^420d*(y|W32Qux)r{Z&5HQ@31j=H|SK7o^X_%!?=u=71M8#qB!eSN*8&$1AU zq(>F(lFq@wL=h1YDk>@qh~m#0%S}yXB%W z>*(ueym}=9Eo}?gfajk>{iyt^Sp2fX&c;TmSGSWm?-^$kp2o*BwY0QMO-#H?PCgX9 zc|TV5v8dC*neX3i?Cn*-6!MHpBG}S41)=R}^2T;z&(P5hH>hkANPO0tjh17DEw;sX zB_t%^a>YO{ur-+11ZtX^CP9@AeMMAQPBz5 zPTT{EOd<}+xEJOF2jEO`8E;nh{oNvphMD^2jYQ@0G&k64%!T61(bb{M5(=c?prGtI zL-L|`zo{$^adY3-briH}&J?aJ#ySxv_1W0kQ4U_-7+@<`PrmC%_rE?inEJ8g8;>TW7HDBbnZvw%qx9vJm1q^15Y$$LURdD;>r%4%l z|9;K$OYcl<*yU7IDEIQ21fv60HXg1N7>p6oIdl0kZ!VZR+65tF;e5Wsfg)79gTsu%di&n_$|T)v#wSm5tZ@?IK`%`cH}?8?!n1_NIF{-TwJj_&r> zos4D>_5@P0FZ20K$X0=~kHuJxWGTsSRvrg|%)VOq<|bq4 zU`0zOE$m>Kq(}W6BV<~KXjVse^B#icOs4(EF#f;9Bbub^xJqVL)+s1G=yrIO3bL}K zvkBt57cz3`P{0nKOaGK~u0gegHCVK@w}*?IK7E>KKgtwE;-XPO-h_$ycofDWK99Js zdd64R_Jt4DhC#|p=;FnTYyp;Vtp)8`wy=?2+IDWm(SG0B`p$1-#q_0p?=C_PSXhkZ zh&evf8VoVh(~EIq2KSj9C=v7mJ#X2O{b47&#!<_P>whngjgNCCSfdpbynGq8;J2}M z&Fx#y&cVS!t|oWz6^H(p+jI2u11l?KB&DRHsnW4-jQ{e%Ne5+ob6s=PT+1c1jbvjK zk4C<2Y@{TNR8;hCTH3?=qpwVSc!F*g)-(jIq-xl9287D61zq zIXg&%w~bzxF?UY!P^M~FEo6`G<&PgfqHu)wg`qo`fo*cvsw*qAl1xfm0|-Z*N!YFy zY&*gNhY7vZ^Ut(ygaz2(NoZA=`*RTEx%&AB{Z?i~51w?rt^P=81RPU|a3xb=a-lnW zfDYK%+WvwlWNVPRzMx@joB-HjH7HW8MJ0Ch_dkL$&8}Sk?%f{$G2RHaBx#>U$gsBh z`asAYww!CH_p`8^+p&X?u#p7hK5+V68V#B>y7+69-O^^uv2%$Q*vse#Y3b=&puIP9 z-eC=9@38o4d=?`+#XRgZLRKgM$`1s-0mt?Lj0BL2YH&4DR0*y3-_O^;0`3I|Q-R)- zC3(+nhi8Y4aE9vxf@%iVG5M*O4~>B&>$>JKH>O-$Utj(9?I~K%@1KhEQ;qc!m=xpG z0AN-yS9_#YW`mqW9J3UKkZhNP zBybbg5+m2?lw_Zkh5Y96r?RuJv~ze5>B4Ob0#-eYk3S+TOb@lAlJ^&4`8IBL>dK74 zz5qr>MkQ6%TVRx072ucn^Jyz9t1T(X3^bV^LXK#(ha?|1M*h;#**P*fNg*R612xTE zmvxUx#nI7`YQF&a$jHcRzYS>^7=~H-2D+(fX>V(5Q>$I}?Ai0nlbfb146^gU!GpVi zkAz+ZcRG9a?BY!E5Ld10xpUhz7LvKemp4{_pA)j{qJWyhE#%M)H8)e?XwiG;aZ$;6 z#@=mRw$s%Z3>ki5V{2=^G&jz0(v^*D^Ja5U+^8rzf=vA^|C>m6ZX~b}RxbUrJY-D> zxItIGDa+|Vs;n-03riinitNVYaJJsr$7jSwM+eYz>zR#I2P{@@tjLfo^L7FWU}5`` zWMQM$2k*bNxah&a#8d-Q1BYAI)|L}CSX-f`>OlGReK&60fYX^T6gCSnc0@vg3H($Z zsDq%yPf1$^02hcgCS~@7TvDf?ppgC6^NinT*^M)FdO#y)BH`K~e!(Wae3KB6O=*2* zy#)pRk4(vE6z{qDy)-p7CsAnuqhK6iUyHF2BOqL2-irlepL$>c^YimBPUqwgPfp&2 zH=F{Y7a{l!Jn&xvw4gw?`10r3KfR_z3}jsD_7(v{TZ$s}`*BzAKi&F-K}&@b2EhW3 zO?5zw=GCiLVt(tAgo75c7a_uacn;eR95`U+RygDsKQMVu@K^xLn0!3 zU0hrWUc5LBTc#ZlXJcn~5l5Y?6DYuV^ypEW!7|T)0%Q!Q(b0iC@0**Wra@A7!c zyT`rgC50p@P1^_&r$Du0y-YBu&Bga&tPFxyR3uo%+nldlsR6#4TUjjxsve^$+kZPW zxcDImoY_=InwBZ{ZU-TN&1cDPG9EUPU9SNw*25V%;k)WV7&`m-OlqMNhTNW$-}IxZ zo?P3kx!AddaPQ0BM!?sUtetrFADHG;J9$Q4Ugx2#QRM3*iVwUmp9!C%)emZ^ttCHw zXP54y-+Bp>U7rp`|0z9*k+eK!VB64C=xc zFYL!9A(6{F)}a?*R8hfv0TZj~=%58(>KN$gf9icQ(MMr^ex6_npybJVO&Z#CT6Ume zHMRHln2J{#M#p3a!^!IHn~V;9^N&k8TGFI%@`Vd_BRt@GG-7@PI-F}012Vn`pl=Wx_=M0sFgbIQG=6;rR>k6c=ec%Ry91@}-%93uyB)PnR2+YO zsk;kygx0j`8W&NNQs|0HczJnsG&J0U9YD2xyE&rM&6_uG_lHq10Bx!4`mxaRWpQyv zQIRlOdIO+Oc_}7T;$kg@atIqAU+A8rYRUKvih2=}O;+iajMO3|kp-5Ql}&#Cu6FI(waY^l#zFB>QMK6nHuzM;9lUl) zp<6(*)!yA5jfl;mJDVOymkXc~(Ej1WgH-za79U(u<2l@sTFL! zw0L8Gqqpi9JZStegS_hw>dL3c9U#<#$i97G;IYKj?}rSQ1fOyIrj}W)!dkV#F$HED zmAY|CxKGRDMjLp;EGgw+T1GEio9VB^vDe}F_B%88f2$4;)|B2nV~NXs1vkbvE`J3A z?4_sQO#)*$Q`jsv{q39J$&+zxD1UD(Wu!&G>+z659OaL2VhAHsLL&ahj~_)S!!g#JbOI-WG z)9tRILG$d{Gxp6T77eslC);kYoxJi@4f6?)*$fN~8<7FHphK`Jv#_wNBXncaZE_2@ zfWI$;=sjW#8NuYtOv}xiWVrkG*49uQ-owhMfdtfJ@V$HCjj*BlX5Q7;Yk@;^r5N$X zQptiA7QKAA2mp&*O_J}$R;RkEB}pd$LCkTj=z{{fiy4`ieowZi z5GSOxRD2IDty0W>rhm*}T@FRdzpw7x*@oE(Q%7S6OmNUdtxtM?)VLeVE`Jt}7(>Jc zp}@Jn9sZTLghZsy@wAwvq;tl`#(*5{tla++cGpKl%RzC8Vyvyb4RztrSHP;Sre@>h zbS}ah%%Lyi91FZTJ+B>yxfu&PI<(S$C&~CFqSm-ZV?@0Wc1Ex3()EVL$6t8z7(kee zyC$p!GqWnR+82nXLH!Q1fZWrG3J631+Z`agz~fHZb#Y{kaJ}JI!b;x)U_$FYO-V`7 z>YE*@ISFe$JtJce3B)6{04Wo8>lYaM$V2{1Q5``2Ux=;0fJ#6_XVY21b~t|F)rliV zZjlI5%;^B&#i+oZ27yayCpg$n0`#_S*`mBsQc~i*y2#HW?X5&oQ82^a&Ckw;&2gGm zU{49YZ1FKZ1>VS|ix*QxPjAuPUycVRJP+_cP#aO@!h!+~fxT=cZc|zd)7|&kN-n+I zl_q+nFt>%?Nti7wC#MPSN+ge<7c3gBhiPf-e`h`&n_=3&{}%w6tpPea5gn$hvvZWi zZ}n6}nezx4HuIb=qH%sME|va`uklW7Dd>=bNY`{JRh5*8^}HVx#KjN~J|ie3q%(e! zPRHGegGy=XDyo&arn>sPmX@5LprG&i(gZz~yt_hvK|vT!;1dkXSUBY5e4BIE?MCfi z@$wSKf^3ns`wIzH2p5a3X?^(fzyMd5GLo;TK_U93u6gyJ0TWYOwr)Lq;slLsT&|Y0 zb3w=QCwLc^0F=bUk(L%M;@^O}`}@v)M=v`k&Pi9Yx zYK&>$_dXYwq&&j<>*HY5?6WV|NM#mvJ?CY2{Jipb>Wi}p`f6`0)SIRjjkN2 zg|K4|D_e3BIuuC89o`@6-!^4$~M+lCI`zU0Q1povrU)m?6}rmAz;HCO&d^~ zWT|?O@Q&Dy9+iWcj2}m;rs;W{M1zzIB{k*C$-|>ldJUu`b!d8entlOktuuT>BB=)> zl|6r+0X{?^#F!bfACNR{&z&$(RAy|ft&gppRadWz;?zE2-@}vUnmPUZGAaQBW*Kt_ zD6>mN=`!t@goTBnfWE-NRsdmql9%_uZ|$3D$6TE?jvOtxX_};wvGFeuYt={5-QDg> zud*5hpV{nicmG4V5_CQ1Rce==qpRz!tvd_M-jea0FCakyo`G8c&Kk9qnq-DH@Y;2p z60K(|MATyxwz71&00w)a7^Oi#VXh-@%oIp4;#EYSm0lX#gNR{M)s?2x(Gy8*(SIBg zqi0rI&g7evw_)rPnZCFTdwTbduA+yh6?AGWCY)$ez^bM!ZJ zT$lJ4G8fBtJhCrW!Ga@7ruN-CaQ4E+>nU8krWL{9 z7D|2(|1rI{Hc*adKA3p+Ejw{);z>_x7v0deXwAs>3%c@(iZ5(C(_a=9rD6AB#Wi6< zGhz&(EfE4ke9mG}$`b9FGq!1JbhHL!1EfNgIca<}=4WS9LxVXuBABkNl@-A$x&JV8 zW#;l-hT%zo3*vjeh%q#%kH9X*{rlV7+QKlOb3o84xMT8}+R>DMJI2_Fx#l=Ql_f3( zC;F7QB)|0%ojlMC%myTaOQwNnbj7JgpkKx)Ou`Oof>X&EU|?X-4z38oViC)0oEmOg zH~9?Y4KpbW3=AA01lG7TMscc)6XOdrGc&dqFIJ=7D*MEs8ZE(XQ`jYZZ zlq>t(0UX0{;S320@q_}77(*I}FjwC2!Ub(r)%$R&AB($ZYYkah{tbNU zm+NhGMh31G=R`}qBAynM19%>X^cDOydpXD6uy=e#HODKR-coO18`fcDL-aIT1CkYu z3m4+YHns{NEo2MO7Y@_xl$K&W&Q4QC0_)Q9>q1W}fKmEb#&3OR?DWj20cR0fHo8oK zoXnfB7+MOuaCX(0s@~pxM5x5WQwxVJXKjG4jA1;j3)2s2E;nOOW#&?lw>JEj^Q@&+ zvAayXQ8h~#P7Fc`|H{e@)p1S?9nU@n`!|QZ;Z(}t9;m-|=diTXmVZwIX9}nM&1OrW zi;#z%ME@!|Ihm`e;L5~V4==9@jir@8-?o7YNqWpC%VEgwGg4g*Bcs)Ur4JalLG}OI z5j}OrQ%@nYa5?u!-}KBcZX(sg2Iz>#L`BUHxJo$D>I%qV=Ifb8EWXAd?q>5Wh8;68NbU8+ z_cAjZkJDD`D|^O0oqmmJ-w*|hrY37CA-WbFw(^_<3rK<7w7e!8L~ec%B94_0O8SN@~h)HIL})o*cb}lOnMj>XO2nTXx>d) zb@<&QKYvmaX`GlC!R)jiB38F*P236n2CwP}jxXhX01WJ=k?-HB;JM`*7O8L!T^sV* z2cxcoa&vOC(`BG;^cUUe)-=`F;gOL|An}VUD@OzcwJEtdII3{+55+c(eED({^9}i0 zzup6)o}#7;oN-h|>}@ zpg}ABe!nd8W9M%rbYKi`$m|-#8eNMoJzloMO^R)cz_hd%ue^$QDSbU zaxKQ<BmI|fiUYr(8B)wKyI;v%$oQ^pd z^sfOh8n*{vy}IY6l7kFhSh?V8Tr~iH$oIH}gccw21w2(*jtl|I8JJO8T3XKYlbS-d9r9jH z$Z~EYWkFID^+5u%ZE9u=pqYumYe`AT)YCQ=Yu5e=w_O<%#2j*Ln8nl!-7ZsL86|CwotcDx4rlF~g(qc5{% z8OiCL;^N|$dhVFNVnDbFShg>h#_`)$Vq|jad3rk08f4?b0x^?@2f4udASPz7h(n)$ zsPr<$KW6JmtLBHAr`X5Oz&d6kX6}oW(QGvUu6Wr3i0v3u(B(E=nc*)7`!O^3vtlJLg3AM)pSwI`eb;}6KHA#z8DIjL z16K<|6) zGRhs-slO+VC;8%9bSz&}b8~Lt54u8|pc%OGDxWv=aZl-d!Xg7Bvj(90*y9)a({rO@ z-L%3m?0xE{66=&3&Me~+g~q`9ah5zdq}s~MiuA(K-{It+g8N5+B^qRgoVB0s5(kyM zr)}n(Qvq1bd1StriAg)o&8?cY*Vx@v0Y#)Yj)&YQbWHuMwol0T%f*(En8wwRo;~~L&lxML^s!%4=rVWVB#|F) z67-t4A%cZT40Lb#T$(-iyr94z9)}Q(GcYi1TQb-Fr`B02A8gu^Pu&d;j-nd*_fUsq zaj=GCZw5dNZf+n(X!Sho^LUeDvs$f(w3?fnlM%TA3^#EwscF0ym7*RWe?h#Of*~ZM zN?&GKgV=UtfNk)*CK@L!aSCf;$D~cM6X`1)F6>2nmiDn#WZp<0$d#38cV-&yRe!6h zD!yiX$X?NKT31<|bE^QFHn#(uSBvoo_14DSQrt4c@F0#Z+@;Qz7IkF>CH}A{O4gu? z4HF!xL-YwLy5m>y+DK_h3E?~F0}jSVej%p-n(|?N(zQp;Y+d0&}UoR z=E`Zs-S!yzFfuSG{et$FBiOwLtAK#kv_t;0WgT{H_^krOMSFW=f$o=ZG}tnPT6bAw zMmQag9)CeM)ArI#No{RGlU6|%w|x;!??6SWkF$^z7>^(ddY?3%9aOUR3CA2dHH_byG!%}>5mg6ip z!vwuN8=L4H`wB*ik}mMySTw+!N3-LxrWHMNlGG>yL1G{e&T_@n(=tp2tlT+--?r0f zI`qp=$;xNq#PBZ>)l6M16Zk)a8sX(KAZZ;mn*AFdygxT9C+RhxS${<{N7xG?!WQMU zxNqYyG33q7Suu5zm><D0I0{QQ?^Uvp(AWau*oZ7JvbVqD>U@L%uT z-JdUtHfjFXyKZ~`=Uum$=;*Z47kPom{L8ZoDTvqNl3{rrAEEQ{`q$4?{+T+HM7)>x zqHJD32!2CUR8(11+TN)%#A|qd##43i|M}M52KCU6(NhB^RTOypkfeO(tbCrF+0Fk2 D&kA(2 literal 14074 zcmaib2RN4h|L>zAvMCAKD;1$U9Mfjl%DI(9A~ERdkc~(rDpma5 zpN1O$&-(Iv7yh92*0J;>kr-QvFRIi%j9erVA4!*d&?F%9%dJ40gwN~k>IDb#S--3Y ziC^Q-E5ECwFZNjG{K=NGTyU?;+m~9R6V!W{`1y! z@UiK$%K6fDA0ND33Oe_yLG`WQ$8Nus%;29ksscIw-$o8vTXR)LrMgU72Aci-XkeH9 z#>GLJBR*{Bi!m9FcB~>~kdFnKMVw1fr zM|z8sGzSCq)B*>+R>VamRqBXddwa(J{Aj|8xL1zbD&)xedetH~cXxLKBO^zzfD>DH z@7_JS7%-fD_b#>C?L^B*r}z~V)=~!h^YwNt1gLJ?zI~v$K0iNyP;R%lcyoXMwx*`0 zj?PXhzM4++dlppM+S;zJt{U3fTXrd*Z7g$Y7n=3)^J6Os`}1qX=7YkSVG^l6>>tm^ z(6wFLwr%SvHZ8HTQyTY+Y8VT37#tk5|I`{Au)ZpJ?6z8hX^9!XygYksY-~?o->?3u z&clZfZ{D`;@7mLVmDvGOcwe7UriwqKb=B#Ec6L1Hzl|iU%)NDbm8mrI;jzNht6OpN z^QR?FJmC)gwcPY)ea*qeWedr`%&e`_Axyb%iz52MDY>{Rz{COtj9!jh7f zw{Lg2xw+Z=Oi$;isj1P>)ZBRG%9X*#{(I9_Cpy_SZQ7)9{5VrkP!J6bP2+fbV(oHE z3{%UiSBy7q+@PVQrMmhuK^e5vr!{`s}tioO#x7ykY6 zmpwC_UXpvV>pJ$fIa@P^L}NB};z@|*yku!%Ax*A!V%wMZ)!BKiBb%R)(_7XrjV%V? zYSg6B7a99W;kXIM&SYWSVbjm0>BYAv!uW-RHj%u)49P8j`^c+*L-yd&qx46Q9+f^j zV<03Vl5^({$e-n^N02IgdA^pPt3d^yY5aN=LUiJFthIN0sB}&!2-0!3y#5 z@rnhTNNIadv?cLtj?THF|u7pbS(>%@!O>bwQVZe2=AVWVc`rqR^YEM+t`H4O*|7#(ejAcf;0 zb8>PHo$kuJc#(=-!lLnA%a0BG0?#`;vx_Y%Tv;S-Y92m6+cw?wy5Kl1>D!XFY*@0+u2BU0gD1GEDa$)lTn;x zCSJ9?nHkp&8vlNFht<@H>fa!f#H6II;9TmHT>t+5X;XLW)-I|$&CQ2670z%|-6=7D zz{=9wnIcL{I;^d292BHX#iw?A@2SU8QJblf6zl8j#pL8tDHL&W@fke#U9;IU;%-@+nx@*= z*r-)lbMVGu36m--2N+07bSSsfvh=NZ1yO@Dq}Kq3hW3X(LetT?xB-FhcKf3v>6 z{yob_)a1x(*S6)|y?c35PF`N?wpwW8^wQ$*pMIop+@*PSQPFPF=(D&TD9BU`%ignN zfmC-q-j??C_mlCvB+|d%OH66niX&zjnlX%HJ=vNI-@k7ly~tEbDY@A`?$8`bTNAh> zGEyH%9OnwR*VHKHrsL{=gv^fH+w(o|>RN2)4I4!X($Ldid$fJ$iLIyae4>k{)KG<~ ztE-d3V`FLiUcX+%^56z#WX7nMUibCcyST(uRLF9x1~A{Zu8yv)RU&yGVxv_SF_$ zPr|B#rna`0hKVVrs!Bd2G&CDabo}^n)xhuMdpzg@Au9vs7FDNreqUN*;ozX4x6E=S zFFtD=S$HCCWNf@Ro~SM$Awi#&m8IxCN*bzgi|`q5qasl=@x%`g+mH_*9-Hh+OIJQ8 zUQIuaHbcdiPEz!nq8B-u9Laj zxPdX8V~a+l>P)ZT z_q8=qTU%Rfa_)sczj`0Jbk{87;wc#!JLS;a?jFrJbRz7J9MxzW1qZmZsp(=#@Y2*v zGI^N8?%PPivr=8fXwm1W1YK+Eo1Aj)#)lP0>eF~s*oCl(ETl~ma&_>GWP1merfR}F>yKLG!S5Tn=n z>X(J(dl*R z1j{;D7*POPvtnRuT(U~$l0V&uO@8)-OV%}M(C9kQG8a6Dw8_hpii(O9Zu|Irwss;9 z4Zv{v)h!1PkFKa~^KT#UW~l~V;yDmx|M5wvYkwijr}1$dnB%luS9sMKafsq~sj#EF z5hwi2a19mOXhziotIDmQRc*h2F4fYU$cg7U!1?;FzNUczbLOpEy`{D)Lc+q?xI?sq z=;~?(yqrXHx9#z{IcgMrdPauB_lZtE0Wg`ykr5s&^G4FP9Xlerr=8lb>>8;0Qsw!6 zbaa%2WmQyEw4Zx(-^L0j+p5BqYRi@_0YO2ZaJFo$oSlX4-M`;7y(AO(-TCb2zRmBe zy&kNF(6>F^&Xc$Wowz9G`t|D?ODQugxz{&u-rS3Zjm1&)zGG2~zG{dAAFFdGWNvKi zAen4vXqb2J-ixBIBErH~QJjDYBR99*RCn4FdE*8`Klcf{4^>*|u@;^-!)r;YKi%G2+XSLfep zlF4dnYTGzDkB~Q`zm@<`ulf?k%>v(#Duee zK+xacN{Y}kIBf$7(Q1Yy3Ss3{B|3z1zO73+S+=@>*JGv<(aD%LidMy8iM_$3Liy8 zY^0~B?qioj!eH*X(Qn@p(Sy*@a@$@pk}4`H{<`%1Q;Gln{X6GC zc1Z~xpr^v)Eu$(A6KHh=x{;J^orzPhcy3Wq=b!uFl8ctEb5V3VMyID^uyjo?UozJkv~{aD7n%{U6$z}MxKm68Jwz$v8c>M3Yd&F|lHnVFgW_)`6mMB2G?C*{hO==^+P ze;jWdwSLyTs%afdH($Q zN{}5tUO-TBk>gqMAO-xpchh>luiD!d*>yyT@bZ;xFTb}H#Mc+19(8@ZLw z(y)mhYpwAaw|8@kjo89;==kvmLrVk|&(6;NvDB^ZF_}))I5fm*TyX60`zp`u+}sE> zd`F0-bVVNl5cP+yy#lRmZHFu^cM{|ujEEW12G43@S@7u5eu7Duo0~JUn3$M6v~SuV z>ovkndU*QXz8^n-X4lkkV7Jo`1k0n&?qp|QTv+g4o_ouLGl)IVx+(AJe$JM@Eo~Fs z>p=}~KfjjNShiaG_y6^s4rtBP!j#(;xA(7o``8Z3UwrgLeSl0g%`c~=-KYKh{ioTF zn2Yf7k>YmjEq%Qt!*QGKM16~&uWvIboLc2hqo3(jC}tFuZkKD%!`l`Ao9yl{X^Epy z!qJ~lx_1f+wkRklv_5;*X?nhu!ji7wmDTz&H9r$jFXP<73}!}%G4vVenu8ZEsFC>g z?>9b^A?Eh`d)MAdsXa_+SQnF%S)tPJl$J6&IXT7e+#hZI)O;6jU)zfQkt16JRC#c~ zg@l@Bb8PqM#SCl`p?xD=#17X?;n{St@2B;glkFK&lzUrJ zM3~Nf8#ypIH1w(D!4uX@or6?Bif2Go2S>*Z8V|Xg28vBV#t)U4-5;Hs+f#Oco_YSD zZJA?~$?k&SwXaPdKi+=-!pqq?65#9fxi7!Qdu#*P)+Itu0o+I=Iy$<0b`6{&A|hxL zTCg>=;yIdhm7(v(21?8!O~Y^AQq{RBx-OY^_Wc1AOa=h`I z2PeAo%}q=iTU$4Y9?MKBNjUi~WW0?5^1HFEjT-bLT{UnYZi&A#u_U<&=*Csw(7?jV zdg;n8mFC`F7W~IL8I^3`H)KjU46a~+^IyKyKKp=P!rJF>_3G7`fs!5Iy|o{tZ~@|U z0am~@;y|ZKeZo!7x}Jy0Wa47SjvXWR9D?m3a0TR-3rC3Mk$=yfgTv}BZS7GLJuM{) zfrZ%Xl3u+eg0oa&i*Xi_3GUB9=lqbm)*6A741s*5{Wu z75eMWd6bux@eAZMMQnKu2~-orE@h(wI1&}e8EFW94Ov)I0TRr7ySo5-lZB-hB&G-^ zgUv741f3ln6jaBAyOX87ijq=qqWWJQGMUhUa-Kuiv=VtF4PzuSim`}B1_pO;?P^E`WSYdH-AK+zXtR)8g z=qTXLM#at56}Z1PQ75nUf&YQ3$^Edtw$|3ho*w4t=x9np!n1IyjrOjt9i7{uNj{(#1fb>!}H3otz@}5JHDCzO%se2X{7Y~9?%DDFz ziYs){rJ6*(?>nTa>GOSpz+w$uU0V1hnRzKZLrgvlb zXu)WT=y7k<1gR0*M)W?&TeJ6V<)@G7>9t@#Yfp*;?QzW0`sLYDi+-(td+KoNR5U8w z*VEP0GXbs!iDXrEns(2gJwif49j`+N9Px7?j{u+?n>_d=RK=>&UHEEZ`}jdPeyBPU z3A9=@>~H4dyT@)RAGEZzoaM@wEt2F(jKN;Fwzq>D`*|gxgG7O`k-R^C8>*xuc|%Bm zAUAe)79A_SWw_Q~qIwM!^7`HrS0LR4RaCg}C|Wu?G_dPlOtPfP^u2jgI>2}K>4iVu zqm5K(vjS>rJh<4x%F6wHPYY#@eSP<7C2&5|RmKt5J=&*B@s96nX^BX2vU+Gwwf3l@ zTqp&sX{|afZ3p0txc+e6IXVa~7GuvW$Z$fq{QVP5Sd~&zQm$`HcU_K)%f5djp9@aC7Dn=`9$AJ__WwCDBf7C;Cr zH~~4Ylb!b|6dJJXMo_XdXU+iPi^{zwQ-?k+2H)6UL^6!pGv!R%U1A1)$;P$W4jLPz(^+CN)`XF zCQ5%h#usazqJ*~k`S}r&4iu1vk@32fme`%2uuOb?37$RLHg)#w+19oRvM2+Ho;2PZ zc7%_Y>yaaUZ$muX-5q}|e+Elt;ZX~r(O58mS2Yf3hcy}n$`C&L-s1X8_$MU3sr0_S zzPzDLCX&XRH5`X4@BR^sYfIpAf`v#htTQ9^vHM+KQ96g?1cn|!zCG*9*DDKNI|GHq z&(D7`cz;Q}MA7}{f40)Jibv9OD>8#!Q4$l|Q3Emo3!}<4?pmRSUW|LCq!{62wBAzj zC(%&9@4lrH0|Ox&Up7xZhW*?1?AbH1y?fiiZAK?2g&)}&?k>Pdi|1Bi1=M}I?&Ey& zBtNVWxYOY`Zdg_J9e;4*DZySE#}^lVEIQ49e0sY?4=oZvhRrz$b%OVa0;Ks(+m$(P zUh`{fY1v39J(e+`DeIL0kPJniPn!sZvKnoc0e>$tCPowGP*qh$3P1CqE*q9|`o5Ew zE#A!zVX;7LA68aQesWh0SRlc=OmpQi%k!#~&(4Gcw|$IUfNaBgOnlxQ z2M-?PQ1W$7?Oo=$%|hl?bK_5dWezV^kZ?8MytxbYPoMzYoU|?{0FmBx34ZXuef#(4 z0+S8R%-C5>54e@Ny%s?OV`1P{OrlUqPdq(_I`6+{xxcTsmmepKQ{}vbLQ)7^VF=6J zkXnYImy16`l!KPVTw1<8{dWvD?!?Rt0U-sgtz>sdDKxWKUq8PhBpZ1J1={ANHrcR( zjUe1RhlXxQNJxM`P;eiy6ft4pDCP6>I`E4oCMOS%jg2{bcmZgwe!*jm7X50$-QWmi<0M;tG<^qSs}- zZ7x)wxK&Z85F^UO&dz=oSwK+Hx-k)K{AqCM=5c>pdduP$yl*#nYn8=>8@7#^dEwxy zX*-ZRPg&Ix{VTbkz~zADavcJCe$&!89h`4(Wo2D~hbbs4TOp-iy8p>F zwQE{{Eoe-iPp!11Mj}E$>T=AWGB0lv1Pl0?Z>m#de0R)VJIP5W8J|z&;aa~f^78Tq zCMIM&uMAvFQaDT(9@T(wRJ+;k3ajm~$6C=;Wc;R%o>^Q@Yn_%dAAndVlgajw=jd)) zXpk)1w{M0X=T^VK-4e|ZfgVo)Yw3$uw^Yhdrs8w)adA$D6KX6+7t`Ty%{g3dM}THX z``?1HB#*vNh*W6k=t{h-i5SkTK5*&oP}IBz!zs6?6Zu={smDJis;V8)HDNl=372!G zFQ4va{z-&tlAWEMib2b+sYk}3S@1ZK$#9LGCG`xAjh(#w@xn(jKulv}V|PyL>&?gv zx&K>cxS-2zr{6pmJGGtRt=L{5U3rcp5VFGWOLO-(i3JDqk)d(wq$Y|I8M9oxjFCI^ky zR%n%qNlFUerE=aLr^Mn(h!QM9A26*Ua~%_P!!A}<){cRJ)cN`Oj_1!W6W%g% zPGBOL)Pb(VR%}!0zTMK=It7VB<(UsRl9Q8bf(|cT-g*&r*auAPgpY<`3nqyhD@zxJ z0((ds-a*=r3;+K9advlq9(txPkM@?L&moC!?5a}J%i>u}L^V4O$5X^)WUdYm4|jmk z!+CUrO>HyM-*19E0WOeWc~#Y2ypx}s`oG`%m6Vl}8yXH&y1kBmm35#iA2Nh6q|tH- z!jE+G3fBKH`5)Vlit1`nbQU7GD)_SkBH0HbQV1(m)}eWm04q)5(9lpaaxu7ZeuniR z&mE9`#N*>G2vx9mZz6>P9(5S?+W#~x4Dv!$?e_5Hce9xWB2X8#GT**8pck|}Wl*f-%JcnzpLdV7GFiU!Z z*EoB59S>2v{cG(TK?Cl>!~y6CqG&%Y{ao%=|JQ>66NqGWNc%xeO*)u;>wz@W4_vUS zMCIhS5w#RS4XJVn{ z8NyY)J$G?)9|ecV^s@m0J2yXgl|ljPX`;6a3S8Xxz5HaCVx@hr0mW3Q9tKK}!p9Iz za=GTIH?s7Cx4Wl#{$dWm$j~rb#;J{&#SjiF*1fMQZLg9F2+(1K3HdmtaR==ClC~%B zmyn1DmD0dcL+&Da>xBfQ=g7tBm=P&*T!(FiRo!=I2DeU%TjMy96lU1 z_!C8R1Oo#`OP7`F@d$qZ^dsNG0p)X;Mz%w^<`tEdMD7KJqob)AA%aL6-XdEU*REaq zAcuJm9vp`aDGNzi`ntGoH-&QT+BGpXwJgMXeEf52rw662YP|WuI&Y8+5KpJA{#x;X zwUGbq$@-PHE4%iXy+WHLvTx{M5%ifdSvax~+dJT)u#kclKW$D!03ts-T)UrzmOHg4 zgPBD?UHT$`rM4R}#`4z>DnTo=+o_oSNGj*&`F8BsQOaYuek@B>7rRXs3UEUIDi|EJ z_?loqk%%z|ReSs3L;*If7uG~9r7$lq(r+7?jL{6C6DLjx2!M#O1`CR^F4r!2MpJZb zZEvNtO)vf2wrkhRd^DZQy6XxaZ{p+R*1PsTO-e{$z|>10)GkGbnUlz7gc#sN%P6h! zhW)!JHCy{Ma!OU^|{V)mv85x+)LVSv1WoFgL=i%+z~f4q*V=mO)^k5)6gj zwU1$Y$GD6A0?E4TccFc3Ce3{Qtebg) z;%dEHOw8L!4nr^mry=MrJ*ObF_tNUbSC;mbRH6;t{5d$8iO9S8O*d++0 z2NWk=y-Gx9MQ=CIY?uXs@LSWHl#b7dGk~uztd^FRHjW-eMB1==q5&@$HDH5@*aqrX z62BKdh70Qd)Qj|s;H{V6@q5NwpE$vbcAgf*$Y1`IfxqvU7KfD|9CMiS(MS^hF5Uh| zcrixZP~HqPGc(@jFo^SMu*^w%|Ne~zq1JJ$398){5BFj&N?48V+kGqv##nR)-R8E-pNT&-jGCs>SzY5_5M1n>pGwz*r++wv;&hmxK*#j$46om08x|u z>C^N$#>Aeo{JM?d-X84lt3=OE&-3($ea9`7$+ql;wPtD@WV&GKVNi zwA8)fQ-Ohju+qjelL|eXm%22)y`>2fh>SLtO_Z0%^|hdea!dGv%Zz&+Fj4@7pflt#~MTWiU5`HaX=x(_UzI0@hN*@ z5CUQK3@!8O?b}3hg9$A@5fLq^bvT_A92ZB(57GqPnnecY8SYtEGh)S`VJu~n2JvSb+@%)60mOwd*qEv0Cmp5TM)&u=FVbafGA$$}B`qv1eXLnZ=&oAswB+BPKbg8c+RzU1@5H9MWywXxfuPM@;+S|AkWgFzs{19$99VzO()?k1A>FcX9r3k zz#HN85fwOGAIJt-utn^2>R8SazS)FPzmcEmlykW&W%7;PQ}`WQs!l z2p+uTWYN%UX*G6l5>2f8-OBQ3<5{HmV42B~=L+6> z$4LWyD<2-_Rq!=9i-w6j2WF7FlZAMU9u@1-89GP3 zxaY>91v(7UI{n=m+!PYGwws!o`dWIr4*3$TG$Im$&|#+JHTq8xu7Wunp*PxxoTDZr z#Km)V?mv};nJ_|9z=lyU6O&Y(1krOvWaND2%rV4m&TwVGy&au0z&e{3rF-j}eT*%$ z<@UVi_Xx2Xsbb&7o4Rt8&Xav)OS3`NA%d6{7Z;P4pX$cpTzY@zRd#D~#Pmt!o%;Gr zt}xVO^RJaTAN055rw7us5hq9oEZCo!mqD0`GoH#}?jj?}5g(LOmy{V_M_6|jprUvg zVK2O->u0ZBUV!NI2;D$EuBU0Hb4=^Qr>|eHfWbInmaAuA;4tPM#=d>qE4PE2yYwahCy57gbW?aew|B zQZt|nF{&9`0ZJdyKAw$msBHzJhs&ugz9?0{GQWJAf$0~^58V|^ZpUH$l-aT!g2DA) z(^=hC1J>!3j#`@>;jod^O!O<*)RuZ zZ03FSUMTbkbe~TXohd}l%F4!8a(^15n7kjxI^&)`RmV+x+&lbJ$w-vZ3*>kB!cj{O zPEJSU)Wj6s+6P1##N+@38x;wp+WW`Cn0WPy&Ny20!rEF4ZWI7PWK>f602h>81k~8_ z@-j0I&#Qdf`T!Qh^HETi+*nA57V5Gf5PT1~MVIx5=7($9fYOdXod*aY{GTz~-@ku5 zUcH*?gEtOxO%Gl`jJW`sOt-2(30m2TWa|GoyF`U(pjPSzu)p!bpdHoCy5ynQ_wcWbWNgS{&2Il7Nh<}8uL@Qyc!$>2M2oGa% zaZyKKKMI1A2wZVSS~@#vKZYzZP-tNGHsc$FiG*&s5neLk=Ay4tkzgevh8$4if{tyx zw%gcydB*VU{Gg#gDC7r39w&&`==^*(tv%<7xNpVNHByn%&v z$tROtqAr-0>k;!hrKQK6Uw`vk$W zkF6)@@J0Dez1X=y0}jQ&oAHSWGA1m91)7S#6Z9C17pqfs&ETZ7F6;k3Vk0y->FDl$ z1Qxlk9@T(n5V{@J+JVkZDI6JkRNmi%s%SO)!A3ig6uET| zVL1L;cFSNrO8#_N8t+3iD43bkuP~Ler)-Y~CsNCNh~Xppbc~E5XpWegGy!qP=mued z!c-^z1tL9hcE|L~o7&(!lUZp>epB9_kG(#sp=Xbtmx_#zW+ffb*S~Kz6t8nfe{Jr; zQ?p>n+ZzJ?t@?j4>=hBAMm#4iD@#6oT7sIMgGl2rI_@19xs@Jz2E(V3=&C_Dw_^b#8ZgX|+EBrP z8E=at=9CTpW8zm-Z2SEAvtsb71T4+kYC2%pkM(to-6IaTxpA>WveM#Mw}x6!ZABI`hO&R>pyG5{$1F#d9#lv zF9!$Bf5m1+q5g2!W2?4_pX_%D=H%jP`S9V^``|h#3}U1jN!-dv7Q!8zYS!obzwd)^ zBW*CGx3;!c4PHGekcj*PIxHHqDTIND#czdZ74ARguDSO0LvM|bQ|WQo)K{=Fc=n43 z=*GRbF!8iv6ujooM`Sa^L^lF4ZydPg*#SD3_f&iabu7NC^OiHSv%c#X-MhaC!WmZ- z7#tL27I^%Rbzx---T!5rX(I@Z4G%JgiHQkfax3ibPf<$Y5zD(sbTEg(hJwaUus*(e z@tBHXss4e{+9Xg^*keu;9akMc zm(Q~N9cB&fAm`tVG&+RAIpk_&AYJh_*5YHyVvyh^?R|Z$5TK@ie;2A&S(%u$7KQcu z2VdcoyS%=o9Q`q#L*|e~!;_(<2>Hxh_dp55C#~w*K>EhCLS|z(8V?puU?6tw9#+Z(Mp;93gCwJ!n;NY(aJ4Z&AANBt_d{yuD zi2$}ZH4Cuv#PpCv*@@H-GSbo-=uKsa{kYXaEFA4mm>oDY%_sg%=+~6{>C^Fu83Yi7 zs9+cJ+&fK0b!D-~WkE3Bq;Xpro_qaa=bJ+x z3hh%{&%PM^>b5!)vW}X^k2f+GZuLVI95HpLY2X)7FdA9G_UY)l$ zlUD?pOhG`Jb?G4TW06g>84i@|r3y!h>$PD%=_(MnlW=4+Gh6e*BU9L$eL?RsH(fC( zwN+#mFUf-NNx>%%c5-nUgCDx$qZhJ{tuzA3lENlCEtARQ4Q~GbE8vkTjg;Mer+CP3 zxW;GYO%}XYnx<1vMXGN6 z`j=vLY&Pf(GGR_blrUb)%Ca$7eI!+~;y9Fn`!QM#<5iaAD_h`ZKjrrD(!OOI-3kl6Ry{WknkL<_8Mfn@Z-jL~t= z=UZC3Iybxf7$)*n5j0V(_y5zZ(p&kU^L4jKJxYRmw0#Ee?B}F@!vi?_1`{MH5Ref2j-Vk vU;jJel%+-Be_pDt6}TGxpAUom+Y-jL@QA5Y>p4EmM$$cej9hxi{?h*d`jPc` diff --git a/doc/src_intro/img/class_lidar_driver_impl.png b/doc/src_intro/img/class_lidar_driver_impl.png index 25e0576a43e1592fe7dc520b9b2b6d53f3916917..731eab8a32f52d2e9506f5b223a065aac353627d 100644 GIT binary patch literal 57777 zcmb5W2{@MP+CKhDQBkQB$&e6{F%qFNm3dBPlFC?=F;hj!STaPWOqoUI3}q~Z$WVwP zbCjvf{^zsS`o8_`PS<^3UG>bitqfa9B+@p8v$C2b z(gqz8iR{Q`3jAceM*a}~vE|xXz3U{>_FCe9WZ^v9_mfBmND8v2wOwL)M60l$-T^WiOg{eR|5`NCJ~GaC|VW z8yaW)`SWM@#i2-cPR_`isugXsy!7<+ACk`OxYQh@*U<5ZUBS(*x5WOA%9CR{;`daH zny<4B=CVsx)>3{z=W7EH`xuBW2 z{5dtp^)-*|<%zD`khr)$^PC`d1+^#s7ku0`=S2(L=B>23bxKX%F`x95;12ii_gq$) zn2tJnIZ-qH(@W>8L5(}MZIesUe5#rLp|$mOZLLpV#m(!#zP{f2F}(wSb&sc~rwDiP z!LA%5nH0^A&nqW$a&m+%+mcmhBG|{Kxr6CAM9t03B_t(37hg3ApDp!Tm%@K=>0FN* z*OvR&Q|$-q=@}S8qoeh8RUX9AEGCb$T&eciGB@>Q|IM4r`Yi^2>rEWX!%wbWxO%l^ z=v^dnTbF-Nnt#r>2;6rxRk^IXS~~ieZDWyb&+~$UtPb%#d-rx)d4{sD9zA~I#8Hbz zT2knvM|#gq$?i~W8(5m35Wd=1-ZodYGD9UOD7cY=VrFgm=cCBThJm_(yyD`^gY`j= zA3xSE<&)lwI}_A%P?C8@q2uHST@#PG%-qVxj!a#$g~5=MzvkwW&1&v0EG#^Ti_5WJ zWAR!!-4Z8h*;^twJUm>!IQ-=M$O!qbZtGm!yYrDVDu@b?V^3gTzA> zvme;Fw6r8EFF*73HF;-_QGjB~g|(H%lCm-(yWZndy`?q8NA{Lp|NPRKACKq$Zcgq+ zk3V0W)3mvzR({Elj@k8|?J2Ug{E$G_BKe2$v8J(o%57ZikrB52z! z{Cnz)5^e?Ar+f=4a?0(pCMNNCNV|6LcKzl{SK>N*sA_GA2Rq~$p8cop?wKahey*Vt z$B%yn%EGWP$P;pNcf1PaPGyhsL_Fc*2&jeZ#(fHN_2UnjUPh>?;>rTU)z$`7)2|nKNfT zCdyG|Tc_`dpRJ=a`SrW!>fqSe+Z>~p^a7@&kEtp(@7@KZrExj^`1CX;J|;%l%}xAF zFyptBWu;VQWo252)dh3&E!($WT3MK0!SXq!(OYUi zNHIMBBE#5_t$%Vx1U=sIM^lG03DOEX28hbKI$YLwL=a1gf-TeIgq-fEr z&G;VMXoDVpsPFHOzeP^zfKs%bNnAG9xB?3&>G|^qtIK~LJ$R5{zedU8?)~&B>$h*; zYHMqsJOAw4O4k*}KK6MJ3rnsbZ70-8X1v2&&zvi-VjVYp+y%L zm*@6_@^)X!>cS3dU2}GBXle>llUno%=h2;6nQbAL8_YkKYiu-8b1=D#HC}tQ=1aNj z?o)&0*5>9(D_NT9#C9C}l*cwd(bZ5>L+)K(E)nFeUudOcsaKb~UnxRIqYP_<Uo40Hs^B2EE;;&i}x_kF-6I&f z*n+;kz6|#7KYUPkN{eG9%8;S`NW%AG^&FF`oE7)c53HA(qJ68XPWF4POLD5lsK;## zPtMFVFcZ7n9Amb=wu%-0F9vkM>BHo{8=n`2K1+jfT~C$oEVZ#x%`2hpCTchv3ARQ5_=rN_-8o6pq| zyatbt+aJUoqx9d~UHJU@2ftVy4aNqnhUzqpq_EX(48rQ3Ig`f^b?|;pU)q1d=?8th z`^^1%DK9Utpnh8$o3PV;CLZ&9aQAHbD~-g~etnZk7~MICMHVG`l^K=Mux9KjpAMdpmPZ^RZsOi-?EzmB% zr=+HG51x7P;>G>oU<&p6;3CV96yB(cyBHbY)0w!FUGbzUJBVd2Y~2|+I(o&}bJ2p& zxcp6VzvnybBcn?(>2o$|k>TMfd2A<67>s!+wG^QUUiN zWj|EhbUvi~_*IP9^*3+dJ~gTG+_-5|9xBr9J9iebXo;$euEEf+*_!Gi@#x{ho&4p$ zHvFvk!`#=`*I^}d?V13P#~{{YAibdU=YG81xorKqmBm@tp>SPn53|Ow!zHDqmVr$f zDna{2>%V-7-N`1O@a$OwUQ;Ml_$bau+RuUW_dBdpyUmIXP2=4B6@gW1kxG$#f=)lq zlji2;@HXEji~EOB#z>}Z$qI}ooC0x+?T6p*yY&9?X;agL`scU&iM3+%(rM?;ov&Zr zBDZW$+xhzSYc$tRy(h_MbTtCi?`s;317flIa5)d0RaoM5aCGG0jZA5LRZ@KToQrQ3cobR=WyfZqMZ9@C!mhA%hA6xm8X9V43_@#) zZCc#uF}amX8P(UnKmIRNdEj5)?*D*nxAiBqdG!l6GchqyQ&Wd!yUq@8q@+wbml-}A z8XCHJ`}X?oZib^rkJ{MS&;y(8V3r_##TrAiJ?u)qZ{PGl0DnGq|JHZKFJ26OeSN2} zgORkdvXZ8o8>bnWs`8`_y?<>se!bmFtkAZ*z!JS%ej*R(WpHR{{;@T?Lfa$F*cNwf zZQA0i{S^L{Qc^%1hK7dM?Cs57d6TWocbRlFKPxzMzhiZ2J_$wNrl%;odUkC-*URkE zC3*DTDD;PH{lY|rM~6hXwL&vwIB^p~4V;{uQtl573>1fYvu|H|!3cU~_3PKS&{;Imzp^DVZ+aSWadDZBet7!h zQ(n@!S$D>`yAzzNt6Nx0yw)o_C-JB+T3C>&i`$*MoXNGCRNFtJJ#zG<$I^|Iqr#{I z=;-ypJE@&kT=SN4L1Xw&FV6^hDQ^Q#mvv zDUtrExs8qT+oo5q656QI39dKCpEMbB-Me?MkB`qa>=uiDUn)8RdTrZ(Y~!o8w$RC* z;-i6P6$Ovh*Vb-W`}*s9%6?c^#g+J>g4=4fx}Q36oJI`_Tq z?>Au!0fPmW${++BP%BsP{w zRaF%gQBkZ4t@OzG=Ok-u>tk2@lyS>ZkUo9>Y-Vk(ROPu!Ks3@sXLgcqt}!0Kx3RJN z6%~?{JD3R!=;G!!Fg#q3Ybh{J(t4)aif+Kj#59Hr+qZ9DW1dEm{LX#*6ka+_Zr-tj zlbhQg4<|G{Tn@PNxbsv@eU%D8aOurIe1{JoURYip92mF_nD(=BIY($rZ%l$G^zmcA zTerxRB96T7>3PzbZE)1GjXmX27=Bz_Thw_Ie;l486FgMyt4leO*U}C22qe_aV*_A74jz@)rP-W=7 z+w5P68_11WGkD#(eOoxy>{F%33EQ5cP3ls!>a>^LJv{CQ1}5M9Gj&`{EYD^7LIRhn zajC;56BCof#KhxXYZ8)fbEiy9SiIvTZ_X_LtkTu5YFoT=eQC~8{KlwvX{lJn%|GV` zOkF2SoPRRM#l?|87~ZIc&dKV~vW?$R*0HkU#zX3IxlKz;TMJ0oT_xnIIp$9DN#XpJU1?VI2K>C@x2 z)#VqivzILT>x1_16TU(tFE5YHVv1ELExmy#3?H7#95E=$s+K5h?dag(Utj%0`q5Jy@>J&Dz{JG6kdtd~z+w(_aeckV;`udP*Eqc(5D))_br&D% zUkN${o?>|OyN(ijbNs+Nal4*QoHh!t`jD#5jT^$K4d>6Fe|~*L^)B_k+rGY=f`fw_ z#h$6g5+xNRdZUbt3?Qg)KtMqKMLqOni`GQB6##>|@eV3fP~)4EBAQxSJlS`$vw5SU zqCg50(#UmIuIC-I?fyD2Pz?}wEAd3E(`5HI{2Q9W=FOYc$AA3%8KRgn@F~xH&#>MP zJOiT8-WdHrcJt=V@vht!6R%Y{FcPxS&g}iT7rE~%=q{)#Dys3KTi=SnBCxLRg_ZZ>d@e_LK! z+O>Z_747Qs`#8z{TyETBQ&TyHkJ^R+{(pgJm|0qGIrX!zLL`SJVPg*}2f^ym8F|V* zL+6g9DXwI5pEz;CB2cFxnCWd(QwM_=uGCRkMMY3lv;oQnHdf@a{L?b|5M~w7%+`+| z&A-2Ss3`Fu`La>?2^}&rGBB`qD-lqZ%b*9{%vX?F$!u^kt@?c=yNNgi4 zWCqtw6cj)$d)wODjyrtcj2_Z9x;c#V@Zl{yJUm0r*RNmC{%i9BOp&cmaFOtSD8_-Y zv9bA*?hESX?$TotbiDe>H)vyHV$?G`u#1?OViT2$9flM^M{alY(EdVMKDOIpgx$}Bv)j^(5+=$O2?)D-5CnwrWm66PGc^n3DM z(-ToK=PAZ#YVpGmcCfCLN|}MH&A&t)`uI$3#Fx%E0n3ws7=wlj{UYrh9lWzI86!C)Gc$I1WoBHI;0reImfF9Y zQ#Bb+wztyb$qDBv0nZf|xA}1$o_IDYDypH&yLUg*XYt}tP*W_mUYF#iqoYGvXsErv zTMV~PeNJ3}k1v>2<}TL=>QykXSUBS+dtH-|T0UHJ8_ zd}ZdHtehNVo5v@d`A~8Aikoy=3oNxrcKwyvH%?*80pLFD6c0-Vi^2kf6h(#lK)|=m z%*-2xYVlIpt^2rhjdbj1hgF8|Yst$~;HF=^cv0ZWhXbHaiGhp1=I42fV^Fairh3IL zT(}@0EX)oG5gfZzfBr#o6`PTfQPBJbEa&Anu2bEG0avS5&+S`hU|?wc{`QfAqGEM( z^VGu`KC!7;;Qz)TQ=R9LkbH;jLL3&%P#IqggVkl=>(n6rms8-OrK2d&PM=% zEaee(BlHM@SLRzNZKa}G98C&QPuEuLDTw_!H5H7yGBflJbSu60dS)XKEGH+YMdN)m zq2E9IO@`*!v$jG%d6%6@xL&LqS ztRpisGXwx4VbN$;3TCJPHUjWKHgx#eCy7f^_Vkp(^@!v|vad2hQQ|ha__n1*w_Zf& zUU2YsYyc=|l-{^cFKl~`4ZUs0#|VmufC8lIqg;Egx;Z#Fa2+{v5$gx-xn2JR`G=nN0p&O9$JCiIY!moJk*s_?cVZO2fz z$;ru;m6achSns_)(mb@j_H#YMumM%@h2_UXDM_TSLqm1wyRv{<*Bl%Y!TYG`1x^j7 zt2$CMOPn8Tmsnq!EwK9%{onx&8fhI?s>bjN7^o1mwcg%d7cjsDNN@`+UTaB?8Gad> z>DpPw716-<=C-y?SRPxpY)PMCbAt#YBqVeN+8~qo4fWr-MlU0B(Nhh%L+JRtxwGgL*389zV2uOsnZ z^&K7IQXWf$6oz8BA9cr~=5u~8zhp+S{I$;w zXvcNo*V9h(IukcNTohJpve)`rW4TMHcGvfblOU&m{Xh31ll8x~d&xupQtYj=wF-d- zg7h3F6t%U(>VLen?#$8{)@rM7ZVraz)M**3$X7Ef{GCl9bR&ASPP%sEg;B?+HR5aI5z3(>JqXWD1eoAZbPe+0(Z82Y(`1R@t_nV=4TLAt}p+#g?777)Q%D8jHr}^ zKB7NzSKM_bx&C%@Auk7qZ-~@Vn(FMs*@Cm7+F9b$U7ei~?d|P~BN1-2b%LeGV21?W zzP+K{%CR({M|ar1z$jGl#UjAc>NAIpPc336p)ffNHSPfb7js__KsmR-V*K&tWh54z z>D8+ysm#!LhXF&`IXGGY`=RcsKu@#3ex1;S8+BK0ZEY7(;Gm8IuWg5@bnl7i)eSVX zw8?_kZa}RpuA9&K+k|pJDHh{$ExnLD}< z)X}kAz8vq7+UkVPAhot&o-lg1v%jAOZIY-7@C1fF@}^7gsoTs1eN@q|JHkJG3p8ca z-4=l3ppeq-U6*>=X`uh5?EK7DGI(*Fwb zJu8oHPBH`yc6RnFlkMT!#xDzp%>NDl%cXS5hbEtSrkRed*j@%QbGW~ohe=$k+x=y~42 z&{r!LFQp7c1ir=H>~L$wrGpHiaP6nvyZ0P}u7|t(!rVtSLc~Uu43|pJQ0(akKT4Sl zpyRJ^Z`andWn*XGXkcJ~3UV9^6IXcw4L-ccXlW#aOI~|%-sC?(_o37+TeoU5SHJ{# z2)B)=0f1KqmC8HuWh~yD+gU)z!p7!39%4Oc-4$qQ;ccKhqz|A6sDZ-cw2X{dS>4Pu zG^Zf?6pm}{(XlNC7RIw`JXi}u>$=WfFRbd%WsW=zAuMM=;!yIfkDSoaG&W`?un)F# zqk|}x`7kUM?Y%zn60SnvNQE=Cm%xFA?Rx34AmoD?^(O2K#ckI?H|b9}9YKwGU0r=U zFpwHJ>-IU3rm)<{k_xY^I?^^j^ z;qKzlPszN~(+>jeIn;vA@Ruv`1#ca zsZQ4&t%{fO&>y_38)`Lvze%g`YQIzpTb|t)@wl5)V&EQmg@qh~f*Sjtm*Qs}LH`X` zo~e!(`~ytDFJJzwtZ8VV%_|5m+;G&4IJZoiQP7AE2HE1~ygbz7sgv*YYTc7+Yt zuPIPvVoo@3C*&P`!n>^EC~RC*N_di2aU(w--%C&brY%Lu_19N2^@4WgX_riYZH_~9 z4IQxQj@f)tPbtyY(XqX$tV|8OFa%WtYfbHQ|KD&e%+eLO4+4E$eLs^zMlge81_5cy z19H>XZohXo_^&L$>N0KvJ#O56fBy@pH6#KD+?ebRr!#gTgMNZF4&VscBjMkGL5Ozc zF|g`}ckigcN8vEzT}Y+_wfC{{XCZnD;b|DV4(%B#G(+piD=Mn5ufGc$sH5adN7I?m zWUth=X?VX(J-@d(%M|CCH;KikFz^}?tLUOJhIx8v@=~~a)^32bO zJN@v3ngqdw6&oqDfG@o6J6at4j-bd$I!Ky2!I?Tb9YtO)vA9N zRkFIZbtfeyrE09WZ*K0@!f{rGy0|ypUWBUF-ECF=(W~vpj~@Uzz7BLcbaC}gN}<}a zIjfusnsRaDh3kqZ<2)E7g2g3+CjUw>UQFJ-80D$RYsuES-4xuYg2m zYzCaPHfVi-7lb(s>gl-Fw+Jo;0p=m-yn24`0_wpbn+Ge^b%B6*H}xpgdrhoUL!C?$l3KF{UJ zXMFNXEvZ;y&`%nVnEZkbJPpM80=Wge(^(}YbCl7A#l?FEqFo^=%g zDRnKi9mSWi?Jao-qg%*pZN;3Wt7EdyJt zDHk9+zJfDHI;)@nrTBlqgTlU@(1RkOK0gNwB6wG!)gF)K-*vEN@eA^6Fr(oS+S}Vd z#ZPT|OEeTrIvf-YfMRpYXSNPDgp9yZPK3yl1-d;^iqcRAlNDD_!_3@Fh+#_n721~j z2>l9ga9muxE!X5EKwrz@Aaf}41wVf74v&N?l{`e6H5&~NuW=lL=#v{DEploR6 z%upIEtUo<}njfa5s=6ILp`@gQNCv>JEODGTm*TjEn)*9rZ=gyzI3*X|p{ZBZhl=1~ z1IApqeEA-pBRq>itj*f``iT3d0dyN{V~dK406TSD-J;>x?h+Lhh1oIMp1vC?5E7y4 z8&+BsG>Rld99AD1m^Cy(3?jQA<?A}9dw^toB-(s+eZBnm@8A7Eq-018i$z!ajltgaHnaLbINwY~wHs>W0OY>vni?5o zCbX?RfQmTLTzzPy-GLvg;WNX#*TUBXw3Y>Ok-c%FfJWL6jlDHlVYfY!DOQnMZ5cY5 zK0x-zoqjyVFTrrPczAd`3=3n2K+H{g7#YclIK?3pUO7$8P`m=_q8c@eRC(KqFHLn* zlZrcPDA?QD%B-3hL}p`%aICc-?Z0rOXMmabhKGlrRZ;0E`%>np6c!v=SkWQ8h8yU= zhvytF<*z#jbi#oppENDTKh|<`otDT<%|wY4n zhzC4@JH^qb!g^u#6*yJG>B)Qk{1reKZnV(FH#A3%9JzMm#>Q7@Q$UJX!wpcB{eWht zrlxE@JtrgKUBSn*veFA+4pEaA|l~nh=}gw^h!c7z5U{H zOJZi`JD5!9k)8S`*j7O=6K4n~+}oR!!h~!~ns$a_RsEBP4^N|3q6#6t)0(EiRv*li zId7LO9Ihz$=#UCwsjJV87eH`>T|@r$>sPpgK0XPjh_2 z2*$vBK40M`0(kf#TKE3~xJ0VL8&1G(CZ^T1YTf~ZHNU>q+)AYHf2PJVhy(DacjEQ>7fX2w!up~*g;IBr%8eVjcpg(yPzZUhEC@}kBO*ft28Nqs-vL6Rm+_!7K7*=>E+ptScV#c1;aPk( zk;nj#)NEq_wK+L4N?Q?rgo_Ip+B%ClCn@O;S||y$W=NGTJ~UJ_MfJ9R_As1t#^cvc zeg1FY7F}K{##wJT}jTNpc zp&2e|>)1alytog7qmI7qnu3wDg4+hiq!0~?#6oDw<>Fjf0h#4ZepFW+JTAkBE z#|;2@1r{RsN_ZzLFYh)i+8{!0PEJYbNK*;bj?&*>0UOrS#@5#IOPL6XfZ6S78bkyJ z%JA2bkp}oZTXyUi0ajfBNjqXvS>EOjI+HU^Mk9R<$d@SDpI>mIrhbPLdKyHU?F(#; zumnPQonEW>&f)=a9gXmO{zZkT{D7Z6J~WN=@dE{QFE#^*mnk=-a4QDyLqsQ0C-WTP z=UO!L7_U~O4)vD1Y7PD&O8NFT*wBwpdP%_$VigxJ(|4t#eAiQal_xeoER1%@?vG{p zROp;@J6IcGF+m?BEG9%eYFk_L-ai_IOz^_yvykWNyl&9ziF4=9!8DZ_E9tn4FS;Rm zniU%r^@~gZ<_D1-fsF_l{2rZ|@E_iC!Un-|%!6@YVd0;_=VD`Krjbe>9v2s!l423m z!=bPzz3}iJr=NXIxLJgDPeNITHAq88_bkh&58n!nieA!97#R^Ax3aH;gEEjyPp$w5Iu9B?$aw$dZj2}}8uwEI@^Q%z| zMXWnXzZzJ)xGY|O^!mav_Va+KXe3bf;k+(r%UW6=g~&@kwzbiVIk5M;&j!_N*>kxq z6(UN)Ea5_;t((P#X13)!-nj9hqoad?AJ9x>Kt@{nw!HgUHMNE>Uzoxb>rfXy7g+B8 z^Ru5)*j)YGxxKEgu8omyPE);aKfkyfew}9*4b3YA@xm4~R(Pi~B!)th84gR*Si@)t z-yYU}2tDI{w20F26DO!3yqLkzh5u6fr{62r-dI^VkW>pa7Un^~02FfuSB(q5%<*F+ z6z&L!iqfIH(VPik)@iQrTrHy)zmbLlv=hN88f5e?U~?Q46Vn@v;WH}R40O?o$~FxJ zatjvz&;mN5&yy!l&^TyOGWQZvVXz16?&{B<^&n&W9o9PgRRk&kX4?wVB?!9yFh1U7(m@gSWB6!yVdi52 zv)f39>;w~1>`~ldD(N^LCLkoV3qHXf1kZ?XTiw}tE?veom|2n=f|L*1_-IFFB)zCz zj1bMdWyw^iwhrW*>h5m+-j~j56A@3I@c3{sWG!)VE1G;<*w4ho3qHjLp5#+eQQk*h*{$`4_uEnr=Uim(DfYoz28UQJ+NU@biK zcZ@vySRfwCxww=7fbNmroCi7$;hCzn%+XrV<(KJB78ZWcI z1(62HbDGpg*pR&vJ3?{d4-_wdXp&S=t6L#12UW2+B$R10)sc7b`0wOq6~20z2;$L5 z4`%)<9K$k(>hUlpCa|*7GkbV)WaQqRJ2Jjh-fNEtnI1SsqVseV_|72SQpc^3M?vk; ze^9N-o2?TQ=Ny^fie;3-2+=RH(VIFyg%tD2J_{>{>(>!ZU_WvstMi0531pLqyP*{5 zw=C;%WE_tS_>0Gdq)w%N=Cyz}3b6_0pawa*iDYWn+XNB%N9Bjbb~ZL_wg51Zr#J{j zi+Z2X_lGl8F4G4QMKjQFG26}&{@3T6L#yN(qW&L1MN#c?{y zt8*Z3?uP4++;x0#oczpuJiEdk*Ky;2lBZo3u|5(tRTaurbHwYU;%Bq7~TcbBTIU1G@H(Pk=QgB6+m3(&)A`w~~=*B6H zXAS?x9p6>36%-Z@0oT^Ukwb#_1N3Skr8lQqDZc>4!oL6d?c39=dyYs|&a9v2(&rSE zkYI#}N~m1tat!b1h$HqJrqcv;LGt%KZ%}?mjdn{QUonl3cuW3BKF`LdJ)i zyoHLYrllnW*H7q+&&_HYvz93Zup<$qH?XWgL<$`9I~c(MR@PfY?*vKtN| zz?8z-vtQx*;gg7rw524v0|6$kBXSA}MHGtZJNFt+^cCc8J9ACc5JmWFAmNE9Co3yb zAIn=Ob}=zE!5<~?#7J}OAQmVgmyc~P6rbc8)5wX1SOcc`zchK>X|2`o-!DR(5fBhi zk4TIHY(g(V5F#3uFIbHWLbyD<#V%v%kOUBN{vgzF=6`2{ijYKy>H8i!ONrY&H%t_a z0T4u-hzKB=o1kncVLu=Xy`k^w-1m780UEqCS!@{=HOu>Yk&Bq5Ml;NduW8YO%2 z#iCj&+F=Rks|5xJ*H>3>K*oUR>5vhggL^@+Bf*=7yWodl9HILGZo|iYVOB$ta3!b| z50J;YVDeKQIqoLMOV|7UJTuo7{G#%a)CtdDz`M8Fn@ z7JWufxuSqbFhZvwp^e%*JM;hP4aI8w%N|0?YX^%I0n*Koq0w*gFzk|Z`%Prt!sGbs z5MG=x?*I+8*ffhj*N3o}42M)9egHAS0!p1aGqoz(@WM&4?CHV zA{p$OVa4zth!wB--^7ZT(y@rw&pw3RLkJRTAi`+zd4eQ)>qK+Uo@N|XX17I7zP=JIetN=O*ej*@Qt4zYM~Bm_jj@FURQU__)=^jDZ~@v`uCEckQYM0}Pu)1x8x^ zaPFSM6y7+w1^BCqWhezGIK>VOGHkV6Ozfl0$EPbRMM66Bc)F}Tm;j}b;1ejzUFo%l?kZjeMGMrj~ThF|4^ zyc7<0HH+CV$e-y*ZifQ!M1bKZaG9d8JU4y4A*BKle=XyyR{s@K`P&WBGPaa%ooMYc zz8M5=@T-3RRT9RZT0pfjgyqx0z<(ez1U3t&Mlb*3eTN?!-5MXQIThLlA3k}a1c^56 zleMjFP-7D9Qi@0&+p-w{G1c^ufg+Sd|9WBT2%@sNZmO#Jy3CGVko{ zB%-jFnivvB15Pgg`KcR>K+)j;%>LZRPs!!-a*wy52qU`_7Tk_#aWm8|B+6S5qTrUXh4$9NYu4Hm7%ns8`T)< zg>M&tXT23MNg^FU2#thl2!TbJiDqgmw0*(4%8c+v089#74f7G#u5fQ2LO9VxMXJ~L^yj=m1 z&>uR2KOV*51{mZAKwEftlrS+Bfcq>D`%$;R@}oRlPhv2ow0a^Qe5lW5a9eA+>-BHn zzq41a{x%@e4l=aMRg5T~%VBi}kVm_WgTWh^Kq%{TeEN_X8vRnwbGD-sj=5s^8Sp(z1h+^4?ZD zl85F$9$Wp#^s=znSQVsx&nha0hGcN0Z~flw70RyjJ>6iL9|{7R8GH$=3Ykqb$kRd3 zKC7&pHD7LhC#|}i`>#P-$tUA>(O)!S0?V8|yBXSsa;$ivY9oTqgUCLmqE8X=5ds$~ zh^a{<#alWF$s%KR$UDOva_Al@UOeGqp;N}8$6Q| z7|=}nf7@*@L;q#BS;uCes6B;Fh@1m4lJ@?6AV8l3T>NhC#6}|E34bW4&A7^wKnOaE zE6^ebzJJ$F%C{P@kJSBvu~D}l7R1bR+lyp*@(y6gEAU{WEDVW&DAJq3G`CT$fd)fz zbNR7IE`hHUYJMxj9K|c7o8H2FL|&W^@rs7NzBt4#CB`x&^WhJ}k>w80kRQWT!UD2? z5C){9%r|Y?q)%56!Jd8z2~h~~osV+vvMZ!u0qT}bnFqybdtgA(;@l~I1?axk*6&XI zEU&>F7Gx*gh)^*UXe8rd^L&86h>6y;WH>*mh)rS5A+477zLx427&yib?gj)<#fm!~ zJakB2tO&dg%NCoLLqfvPeEc@lxs}yb_*buCOTqrtE#>;RBu_I6|0e(w$SsKe$xp;+ zLe&SLio_-cXQxv|Y}4L-s4*Omb}vvL!e_^?4+lCBH&atQiJXG^fTSc7mz(%8(^n)^ z1$>ej<|`YiD@AyJ{`|zMp_d6u&NDBhn(7dHA{=6g5&U3h{q*Xk1}d zAVx*A{>N*b6V;zc53({Gv*GewUv;+s_4TwFo+=VQ{CFMo@!iBeL@Os`rqPLs0FbCH ztUjMAJzhdF+XL_eD+Nj(FSd)Unb}ifi00R?Uo?OsP*kSTcKq<={ZMSFSp6^Ug>OX% z|6(tYnSPI;zW$m2$^uB4Rc|B$UmEJ_2T)zOjNQgK@MK|o4M6Kn1l1jY8X)bLs22?2 zEUT&-jA`OMh>skENC+h2hj_OUQDoo%MMg%#Q;nucyh70ria^*)KOZ(?=yj*}W3lV0 z=-yes`e9-bF~9fwlHW_W(MYRc`5G-zUtr75`v7M@FEoEA>*3U2z6?=V{y zs{JQJD9J56UK@bR+|2A2EEq)i;3KhOkAEEfCO)b~T{NBe!WbPCv)Z~kd&H+0nV5i{DNPZ* zY+N~jC=?_d0Z4GzX)qBlV2}xEWHLFmcKGJ<5JtjY)&TL%=6bDC?bxv+dy-%x5NSq7 zNAV8iD9+*La4ioWIB=@;&|fYOH`L2|e6xKx$^ZZZFMNLS?XC!Z6ICd~*bNr&&`-7M z3gM4UXw)p}o8XEfvVsCRfXFBEah6B)qfnqtO%GTVGLX=s zht5ymeg_zW8gS*iwUw2kzCJ@~X{q9wgd1f85||~*V0_oo(slmLXOOSO&(MC+2vaJ$ z5vjfsrYpo>sNaP0c>LN|@BE*z;qiIxR)zBW8HBH#LKg_@N`uv6(fylisI;ss!qUV- z(Rg{l^@d`OfQhE#OnCBTUz)^TUpFN5Fg|yM-fFBw&uA!xpMOm;bZ#z9Kt3$arx|ly z<3G1&nxcxL<1qjxAUTVgx~B>%dDN_b16@i=%3$0zyG=N~HeH z|9NVlNK(L?D zv=^=!LPw7h6Xn;3-)pRmLf3r+jp_&!3OzY2J_2lG`Xvd?n3(bTXFwlins75P>wsl< z2S}8JEJEFv^~*os*I22pudho?>M14%cRo_(QM_>FA%~WRaPmcli}VI2LrFH~@o$d3 z7q}C(Gk;D{Zi}E?gs^_#BK_S5mO_e(LgCr-<(^(KnSXLWI*4=R_l8V}cXhb-FE7VT z&ARpfS#_&yZ2bED`$pVYrzJdB=)FH3ATm4<_DFseUx}Utx23?%5JJ#t zXtc5icQ!UQ(qQy7#r5XRL70HVtQBe6%pP$u39mIq=rnSMhKv|QWZiY2So%kd%ju(| zqY=KY2B{_Ui`NFlYO;M;R8-OV;PK-(`_xe+yu-uy2#bh3O-}X!L`ed*)|o%V$yrr6 zO}~$t;?CzHV3F088JZ)f&T2P&Ls;2 z3K1M#G&LNyz$^jqrVM6v0cq7w@E=gBK*$6j;ci8?9ZyCE15`w#2EIRafW{QgKQRZo zaRV9T15~0nuKTC@t5^_Q7C3fHo=CnT2!QdMqTimZ!osv5b42zXInxc8(#he)ZH24- z8kUFjQyLf%ghNDxo-hw=TIat9+WsxP9JfeJW*k1`!feY)SQ%Tf&E|ggvmmmY+iq-) z(*FuX&&ekFjBsBY{xw#>D>9O2pm|^M~8n2D$LB6Ea~Z#xlLJYX!saP$&2 zX*#0>4FmqA073zqeWeiw+UEUYWLEtqp;%k(;?>?mL4Oojw&?gc70u)KU0!icKPk&n$WJe(pdq^#AMSuK~ z06pTa7ief`NT+^mgvu+1g+QDq!RxeP=jM&Q`*@I;&^~u=0R1FpyD2Y7sH{vJ*~bllzv&*prQ8s-sZUAdVy6|BWET_&69@k6>H;rOKY!j28Q(*? zZ|MVzZriR4(o@$P1S4Ab%y|R>betmqlvB`{c}_(oXxTtjb!E5u#ENDl29$`~H!c`Iv+l@>-DrO(KP&4;_=E)R@gbFHAKZ8EhCw1TMvSr*s2FHv z22uLS-Lv)$HV`jL6`p%s#5}0-;gY-#J_0bm^bh1u!?bYGx5y5b%J@5C5Rw$qV6C~O zFq?~?pE9ID25J)QAxh?uE*tHM;WuyIyjoxTbCPt`jxmTpgN$&JgNomomh&REWD0Hr z(C2&q{+7Awt*|j~?B@ zc^$+ZB6&kagaz4{tqhDWt)=y7Hvdr}vmSwwu%Zs^x{tx}w+hn*7j3Y?x1CGQ$jJBw z;gf>rJazps#d;&4IBbqQtmRn0Uibs!Y531<#;J3P+e3m@1US< z#JN9^3EsAc)Zf@J@;-{V7EpL|g}YYFyI&nF4I z+r{w(=hk57)Kr|rC^MpcL74M+)7tvbkB}CwV2=wUFge~`$n&|U=Off5Kffz8-`^sr zu8gvk3Y>TFV0Xn$QE0*l6uf^!xF&z9*6rulQD)J`<)E`^B=xxTd#UIdZ6z@&8O z%a1}LeH`v zJeY{kR}8A;8%&5JX9j^Fkk7E>l&maVep-6^v#?!=4+nB*Cxt=p!mZ!vjVB$=WUd9# z^Om-b&i$5=k4QW`VIn38h>Yir8*nF{%4i!Ks}eH>P%;3Y*nl9gYzD^rOYGU^e|&y~ z{1$vk&#<_-=9J0LFYdu@#*}2>26FPTq!6h@;1c1U%M^n~?EL&8kj(bW#+`JV;~EJP^bhIMGuv}R^y^}wDt59kk*4XC3Ns$H1y?tICc#CMn+baj^CJl+qP{u%b?27j|-9~B3Efxyp8YP zDWDEP>AZh-MGgA;DbyL{1Oa8cG3vN;=g{}>50LB8PO^G^dy}@7mJA%5c92}`9lQ(x zb}P8=L3FEwSaFF^*73<=*AL;7ui4`0nm9B=Fh?4<5(|aa)?( zYzLEqhZ(6nh~>=z%I3B>!?AN`Hk@7(Ob;g$qytebc zmuXm7*eJ-PtSl`Z-5IEl@6#@n7q^RMY~8vQO*jA%q7usL2qI0CUsRNeAwI=0{=kFqa7VjS@y$iBw%(of+6BsrIxFhCuA$ z_T699&6KlS783bq7^=IYI029d285+!+qc!_rB6bKgGO|5@DI88Wds#L=O$4GyC z-EgY;iRcbk+i5vD^*HK@I6Z*R@|R+v^YSAlK}N$f+#D^E`T4t4?04+{*9Z{3Gw9z| zT4ZQ%pC|jqS3e|tNm#T#qAm31en!SXY!-(u02m(x{nIiti4*0p716?KfEP<|VxjaN z$dc1CHy7yR#J>Of<45m>%MW0D9|T-Plm!{cqfp|EwRZGG78^YYZW+10og7&vtC2nd zDPdYgB_$3%Y$UQGiN9fsH}!G)pejB&ct(sOo)UppxW)T>;vbFthNQ< z)PrkxYvF1bFsg$M(?b{|rpM`;Pj@D~!-L(G(}8knBOH$>D>DCc5+R`DcS`uc|A{CU z*33PCAtHQ-vPu5onjz_NGu2?lJwLbuA@BpPSXxb|S$lgyzchs;g>L#MgE~`_5D|zYk#b_O#LSQdB6*{%Abm@mJ>s%7cNkgY zyYQ#9wY3RP7j&q^eNl*X0P=MR%Sk&O7WzQvO=yEqtccNFXbc2OL>t0+57fk=2OwKS zGlxL~aPSKWheW*bgUHA;dV2d%)-}9Tv)4C#xTtSEVnT6edKigutt5U>olXUA;o-Iu zaOojJyn;GVms5^9ivZ0XG&dh{2-WZG>Y@XZCln+!+z(Y= z>l8iqO+k5L#E~aZM3IUwx?)Ho&UVA>;j8+33P|U~1!5)_Y$^k6awCiq_&vKIB}o$p zv9+FIIsJbT%!>^4EY$k?`mjoBK?oki#JsmnIeGIpHRR%Y6gqoM>mnuKFtvVlzimo5 zXAqdvAz$@P8%}3R_n@3%{DTo7%LP+LXi#}Le-OjeyOEK&7ZI@+hb%P3lG$e3`^z50 zIyc2-U%Phgl(O=Bo{olvUtf22Jj~ei9Ah3d4`sElfo{9>6XQxa#>5XIS}ZlO-eo{vmTOHV(oq47}J)gS=S(sOZ$ZnJMS zh2@4@B(&P5xT@?HVvZZ404m0?{yGi= zoeN5+)Y6}yA&@?+I+q(;eX;VBt2m496XB9c) z1^^;rd=!G9Nc0H6B~fjkrlf2_pOkQ$+wAQUUX?RVkNHTP<}iq8>gKImrGdiHKnU3f zA=lm5`Z4w&;gey)V<(Kj4IvGW=tm%dv)3O6Xh9}-15K_s{;?e&jxbIwaqM5V9pZe% z_&1TrCgs)KMvfGNVjpg+-J5<|6PV$2=;%?cjGHqUZ|Hd$unpGU)%>cf6UR2+nU>m( zQj2E9hN)Q)3y>^JQy1hiKtXmOX^AnFTmJrAohuzsurSY4L-08~;X5rOYzGb`e0H*y zsfQa&9Ap?YObiNx4icB*C!2W5`7~7cJY-Xe^H7kyxQhS==31U(N`y#;0N%*Dx{9GP znA+I%9!Tv6-Yd1Y1Eq%c6H`2Z{YF$peAplk)~bO)mWRVLqSj?aJK%Syl zgo_hId={|$E*^DpadDU#C-A`y6?izK|jiB~MG;izlyif?D3A`+Zu* z&kf7s|4nWO)Hk9HdU&*%qm8tGro{b4B7ThZ9B-*R5x_!oVp3bx0@7L@3JjUbkI39HWATu>)7&zrnq)O>X6rK7aeRq2gX{?hWLVN(%a(C*P6McI)<>V*WZf zTe3}TMTMJq#`x&ZpX?xo0Uhc;v6y8JBSzGujoqhzWVGgGaQnq*#S}iLPcL29A~r5g z8%!YTl5)#+SBEF--xC|a1R-?MnYSQPKpwMme(NyWCsB$^v*T5n_ z;568ObV6+G8cI=kk&aF3U3~FTe@-Ys2otp`G|jES$pkX$;_(4QNeF+r2GUC7kI2k+ zKydKYYqR1@cn%|ZsdPbi{oOwnT~l0L+~7n~5}{x#4XDsf_MaOL8g#x+sR;`5f3(H3 z4tqDBZ5t7V!E=_>o?jW2V7Pe%RS=TBk-Uef`1oN-! zcNT>#Gipn|ytUQPILD=qjfuHO7{B@W@owUGItoE!4U5Q`^NzY|XwVSbVT8;uiWT!t zH=&m}JJHX&YD7>ADK~7W$)I;x{uvzvoqn+YulYH~#w5#;&>%EFDlLL?93=- zmtZveJ`edRQ6{F{%4^H_3KYu)jCD8OJHJ}*WsUBQxcGEXGhr&vE_tmg=1}7FD~`@h z)zmiAsCODVv^_-zP0d9_ixOF62#|70wQ~R9l`X|ylw-1(Uj-;P9a2N9S1&;$>2WQ< zjp|&T5CXl+Jsi3SSe=QcmU?=6QWX-EWNZ^z3Z5v`%uw^(oA@FghIuLdEyLLCDp- zFZNR?t(2N<%xD9TfEmt{`4>DeC0a{mw`}6`6PZJICZa@8429qKdZAyf&ac zDoSyTdN>pXUoRgJl@n94hmv|0Brz96jPv(=b|FKo3F&slErY66s((7o$P4GME#DYm z>vNUKaAeDhs~gqk+}ZQ6=w3|^0@I7CW9r=#XdAhI_In6nU_8+|Hj^i7S=3QLnU!L*(uqh<$+zc-=6{8=Qcz=&0 zy!+=a)VNG!S8u(ivfRqTqNyT`qh|SZFJ{7;4b$m^Q!Q8jVWF0{5A5Evr^(Yv+_k;d z_PGvUpiPjo1jjys3u#Ivh|0&$Sfht+()v$N%q=ZlvORKnf?^0G0pf`05p)lsmC% zM(<}Pe)ag3^FG^5oVbB`ScTDV&l8<>oJ;aus+@YaPEc`nU%wCBy)4xwGkX?Ny zr3~Pg$n+Ry=IiApzV0<;=l@b$gH`EN1;J$mSJjE0W&=}Tmk>H|XrxEt-{ghtoSnbp zl&kZxOZSoctV114qcx3@%;esmmKy>TVD;7S%~=m~e}vo}8A3P7L?p zVN?dNpi-Wpuv%|pBn_D) zp4W(#`OXzs#&oX?59N$na1*qC8xbTfnB{~l1_H3EPX{5Ej3G2iy^ z@#DSA?uFMxYLQ`m*jy_LVA~R8B0>P5^u{+&@ODc*W=WYMjn&437Oxk$k@%TFEy)Jc1y>O48}fHsb-x* zhz^Ah69*R&AkbD*ZwBa(uxk}KdOa#;fyb_1tpztW3iX0QI4e*Yh}?C!fbu~;eET?4 zcmOi+aQyaf-?{LscEx!*(rYY$qhW>Y2de)F}-~^2i7&_G(#1(WakQ$F7RxP4$quv_SW*FV3Lzt{IH`In&#@-2o@mR+z%+BhAa#4 zgHjiYj!$O!sm4W8`(j+-7WgK_#MDD9CD@I$*i5fFL_9s+dWySl<@basXBwmE;V^5F zx-d{$4?)3m(LHbZ@Y#!?FYOvCD@zTji1U4l4<)Xf?i*kNfBfVcbk ziLn&)$rH0n@=(m2BVL86B0C36SNeC699j%(GkbLI{ENXRMwNyq3$ooDmQN2MI(Z$Ixs%o z^@K-iBY8JRyDxXx32$$=PAXMVYoXHX*=L zJuNo&=xzgS-n(_f73clqP&o!r#X8TMw}VvSJa?}Am5?ERSDSVh8pF6qOBHtIGp)NN z-bncJjLz0Wz%;&dN=^*#Oi3xgPZeEg)JXq0n1>xie;n`~tPz6+=HT)+5OVJ8kU@j? zQmN8?n9Yvd>^FMYur*@+M64+CcA7OSfRx@;@7Ee|pWsJd9v`1x^Xs&qjP2i}gy{Uk zcVPZ%-n(l4R6d8j_2zRUZQMOMHr*3FoT*vCYo7cBcyhl!YKs3jwL7b-;`QS4R@&cB zUFY9M>_9t#^ivUb()d`t!(1ykT|9?3RbN1y{eWgcvm$+l^@aYXwSl3goosaHbuI5N zkLR@3b7_vp!Zx^D=0+j`7#p2@tw_9UAAfjB&r?%Y(S(MiPnu*G9ZK=tsY{nS&{0>{ z)@}g!vl-XoiTP*I&%LZ6bOs!M{ByA zwC9~oJUV#|?ZYs1a``St+a1)6zkq7LkR)yY6rg6@=}tWtqSiD1P{L$Rov$ZDPpj?K zo%Q?I6tk7v$K)+LK7?Z78xw7)e=nJ=3^eJKl&Hv0y0}$aaJCy_@gx-U-)GLz@Y^mjd|ep+~AyN{{xZ_2eDFf z9TA%15j{WZ)OnYOasAuu)y*@zk~rku;9g;`%cnVzH5nz}m^tKULzI?JJZ$we-ejoW z9KN@m_39SO#@fcd$y4Kdx4Y`qY_$7eZ-A%twuF{|#>YJW|Bjv`m;l$s>cH^kDQf;_=(Oaf^|&KP zIKN788qinncHSh||H*MF>pBY@GfMchC3~Le8aK)r*LwVZJ@UQLNr%cj0 zo}5xSX@EEk6Z@$IgF`}0+XgH=l4v?2Co`=Nb5~D_7f${AVDzG{5m22>p|$vef&b{R z=W&s@vkQ*Qj~`QhXc@`8g@!8ds*0%i4zf1mP&9z7^Jx-;}>0Bs^CKQJwA z^}3}nC$E`L>5Q!iGLi^7)5RXboU-qL*kVp~$iAClOTJe)X=nhUL^4NVK^H88x1TXS zYqI@DCsqbnPMmlMw3~%1>a28dbN$UL#k5#QXkGg5a}1hMA}p?Z@b|A@&~pCb8!nLu zmNEd@CsHyi^0>2$%YEX0Y*JE?tUI8nmnK+xcU}nG+h4rHERYK!aY?+d$zr<1;`>=y z;pn^a5@*)+cy(_LTORJsfA*v9!}f;Djlf+5MPMKTG1GoEx)%zQp@iohD;IA8G|y&tTF zMEQ*y>jFyq0q`0TPOp}Ja)x&~iH*G5qD6(b#0GoT^y$L{55TFL)7M$!WB9lhEn4KU zq{v{eXn3Bqtfb0rmiB ze|TnIJP(p!_P@}?`@&gIbskYqYf=5lX~MP{-0&5dht!8-;ApS+6rs_ah^B#$&P$@D zB1!)nnYg)C`})co=NDM_$va4F>#M6P>W?q)Z*|{s@Sx6)uFrmsCVTNo2b`_Cz9jCy zvE`SI*Xj9!8;ErabF@-T!V_IXrl{nnr-$fP#7~eOBdGjQPfkX6NlCO3OC9mxiAcqc zr3fAQaHb*{a9c;|%V2X$x?J!uL8*an1j2-(gCkQTSS-Aka47Fs3EC8Kazc6mJ$0OT zH@n=Q@=NeM5Sk8%pnz$24PLqQ#FRPruTQ~DM0NR!6*GY9mm@WY!1{Qz>p?=aorWX! zV4Qs!m=Q3LkXJ7t_=0Q9jx0@0lc?6fjrzJuXWcpn#!dO)*XdkY}(dxPfn< zc{x3fPB}APqtM-|a=V(|=0UdyBHt5tOxOF%BnuuC^nscQ5u4`o#oq=Bf{xVd{;VIg zW;oV8h&zWy^ike|3w;yZ?e8Q)Ac;P`Xxhp#0gq!`?na-9hIv}NI@iC`By)2GlE+@- zXiE6XmT$Cs^a$3f>E~ehWngz`~ zf!1k`V8)F21~v#le?P0;T!yxFNIj1t(!)R6L^vGZE(S-v*ej+%^xfT7q@e zDc@M!n0D&>7wmdwIuq)5%&&Ce?+AOA87D*X=eoP*Hp-X0zT1DxkEEZR#(UY>#S??< z+z&=o?)5`!=wGM1*MA}qLv@_rpWs*1I9*NYA8E$s1B8>cI`r2DWpmOVzoNIq$4yCp3j6Yzw=|3R{AI>(la1H(ix{N1Fr?_LV=l1?4<759DbSNa|wjScOyrzF604G9ABtK1YoLj0tXwV2MyP{8V z$Q%$z+z#3CQc^t3+=#8iotXI@=d?_X?v#Se0#t)tEbXZXwk5D{|77<`&VX z9IUKrLee3KjbNJzlV_J;?q|gf$wi)0~}ezTN^0P?yOi$hc9! zZXZa0FW5s?Ljgrx#5{!wsBIV>0d8nXH+xzmTH4^ZC;KL-b79rtvdq0bqhl+QZm0F^ ztf5f@s#H8L_uf%&(ZZMhxwU){q84H#5z;8cSCd+}F}o96KCG#r^1cEtEc1)If6(*J z5EZx3tuLP@yC1$?H_k+(DbMT!RwmDREfW7$j-GY0wX=Jz?V~OG%tKDrL1VXJe(O8U znl@cSnSnuwDpn ze4Y05V@1iBO~*CHF^slWR)nB^rhPYN>;c0NCE^vH?cx)+FCePN|5Nz8XYj?IM=U}P z9^8(i?^fHTPP}^=QRl##J2*4~E&p3p?Qp1KtIA&BD$1|^uP-DVJ^Jg%>FU=;+a-FLD#0T(ZM%W7a6mKZZ0cM;N`& zv8RsC#xX!r(*h4%ccfZ;@^U7~hC?Z1LMieY|k8xpUegO{{%I zNdS{!1fSFOwdGC{-!$MM@jqWjB_`{N&?wYW$i}a;Y?guC0QjyeieZQIEdj2t(MlDT zmuJTJA|v5b(^42x==3bgL5RqPfbb@Nv%Z~ceA(8fUmc9zFOhoGmIw4hZQjNvVe~tz z1G) b^5^Jao;ue_wU=uaBcvE+bQvJCE6Kw8rS-wQ;8s6Nm8;8E{H}{p+E)wWDqs zf%KZI%?lcJr05`tQ7giz5RfH};jpsB_G5lQj*DP^^Ca^Kdx7xUmI#Dws_ zaCx;zJJL#!Ul(zJ>s-EkKc>6J<6XDMy_@Lxw4bB!;YY{(pT_e2ysgZgO@m4yK(0ff z#$(mj`9Lo>GUK7j+S}7ol;4gOS#ipXlM`E+tD)Vw3Z)JRTld3qL;Mbqvst|y@jS^= zJvO{sPeTl6*euh5ZkDmTT?X#6BP&tpU3u`J8AOSQc0h{yFj=?Bu+nMvp7VF7ooxR1 zmm0K9cfWxxV3`PG5BtwyZkgcXc4RVGpyaE|%Wv9EaEF!T9L+!vq41&cbU)|qGdb!J z@0#9O2Iwj6O79>0*D!}F(>lO0MGa$d8j+#+jQs4))_;qqoyxke%WCVtpqhNM=2HOq zVyns;p7-vPpY!&j(T#q6`{rgI2-YlpuzrwBBBNjgLwbAVzqSK^ZO70|_g>n(V+XLo zHocSi;v@4ZYeWr?>x>CtFbt69_>6fZ`^hQG`%ph-0ff9|b0S}DB-sE_aD#u$RWKtU z@*s30Vr(yEBja6{tA7_%hciSd&d8L_nt8`!VlHy+$sxyDKJ8v7vYXn&*ny~e!O`-@ zI{@Zv9gxXg5~lYT9t!@4(s~ZG*_tDIxiv;UpFb~Q-%t$&T+UXgo4y;>H;he>uzL8a zlfdeahw81n^es%JJVd^{^Xgl3*OTP%y7S{#7V%GrkdPIENZRtgyjOcMc&(>s-0O^( z{cPe>Lt9xOfbaAs;NL>Z;?{=Cd!wAoJ3nRX*Lr_m@<0DUD5jnIwKAuj)Vuw2J8@Gq zG>xYHQLppgN2((~4@pa_o>zZtw8VvO@4qikAG_&i^HaetunWEQWFt_D0K9Zg zf~I4uvz|(S@#}HFx19`T$D6W<6=eGqS2fjb)z+^nzIHtW?0}EL8FxQrj>SF89}tQ< z&MAoM%i!bgwUuRW-n@Vq;o2KP262UYQ*HKIMSTTvJ@-Ms8nBB!m0#Rz&in-mvMbPD zixDFAf7NE)rGPq37taW+l)S9F=O205b#Qgg{_3f%2qomHw(9x?r}n4vSb8DaM=hLTeFeVAuY|tZ!>Yz@9yuX+)p%ZwWDvb1LN-{-a+f z#qIp~zN7250INxpMm?Q0v+3100+f@3A}>{P)i1)DcnxWfQuwCEyP+*!8puk9?nn2j`D5CC1%qF~7COT&uW7yV930BS=WZnJb7<&z`lQ zx0b))QyGLmApgIBh`mm?(Hq|`LF9##+6y4VRQU!}Cv*s4Y{|L+=J;C*%&*VR0N%*+ z@^TdbaDW6Lx)+3C`_&Hi_Dx#1u7}Y99hc+1%&nM}aS@aPX|LGzy~A=LGqFJP!Iq&F`u^17!)&#$XUY(A(Z^q`wt(Ml=*Gm9Dy>#EW2CRuA}JS zjE$Et@C7*?!F&}$;jY|{&D*ylZlG;vKwV1nrcDE>Ihhg7qRfLgVA7gNfLPS)Z>ho!jW15cGk2h znAc7SpFQoy(D5mSL2LEjv%uNe6uS^4>wNwD(4Wv_O#?q0xPe*$8{Ciy{o%ke#>VK? zjOksQtE-POHYRi7?5bB$Ss6`{Vu2=Mowx3nK`59dmLOkJ^&n#I033hH%=Y7-SCXrxhx!n>0nKYGNZmZgT)oSB^aOOz!=cHB(FWpx!ojWQfTd{L%O2Rk^p zG7ev@wLmDyeH4BN7jY9Z2RmeO6Wybcwz(1DASymAhi zIs8!>t82K2EuX4@PgLD|^6SXoD!Zt|hetq?^Pg9w{zwlF*K{1?DKff<^{mm+9xPSx z0aH~{Q0%k*ZP%oMTcoH5qQkaTsYzxQ9bfVNy?Z;oQH8-3+er}(h*d#J3uRxa(u_J7 zp>u;@Vt|_khmU6!*sV~ZWMQDOOX9WIqer*GDV|8)-EqzBks%Cr(Yo`E6ijF%V38S$ zq9z_s2Uj79Q);rXK4feJrK@Ts_#zFVxr^Nxb1SQ#)$4+qsT}FwWUiHN%h4xJ7o37_ zcHh|h>)XdQfh-%U>DCkWkQx&a*v?5~#%%e?p;MQHG~~ytPV(o>#|5NM`MJG;-zlrI zw1oU+uCDJ|7X0&hssHttj066MkZ(Zql}GLt-X10Rcx;*8X)m zgofnBr=Hv3cj!=;ub3#$azGoRpuX<4aK(yq##4zrpec>XDe9ZIY>{a}e2v6Lcij77 zR>OAgRla}w+ahNxQ{QtxOHM^~?qm2*Ex@0j_|40^W+YP(^#C0M_I&BWn1pKiyv)H5 zE$!_a(!Ps1Iz^2MqrN=vKu#3hV3#*cl#4qC2r&!Tx1rWbO&unc+8z**nP^Q!QiCJ) zW+Xmf0t3>Qv6B&3oCYGJ)=v=+UhJ!05UrjZiHfSl$WZ+I9UC^(QH)+*C+F$l0FP}9 zXKp|+Lm(j+J8{Nl5?xhiQf!4@y&w{9v}Mm?)=ijKKJ0hFX1hJ-?tbg-Y!#`Er#)4) zm%-OsxsR;a%G~Sl*}b8m8;FL2AMm7z56pbS2Vp(Zdb#1$9a9zmmlk+B>)Fe>W!*MW zL=gqE(pIk)XCj~F4@WW-Hz?g<3^$5N$gTK8G_A45NW+z-;sVnh7`nQ#QCpYUK)!cQ z_xxLYD8pur?laGXN+^+WUByKnUFYoE(RTv*r1ty&rmfdaauHI|Z(~uWZCrK>9 zjpy{u!E;?qHs86k^~cFuF#}~Qo{9ql@QsL;y=j-A&^s|K{Arsy>pXDx6sa=~IWo^I zdKFNNu<-CT1VT}1!>nIn&2$r7o;+8b>%~2{6f^w$~_4*rJ5&m5)isj`~ zvY^v@qA5Z#DJ1?D<8QudW!Y0q`e|w@WHzAznL!nEmQ2XopYo&}ImM|8`Kdi1S_h9~XIzv%UT26}3663c25#jHBx8>ihgKWW4b*4ih zbOAW}AYhgNg%{=GQR-25P^ND~)>{WgTo!`UN=UE!>go9bociN3(^lA#`eTx$8cO;PqKLkx+SE${rGhSyhS0NM3sFc3ZG`K%@X!eKs# z=x&b+sSbEqu*{#>F_RGdjVVZlpUP==kF}JJdC=Fb9}oR4l@DLv$<_ffYUtbEdT@4v zm{XD5bU2bW>)ErmNTcbRY3t{gAEWZWUN=L!3(WZ-H6mdgal3tPsM=<$-PD7(-w(PB zuPTO#*k^}f(d5HTLGV-y>Hgc^n)K)|-ZCmr`gQL6oB0jw(>&J=b{R^+(8uXkbD2dZ zzWhg1a%QW_vzQ=hMGRk;mlt^Nj}_y)EkAEe>z(Hh)OyCbUc$2dC=t&rYt?$8LHo~N z+6y8|gEHmP9}-ns#{OYeYE~)R$J7hF2Y#daZ7&p9zCvd z+%zL153-G{`g`W;CM{ajCbWW!n5{3J&JQ|`Im_+_6?dT~|8m*iJSs~&QXAYK0}<8f z&d<8=Q~R)8yk#335LAv5lGSgx<>*Jo@lK&Kr3XO4#68&no!UPxTXeb!ml41YGak31 zBeMz-boRq^H-=ukb)w>^*PC0&oZwS6Jda4PzVs%Z~OKe*rgmt+Aq`WG%|8zkRFHja@Y+1u0dF$E)S-rdVM#0*O#h)R9RaK$Mxe)Orjs!je{VODFw<+q#*wM`XcVAK0A6-f0T8% zXBjYic;q2ts<9=lx=NjQz|qcdJlVcLn(2arY9 zLeQ#ghw&Bc8cp@Z)zv>8rDq``En2#C1C$(f;Ri-i3<2<|ze$pR)TwaPZ4H+GQ3r(Zf-A(#@c}G6K*M zdSpp(*@C)D-{ds%Sw7}Nbs~n77W)bcQd>1K?-5q7UWAsJRia{|rp4I#F-mXiWX05< zY`#uy=1;p#W?TE5el#z_Z$`~2$7hV1d30E#rjZ&));{$)e*5Q*)Z5!@w`_7Lv^4eD zg=uqMcC%Xg^7f~FpA5{RgSa>Ivge@Tu#COE%)uKdv;t)O6NrlV1u>~J@%1+_k^4AJ zv)scBCdQKiRwiF6R`lz4!Z4#-h#85L^^*@LBc+}?t-2Q3w?mU(XS61o`qJNguLi<4 za_wL{d2(^z;Q$vCLbPov940jpDKjGg#gsR}J*V`~JX$8sM2P*w(t@%g2tc#c&9a$G z$)6usZ|cq&dU5b$R{$~<9xH0%T@7RUv9i*M?v_W~zz0kj_0d|+7Uz{QW2*hX6ykwP zrNt5Yep-(hk4;eH824`vV=P8|sr`U0HYYX}zy#9k$4yEYPw`9BqSahEe%tKF8G9JZ zvy25LT64X>S+uIV`=^Mu8uIPx)oQP05@gN9r28=^4Cs+z^#dJ%a~z-SRw9dN6l{{8 z0fQypTi7NsszoJxQ5JMlYA`}{8}g8iyf7~7nN@n3zmeS7m&=Y+PR4%V0A(?<&%oge zF-_k$cx5QcnMBeB`OSo4VK+lJBJ2416NA?c_LYzo2e8)M#2*VP&!_<|WM?;6{U9p2 zf48k)tHv->E6ld7wI9wi$lF{Ik)q}3R?@<9n|YehuBNIS>RxV708G5_FR z4nION((b&nvPdng&=@yPNj7+pWMu=QLIOM$kehOiHDQl-Q+IL-f@>Rn`T?9;d_Fa7 zyH@p=44gQ$9S8Tl^m9yNbnJKYZjPyjf(Ah}i3u5SkLYleOP8)OGS?7jea4}}nsc6C z_LbS(h3D1Rsv5Pn@eM<|Dq~DWc;w4VtFfj-gFe5z{`qf4<_+sbn*IHE!&)zYGcpA9 z0q)uJm^$YE0DE51KZ4Bw4Vqrd(t~II&iIEdE33dWXFobV{hDRMpL4KQWxGZj8$zmP z=guw0)Wt{Qs#)`>_O*7ViQ+3bnDxwe@KTmJv8F&&An zLvwWjasyNjc<6dQCjT$OLrW-TOdMsr3EmLYbjKMOY*|*W01e*&^f+_gye%a5k$HRH zLRY9FW(4yhhsZipFk6AiWMqW5=JfF%t0!b}C3EMHXk8&jM8t!*XcWl?KeljL(>?!D z0JO4#i*y+&n$sOwv4`B_BGVC@-O~Sj>;TgV6G|C@^YnI0AEo@P(`PW0qlq2#^jg4| zO^S=cwh{E&jbBX*u7u}lCypvvOyFM7v$^@Fdota2h=Fm6myL{r&dq)Sn*nDe9@C&O zeC3kZx-IZ<=3;T7lz|b&0F)oxhf#S9h#`ljf&44H7*-*zoWROcWF)!A+6fU41U3rK zXvR^+MgjGfEqJZ4oX8vaQX4toFA57goXKbAii#!~0u1R$!ji4EYFs+MUDMRgYBDVV zg-+vLcRdTdY)*#g-1>bchLF;av2!UUEn}m+zE|kF<^}T{<~{jpwwYkl7mXkQg>*W& zYH?8hqJ~W!9kHui9Tzmagi`E}aZF2@I^M~A#E2_~@x{ny#2`n3`^i;^ zGZ}+IeglvXQ#=d}7U7Hlw*_=&Kbj};ouB}c$Ee_d!$fc4?>36m?$aj_HV`ZG_D1jK zJ)|!-9OMdf%0-#X+ARcmBBo?UxMS{8CM*Bk#&A7H% zA>(O87SW7BEe3XP;ZJW$jf5$!eQTQL4Zyj$JA{N?AEn{zD#$u-V7rkS!U2?vV z!(%$BW>bDH;@j#AUg4|tU>LbwA}0Zd5Gy!L^m1H(5FhbmGK#iLq;nAOC#DMjnb4g6 zB(&_wp?VK@Iu*`x-PsB=5JG5A)F0|V4|{Z-FVmd5x$b;8^2-zx znVxe}avdOZi2dQTn)kh@c=i?=V>-7SmkCPJ;)xgP(7%TzmEJ%ANMI(pI^J zHUNC4a7?-q6oMFNS0Ih{95tefwV$H*AfHF%r30k9|c4SI)CO;2u4;gzC z@M=@IQUd^Aiul@v%$|%0H&6figm;I;9i?86umi*Q694HC3AB3vt65!H?;TwEp7{FrI@AL&yufo zNZmp753>2?2F;O>74WKfR|Nxk5WqIFM`OdvjdaAQy%qG4EnV89PQ1n|sgDN)6WsPG z%L6g%Q`PC-WNzf-8_RxvetjjV^B96fz~T2idt9ZM8XfGDx7d(*da!Z-Bwj^!oXr+N z$mI8OX)5N=A;Ho_1yJkp%NQ`O2uP-1;v3e=z8*+tr-+ygq(oA_Xu_EP8XoZ-GB?{FOi?XJHMJP~=ZZZqezB$q+H2f1uE5jq| z&>^<+dEp*#1Jql=fLPGm!>l=Rl=LeK9~rwofBw9o8alPTM<$$dc~~R+W_$yo%dlLS zLE@Ew#8*&l(XnN%{Y*|X z=UP%MGe6={$hYbTfK)Np3s_h7w9{S}0V}9kt^S^M%wZ7qI_}-|aRDtN4YRb=mqzgc z3OVjZ=jt@zrMQXlw}3Er!)Rc&gaWO#4~`~^4^NjBNbd_xsrXf}>O2WVHf*r_kv$#5 zI5F@rvp~4q9)mqto?q%Jjdg0Ocla&kS|%k!7h0Fx;K0gu7Em$S27!H$s*X;=nWsG| zAlK65@2B<=A3*Lo2aQTJy?Tyge@Zj)mZd5Abo%^nGZ?m}C<9Ri&<)FiLlVP_moKja zhQ?04a4yBQy6SfuL??8@hXKZY;|d-<+C}>93zS3h7)P-Sd-jrExV-{4O{~6uA&9An zX&w`qc*Zq#+C<(3(OpGm2Q8e_Vv>m6Fzl8r09 zMQnoQg4ToqYg5uEl)iLGsisSRz&dzY4TrdO^QrgTgA-og-Mj(5^3E)r0IbGKx|VnS zd^(RbdC~J4SaaTVzi=;h#p;Z-%JsKs+&&zWfgI@^!SB}Ox>Wwu<0d*mZyqHs<@I7?Vm1ba! zXI_s^onAEhe5_dZd~oC;1r3zOlM3X;keVa+19+A1mmDa z`HvnoY1hu-s0SL%&7ALc=9$0Wynap5w{dtl7ABLbSSxdDhU=Lq3+<4kLt{!ayIep-VRN?Vx$U(fkS0rUwE1?#QofWM6Q*~`Zo@T890MS60=7c@K$v_LVnyg zboGJN)xUQ#UJ){P3SF6{W~6qPE-x>Pf0)FheH=r{2OZM}VG(G%$>hnqe*MOHZF$Dv z-$N_zzqw_KuUFvKxXanAetlcaGJ-2Sd4>}&KYVz~c^W`aky+o#|Fe0xoeJwcv)~GSe$r(wnWyBD9E*UP~%;O z^DPOkm&aTl`k}fjSFYT*Z=dYZGCVnyrdf0pm>ZHhS?IlsK2)9`AL%>rER%t?!y0Eb zR#uMSfl1%VkfY11rSbO3L1ew6!a^U+X}I_`#m83cZ?Lg~3sgv8B^!ZOBO4pX?FiCb z{O?xC`EgQbPE&H*cIvuw#bik-X6l83K*B_44B^M4lc&VMS%NOX2%=Q)bE>pJ4E%MP zgA0$hAs=Q{g8#fVVaKH{!P-2LUpCye8rmai+NHI_pJovHH;za&)1Lo0$#>VT);vIA zSQw@&l^&!Z?I2mx4Z@hm`1s610r5q|0`PEd$!j4&*o9j{3e<415tNYIFy#rPx|Ow%9A$r$B0NrfJ~uFEC~zG!aJ$N@payT=-0PUK zd>BRa=n)fPzh4Bb0`90_+*HZYHQ_m8H zjgWGR$cfIEB)^%K5gw6pJd8unTb_v#8Ymp6BMN#$A%UE0&)$HGpa3yehZ_TrT*mE= zyTe@HWPZ__2Py;;0B@rObFd77BonsQ63l}9-@5Otdd#1aZML;F&`_Th)-v54w{mou zUKB_Pi$b{DU8$O}u0BZDGJV>#fbvn{=As+rerzIG6Dk>&D0eMKEuuC3b5i!~6AVe* zu{tdBHIXQqPuSf~f00NlXg@eUb+gwlv@LsqsnaxI9NFMPJITvgi?TsMvhD_qg>O3^ zb4&iG8B6!_kKb8U`JwrE*$#P&oNF@48-wdMNmeqdzsTqyf2 zw3?G)#7Pph)EGolVdKm8m887pltcMA-3nH^2q%5FTfMT+1{it#LHUvUZH0K176|!P ziQ!}vvI4dMo<*8#VWk_|NZY*N(TV2%;Iy218P503JN%ZDX3$4F=E@9_Sb3KW?Q7Bb+q3}9O(3l$$-USuMrfu6OXoYWY-~sM?CPOE9VvUT zDjCOF!6)t_TMTF&+@39yr(8k+AQ(q$F0=X&N~F;x=Ktx28^#AI`{cYieB7_1^Q5Ud zho3R8IsJh43)v|A<3|mb$PWBxXV#9vPmMwov5#I0Mj4WKjj7*gOH-KIeGRmKo;&)) zB98&9oaLX6SVV64wc65B6}JB}j`&kUX~vi}`4r!8knICI7BU3vWb|%san!B8MhZ|% z_f?tij|6)dDr{e{U&oiKN_uPgU(eqRWfXt8bNjaL540~G>1(bKnq*N8FN*50`HHlp z9T(p7uizfjW~g_{^(q7w&f_#(@!8>SZ_Yk#^r2UTxt6Z?jmLd}THN=vG%4-E`{2!C zzdNk_*@ZT}rx_h9SdcSj+v%|?YgOukw8ZD``I9|cz4`3u=9ctpHR`Ld{sH)9m}`fq zlBq}8F;0E`i@*|k4I?6g27mI*S=?7o z?-~+M-iSdzuch!9F(0p(v66r=#x%!ndaIi0oxBXP9zLv{J)rdHK)|1f#BpEF@nd)E zItR_yFE!3rF-$wtjeNcuaOOER59+02%}?k#oS^V<_cHRH{u2bhpxeg@!#?ilT-EK{ z2d#8J_ons>dx{kxi zt=Ii>;2H|BTMyRo7dy6(<7BX;VWYaBq2VKGY*rEC#|48_^x@ z!m5JkPrZ%G`!YkpT;e*}$*1Lav3U$w26UpFj-30UC1mPQv)d72Gpxx{}S$Q z%sI34%9uxY@>W;LNj&Wb$ES~A9RO&j?8Q|`+e)J>lgCI6i^aG7J)j$Z-HPnpsW1mn!p5RC^czF}MP zHAHv{j{~~wM`M0ed0$+Mde7=6l~!eJ>2WYF==06x2j8cyjp*c7z3Oa9LB6gYA@Rzs zTV@9=r_ij>#g^|I7IN+9`{e_{#{e8mSc$3tnUI;D%VDYlD;HK<9o<&8Fo@+5y_dW) zHyD^8|J;{ls?EoO?0o$Cbq*UB*nrf8G>au%{(Fv$zyl4-<1K2tgp_~nXmbltvS4Ye z&AyPDx2osl-u?4~jXwM}p&A@YNQaa$DY>1b6#ft{wM=+S)f#s+AdM2|U)p$Okbz~T znEfFG2@mf`CWTXJNy@d&i0go2(r??gUW*11HI0qeUrz#WyvOD$E}9m&I#nB6uI;B5 zBsiwcIOs-`W)f~bH|kWknD*ZTFKmBYt@C!VXA9*xchYk0TjnAUMo>B9-K1f~9`7AP zm_=`{?7MH)`LkeC^VfKGYY?G%*JBu*pp@0WPnBuCF36?(YQt=7VveKg=pfA@?LUnA z@Z2&gFpkoQ_Z$E4{@q?4=GKe~-iD4=S`NcRx~FV)M>fbmuzw-itVhFr$BrB|>IA&1 z!Kgy=`ggo0cMnl;qWRKdmP}3-M0rCCwDykrB7ouFE>N zGRVA8SZRxXf7~A3a4_hF=eyf|e}BFlnHX#M%Jx?_Xui3u{gB}nzpq4(?qtLJ%cuqJlcsljLKAeLA@==C)TN;MEp@WpPi*g5@aisug0U_uk{iKyz5G(5q%^cHNTCW@pJ^~rmM0zsc3for4V zmB0(ffB)YK**yH24?D}o&_>A`1+Y4|ANx?_Q!jMQ%>~Z$&mJh|ZjD~^n-6c)6l{`9J5<3jUe@bUp{p?R15vMrhW;`X`TPhSO1O>}@J3YpZEDBQve(KftO^Ee0mD{3ZOYD(lHAHUs5o4 zlo4(4fSn<>#$SmTeAV{+4kqPv?+|JV-pL};a>Gy+xj5t71`7K_uB=|&&;xjS{ z_!13_$n2P*0qvoB#Z`!gQbar7_uRY-6`sKxNj!7r22d}xxjRH#*sC<1!GkY+?Q+qC z3%a^_{^x^SKVUWl2V$xOqHjz%5mzBF3n!8grSL8ar%tA->@pGh;ukQQKp}jv=KAMC zcJDTgwTyK%K|qGrNHyROMSR6z9mfNx<#vPp?xK_?28(Am zFx^XD3TRo^N$tp)cimT%L8l8OA(H_V@d9Hsi6xL7qY&!=k`yjAmxA-d;s>x{ z9kpYdzO(#BUSP^xR>0vn$v?Z*GM4$YPHLt{8CIT~9n%y@g3GrVXf5OVcRo8L+CLD$ zP^?G{N&@?1ppn!H^MWsQ%B8%WvrfvD!LbH@!%dh5!r?c-y-b^*2Qeu8auv={V5k4 z?f@%SZ=diYDr7yd%3Q)MbO3DN%e*e#Ymdo^F&id|Rv4>WRc+wfz#|>!wNGl+uH87) zg~h=-gp`CQ+c^WWOWJ7vuEz+HDO*}ST1p`3HtAT~XtR(Az$fuU@gb%rGF**X0)m@) z7^`DChKBnnGOhR|z!$rQt{%b-$klI2cRGvdVHU^LG2d>Pm!EG%bE){taQQ_F6VWdz z`__Q00oL4vhf~;Hn@5yvMuUG_5J)IZLd#Rz8o1R0P%vm!M2?3ytDAlEunOH23zN9C>xG65Z*>;DoKvrCkYo@tY(8}Z5S7gqM_!8*M|>Ua`$TZpXT6#A!(>*0fnCA zdzt^%ew8wJP;PAt;BP`&9YH(^@pZ^8I@XUbgCzNbT*1@%{3t0FU(Ts?hl3_6w8$08z=mH39bP^4OR94xwsb`f@g3gLaiQ%yr%hLC(0$H5X*-#{DY|(# zGaM(xTD!FE^eyd8$2a;e`E~F8>Iu6-H@;(dW%smC5%26<8Gl(-yRxd~>G{*sJq|B4Rrs;U|13RD^zL)eUUG>Q(YvR=W-;+K(r$i2~ zw980OzqjX59kciUU}f*tT~8Mp7}+ezu@)Py`11H7SYn^*d{7&TZ{P zU6>TPVmzIh+tbPA1!>iG-K>&=n(ItCy%i~k%h4^wN|tk9nWXt97suH41Rrr*`Bx_vxwLlRs)0!2OuWU&ZzGKXt3Njk4=-fFpsWM( z`Joj2dpVQOTREp7OA3$FB;c9{O#gAqx~jK(oUpM+&F()x{y^vIG*hEg*OrG(x2T^R zW0IovsXG5Hi>2 z)voMb>Y26lSObm2I1f+@C^drpy8j4;)CpweBDnyroekJdkQH#!o088C(iISeCiB*4!xmNIb~E% zY7O!2B<%+>!m4R{``}Q=sgrhjGby}_!0egVy>H(jQo+1cZ*JbDrjjk~{rc@-h}Y!6 zTCu#P*Z`A3L39@hQ1K7!uLbNQYa;8Yz(%w$qv*-wiFJZO3w=$sQos1G`Z4y&eL*&+ z5l2M;(!Tu!n1xxLUV#=SO?W~xAzEzZVB5JlN89YwaSYx5iS+3-^9GDBxGg$DrBg$n zamh=pM?TJ6HH=4cg4us5HuK>FXXiY|%=;0&_U@L`?hZ}pyn}u&Vy}k~Bj?YrO#P|kJM@tJ z`(z%N$eLxZA2L&1y24KY0-*3ej7J9_paCASPDOe5E&DpfmNz38du~fA@dbvX{_WXk zopQEPw`&GL-_Ie2>L;4ncI`a>2SZP6tDK#I*l+4{mX0fdlop2^1KwE7$M%?M(m+6z_;) z7?xg#AOK0Y&yRRlERMkT`=DQePP{Dz5TH7Qqfjj({Km=~wWQO`zJsti=m<{5t+{{F z*@}^axQ_u2c%CrUC7!70b=Wd$M%1#1wLaY=%fX} zE^L&n0`_Vb58yyC%Mi*K+A$n(w;D$5{Pd*s23<|elry~=H*QR@RmW}Be%p`#kk4`E zxe};R1qnF>pw5ddeDh`uAhxW(8mf`$U9xOy z1^GKG%Cs3xR_GghYJLU!QgNAp67N^=12#XMKN9!_O#;6I-|ZZGl`3Q+7{U(bK=87} z+uu#I;LWd8jwjnR8*+$rvOg}*P4E8W2Qa6b?vk9}I9#n`LeL`GtOdGuLQgHI>X4z* zvT;>>e(a*dm3O+yAKrRc5wC7LHAodA?f{|T#208PZ-n#12nO*f3|R55z4chh}& zU%GDL8prUr-~+T)9@>P=PeR+sn{D(h=X?CmvBm3^;< zjIm@d*KKv@Ngrmj>o4Raz?7;h0`3tn&hOv9AA`bUs;-~LLCKyOkdwnP)}+%Pkn=2m z8f>H`uiU+7+Nz(Y@muLU7#uejw}P50w4@AsNHid_Z|62RwvH2Km)=SaaW!0;WU@PjY@JK_Nup%ykb!3&h#$%r)pX zaG)KlWAPCVW_~Jgjw8~BC`uXo3`jx^ac#Z0s^@rEjSj0YdIp-NaE^BxQ}L%F_%+4K zTIhWc^}5+ZRA_#B1V^4K{5>5x0t>9RFu&v zu*Wy%fVpw>qbDcT{`~%_db@U&k;LRP<`yxv-(@mK05Tm;Z^%4N1x5slvZlu-wOg}f z*|JuFVQXi+h%c%7iC;z=+!4S4g!Ab*VnfOaVkDhxmV`}SX+dt_%B?Ns)pxCH$^0|p!xanD3YbMt^6TlY32 zn9#;l<^2H}+k1Z-_T~qFesfK&g?mK0NxxH6Qc^iFPe;49i6h+oJ_I2jQMxRKD+aqs zu<5rDgM9KK7r%?n7}oIU>reL1s;xEUbPwhM+@_gY+-zeorFHd@wO_h+zgSbZ)4450 z-FNm|G`z#|cF*=$loS@4Ydtr)^z#mPa*KTqn^O=NMP7Ud24q>>-={izN*O`Vy0AZI zdS!h7A79>$Vbb35$hIJj?u(v}h~(Q=)O*6^mJCQMmXvATlDb58s{E?@S*|u@KBXa{ zv)hD%tlZ8kb)6?_b}Me*G2V5x@{Wmd$5WGGc0Y{oV%-vSaM*Lfv#1x{dKsYU0AF** z+B3wAUz#D}5tDvY^dXRlH=R$*c1pZV9H!+{`A{vsRIl9K!Z*$`R_sbjw5(m5?(=#Az(x&w^}Hj!P*GnbtWJj zAQetY8^8-%n;&lD0)dN$;%ZJ#C@S9;W-d6eY?OR+Xq-AE{|&=4-&u)_5cMzu4K<6H zJPrK@=ZAW-_5Q@9zdVOPRj*X9uf4qP&DY6QT_USBP205#>KD}c&qi>y-qS9szZqlN z55cBsxcO+>${^ZEDtt{nm+aAbpz`w`9_e}caBp@SjDE3_4Q18{HzZLPs3Ab6#_KG6b5g^r6wNHlu1-}R&(&kd22i$U15Y10z- z&jVvE7_nkqRuqnV`uh6K2lnn_XxJ99X6~1a=Jk?L?S@!+Er7z|&O5j6-JoTUfEJ19 z!+JDGHW)atFR~HOLD1#~YOntbhjNSVbyEYkT|`adm`>CJf0{+CbNfj`?usay^MO42 zJBH+K1}@P;lnPjw1+30IbjMtba%TXB`hyO@9|k>`j+%*_y$;L|B#gp!eB(YjUB>SO zLW1$;)Ji%9y^44F_+LO|$trvr^ynq&dYd(Gu2~SwqXC|6&4;*wpB62%ddTHWa2mLQ#AgdERB8#LKhUFLx$}VD22!>Koz^; z`~j5GyO}1T51s(y3}`urX*7`Do|#`D@Tj6+5P4yZec-}SW|U+L_AP%c>e(-EP1$x% z-SV7MB|njFlwVUfrco;AUA9M)AP8PNA0~lAF?`>J+La%~Hq&$n76oFRE>L%5MOj8F z>RgHr;3YrF85Zujb0}cF)1q;SwuEU)XX(td``YI(Z z@~8u5H{l(w90r}>rna{mTHACceOB{bt0K>$F)Soms+pepbeSx}qd=}!xnV_@Z#w34 zBejQqG~lWKLt7l?UGp2tgV(I(`X^+hV)-w~C_4u5EAStxVg*FPT*74PD$(95ojPC! zyzCS?KHOaPz_MdR_JT}fNU`E8U?lb0br2=!HW9+0_eIa$j$@w*5`hr&C30`rpgO+8 z*Rbe-t}UohL)W4ugjM0%DZRq2wMCZ5zkBCIH6oUy)Bt=FnS3;IZSGXR87?n8EsY6{ zME0hW`mF}nir(f11<|X5v^4tysB2-&(8GnEa++$At)ufig)*KWtT*z@-<(SEp?f1k zP@fPOkQhHNDY-_*0mqPAYOb!2`k%sy_bVW7ANJD5T3aT&Ir*QHAigQyXO0LY_}arF?dYnxM8_UwJ9nfE-!djd+k}S3*D>S|`&2vZ zD;CcFwQ(pwMV8`bLW;6JIysPKUCkImMV_drG@n1dW*NtpgKaX?Hgxy`aDn;F#khx} zG2ZnVuZp9kv?szXteaxz2^HHRRyJ|gH=_^zq^9O_l}vvJvhLElukGAsht)y!VCKT< zI!FUD;q~Ihi%w^rgWvNFK0Of^LlX35T31QCK8Ba;CWovJF^j(L_drB}jM_1m5qx;~ zr)HH~0Q*mk-Metj2ZJWRTK$JOVO-1GxBsQtXVClvsv+a5V}GPFA!&|4!sF+B>avUR z5)fdnlgPRd?Qi}(_WQk?KtU_wkq8v8%DN?Bd@vw^$W3 zuf+3}mWSwck5Z12(@iH%oY!{z<+Ah zd&nxPkm8xt=5q+Voz$n1cF4)H!%>!8;mh1(%MY->#=LUs6LB6Ae_T=u=5hPL6e1E5 z4jx`K6&ErzWy9M}_;An&#ky6A0lJ4UPL5z8`@Y_p)G@8XH@W)y)vM`i^kij2MaDzu z921@%s}{5uMWt!#d;ijxNm$SY zHmI3FW(i|K;dGtw(AKy<_30zZAeyXx=+tm$goqAD9i`^fLb)~#;!Awji`jY)K~J^~ul>?K>YrMG@InBu=|o1+1Cn-Vbv7X_M=dD&Pv3#Z zY%SKq42ql-8&jHj`ow7ZdI6)j6tvgovDR`}=><3^opUYFMM=3LCB(92bC7<^LnggN zSjIx%?XU`Akf#aNga~TsYG*x9;orMixgYNVM%_417BQ<}pgU(kL*h~v;2#%(Qtl3& z#3RO#@ayKi`O?8nL*Yy*Cf^bQ3u5>loVx6Mg*;}E0EhVX@Cf*{%2I0Eb4y}>6%D{6 zNX%y+_ngiQKA=O>wrzje{f2Z`cT=8pL8ZvucE(O#B*bg`=AQLS8{splHpJ`Ol(!*9 zA7(FiygC#S)+yyKaQO~3qDV@mQ$|rrMB~3QnzETj4#V#w>_ye0Q%pX8ehk`#5SmPi zm}m;y$!e%^_{-w*aveY^Q@#uT%6%$;&IkZZgR(DQ!ceE;To0~j=ielZV#6+$G6jEwZI1xzI)PEuGC z)unt2J5T}Jls59@QjTAVPXyW(8F)jYaD(^;ahO}Le+{bX>It2Dw)%C(Gr?b5q%!-K z$;ts*KI$#E+ASc328hwaBbzW3jk>WP_rr9V*I|z3)$1NMF@J5C$%rqcfSs8lUKI{To%0m~f*ggkEOQG@8rdsXX?j3Es0{ zM(j?cMrbDkK;UxVE8_{ZEBio2amMj<8JczF98*Xu{8S< z!VOa+m`Zs`aH(L9D!p5((f&kPG=dWH6Ora#j72A-cY{ivKM$Y&8Oz9x#OzykE0Bne z2ZzMI#c-o1sK{7^B`nI-0rZ9ExQ`rT_(Ld%#o*x7C*)}H(`2M-SHibBbk*#Mvpl%s$mCd4okI2AhQZ zE8x-0(O!G_&}L#vt9rGn$89d#xyLaX9=0E2C)_I~__R9IXsVa~zqZaauBSBY)-EomfevXzjev6e(=7wyxAk}QRk8KXrc3YBC@^n7og z7tf1lKHiL({+<6h_qp%u`fb-3KT;0I#&FsdQfa)aIB&AMD`3mC!IKII9GmOWz5aO) z&u1mPpwKP=lY(?dW@5`I~59afwIO%rwLRhmO# z`9QlD((-hr6Ge;2`hrG7_cRND7hobPON^Ej96xi-sX>PJ+9*eU!$2%q!hD~SvJ#Ln zqyFfS0MXF?$jLVUexy_X$F!Hp(t)1!>G&oJH0pC2-f=>s*~_S1 zE$vKvF=u`Yhln<$0;(*T))6&4}gnNk1 z-#DyX9R^-JR=6F zR?AY+Kj#}9Y3bDV`SX32C-lKIu9C-5ymD!01%;NE_r^C{XY=a$~a-jHXkHG)z1!l*q z1nDiJET~Df`L1~G@V<~w;!gu-@5KxmbtD}R%?wY39@Jt07U~hi<)DsdchK z{XGSi=o;DhEzi&HpV24@acmk?=*`mLhfkiI67(=d44s*ThesIMeeF(+Z>1S3 zfGIntA41pUL8?NW)nYzF{kaM?fMn}D^zY0j8s)qEfRwVs4J!pN z$*|$0QjfM=K?JcR7?PcaU{YiF_Rc9uM|CYizqmqFm2#4e6bPgf<)A(Z1v1Q3a)7Mtx=aChnhC-yynCBa{!-K0&KdS+e| z@0O-@!fd2r$B?|S^|MOlgr;8Au=~Ydn`5n_uK~=Un~9**6~*5Vc2CGA(M#P4HyB7Y z$Ycsc5_Rl%5&`Aoz^OpdgNFogQz-y$k)3pvo}Bd?!3)N@)F*Q;eshi*0-)}h8K}#D zmiK#Nb~vA1@|`_nkN1R!du%fL!KvqHf2{f;=Np~7IwL(D`=m_X|Ecef#F@CvKV#BK zsCwCwS3fxSQ$){thT!gKw+t(ws#>|V$9i#;{Iv}68&HNALbNR#`3(@XXMF!dk=3;4 zT&dWf`TmIut!K>GQ|>(acFOdDL*2dxyepVz=(MNy+6wcMKzIfVp7mJJ8^VT$a6~e8 z(AF+(Ls-^b5a?kO_4UnEz1{~uq`?|FVuV>&N?>Y60Zwu0NEFS#^9Zjv0uK*~9v8)F zHH#MLFADdOy6YcX2`Om8=G`mN=2-Gb&T*+lX!9>8B?V*38BAeHri|&@((?zbAikra z_#W`iM-jJaaXC5ph!B@lq`OQL(ne+vsH1K)Ljq8CaabyWzW3QxjRqU z=DN1tqNt&7_L`qPt~}_9)xAyE*S(vmwrkz0L47yR?>XvZlv?CvUmgAH6-F=aTM*$_6T@|cd#jrm zq2T3}U2Jss?p@ROo2)Y$@3iV66gsGCl+d!ZwzgK@ml&n@Z?A(_qZ}xLfu_SMs;Y9Z zHzEOyr{*8--L{7Gy+~fT1q=XHRAltl0^03P3JPNA!<_Ibw)TPajYWu%RG#4#jbwp} zA0TpCL&I`JpYe!wHAjqy5J)5Xu_Axu@Aff8!?%{IHbl6%8%=*T^M=#Vks>~q>nz$Cl6 zIm1GNiE=d1sg2qj zv((CDrr!UUAtjDjYJB1m?z2;v(GOCqt;Ssg6RfH6;M*Y&3f9Z1smhKHNy|GG6cz>+ zwjI{Yu%C+x9;OVvDqNvb5}4ETSFc7IW)&6`%!d+CROEr*r^&qLx{z>UrEsegZLaZEburj(Q`Me&V`!#Hww7~0Ygoy5)y7OU2Cm6HA zOjaeci409s7K5~ujCC7gad|4!pV01#U@fUWx<8+g5ALi@yNbBD8m5SLNZ+l#56o*1 zyb?ESH%s-2-w-)=<9z}ioI2*Huo`p9AF_xVp{14En2zwOG~q!w{4#TQ%o9r2Bv zIJ4(3T)3MQOc9xiv7Kb+w#6a${;<|@jybJ6T|d6g!Oq5JwNhR30Xa3z3v#luYDaIo z03YMU>Ixbmu1{0bgk-#O<v0XOUY5-?T>*I3mp=oduT8s~NA08>8@ z@uvuk*>j@_Bnc!d~OEEEYB7l%)Tn#%Wl9Tdo81PQAzQ7naZAz*4(&m z9og={zi>~Iv}?~E5&y+cF^uXefD-zl-#*+fD~%g`%1Y;kjnUz-u!^Xms~#geR7S_C z4K~FUd`~}lNGWLk69AP+)aSm6V2pg?q?XYrW3W`AXNgFeP%p-QKofD7r+j?ky8Le} z-rk>{DkNEUlCnO(IEmnI4~{_qFEL{xEOrxQd?#pP)+`ocMRF5TUW{YoTZW`oEF#oZ z%N!jE?v(@d0`rW_$r(f+&ba%$(;e+j!lNts3h3z8k&(jm$R4*>IJJX(+6POm74ayB z9oaDG1Wcw+-)%NtMhwL+ZOQycD*f|?$M4o1+4R9t2ErwD7#bD>vD1}@vH9a(&v36YGD z8M8R{?`d1Des^uHIyWGmM)2jP4vyayAm&cbz{!Or$q) zM~s>AMCOv$$25vQF$cTGgrmDBU4e9{j$=wVNl> z|E3(?!|0u)J0hN&`M!+45o1Ih`JZaGfq{tTT59#X1L7~%2`5qhkejJQ$Sq~C1V@4J z?NH;+w6{N{&w#E@SPO9l_u?=lXxYNP3)Bk|as^~j=F{@>6kk$fMvTG8;S9!SIJ{3bNah((s!rPYrN8L{#fDrqrlmAVJn@=g? z!U-s1yNAy`wL0xIbRuAS7v680D@uWb#n1XP((KGUVO%^|NNri(-w-0(0XS>tsw3jl`q9K7V;jZG38ToGg)MBzaLH1atJ@U$AssO9Mt)4+pOnM+vCFesF4Nt7F*VU)sx0Q5=)$AXKXvc^ zynfAj>kA>8UU%y#Lv*MfQ5(^($A0AdEGIcdAEP-dTm(T$zGQasTar%{$EvG=>`>UG~Yc2W7#`;MAWyIdI1I0dV3X3VqP_*E(5E*Sgsi zt+N*4h1fqLgUNO8N9!?llGn@E4pB(nI832Ex5~UhzQ((oU;Wx83K9#hOZV=5=G1aB7Fc_(KbhG>)zH2n zHU-b0ti&BDnBX<1X3Mt5?2k;`>q*}RTo6fGI$t|-yNi>XRch?3p=T#5oOo10p!7nL z^LrQ7ext=jCH zIaNi9mlsZAkD%z-ZHp-&!IX$z)fBVT7)Y+{xpaJLXGXc}T|smlF8QK+wZT6$REbMS zUQz`Rg004{XJN#~$&PV8#F#yrsPuh)dP>61FzBkty^HcKkrV*+pCX!=sxvqC&i%sYOWJj58}TDM=CR35-+OHA%{2 zl=Rr+-Pzs`6|Ioo>jgOfckHbgFxK;cInlcB2Jb?f#(rjHk1*`k>|9P= z|Ly$+BZ?l4(WB?QKe9YdONT)%rH{qg1YX$C<5qETd4_?eW>>zbdu^z7{<+seGKnRJ z);pgPoT)pz5X`qf?d5ZCpRTsHF+?Mn_@0lI+k2HvY3a_>xc8@LJp9TspnhRZKzyOd zycd{lb+~gjQ*AxHnJ`&osO-01vaOQ{0d-Ey-t+je9VY;l1Lfi}Qf=%44v<7@*wO9^ zp>mC>TJV2U7cc&m*b>=Li%uxXvcSZpuU1v5!a9h79^*=;3_kH8n{Yz}zxnhp;zgm-XUlKN zaim8wA^8DBgcD4#?lep=ipkfHfo!Aa?#TJFD$Ynz*!h6eKXrU1lmJP zpeV^i$S>1;nbVb3`Iihe27;GDa0fB_==ki;h_2)7U{kU_Ja)dxEHNV4C|c!@&mQ(R zZewLue|Sq@YE5>y6=VBDUG3o*5C`I?28WJ)uV_-Qq`k*{Xpy1EiEMp_r?qCFWcbA-r~Z-y??%a z^6!7w?>+eSZeza&=eAibCG?B&o%2vXKzhfQ-60F+crr$BUYjTYr&45Xb4*Pk5u=8m z_O#4T+c4~PO^pc$Y){4L#3TabC!N$nTyheHruxA&qB~KlcBjS(qA?$dJKz7|oIw28 z(K$Kc{{9F*Mj)v7_vf8XPEex=$N_6^*`VK%EZ^*3}J#YLED6 z-@5Qgd&~U;jgM|WoTsICrr{@!Y^G;r+B}NU61!h(T#l8O7b11si~H6naD1e1dg_-x z>-?F-wah|zB~oY$bo0R=tX4a}y+;y$;AznUZm{i_V7$s}e(v0u&VERi)Fw<&=H9=4 zb4L39v3vN~ic~)j9K-Gq8UJ}Lj!ImcdFG4^1=&uJ3h}I1v#HM4o@CbBJW?r6oj!Aa zYo{662EGaGajHLWjUK;*n7PV9ehmBgC&5X{F>Y&0d``JlwOdr1UC14>&==Qb-AXO$ zuK1MnV6xb+l((RA6@EK9;>+Zt2p{_H?cIr>)S<*40S@wcD&w23*nH?C9$A3q*|9QG-0v>UX8>PK&HdpD`U z)qSp#Lw>HhQG?Z+9Abxj$Sai`G}vyKjzct KnkJYm_4^-}{H8Sk literal 66141 zcmagG2RPPk{|Ed-p|UF@v&(3RkZ1_iMX6L85;7b1NTMRjrV=SDBZ(xWVegTO5(&vB zWK$tZ@8|4(p8xwi$N&Ex?{V}T_x-qaUB7Xj-|uIA&wzvbcd;*Cv6!MLcCFp?Llnhm zNKp(2SefyYh%7FC{9}>B?&D4r#Zf{2$8cMkLy)4xC@uQ-Bd&Lc+gy$;J2uBMK32bc z!J2vY_6!Ybh(Zh7uOTPWpyQ~dS>fN zc`_x%*3nqa?x_{4O=W+3`m|d1Ezem0-EA!A`|d>Eo*1ohkFAzovu34?jEv$@OUpHS z7j$E9pZRk9-~af!EUJ~KT#gNY#Q7wTZ(V1Q^|*B8%a<<)4l^)NoACi=(suZMsA`d0hu-Mh;lPMGrd z8Shx+*>L8jm6a8Ki@GCwVs^`1g&f;A&24ToToV%$3jJpatetlM{T>geFQ0^DeNFj& zO(S$)G8>YMDwj*U#-4+p;E%q5po9G1A3j%5>NNZNL(5YN-^dROGGez~lA3Todi3aO zY3bs=c6^7dxl7LcmxTNGOM4~~lcrcXIGBU0%5O^_ldv<+JGaJFMdb4DA5Bs()Ev9% zJx><5Vnj*s-O_%Jd@5s#b-a6p$XWpGEc^j?V z)!ltH%l30wc{!7hkB`}0N5O@qv9YlhP3gklfBcYl>f3kZ*fAzb>Od@;NU-0-hpPt$ z225&Ww;66$Q&X#n*~({-ZCB~DgfBiJ;p&qoaw;D4LisLZG27D6kOzzyk!E;~hAGB}gdQogz&YY8%m!KW3#IIz-KiZn>rRqMbe&U2M0|Udu zloST)+-R$S@YeJ6lP4u`6Lt4?vbf=W$jqdW*ZxPzrliteVC(sHvPK2|e}46=MW|d* zFf%u=%$l2>?Jo0KvU~sjm(7{xnHRpDw&^Gmrf_eJRP%GorMhYQ3(uT66JXo?>67WJ zn=4n#$W&Ga@#UTs#Aj9nEahIdOd_i|Ie8Vn)p5LY`)K;{vu72WI{wU07qhal(Zgj= zIE=P#=I7@xX=>ubUNCG62nZNx&b(joV!Oti+n?XldQVIk3=It(dS7v~iK+^9b#*y7 zIqftw6ygw3c{LIj9UW9wwj(h)`92rD}IGMb4*NYd;T5}vJ&(vcXfghillrp+aeLC|bGc%;+ zPC&pSsuM4(^^*9m8+2D!*TUSRd-m)ZpPsHN_v3W@S}$4P_LHaThOk#^s`R>b>$sLK zWuhXK?L~%1M&#|=Ra7p1XZ7P0?HiPnlPhUVGvMap5_@r=sHliv-fY2igwy-@?c);@ zrQg4PV4$+?+IT*D{G9yq`KDJ!&#`AnV#T#_wJQyKQDF}GrB)}(#D33df(8nY$$qQIxujtoiRH*yM=`XMScJN zor-VoIYvqXx9P1ufg2W`H{;@J3#X?$Je<_xwm2`w?(xdVSU)w|7PN#|;ed;GXStjYyOTU*=S-d>8UUBjGgTCHZ!p>2*+!^a;RWbYr| zW^8Pn*`ckiox7;tAj{^8uP^h|SVyg`$3*u+%G54lZ@8@KkHL=zb#zKcK4}A8U9(+FtH|Rjb|LnQ-m}x}r2g33+gn&$Gf^+E33!Qm{Nmo~ zGFriB>~>{l#`W%ICuVth`S*2oA*u5(@pO0W-pzXT>Q!v#MHIiPn``RxO0xdu!l?M? z&yRG!oSZz1_fyo!A)nTRU9rir+q?Oa^B8jgxq_vu_E)s#I@J|>c#wss_rhxV+O=yt zM@FuDdQw6vu3T5HT$vfoA2T_5()&dI`K~Ha51S{y(+sj1xm084#>+V~E$V1F`T5F& z{ESRYnHPUpE#u=eA8yWUo%=mEUG*+zYv$>lD?a)bw7jrp zS+#1_HQ}wiZ{EDYonNoWcdyA0@=ugfO?&vTvuNG!{L62GNEiD#eP1ObG12?^^XC$F zhFLZO{=2Q}_xWBB{nXNu5Ff8@Q>ON9Y;wG7=l9XJe4}`8|J5Jd&;%1tsC_AY^KA0* zuermq+EHgBq#i~$+$JsNq$$(?G$5(B8}^B7U8+I5DwnH&vi1MyN0$;`VJqATeLi*O z#J_vy@5d_AwQrOQ3!gwvQo*u8KPZe^jUpe~)`IKzHd%MiU%w}?dOQ28Yh`#Zz;hxEG;c{o&U9&>U?usx^u$S zP&g_oYT$GB`tu_#A5G@^`ucWjYunbDPfko+2@U0G;=>MM6W+4Scr zR9qIsD}ybtyHLs6+Il-Z$8~}>`(tR;+`iY_kF285nH{UpmjA>%^}i!^5B+|{(KF`L z_Us!sZsgx~Q4y8AIl;Mz!@m5d`TTGH-Gh~QiOJ|C3&noVuBlDEH#uqO5!pE1S;_?D zkQsjG4lg>w&CpPq%QoDVm!BU?LqkL7zyK>X(;c+_efo*5s9$1gYQ--&u2^b3P3Lwt zUQES5cpy0;d4RcbtZ0to`0?Wk(;E~OD{>rr98ju83x}FA%$uK>T71rup-Nu8Vx5~F zt9o=aRig1;aa{1UEStfr&ZY=SgudbkLX84M2M|i$$$kPvB{B!+G%?FG&3p_=_?ePjn{TB=9Ll> z3uI+wpFDY@Ze_JLXzm>BRy+ZEMSQ;^E;bV?QtX;u&rNU!8C`dB4Ni zvt>WO^)s-J-OaN6z^pbuBaUA+wXzCC1@4NrFDmt9U@|c^E!{CM5D6@(sHiAWq_}b8 zy$25#s?Yv79D8i%m*`sz(Uun)8ylOmYz1+RzUzx-7@N{hl)nlQM|l@JhA*fUmyuyd zciy#c9~)Nt6UQD+;ET?Nl*8{oe!QK(ew}jP=beokcMOjeqMjul2R?NN7&?@_lzZZ* z+m^qzx#RMj%#YDFgWy@bycn zi&#R1=WT6lEP7sE4+{_9MOgrw9WgN2OQ*+daZW&uKd7tAo05{EgTBVief#!pooFT7 z0YHMV*x3CoEiLEz-wD%bd-m;hI>|MkVj|OxQJJiz3 zs=lk-FTj5wyW=vTuH?n<1Kix)#|;cVbe4MMng{s%#{)4RLU#p1uZ!RAwOT^L+ut8} zPV4B=+vz9rHR*KhL`i37=h>l*Vt;>&zM4oy+ZM%uIKP+};WXpoSbzV~j^YCsFJAoq zH93xlyY9K=hll1>H@>6oFXgU7M|q7W>F@vR*Ds5S?n=XL*#8M=Ry5jK7nkIlH@N_^ zADpR;)rnJexA@lgmS@Q36|n&b zR}ZiMHvi`BTgjzMm#&qTMxlHBSb~<|n;ti5G5RCi(mi2F_s{(A%687hi)j>j=Jc{Z z;?%**msPpB@rDAa_g5D#0q`_m;Cbn|o}T}24$re^&koc-*xQg{tXBX2y%^q0OP;fI zQ!JRqr{?DOO~xMDC}m-{ZhdQc$8gwKOKXv(rRD1a&4!POn+*YD$bn82F#}loa(t%M+u@o36)T&+6qiv?<=3am&<3HWf zYk@J*JT_gLvhi{bRJk<8hIe$;%ZmvhHU80~K#%#KEO?9ysqaHgoap^I9)DD+uIy9b zFrx<6dV2goH3a2jeF614xV)iC-n?1dmhZwsfpsj*%F23@mDP8-7J#oQ8G8f(nrZv? z?Uc9ECto&!GTZ(M*MX)C(JkkP^)hS@9^^tj$m!_m?v}g!%XQiEDxC%NxQ=)Mwt7R97!aJ`l$&_RCE--Efh*tMZ4}uLHKO%EC9xXR9^;TBieu;CtVdHwqJtP2?Ls=BWL@B)*4iBDjl z2!=#a35kphApHYy(!S8^l)lC--i*F)KRdtuq`ZR%@PNC%eqEDwAj7DT@EWQF?9K=6 z)U4&XC4tzVYinyc(HkgFwLia>;+2%$T)ETX%bVNGb2o3@Vlp>3A9ZnecMq7m4oC*h z&dSQ#$;?dwt~qp9EV{eN@#^Pkv|%pR1%S)9_4<9;1#^zfV--3$J6F#Cp1T(>CX}tI zp|KK8({ScsQC)DAKu^FDSu(|q+$Mf_J3G@Im(E`P@@b;QmS;ey|eR1^u3dfYqZ-8`t|ko zXXeI=8CaV}e${%+d*Q|H*uI@1+rEQ0I_Ow-3<`lMs>CLbc@4 zQF*cW*##4}az)M4r=_MBa#E=FnYN#^F8)c@N_g;~@&tkQT>}HJ-qw9+XrQB-a0vJk}_nPZchfEz`~n={vc0KxkC z^XIEquSy>3+|T))=Q4KVRP~+G*RNAb7u|=llH=6Bzc61p^qRm1X0)?PLhl9}*4P={ z&dij5d0o&CP3ohx_+m!a7w*q9s>hG>Y$-v4g3DdZ{O~vr^{w?I;T8*SkloUIyW`46QvzE z@ZQ6Ruh^~DpU9JNzH#OGmIoJ5++C8<4_Hx+(Y(vh6f*5QRIl;NGg6&jzDT}^d9XLU z8$f>d-o0MnKUl;Q6IG(hk3@k%CkN5ui+=VAQYC0p6F?^>-v{bkf6d6Bu8F7{p4D*j z314^o>X+(pCN5@M?C#*tyLRsMV$W(f&5+@2LWR2yHNzC8h4TJ$Q%XC^+rH>0Gawfe zrE>Wfzo4?6cTiAJ#iIMmmoMLhXMu(={-en_sI4pXWktn;!b{UH!Ie6{etq2*IWaxG z3$>aoLG?{K?HwI)d$sEHAhEn}YT5<3bI`yb$lsq84{WqqVq~nhcLC&;;bEJKs;a$h z$Bd+;q@Fx|+FgITHP3komOyy^FBEG+B_&p^a&jTh9@4-Spch82%XXmhn)~+cyET{V zK6jofD{ag)uj<5quCG6I4w|SpH~7nc{w7UXHZ)Z9ks0!_1?I!Dj?Lt($W;Wov<(!XibC^)QD*&vgZohyI{W&3@yJ{+T`EU$ zZf|b~_snT-i+>4yqMuo1+odTYu*li9ZrTULr)=N;INJjX5Ez0f(40mPuPG6~fB__u z@^A75SM5A^P7$nua1pY^QPa<=sX9Sz(b3^X0b^oeVHy36Rnmjj_2l_;djGqa3GDo) z{J94HmoHxq)ZJ$xx`$Q6>T5!qd1AJ@yd3`YtZR7qnq6C7*RP-7^zzTkK+f`RZf?Hl zOr)|i@9tg!GDgQh^W}|4OPc|ojc#2J(qxHUl8LuR1g8#h@1Q6CH(`AzI*6N_sj`Nh6pu zS8Hg}&$T_8JEW^CwPeW>eaK5kj~wCR)^T){zi{CKfn@}7JjW(uREJJNryC|F3~X>G z2ydXOre@zDxL8VR>aC(8)wi+RqTf_k2khpL%y{tNhkkHONctL`z>HHIeB})q>-?|< z$5`}=dRJNxY*kLi56{n`8d`!(g5T}Y}f30FxgJBM z%Ur+pZM;-+J0zs^)M<}4-t|V;y1UIF*qEW1<^bS}sJi(BckeJ8O-11glv)0vesXe> z3ux`pk0+9rgz@&Z-Cyu){f5z0Je}O(+@|FK^nq)f^=i@aW2m7aOx|K3#=wDu9?2t?)MGfg@>9O_vM6kp}f15jYn@?L{DQ=ll{aL*?hhi zwzUU7=W-q!1c+rI0%<(J$N8=7c^09MYpmaqBFFhpyFM!Aad-v{z zWMztKO?h5nVk!Ihak=Q_nUw_v1twNji_vA#WnjmMiHT7#Iv^74bmF`p3p82&_ANUv zFE4lm0gsdkq|jGy-)cZfmp7|mg`#-#(z35mUBI~_qN2J{?6p-#UpD@8*PqjlHXagE zvWd{MOFwph3OIhvR6bZqh0k@|8bpUxQ|;c1mgeAIfA(ws7($nAtrEOYsxIN`&4a4-d z$jTDoi`avxP!xIFGvHFErp7*Al*m2zl}AWOh}1y53a3(f{f+yNAG1MOq9`mtB~P<< zfwalpnespg9q0H4Q|1OTQ}nGzKcW-KqZ<>8E@Ijbyc{*gC!=U~F&v6=tkF8~=Y7#i zX+|ij^@qrdg5GfO*s&_CMLCB~^+?+S{a}e*H-xrpYBCcYZ)8Mf!|QYT=SOaagfNJU ziyP*h)3WN;^1bl+A7yy#W<>>^f5nP2Flv}9F9GOHEG$^}?yc5rI%Q|ap{%S-m6^o6 zd9$atzrX487ZVyuWl|-HTDOQ;h}vlWYi6QVMc(&k_Fq{# z!i6=i*6$wz`NXuGOH`Eein`eJVnOG^s9yq}dW;q!0vk>fhpn=*lE^b)e)1OY#RBG( zblaR=A*~olzE&(RVAr=T!D?R!0S+2eJUHmUhh)whBHLQ@-!gDX@x*|eV1cuOWnl-I z4K}2>0+yy`eb!sEW(|O`Uux=5^yp%$OZ*7->EPht#m}f%H^aidGheKf+jsc6X4wFo zDHA|7B3y!BN$tPuk47lAYE|+l=b%tkrn1{g`r?1D1voTxnWWQXuhu%fCsbWs9r0kn z)KGC3ii*bZMv6*m0R$0g6|NdSwi8tiw1QBRi&Mitb+x6`0P;1j@n1nr_b=?=>EJcc zx3XFbuefGw;=SIQ$%`8^pBENxgWH;GedN#~9u!E_n3jhZCAcLc)6>!_!G(MGD7=*$ zOE}G$Bcbuyu=uht3ObyuWl9P0p7HTwCr_O!1)c_&hcm`4y_Ac~b9{W9S^NyuMb*B3 zy+~72lNd^}hB*|amu)8uVCvP|d-B{^yD(Avva$gD*&e5*f9UN>83WD~ItZ*)AV=?OFw{ z`sUrcY}f|Ft+`9_774z*8xzAop{RPn)gl6^y?t96|m~4q{jp6Lq^p z?}1SI2L^`bjP<>ZCeR!1H4U=4ABS++E>U-hXV(F6g{P*b0II#Svz2%3*dYg_oU)%U z*icg(l34M9UGmJGrqqB39|Hk^PV&Hg5E;?f-zzUeR9t?wu6a^iguEy%(|WEv>B&V+C+? zL(~qscI_H$u0W6&3y>V1xf$#{9Z)++jG&!nRbhAU?t_CRNlWk8 zkx@}Zuxu;1aEtQ)Xl-wQV9}yQbb9aT=zd5UL`Mbbybn|RJ)WTC)EOXAMVC=S8f_Mi z`EF2FAl!X)`hi%LmB0~1MWrRcbw7l+x<*<$wQi*01^E4;g9qcGE<(@*n%b?Q;X@QY z^tlC|SUIaVZ;pgGwtCenKYxE-8GSl61H?X*chT3@#*O|;DYaYyY(=ke|TD5BO~nUGn;gG?P5W%rabYw&1c5DVD4Dx zZcWIe|Fnj3!U5itX}TRAvToOnVA`r`b4dnsn7P@yu7}6ErBwh#AVKEig6)Qa?Hj6`--B3 zx18(by?Xhmkx{H66YCXqPr&9*n6Isu0O}zOas?%Z9O3Y6mY5kFw6dE_UIzi%%=t@i zZ%J$G-Afq-1wzp2-r6OP<}!Kn&E|1$hZ=bB$dP43!3A`tmOR@5s2UsVerU(I_?kwY zfkXnVTG%iG=<1W1>6kio&%UF`b)ws+!Ztx7W9#|h5-7E~58V0tv@LE|BtyaQ1ER}2 z_mxpS;-Ouc_aXxFVX$<IDS`S>4E5$8>_vZ?Ity#Qv!_0y76%-A|@-`b$HTl=@QAR83ZpU z(c8Y~0vODNc3*nUq(mg>+E{Mfu?(ZOs5Vpn6n#mV3S2oMWJEZmh@kWQx#G!_CrwH` z87OZrIn}sety@y1ZEYvg^La!>M2M*f5J0i6x|Wxp?}bpqyStkKwzjLQQ-ljrWel1K zLOgx?^oc{)4vKwO5d>cGl`F3VB^E%h{`LF!1Y!;R0s`1q0n(Rdzgx;m=tE}1M-!>R zr2sNepGc&VZ+`w(s0q2tR@BC+Rlx{yM9SiH_N`mDyui7bC}?IOw{Deh%UkFjd=WCq zHHfpfs=q%@NT@gQ4)Mpc!tQ)x-6Z=rAe5Wsnf<4L_`dtBt)@Kp9tx{Lhw1F^X910Z zY#_qS%naztO?W5lImbEeD8)rsAGhWNL!nY2pb(4~QC3ny!L~uN#uqLw2ndwrMcAC1 zHgCQM28aH$6ZSdjazH@j*3q(7(rAoOc~JSUqD%O4igI8#5T_GAcT*JwoZEEq`)b1z zCvu;n_`QUHWNK*{fGykusc!iE#p%)OuxZL0 z8+ozT;jkGL?mCZs+Zs~_zDwdgM8gGKX*TiZ`d?~M!$Y0csqEkXdNAF;|LnUIAQ&!V zz)a&=(r>Q?IoKCA{aJ`18af7n!NHtcTt-_ve_fr{g6f3Nyn^o0)Ogy}b(4tN<#kOx zX1*7qRghdGA|k>L5_ZRq9`!+Y+Ov1>O3>e(84sK zz@vGQNC>Le$xqMK=668r>1~C~J7+hPiaWRO;olktQcJN~sBO{|j zho1pcFTz&=Vpb8?P+i0_AOzhr0OmfF9uk~U2)De|-`td8y#D+!G>DnLXnX1j{mnjU zWE?}HnysObteX&lz!lTlYN#MDe-G~_AOoPA#v`R>bED75LsByKyrbhi!3ed zqRO3vjF!2e%9&`*&tJUAy?95)KocATnh$KrXQ$sLz$$yKatCG(qdJNgPqxcoLxAe+ zfcVAP?`w|g>eiQBVfy;4R#iN~cd2;Q%a?$fw`!)M&kn?1L2Wq1o-xmH-AaIg4WhY-rfsp?ry%d z_p1WDGYKiFtXDCys9N^`T=17(g6%ls7f&}GKW2X8H=27X>PaSQ0|?1eJf2i@5^MQC z`9sOuV{Jw5Tk)N8?z8944ZLRnuhlqp>On;wL^hHp#IAH01Nkq!cI<68&ww-lV?z!u4O}pOPgmNhy3F;*pDqC0lWE!2_xqz2Q#zyx zk}E)^K{NcTVYMDg`+^!xERp}F9SU)C8zv)>F~F6qb2I=42r^a?@U<*}+)5Pd9K=Fo zjf<`|G#m*CDMRL%I$aE_TTf-%s!}X+PW&0-AD~0jr z%J*)YlH7X-zT;w)yw*$3OV3I$eSfJMt zVG0Z4DoRCo>(d9=+vTwCa&vPxo$X~sv?mbFh3H%Gmk2e!eO};RqyK(0{v<~jz;&s| z*2{i_1Xsz}ihuo$|RZsC;(r)X9@2|IKXF zBWzy4a6)&`MCZ7N2Zz01QBhIS(y{_OslO#;8M`#KNYA>*kNXS z$0<)Zy{LXH@s4#eFrA5vM&uqlyBjb1>+o?g9udwJix82GI$qC7lAC2|`tWg*-O z{g8oLZ(LLXrGh{WJp%)CRR4cG;yhFE1-gTS9NCn_3x-+pRCNzkwxmP3!;J|XY15`n zCiwLqcNQ>uGquW|$TNY>a8_eg0LZ-JmnV#AAeDN!QSh$0%&=5(w1+bZa!|7`^MgOg3 z6^@XUk&3Gv@;7(@9N1=9i860G z4IrVVMIRSMgSrrehW#iD1BZ&}14nYrw%%cO^&dn{n`K>ifS`J40aE)S z)JfbUe7$ifykHsQqPzYlcdhz}?YRq;J`q*{jTW`x3nMQyBZ9?DBsrv>iK>I0aA|6oLCo-3?Wa$X`A07yHw<07 z?A<#KPdV{Si|cB5;pi7MH8oKP+h}3^b~_=>^8$(bBqY#aZ#s5{>eiq@a?kQb1n!a1yaembLWWK6(YWikxTY{8r%guyfRcX=(9T@BH$^Ll(pO3 zNH*mOOKxAJ!b0#h%Coc61h%Gcbmu34gPa@)5&t4Zxx5z^dX|)^BV%lTdGe=Q=5F$u z$Wq2l8N2_uZTREk?Wm|ggb{WSJ6H}ZG55{JRaYOT#7Td-!L22zWg8XDpuAne|^uL3=txS^zM{GR=R zXo3b*CYNCmCgU8HXZl@N%9E6B>~8eSfWv>O$lvV5~S-9Wdc z|BYNd4B^b;>O7;WdR06K`!_HT1P#}Ypn|kkd~2+Sv0C6dv7^Yw&g?Xl)RO*h@|N`y$m&&ZPad8NN+Y@;joRraG(~6gfDL|7kl=uRQ&^0y|jNVy}m?Rp$;U}bW z#8<6iQ6JLCCUz|ntPj)E39lI*9?sdmFs_zBar6lWim31~;!E3vYhJ%Dg=E6O8lL~^ z_3JK?4{vCJ5|93IJj%9}Eu;wA9cpAJRzCP3mUM66ex9!g72Ocpd=-zap|LTL{c4oc zjp*521+cN2q4&cKO{qExo^p#T5VM(|pSS2J+Q!Dl_5=ZGn@>*{dNH$iPem(Q@?Z_E zn$DJjR5aXCEDEsebL9#HjYcCP9{|+A;2>?ohNVEg2$}4FA4W7glr6&?hb#HtJ{(lM zhIfQthf>WBfgS!k(MTX^`yqgVpW|sG1{8o-0k7q@^yd|IG6=fwfQSLkbB#zU$gj*m zxuPh@oFs+`0>*&*Z7p&agf46N2?)a+2!TujASVo{)!1oXmq!GBXnT5yr)ltfTn;q^ zjy&wp>TCNSNyEJ%!!#)1K>p%)7Upg4&p}loW=sJ`!JjzG^^QGA)2Y+Vx~62l;(d@Y z3OhSlI05?4?XU+xEpkgYv;5J;6#yZyC@3hbIME1y7~%z2e(J|4c)4{++JcDVKi_Sp z;cK~wQ&g1>x6Bc3G2pXtl~DSfqIp%wnd%tfC@BsL1A+ zL_j;@{byv@?{z+$a5Pod^lj9}nc-)(oui{S9D81NVUVFDa>E(@7bp7K5W)_Gr=S(H zRo0TDNzkAr84Vk`LDof!EGJ5N#cBeJAnw`a22E=_NqsKTUg|918?ygUx20uGO%3K1 zI;^~8;+=WKl9Q5XYu2P_424NRI3Yj|6FEdbMVRI)dsYPR4^3u6GRpzNPgG@i7ukCR zRaI3Z&|snV!pJDrwd^_J1f32TXSchsitCe4w%*>}yVE=d-rtjPSSHi&e3#SLQahCA zz!{J-JVM+~2wIkRZtiB>ADI(?=G2A6G%GuMB|6JE z6lVr%w7sxeQfA|Z4Is1rt;ReaGhHkQ1()I*3NQZHp|8J!>b!M8l|)sFeogLW}fViS8REXUce@$Ssm&M9JLA9-BY# zBtu}}AFIU*dsSKKgWU?zxAF0DMT9{jt7y^;Pyg>|sScgK;K#`4a6lO%9g{>T1YbJ+ zIkqgCMfacp!nY`w2zsJqeH|J)eCSYU&HRI;q)_B9e#5;&G&D4H2b9I{GZW_Eo{6gP zD7d+`<5XjSZl#~?2Nw#fNKSLHkAy*L=?I=^Sk{T!l=$Gmc4*EpRY<6TES0dZ1<+QJ z9&jpE3~kIzd-SM`a4e8D*_ky+)M2w4UcLvvu)L)uD(H?~;C}@lHT+2Mk#otC^2f)Y z<$RTd3T3t^e5j?^LoGZ`=fDBZ{rmSDw#52^ftvQd3X$8efr(;Up~#9pidfpi>;|Fo z=f28Heq?6AQU#s;iaG_^lGu={sv?Y6Jfk!6kcT1Y8Uz&UjS2S`1i~HQEQ6SWipYU= zA(`mdV7Ix>%x!ILXlQkh>7@x(e$J~tG-)q9H$6(?qyohJ#V2?nYjyr2S6R>1}79q!dcxRv;D9s07fc9R_=YK`7XRT z$Pdd9@g}J`gBNXmi#a*_dG$6bEAN6gK#4(8B;x9)kH*QMb}6~}@8Z;eL}z+7PWzkk zA4ho252J$JgCA1~iGi*ysmX}-FNDgw)5hj;bBr{Ck-v}(avkqvm|hDvR(DyZ#hQ$~ zrGwuf>&1Cpy-Kd*u9}Ak{FriV1XcWC*U82f@XNx~B7(j?4|QACOMM!Q8Y_#7M^x1&;$zJo_a0}F&_k1R>D zp60jgPh{RrYu?@|u?9u;6GlGT6(A!K9uf>P& zMb}364f%9_=c1e1`}UcD7J@7=P~dizlBb!ynM5(80~my10dcH^zwtXjCI@FQJ47%7 z1y2gAy72@3ewng`ZCM3PEcfJ_gg>kF4le(er}+QNP&1}$RM0)Jx)Dye5+2S6;`JWW zNP5SQ2gsxn6BgeOmGvIJBFCYNkurVy5iu^Y&6@=vh*QUKY`rt(r{xiBw+KVL?e7eK!R7YUor|N8aYpAPt5Xex+u)kg`zhMTFEX|@nUHvU+k)lQEDl78xo?~&TNH5z%_HDY3(K!WO!p3Oenx8-S| zbW3ot`uh*y0~6EJ_XGbX!`B4wO#+;x(EwqD5LF%@&Lb@t9RNhvGBAh+fSvf2Z1eePSI zHlvts20Ua*2?;Ll5XfIX-rfgoZDo*VyoRc^lZ2F-68$NFbQE+dp00%Z&-M7IiTxmSy^8^ z*ot|y#=tg>P$`rSH`TbU9GICzF^OD~#QT5b@Yl-oU4LvLY`G%v3AX@zMXHNuGf|B1 zyBTdf`HIUG|B z;n2WP?joRV*$vJp(DH6G4v3Q}J{tQQTRap-bvZd|0bN4p(jRmGH?0*t=iuN__+uGL zBAJtZ^=davXnffs&q@-IPO_+7__|}0ZilJ>%GI9_6;qCc~1A>K?>qa=CslE zCn=ZgFbSEXQE=+Q3!(Ai*J%)3a?XBPj4{ObFivs@Q}>=LaQ=L=-}TBLjlDAZ&;2hQ zh_zUQet!3^P-gBLG?4Lc->grLMNSKFYsCm2!FYkTV)*&rVaLof{)^?pL%4i>8xJ2g zKV0*G&mf)A%bq&}gF;u>(^lm6^DOXdLfsFAKO&Qc;&h@ARPWW+PSdI`AOpBWZ9}D` zOdDztw<59t8PtU)0D3~)HS9!3L_#8mEEznB?L&F_JN%w?Mn<;;gfufVb7r!7J!0vr zb!AmmV+FZ@)B=SMxBZ#9{+~W$g35Y&#oI4Dx0jzd3B^xB>B-GRyXQB6(J0gBHy-NHxCc(SPU)U%Bi-Vx7F1> zqxxF2Ds-l;KmhBGKlK)DZIT>v`qk;hIZk3!k22VZbKNr^Q#9!O_(5~SkiE5l+GUlO z!J>bX@>d>h%Po?rgm6TJ=821u9-JhX_#Z~4?4hKrEM8dh=rNsAr-?8CBMoZF)%^T? zLocFcF5~6xhUY+eFVzI5f@v;y=A95SiHOU2=0E#3P$!P~DGhQj9_s=z!vn)0@07R8 zJ&Z(Ge;fl*hM^!EI*FJ8nHonIz&Qj&rB5G*%#&+D#y2rxV*+urbpkGa)TNX9;baH) z20YhjgNj%`Rv1$NMV~*T|yDf z>`9xuK&AwdBWlg^O?Uu&>j3-*!QAOLucM30E=)d6U!OvekJ#e8wh1OS(t~YLF_uQl z9vo|ep$QDl07DZ(ygG<0WV+_3rj`1P)8lmQ)3L$X3yK>2M+t0ihZYqbOkh66=4m=>E81EtA5YrT*as|4@0*cU5 zkb;83LLwNTCqOrMa*6wgR%86p7hxPitAn0?D!inu`sbGunJ-LABDAKg_w}tIVXxKt zXTaYOWMm>^9-x!2-PY+Smtp*w88K`_Z*2%2R99yb9we$H$&bmM?cJUGZU|8?In2%i zXx#?_Bi3J`I}+`gXTR)0T(uL!U^8k{?^M$Jp8xKNI~=$!<@w#IFNrq}MkO4|QVe}~ z&u4o?W<`92nVDQ;%{bf3Ewy@n6A^pl!!nnxJt$RoL?9fW!^&-tVvQS{adPE@~Dzs`YB?-_3?xR_n@$sS;ozFjC9se37L$>F~l)_#{V# zJ+6 zryV)?+hWpoI|N}wz+0Zz_%?8EdTa8W&%UyA_Gf<_#(Y_@+SVBrv!N3gUg?Ns*{F1gV@<^i9JYUP}hQ2VFx$L0E`LMHIfixv8E}6^AsK zWBJO-%U=OlfPy%IlU@u9T)ENrNFIa?2F5GBe+JkRuC#jf?sUJGU?pbo--%y{P>E)+ z$Xj9hqa~Z#M0(0h9G;Y1Vq^AN`Oa8!-16|1#Hm$q<*Mx=0V>4Ow+_M(^KoL?7W|3gztzCgZZZIXpqVO^MQ8ByU2;fIP zzP>!%*tpyz7`AWUwVEjzRBfn={{Fiqcy!?IyJKjBE+OKOmsaI7F`X!R<-liq+eotf zZ1=;FC5}|QZv7xYF7aqFzd{HI1|^C6g((+2ToN3m;WI-l_Efuq)TC z+qbUs37$PDgu(EQu;t^Mp|_&u_Gg9T@DM|@&OQV_oF)XoBB1G2`HY14;u#~+N`|1J zotV82mE`$Ql;UXm>zS+dr5t`dxjHaGH!`_@^(rILiQ(eFVd|Vp9R)svzP%IBA6NkB zye#II?JFoCm@lZ{c-yd0DE)&T_8-RhpD0Q!bW2CQX2QOZXJ+H4;9-y~AuZ(L>!;Yl ztOpJpkR3r3STZTC7Use@25-BK|IG5iyg*l6VkAMFj_BWdj%GsWfr(YJGo^b<}t#D$C0GqEH zkynxIsKlfW8AivXmGT9ialp=IR93KETGo#H7=Fi>bV8|ZJ$mR6EnMGEVvq&5qNWx% zcL^yhGCF}Yox_j8qrf9d#{s?NQM+;Qi#Nukd%)=jI*N;1NAQv=Q20r*6wK(X4iD~=hv`=C{4w>?(c zF2VC+@Q9g_kqG9Qq6?1k-MUt4QXmZP*VNv=c3})c`+iADr|*xsK{!GT{;J2HxehZP zJ(^3<%Q2z3lH?~y4}_80w$D(EP&~wzE#?*yS~ul`hf)qkXkux( z2;35b8evOHHaia>luX18$mC|`9MXL| zF~@?B#Sup|-mh+uipf9>Sz$Qi1d2NKBGtQC`ZtX3G;!RR53})0|p_=5;TG~@g0v@{HnV$h=d*y zWx;3=lr?6^SNCeNumw#(?|>GpzYAw9@pOYpJ1{h4j)8eHG<$hTV}@}s>@LErpb}PL z(P8Y02{o$}Cp+QRy53!5B9~sH8I;um@`-doqn#bM&QuVqYt2nd4W3bK7KsXuDt*rEn*g{P}VSG z1TY5Hiu@{90G)=z1|&Cc*;0?s3ivCsB4YP9`btYc6o=$hiFmQfY=r{e;N;X)5-#TA z@7ay)D-`{4vba-qNDmkgT*<|XlPp-M@u{gk?*|xOb)5fo0X-k`Dd&m2bETm9xvui~KVaK^ z6>$Nq3*T_KNb^aL?w%e3rm*&)mn{5{q}?;Bp{ZF`Rplpm3o!FaRZkZVZ9&xg zDpWM|c|=$|AuX6fvLkC6f()WyZq$nqD>Z~CDqg}eoPvNB z5)&iSw+bWdB=MWQ>M`L8g?US5z{^o$mPsE20>r{-W85#5=L9~iyTdSkF-27s$kczj>fQ7A#l#Z8u zd+K`lo4s`;>>xCh$*ky=AzMu6l;7s7%3hn&h~1pPu`vGp!uu(yP>pQsYh_qvj%c`;1}3A(P_%q^OYG3pWNyDSwvEL5;W^=qs0G-{3>2g+ z%%_wirAJPtg9KoRk%_<4%lj{G#{dc>_kJaSy)KV8(6g8N|T=n6U80@f^@%CI&xB2ROQ)42g)C39ipR`OCQrr#^tA+zJOW%bt|B zoDb^{y;GdlXABf|`BjwopmCb&gXZzDeZo)`$Bskv3Nr#M9U%vUEz=fMnoF`pGy&j z0=iy;@iY=hM#`{ND}sz(Y}+Qxc!feu&$;kT3TMz5v`%ldZtMj5BD)B)mz`r{wI9FW zagUEXAZJ|$6BOZEq>I={U>g?fW4%m9a!ez}ilBLJ5+A~YnHkCM!0|Nxa+o+_9s@)-vud19Ms4{^xv)@&%`l zkB*Ab9vkLPzRe1p(2Z2GT>;s!GGSfzaxy7}M<<8OtkU}EQVVHhYP&i+J%K@`#$1M* zxnap8KH`)3^RP(bmowkidrgcU($`-M1tq|0p|ca+J%UvHpueTV<3Q#rT4PyFoo`*4K2-ve1SU59~c4{KiSYs-vS=f6|nmH4xN;1-;QK$beeRlZ1+b1=)X7i$4|iUU;jR`FQ4BK zMF?&~*F4{1pSvn=qb1g@dmLghl)oQI5ezC+m{{3r01pC_p(BpN*~2{LX?x1%6?*hI z5F+L3^xI-FKs2$1>B7hkL#+yir zQvf;YD5rqhc=r_05s43vI&MSRKv+FKDajW;j6a=5siUr-i(sgq5iAP$$1yn~=|J2K zjQ^J+(*c=)Yq1YfI|~k4Hy}$;j-fg@24*^gf@gv05l1hrujj!}kh=7*nX+qs!a!#3 zK+=g)_e>Ou6FD>i!*yhc5HhL++q+NL#`$cKSWl;MMbp2@~TiH|zLL6MRFyWP7ElY_BT zRgKc03U+_}x(GQuq!ifH)3Pg(8H5AmgOD|VjlmIFuR1A+bvGq2f2w8dHsMn-N2jB_ zBJ8j^vx%rjQOJW#7sFjA01G$+8RJk)bV298=I;-G2@PKJd++O|IGkzE9vZ&spYxV9 zcI~=_cZjqiIg}~o(W67434m5oQiq^54?x?a(=p1XL7WF#0*(!+Z)ixwPnE5lpu91} z;}98~fCOD!3m;1k8=%o3+S4#N1B(U6|3pSdAO0KQ1DvYE=?JjXKRrFAXwxh=3pfkh z2d2?GJdB|yG#g1Y?X|M9QZzFBjnK~RhRnwuS$M-bkc1#LhX4U$J_Khs`E!e}R#Xi0 z2Sy3p4Fd*Jh`;}8Ik}ri-{(vasn-%`Qqt+mxVg9Ejp1084K&(fc6LcBEG9-9dfwkz zslVRPy?fh%+F-wjgltE_#Q@&6NL!cl=aT?Ksz1U9U$SEJSqbIy7`CLr&A5m&8M(RN z#;L_&ZUd)R0VpLRJAkQtLw!h4G#WC8E77jLA) zbpbz{*01#z1vQ%!RAuzL0&m=4j;m#ftKEeck6SA3{|0a=(ML)(i30*;!`=74w55B( zmBdf+fGG;v0j3(e-mFlz6GCl6{l5y(L)2riwZ8`%@nbn48v>Rk0wbJ+wx|~ew4O5B zG-_-egQpDL45D4tZ)3h~L^#KoG|7ArrxC$zEpc1|9k`f7R1Bg(b zets+nl2a6dkT^ha`BI-dFQKsz^oUcYz7Kv363hS^FozCJSyd*E3=fZ^6w1b-v7)h1 z4R6K?Fi}s7c7f0YV8ucK#3aAIxbz=b{#7|DGSU=ZOXeI?+a{+l&4W?Oa6ybCtR``G zs16IMf6bkea2TvmZ0SwhW1z)n-S@*8gIfa@PL+KA9KCey8M*mU#qV-d2|SC69a_Z5 z07GLqnBRgK&4uy0nl*^6A>hETaFUgj+?(>aFIN~0c*n??Ujd9TMO}r2#7vQ4Pe909 zpNeL`{6B>Kd0fx=+y0Ng?EBcVkG)9QvyYvkEG=4;?6PF+Ye{8y zLYs&Rl~j{dwo3KApUmg;zTUsNKDXa>d;c-l4E1_FpO4469LI4UCxZSZ=)gy9{k!Ar z)8ku!?^Aw^I95WbAbwTAr$c~(*Jin=UZb%P96~V|x=Nx82Tc^v*Id$3@K8g2FATo0 z>?#SkrP;Fe72m&$UL9CQ+WTI;f4b2bxnKXdubTo0{lVAb)Ry6EaobWCntAO#TY3W*M!>@%i|!~$Xdw|5m(p0z1KigFQM`C^qm7s`tn1LLvG{QmQujxy+)~$4la%x`Ixvu41jqxf)C3lapR_Ug~rGdPkZ` z8Lj%}u6E)3RiNCXm%PxGEgLg#+&DtyoUrrh&yzpxTnNn$R@m9US(7GriGtEwZpN+# z4n};L?H^XxefFVMqur(3dhsr4j2kF;hQjCn19hGq|9Qk7iim6H6980rERUW(-Nz}P zdxOl;8_^o{#Rv4_fQs|Np9XQr#e^ArphrY#_nn_x%cQf<2%n7*N>_?>w6*WTSi~&Y zgou&O2^dEuENn=};yrcsx(ta33g0|_)Bz9>ImjI;#RS4f3H>mOzPMTSbB zJ%7FzAZco^*0iXR&+4J&5x9mntffL`Nf9B;OWj*3boD=@Nqiy&P}SNwS0QOBzIIa= zDDDvHL?c6vfe{W;?&jr@YK~=+u*bXO{KT0tEXO1Tnp<43}3cqa?cxEi=DX0 zi$rA%{7%;{mo}>5nekH{P^OHq;*tB(CQl5VC*! zno75Z+QZCSH#$Ck_>Z{0r+rY2ZvXmsr&AN`4)NueK5%TEIDYZp)L~Ruh(~oYqn_rM zM@H}X{GsQy6+Yvsb#bF;y+e2>=IQ?SJ(#roXE)SUG2Jk@BsI|OaodGdoNGQGCraaa z)0C#{W9q3WBqu!(P11Xy_pt{w6J-ui-1mx#w>ZTJ-p_L*lO3Yin|X3fJ76U-d=?KC z3K$Bkz zo=zq)3Wml|KR24sd>1kN@+wTiT6OO1B*tREf{BH%fSvT|PpDyqqM|5yr3={e7eiN* zRFx(JSm3oMLNcO|Jx4>{CDhj*Kt@jRn|JT-O`bK_tOaqv_*s`^bYPHGQnP=^yg5<| zU0|~N4*l%p(v3vb>JATUfHup1k~PM?hG`wSJ`km@;6O}!3>Xj^SH&reB>`TvtF>+3X=r@~ zCV;#7ijMQq$?ipUj<9NU@5d0>93e?QYqM`VQ%er%od6XA;rSQU@#BhgwB_79nXmk2 zMibv{oV5e&K3=Vz(QZ77kH5zd<$3^8xuP&C_YmJX+Eo`Vl>S%Y!ylvQz<8o3sI%CQ z{W3I?c~a?zNuAAz0-}^=ghY$#b&0O%6N_?!>Soemny+owByav<&Sx#k1=6sH^t&n$t&)?G zU4F;tRGb@;${;*hMAqFHknN-PyA~AO}c?@a^`%hHl=v@BPlGc$P46+NOjscKp?&+AvX0N7+{2 zh}*$yoXhL(vbJ^3g~|8Zg`vb-3@0IvmU-grze`qPqChVtUd0Hd)>m}7p;UDLefIMs z=so()IroMab7Cg%kn$1uApq&@-!uLB)oSK5j31OO~gr`O=Y ztpK)}MR`CH%-)*Pu~zTs-540YHo_KtdVAk{z`Yv&F0En@9CpN*0?smX_5hokQAO%s zX$9{9!pOH5>WBM~d+#ghzVq_+PzZbLQ%Q?LMfNVxt8_#lOiVu;X1KF7ro)RUD~;PV zm8<2Qt-Bbp?$oxOF{hs9=b(vH+-VT9d~jC#;>)XUU%c1~1NYapbgA&+#rhtGMAlKJ zjZCFf+SlDy(PQ8#YhZa^9s0V+%#6_tgTl95oma6XwYv-E*o*1LLI-YwNO+ySu4pIq z*)ZzR?CrM>Mo*9{2HUjo?Afz|q{&nX_y3s;3*EfAl;-0)wHfKOrnuJ&VO8JOLMy9SE`NA<28#Mk{ z*2dthapJ<(t=m9-Fa0(p@l}r(Jvx9UTMz=~6nsX!z6-#0}$~W7C{Do6kv_PSOZ*oW7Xp2e-T{m@A=x*)`J zeCgvw;o|Er2IxY4k&NG<)D{zq>{Uyp+Q4ROX!NU4hWsZlG5lV6YWI6F76)ZQVIwoy zyt30fzjl%sjUzT#J$%{Tw&Cl7Z2^B}gdwHG`Ou-YMpn%m63(Z$0Tw+gHhu4Q_UZ*= zfNt}|i`9&_j>eB*e^qvJvMU8uAVHfFFb>VWOk)2W!KQoZEnV;blPC%R9i)*EUl>P6 zNR>cXvd@SVdiA2ElPx5u^_MU2BTm%-V_hOf)4YQh7vS9j+r=1`3@Y+>TDLwzU73EK ziMggtn)K}Dhk3Es!i0qM{{?~ot0Y61Px^^F$e04{I3e%Y(W81(r#hsT1_w{k)pbcu zPDZXOGvVNIy?Wh1h9`Io9dzr~p=J?IB+>njs(7@7JfVc*Px~RsI+im83bhh1;r)(} zkP`vCAyAMp^*Gi#Z2kDU-<3@Aes7SKkG1ckp31lMmRa8|0^|V%d|{ zUsfeGHG!jqI^lmff-}e^GlVE5hdd=SJ-fAI8wp}DVU?>0FT(>x#l3%A{YOdwnxq;8u7Z*So#7F}h7)q;|cwS5_PI2G2Z<^a0?VsKKn-RCI zckD>m;!4RN?A(cqMLfD^XQs8B?ceR^J{@9IGl?RqmKf)WVW)(&gYfm zl(By83gk=T@ry=9Vfm$?aLG}QDYK=AingH)!ab`oJv>oj5fYpMmg>7pP0su7tE1?U zmU-{qUvBk+X(9lSXuxEykK_*DzTSj`5@{8IcQmsrg461$Iz&fDn^&Iw4=ADXq&sr> z$v6~>jU_do*y}4S{bLJbyZmAMW0VYJ@EM7{GD#;RI!p=FRAtvLfwq1R)V{t>jTuHKIA_ZTlg7igrB)wSW26YV>h4`{7x zWMWcVtJ7uWceFX1>=;OpYKXt+FT`aW z0+~kJ!?c8&x3SMxpCk+%yl1vW?!(_8tWH*L6W6?O41KBS8>D9-Krj~E62+ZOdE!VJ zN)yp6fV2p1>hAJ6q9yL6@n1I4hoFbZoo&>xe*HVZ<`kpIG#WBeYERu$FCg>A5?1T@ z>OJxpjz3=e364WM-ua_Vd%qg5ssDqL+ze&?fX4l&`_u8`e4Y*Wj%=Cm8B`|6_674T z-mmB27M=B|mFu)|lrjf8nM^FU^{d=49}k51(05oqUCZb=H*%v2;}HkA0#Z>R7QKs@ zaoKyfZDR|KztYI5Ebo7{QH$*S|M02*fi*hZ%F4_tc;HI+nBt+C5PR z3%9@ciBl*}Ajid@4-!fyJ!tOf)=xLP2bPwjWkEgvRu+gLL+RU^4r&i_fwgO;U!rCP z;~6j~ep>tg02F6slhTz0DY4Nb+^+ig$IR2?yHYYjjKr`RgC%G7eab=47vmH-%I5oE zg4MOlcFcia@~DQuTS9P^Z%71;iI)-0U+BiMVXe++hR>KQq$g{)qBO0lX*KERX8lG2 zfdajcActD3KDo1Fmo8J3+w`QlhU>@bzyXN@^;;=jMm+^5U_GcspCTFjq0|+}B?X`3 zqWO&X|AU%M9Un@gxS0ECe*8wtL4f-2=m;YdzYg$6enV*q<_TUsNSs_z0Wt_P*>b#9 z?37=mt%#lLq^?z}26NxQ5aO{lbFdeYPiSiT@^4$%2pMpvH6RS19EzGArl|`;Po}Nj zJy=Uwvw@8f1Hb1|DT|dg9X2Ue`(WYIML)V8$y@y5%8HiMQ~SuR+*o#mOntX)Gc~K2 zd9vZ?n;AqKCH!@d6%G)r`fxV2y(C4JoV3P%ZsKvNB~>m)R5X#-M%%E~EI|e0g|?lv{Szkq>WHLCYj-zMMTSa>pi5qORU?Du`))(OwXhqt>D;X z7)aJ>SzJv7uM=F1HD8o+-f0&IivrkD=1qmBqu2-bkm(>IwxHmm5v6q$4ju~-;rAr; zFfh5BZfzprK|n@y27o~sA(fq)n<7MLTrNTcOBaaU1!fwxBQ!}UvLq&C{>}Cbp~&Qx zY!sRndhxteB!C;w91< z+^d-XfgJD2FAY0^IyVXKKoy5RN5`5U<+>SI?`$c_I!V-2d;XMED-|54P^-Apc$-nO z+Qs}8ssvs9NH7n?j{F&_qF$c2FJE>A3ID(y@EYBo=5F2J?!BfAH7x1p46mKx2F|i^ z#|3+{k+tAnA`XI25aSXG6KAE7w`*&5@EsN>`Dvb*u?9jyVNXO5hb=?^XaeLaj{os# z%CR+UuMw_8EZsrwhTT}mC8J89r)ofomRk$B{A*;FjZqDM`@JzDAA!=_jQfpI>PeI! z0`-gE1ByBX!CLe~XQs@mtxS(5qQu2~))+EG6dv{&9@VHw5Yu6X@RpMN^#c8W&e#ibv8?i|v81Z* zSkg!01S^+*nv0L#SpUBf2)o6<5Qyf-kR-K&ly%)+i}rbAgTpn!Vh=z;;H%kTsILt)sbFV>*>b~5VM|+YNTed%V)o1>Q#F0u}*0e-dxEC*#1`5H~ zz-z;2jGL8Y(E9mvz3Aux78H^2C#GE@0z4@osGIlO{`pG~v1ZYF8iA2b>u<}8Z$~^5 zq>76d8tSM0Q?1YgmLnE@WQPB#ZF?%K`G!arO4E_cnoKE8J@-JX!shl-$8wlqvD#4F zq0tidg-9j?fg~TEl6eLh$QL{gU7c{~aK41Yh9V83&zVNF14A3tq@zN{{fPsjFx|0Z zhs@C`4xc>Pf^hTusPziWg#;4<5>Q#YbzRWMG0OWd>PR$&K1E{ZfP=s7kJ4!}984Ih zqmThKKsPCbfiTe#*Ht)Isvn@~5Td5})auF~WJ@vgLAV1BQ3oz=;Pg=Co-g<5#W9K7JqCfD*jLiWT|BR)Jamwh_;Rukhp^pPmq% zn33{+U9$y*+a$pYi}_lZz{$tq2Qs#lb}ZN!Lz9s$y58h26r z9Vt5w_&00WQs8s&!rfea264%l6PI^KA5n@y>svAv%TEp&-rY#>zCA2&@ydQkd0V;l zTdfPA)VViXpbp!j*-+gFlXG zZ44O?ys7zT1Kl>5m~dn!iw8UIQ{eaqGE<&CyF=x!5J{L=NWFHO)fFZM-s}Ca-zm=z z0zposVeCI2S0Fa0?81$rjzTOQxJH}WXeP&Z$FZUBp>YJ_BB1*JHlHTi*&*>*I&FvnyLg|FU=={3$!?zAB&`R-CgW0v~(%L-ic zNi)n4?uA&5oBWZedtU7a z+1*96%X5_Iix>Mo{`rPI9WS=;(BXiG>4YU4sB4j0MXr3rhiCm&h`C=za)wY55H4Dk z3tPkn&Q1xb8Kqswwj8Z9Hq9I66z9Bu-;lcOQX^Rw)f%m+kbB^!GEXgA{kY;3MDyL& zJ^=cZRZff`++k`)#nS&F`fyh_VSd&gZX=u9K*|oO`kC@{T#C74J;90;|3IbZ`7Z#p-L(D z)&$?yo{~`&y)3Q`PD0(JH{+yc_8*k?>Z4cq(?vTe$EB@iT9qp)?r&hQUWN1PTJCn6 zK=dK19e&x~G^+Kg?pAxWyAVryFIUJeTuf^X%0E^7(9&XSjQ*9J^N)h&xi$_SR(Qa? zUPMws5scClT3ej>mVQ)IRh7p$FKulvVW_0Q^bC7DDs5I9s$YZbL5Qt}4+9DQ=NW&J>Rgpj5Qq zjzE%Y2X+UM;w`^eb{m^aiS6_&@@F8Mp7?uQ)ybyKp=;eRIh!UG`y+!hMx(5f&%pvv zTbNgZZi?9e(@?yI*CIuw61i#zFg4v=G&7IIX>i23zI_!`S+`9E;sWF3!Na!X4}5! zG#?$ksSgKZKtyy4DU+!nK9Mu(1Z0kUUs#y2a!&$-#NrzRv2LHSyCJYWjC9b8DkFp) zpWmfZsXNnK!E&jP;ddU)YpYJBmBC-`zv#>O~H?`gS*3^Nyf4Z%Yy5jh8!_mew^#Oq~=G3=tO`AWvmZ9&#?+25$V2U3_+yd(noXF z>jr#@g)Ml8?nrP>uN6$I3WkGxNq^3qdYt@!bj*pJ2d~NADiP#w`yrBE+cyf`YcN2@7Jp6B>U*(2H zr{)j6W64tdcvL`B8Qr~BJ2fk<_J+r4D$hyS+)XUj*-A@)JcMn5Ehr`tVmuV@074UU zC9U`%(%Xn|Chy2u{g;P%!e<~j$y+!){aZ&f*R4Y4{ukfhD}KnpH<0N0v!iFs^Pj+U zBo9<<$YqgkuOp80d{;Y;T~##UgHAAYw#S;}k*mTzzMb#MJGIXx%85`MiJiFOkP{y? z|J>mJXaU|YxKKW@8g|B@XytWEE}>MC+qG}6g^0Alkc>l|xsN5pn7R{rtJVhw&?(3f z=}Cx*2Sh8YM6aa$#Cy$_IE`9vKIC71=Uca_3Cq5H>pNh;fM5G5c|xMitcHeQAd{FV zDp9Nkd-WPRV#GNaodNErbj@IvxpnKzXuH#B_*Q}yI~U6IGh0a+9BKzqqpWYD-;~qV76m#V^`=^RA|4;AUaHa?7 z4LhWzrm`xvMX2eOy^v6kol9v#u5UQvadly|tx~5>abF5}R()t^aewn=>Tcua&C0tb zK08Nr4EZ(zZ7P)y1P_ss!R*+)TV!Ro(^t0n%C)5I^oJWg;pixR-(_})kKeQfQI#I` z9kbn(IAV9n*q#qf+MXF2?C6kPY-emhXxBaeT{bB1?`q1$)3}~-n6rHZH*AX)E86N8 zH@cIRRWsn46Os)!%>74vx<%_?ILi8r)isHa9`)$vG7W&V!;W!0WhTYrAPH!sKA;-O z`Iy$pd}_odpp|wcMR77|(5O)gEKBFKIc8=$1bby7`q1IS{b?Os)XzYw@kIkT5)961 z0f4`DSq<>Y8d`4@m>(#l!>!7fqb5xy%@kq)12~n$Ln(lnH=hq-uP%R-W-1PtotQm~ z3%zX38bA@Ib9>RZXTXhDlLBO1j4Bj(aRM5#p2Xeb6YR!|w=yjC^l8)fvFt+|iFRL@ z5Nmb?@(qq4Ejf1lxGVi!*KyYFb?epBhIpfHSw%Qah1l*q!8Yn~I3@tTASdgKx#|As z0o{0-zyvP11x=+KTaz);bo!23|4!y$`NMD#>62jdGxde6TaTs8VTO7-b?LGxo!o{f zSw&@!h7uoc6_n2Fchf~>9T1>L;WYQwmWEy-sBoidEi5;FS^ZOM6S-vO5PLA8k8`(7 z0q|PS?nc4Im|!7mj9v#%k4$A_dTChGN2mh-ug=1(|EK}GO9#6B0x9-09^3Vg$uwF3 zt%rx%#qSRP@n=o-YPbKWD4efu{*gw973;OowqJX#+|!fcsd1&j~?p~F>{P>}7&Z=kC zPoBEq)q(d;=SFC*-ZPec0rxKaoYnX-XBFeE?%NB!Tip&B)N2ftC~3)Wexa4g%CMDc zza~4j?KAFT-XdlWO5n~-7UFt3WX%N*!6GnCg*_zKQot{)FZQ8xb(ris_u`d*ffAkf zJHk9Wp0t1UFC1cG=wlfw5U)ycJ~TC5T$UTRWax-5tH2?kHTHn>Nsa+4cAv3K7NTuu zLSP7L4Y5|^l)v*!JP-8LG=zE334%atCmF8dLf=PJMU_can_quSQTe}yEJkTNHEG+& z@#I0iw2*W4CSLud&XE7MRfk6Q=+*15W-CpZSOZbIu zv^ra1)*jfx^``le=?)l_zCrRMs{vqa2W?x>@Qg}$_A-WQm8l^t~O*_0fEan0B2<@ZH<`t&;l*A0kN1Px#~zaw@%c;5uIQOE@-0=3^9<5?m!);v|Clgm`$VJ9B&8J-h;}MyvhzChuqS>LaU3Meq?3Zga zFe=PRK4eG*7eyB?mq>k`Kg*<|P;hj`J;sge3X%yOd-!FeRdQ-_5|iEcP3oLj+OR(p z6dLX_h6|jLL&CpLRV@3x_qR%z2RB7Wkb8}QSqu~v0`M%3*2*VLs!f)kcz zc-z5S)lo39HIcl4%J{K=phkaD%aU8eZdX1Es^Wo9rdtyc8wk8(=o{_(XeIfW3VWI= zrj)~HO&wAMXtR%2<9snj49jQ>8&ME1DPV{~%p!yzR1D_mncucCooPPLpu*K*p_E7d zFvy2*PoAIMMcgI@JV8D)WpDFcSU7gbc!+wBPle+Q{#3ozGe&_#Q;DLTrr&Uxw(qe1 zeGy3s97tSTkNX~2CFM=H{wd%gu}x#RhT`RYc-LLEOG~nHtfOjUT_$9COjWiH-mEuu z-QwAKHXSFc9?!cNYP#mnW^KLi|9N1v;ohfvpS~D>-ZyKLtB7T*g|sC>y=^RWtW! zpu1C#{7`G+(`G{j>>E>xb3D@m=S*9XdD&29;tH!*>VcQn%ri4nD@lC(c=Pec>IOq~ z?J>eI9KFWq^}@9jT})J%2i+{I$uazWefZ^x=R6wNdMFpX)C)EqfXesrj6t^^0H=#Q zjAB4^@B7nlAZL@wcXAso436ywz?Sg4j{yi)&(w;up$m_D`qZRu^ZfVk)kfN=Ao71x zR5Syrow{)d!d!FHtD6f9n6Q}13QNWV81QVXq%;*bHdaf@<~+!%ln_%5*~vxp<9>0s z_R>45T%ZM5vSP(~jRFyPuzD?d>5d@1%6zN-DU+GLEjsAN`}ZThd7Qg)@#3>U1&ac` zkW~QpB+QyKzs?x-S6kz5hCyGbnT-9|y~qPavstLInU6y&oje--qFwRk#*uqk2~O#( zb>>P|b!^~v8#4-l_^}IP)S4QqX&WRmp)+UiNQ#Y(oJuap5S*socrO3}wwP%Gycn05 zmhE9k}Z|P_K!@OJ#yIL+Y zbF6xqk+G5S0-u0;=nikI`FBA%MVM1&!V2{Pi0lK(6$JovE*OG;GGOB+Hm9;@(cbTp zF_{!ZJfFvqbhVC@AH*9#S8x>5f_uR;v0D2P`l%SQbC=J;=ag^4_H_g)O?Vb+&$k`rc zyhwH45xpa8IYc=eyjiy)azdoFd_9~1{U~qa8-(W8c!nr4FQAdb-KqR;qwb%c{854c zJqDU>p_*qpZx&?3hf1Mw&y|@sBFY|!)lMfyYnXB&__;$sUA9b9^I2*0h^V+S<(#;m z+klGZZB5W|{ruf1b#nDZG)txtmLAC(G~)@dJzUYd6!k~S2N{nYF^suqqQ6f-yG&$y z3VbX$>(g)*QuA=asHAXg+JgRMH}ojvWZ#3P{Mi)K{2K3P@#DSDPBWg9ROp}lJZ!$Y z^_RjgXAkt$Hc-L6OPnxc(Ab&2XEm5fC|v9)NB;w30p7PW17!`COAH z{{?cj`|<<`)7HFI=If?$vzkr>Gvl|Q9>6@~Vyn|OW&2xAb_5|3uMW=)TM8_h%?>g& zE;v1aC_QZDGoR$uQ?(oFDSf%oALoeFu=!O(jB8KX`JEUYt*mW*qj68{b=MwCK&Rtw zoKqHd+USdFdiG`Oj%t>^VQNI~1y*_OkoMnUooUUAqZ&JzP}FxkRs%fxo}`|RDH~=Gsw7? z@N;hVNgbg{hYz=4Vnf{Ir12s+i0q9)g@7x?z@3mqi5%RjiLpABD}v*P`yDN;O;3)W zDKwiyE2HB}b?WkiS>b5*ekd{+gv+xa(g>G3KCBrVH}O3XCdSgFUKoOb1VXMNY^3+6jJ#AIEjGf|Q zFCfcBQF}CF9S(D}ZIqNgpFPlLT@bpXuAWo&iscE&wCuet{q$*j za*XS#rI+uiXuB$pb3Y#ub4!i6OOJlm$^{#?_b*@1zvh3{ZbljRAZ|h*c=P{P_C+li zlx)6>f5yjTpyp_gUCP?YR|YVP%_s^7-K1diZ!OgsJmuaNK2}%QRB$1TJW+OOnYL?%icw;rm^Q-Jc1`r{9i zz6mNW z7num20eMDH4E_yd{~+>m-=vi*(}LPbT}N~2;c0)m zP<2CF-<7T=G6RKIT|`6-VlE)CR$aR$vNuJ9KvWwIo!<3hRA8ZLdUp20f<2M=_~J_G z!~L0<^dMN|n6SRg;VJ~80YvX!&=JeKPgqGAoS)s5sS9d+EDwF+^Ji7AaBVkG+x2Yz zBftz1amikQsO?8kCL4HMhECkX;5fk$yVK^B3(_SkrSR}&0P`Me zuZ?zLmSNmnnO3=q374@`&LVn{nv0?ft^;W0ci~Jtv5YMIgf>^uXqmP1+kA_eDU>3|7%2Zzm{w0_koZ}QtkpiVm_2J&9aJ=WT2u_LkaJZ80L-@djTJ2tjA3w`+VrK#yPrnq^yt*OdnH4>kSuS*#d`TFv> z4?|==?o85$&E909E~uXmu@&N3>~!mzxTZhP;Ddw&*}+Fi&C-WO_-S*kuIE7iPnuW(jN~j+4(ryrU`xe)I8UnQFOS=N?7+>IGmH&V zEhEat1A1M{vOa*}r&v7St}ImN$|O8iXSxxwjz#A6>!VI?VX=xShJz^C#CSuv%O5{B zo27Qk>$oz)431tWPl}i6@~P9N?@35czou1rrMS3wzmt>NmkQ!NR@x^11r!wefrjxX zGtw8@gCvmaA?7d6sp{Ay;fbx0vd`XtrYZKvmTMPn+W-*61)+!2)H= zh}^!~$>n`Vj^xdDAVfD(iuf9kR%kG%iYJ$~J*S0G>fHG)p3c9IcI9t4!2s0Jd~4+t zJHkjbrij-80_R&Ei-;J`ZC}K5QP7hVJub7Qv?XluM5)A&ku*2pVx^!7@EBWyCo>*j z260Y~j&FE`@i%0<7x;$$*Jz%)==R&TodOpToY&Dk-PLG8f|qhXSV>JQI8Jrwg_Mn6 z)E@u0;^A5^!KrHrqH=^$lcPS}YsQpQ+xRksz+!XEc!??>B?dUm!vfia= z{pXrBm~8BNwsM&07dwz`TVuANB=3rfhD;)aQ0d2;B~F~|{l=kYQU?b%hp@hQA@O;z)n^H|44KVzV?}{et0t4hZ1lJ317L z+Z-;Vk6W(XSYQ-cqob?EM8N~(9`4cCpjY8GYU|HX9=A58U09zVeTW0va ze>vwUzV~Hf-S1;IH|7iDedjSm3rOxE)wVrJUx;Q)gGt4~ZG+*Kb)j&Ni{GeyR zAS9i93A#*tYQP2D#_$nhCv_ z*#5SG0xMzaB9D!K^AF;4>Aq#hm%H;5;%*X7U)@Xw|XfbUnRiZUa3(*EihitXklE?)R^V$*{~mw<-p1{FD~u^T=09HC!v^=;BslI?rcCqa?WB74O>E(0YzAZg_KxJH>W&ej$;!GV5sQ0sspnOR%Xtx)vkU!WKuc(CiUq`*puDcZn@srUh zDJlBFX+-&b^c%>UG`VS5A@ny&7;wxB+?0$VU?q(gJ=SQfF%pX%m9-6q@5pf;8T4hB z--=BB?&-~~&#sv1oOnM1#!o~>N|~K_1HVO>IfKZO@{G+w>BZxKw0P&t%Hb;fgwIfiAE}?9gfhIoL%v>x5;(7b^V|}E}<``iq#a-Rgpzoy0Hu8jj+Z(%E@0ekzihA3O`14YB@!m5Y?;9NyVTs%Ip&d5t#)2srP! z9c^A`sVNvy#LZvF>Tx7}Dwat@AlBitH@~;d+;v&SbNJXxju1q2W_qCyfXleeD z>f599>ORs_C8x~#QadffD{?)&N#mYJ0oQW|q_sWF1}+LPDiFfT<+Yh(SaT5ipv1Z} zxJY_fS32G|{$2~LlVgsY&411_$9_#6>6*nryWe-e&rkH824xUfafYi=hAOIp7AxW8 zzVM8Oi4$B1l%no9ZClxonyAk9!c(n8BTdDQ8e@Ec-*i{Q`yv)_XqC5MALj=2$mo=< zZO5UvW)4c3U~cW9qe+KV&;Llfur`R|?jrTT2`a~JpbnR!pUvl_X~;=*_qrTDYv<@> z-GS+p1W4C}o&9gAEweth;GA9f=a!R=uj}B2mfmC}5KUEX(@oux`*oV8&jWEir9b?u zyC46+{|u)ZU;p(_mUEpAuiNb0*`#sffUh>c%0z3QVSQ(xcoSV)T{2}2-Q;DAdrm%; zmGDGx5=I+ppTn6p@`IF(3XiCp(>UafZ(lJCeSy`RrY2~CCO1a#v{}s@+>jdm3Pak~ zWi9`Y7NF0t&MnZoMpYIDr_EpX^8=mIa2dPOmXZTogMtUM9sJghN7-;<+>Z9(M0B-3 zE%%wgT!!iZEstKb?M^nU&P0w{N7k33uLFtr16U^qGatG%wf^_X9%%DaSZ~bhR+5|B2f~SS<}6G%SEP);RljLF3O&pgla7`sY^_ zN~Y!!W{Gsx_O1SUI=<>4qr*d(Xp#96NCc=2%D{cB;Qd5D@)k0Io4WyQ6{A*0QEMuT z261?1SX++)niCoyB{8T?{X2BVbQZps=M$bVaTlUB>U_Ys0g;U?xo8^Pl|0! zJ=p<+R2iy9Eo40ybsIDx5O;i~JUAq^O}7{|E=MQ?5K~un?gjw$06Y#`lc8i!>vHR{ zRT$;zeN14D)k0cu@DrQ$$g2v)|_2I?8r$^Vs zs9%V>2ggzIExMK^4zmKcfVbYKcIt-*j??nv18iI3bFkq3h;Xw3NYbhPPCi9`^vp7% zou@8Q)`i~Y+RZl`9KIeYu&_Q>Q=zkPY06|!Z}k$5p+oKc;@$lHEdray6S7y4bM_>t zl~ZPKWJpO+88}&SSJw$;NTnP2oKP}^Hyoa#Qp0ODw%_*ieg(~QHo7h=6o_dGaq=g8 zPYE>!NRFYT@GuTWG{&&;2V`Qb_~3V6A@wNm)0&I`37#)t{X98VY=2U9+W&&$!{6e` zvuB5K5~-)@F_Jq9oJO8g9yO|?hmO(OYm?%_$++B9@k&0qg>TOP+j0}Rj;K+&Z+mW2 z0o8T3^ySaU7(2sT`@p8~<`I>FJuI}8PiVd9H)x<`0B|WQZ3H%tSS{upT4$1EnJAg7 zfd96~LTKuj80WFhWf*l5YLJU)F?~L0-y=blQThoWPbIo4$*%#pIX=?+0lL9XuxOeb zXd}DEKx9{Dg!cn$xX*v(>lTGu{x$!Gh>KIr^@m$%1Jg~2o-#tZ8tulyJJ{nWe zld5($d=)nT4^V|Wuw$PcX7trI*b=$5xHG7`%J}iOALjvN{XBoVi5M1iU#l?3ID8I)ch?R9D)*N^6(L*1?52~endAp z@u9x^&ws76tl7{1u5Hl5O)w??<=M_(4UMkT)k^=r=_O16aQBaTdFRtCW!>r)C1=8; z?4f{`7NZ(q@i0#tfh)DGYsPKdqt0zbFH@-648%d|jWpK|6IpT?VRT(0FmJ?)+GQ?? z1VyR}^G9Z7p7L1=D!x8y7lwv#6Lff93HKS(bnGa1mAwRxl677RuyS8CS!CjOxw#L3 z<~_drgO=49h5tkGt81|c6$uU}^(LvH6%*4P4hi9pCSwoq7u1cI$AW6>_nCc*;)hRj zpYq#T>prtT*SD2)Q&1AbV9N;Y04Jmatc=sQl7h5E|9O;tt`0QSM7*x(xLmBi%Lmu4 zY!vWyU`(BQ4H;Y2-Ml%x>?MJ*6KVjUFNw+2x$u)nJ$e8zJYG8$GXN4OL)pu4$fFDO zio`BlRYo|Nyne(JIEEaEOmPM{mGm|Q&p}!x#dcuzRctHd?TQ&NYF04w#`X+OQmZWE zej*L|i#~!(-b`svKgx|W3=hR`MQQqk0S)r7!SJr5f4<{WCM|~#n948`2x#3N8X9hZ z3UpSExBF$(to@OOT?eUg42m$M}^4teR_-+){f1%;wuBu&Yu6zW=l?q8cr+HFktf|rXFnkgw> zDs0yx5qMR;{uQl#0+zhX&p$tBu{BSz6TqR=20UZL0K^F=<6wc|##jZWS*je~a_Qa2 z`|sj)ORahB{_)8e7XzF~<#>$qjxfvyqZ6?mTQM%wxS7wDoe^fCHoq-ezWiL&pi^NJ z;I%@HgHvu8J-&C(FXQ0_ZP(A6TTgcH@?t!L<@I*^Riz0DW3-@BGBJmex?tYg3_fgc zhwUHMBz)E#Url5=3W^C*urpw+Wnop{6can^dOok`VkWB9@{5Hyg2UbY&TeTQrbP$= z-+y+4Mowm@U>g0(O*z)P{NfKm7b_U4i^W;-adC@|gJB*Uq9l20S5w}70py0kD}dno zPHGFV7qwVh#Z!;3dZ%;REVQBOwh>mN6QY#Ioi`x`H!ymUsy&w{hO(f3n8TgTJojihr`k<{NDfSW#56yivF=poa!Z5$0T& z11NLOB&~$fQ>DC&pW_h2x1~{7ih=;$t_I_-j12{s=PtcOMI;)fW zPPO+NVoK%fL!CwH5+cX8`ilu70U-ylBx0<3ep~{>k&FoBym>Pb@B-Cz10P^Q@~!!b zo2((5-96lg#5FxZu0ZmpLH5*q>(sbRi3j6 z!-z86ZBtorULmrHjvWKWW~%=DQ-()6uYPNt_5Wn2eg^AKJ=D!>vjLUV%)>5RSorbI zPWijmbHOR{W>11+?|*u)-RwsLHAyIT*HNniI*a`*){P{81pBjXY^5+(?LO>%IRbTYNEe^?}ZB&e%zw3 zw9H&PE5$Mb^Sdh#%T5!w*WLQko|alv13)C5UwJBzYcjbp()+yxYBi6hJ)uw<=zM!h zfQ=;Ij9izMOSS-qnQ?4zh3O_%eb1aVs{+%5?Zpx4=n|Kag8DDKeS!j*|AQV77HUp1 zuQnNMgCM^uD{3@^$P$nO;L)T2{oV{lg@#n|-SO_w0i^{b?8C&Fl~ZPR_GzkHI`q3F zZ}wL7894AaWPRXg_xKlz?FIf`{D$}wj=;bHhH8Aj21;8J5;1`SO@&SoZ*I&>8!UpB zNo~MdCo+pSOuN9(Mg9N{G{o z3gTsQ;P!3XJw-~5z6>0FY4w)8omkVLS9^-p5RCV4g0+xlA&PT%T~*Q6)u7`A{$xmu z6KitA7PkW$e>8>eJi!Tj+Zf9rz$bd46lUldF43g8XRDcsnP(Ok0|12jrLV?{C%F`0 zg1SSUG^4)(bQegB`RgTEL&-=ljO{xV6O<09KBuzS4`6K*RzpNTGR}RI6gFN7{6^_*d1VK41z%R>IRif9^?Dd>MZOPNsl4 z;#Q9la93xoDU^spo+?lUEytD?CogYeh0%3qWK0Bq3wmmP(R;qR@xXhGspatCVxgw9})w4dw3tizJoYKU>kTfu(#f`rir#d`!;mx>S zl&&2|u04_5U<||g@JvvCBpwaS+}d>OHk)#yw7h&NWg=LIp|vRL*r6c9(@`{G|0`=f zQQstwbiBo^hW2d3)~&{0^<7W(jj&7;c%H7vXjL`$PF8=N{1|-xBzCTdv)Nm@pV8RM zj9>FBkVEH-!&>Lg2<8%DjI?LXq7`XFfD#txG9d|oqKp+Qo^xi#ZxTY+5#voz8 zz{;EZI4n{RydLX2>eLzwMEDiNS`c+#h%B3$iu}esH}^>m+aK;~Xw=f^EsU&KC_-X$ z2E?40m^EfwKY)MZ+xLq2lsHg@r4AScA{%H zC$$Yc-dNFHvpy-PxrT!M(Bhsk2*fKN zg~R-~z6dan*%$!|{QdW1x|ZOmg;GDE1UIai@)9JI=E9)vH;$bLQtYzw^8G)_a@D*+ z&v_FDZ(WoNtn{hxp>qPbjvmh^@Zw?qmJqgvn_r&h)~zd1YjN({)vFEl%&s`JvO#kowjsPnft0y_IuVCE=-yAcy>o}p zhud}nG;vc^b$5A zH4#k4AXMb>G=?B&wZ$P0107Ja@)8 zSZaEyu1F(G0hB;ljje8I&|%So2r0)34p~k)Y0@OFpLlR62-)@S5O*l=qYWnYKh&xW zS14EX$NaMEKpcRR7Ld?P4fb1Q0$56-`_5#{kYU3@3c@#D+5jN?;nmGbLoZi;aa z=|3*SHK(qViyL|l{s1{lEvJtTdad9mqe8eNO!U8G>VXT@NYAWciOJZ;3mW_8B9->P zGCM9RG$cf{n#lVs-kW48+icu8zQC%NgX*TC@c^L>+O~Bwi1xiKwyMll6X%_W+NJAh zq-Qr;jLH<+4pB_cp+jA%9|Vm8*%S_fI(W|WodCLmMNkKx=aw18XQQeF^eCnFEzeke zK_4{|WyLuM9dC3h%pbgArfH7Z6`v0ehcRr-2^Y(@$21l%udeAr1H2fM9MRQSO}1u^ z>@~};i0GbtEIP|rT9?^0Jjj+>!hDEyimbGoG~23e+d2N>E>mo6Z6n*BeotMsea(Q9 zsyRkOt8-?oQ`Dx%Z=|6;voWWc@p3vj+2evpX~dr|CUR5tg40m_4q5)VBX^hun1oPQ z26e?st(9!b5&RG>YveDM$z%39*{dTeBE(s1OSDE)@AC7(9(J)WPkhl7u;8@Z!^ z;VOnREe>^84Mbo9VRad7PW~dn)HG`QrR2{wJ`@MBCY4XFLeS|m)K+Gg#-a& zW%;oyZ?Ypd?W1tEQ0xSiMEPn|Gca-?BHz0#+#*NFreGi;j}7fCIxz%_Ut2rjW69j8 zM0bJ7Fw=H`zA}Dw1+c4!NJ@qW6Xb>MW`Tuh>lOnZkYQNu#lFn5sXNH#a8sQIFS379 zZ>ZkqKf?AGmF(WQe*Gfujz^e@P5HdBAH!c%w>=A=b&8j#Znuras(3rNqdZ(DdF`KP_QlC?pYJ~f=^sM*QsMi z_g5Rul4h2-+i4dx`J7!;L3b-N$9H`*br|-RRVW9$j68&-YYv16nx$qFp|1sarwpZo zeRgs26i9*4=9eMaIw0;?ik+`ewZH#9lee$le>dnN_2{HCNjM86P-n=@ESUj3uvP2U zcV$qO~r{aF>zm?IpLqiS(FJj<>XEBauz0kmot`QBhHx zN8vyOr#bI^tiar}LYMgg@~1Yv@B<6%87=bPC^HC6V}m81C_ut}V5#pOZBO z*2WJ8K~6WoAo%Qk(B*kMjg39aYB+(&C!Qf|K-n6Po4)(%tSdbjnH1OF-vikf;z;Y- zmto8W?-8|ce03Obs;BqYNzrygtKDYRnjdWZ1IuYTOXE}Ze~=zA$_1yxIMr0L8(F@^q%|C(EO-xDaH~?gL+E6w8R4NgohhjE zJ7*e0u;U=n->$ZL+p$e!b&{_XMh2`$rtK!WVaz$0;1KujU##czO~C-lNLU6lP)xH2 zZtFgD+#VFM5>7AS@GTqa0VaSA789b#k>d*dpf>BB@^PWQ%2xXd&8ej?~CFh%1b&eB4}c|7_JNJ*H}IZ9DGE0CR8+OjKJ^DN~pRm|W^u z(ta+tZte8H)X{fkx4^3WDgvL_opK_VE?F`eB7Do_x&Rf%J4PiXMV!0+`!oyk#F+9<;|?AlmF|Jg z&Y?|t`Qo(CC94_AK>!kIR(=8KqQd&n!sH3Dy|1lj*5Vl@#m3biVkVvKu1S}I{IOmS z9KHY{0BCD2?A#KTq=JYWklTooR#nBT0Lx6?ZclJ+<_JcH~V8b9p@170|77@o36i`Vh&1rl|x+{3@ z@s&bRQ1yhbO!|v%YcNu_jp}VkJ>s#?S){9Ke1{YE;dP`2xG&0rg2#RMMJte>H&seJ z7lp9^RS1V)T%JTy_+Oge_uOHbi4eS)xQiZR7RaI%z|ISP#xaj5KDTtA0ES5`hs``X zSp44Ve1d%XU_R{r{reslI|3HT1Rh*3(xM9*0k?zlnDResS6hP|dgYSpY;N1L=AH&)n`an%&toD-TAcxw?zid1Qk~RdXWE)lM0I`ld zOV#+(I12Uz_#Wk*h!w{ai2Dvu8Id)#tamwLJi_xXI_q*MaNwn&T<_z@n;BQXl#;=z-F>hU90HKu3&*!;m~ zW)HkIR`E53vmqsn>3LagPLfr>67#410-gVl7Qkc~a5RuaD>_pw=bT9tZDM@=s^?-o zM)q7zuog9KaUrHG+{b5Y&sldqyvV2^YU*RBfgwmmh!=2dJeelUAg&*N&yAXm+GSrOc z&Ycb#Ck8bsDQ-|3I8n()2oiwBR$q}@5rW%7-BF66f_OWjwxT6fUkvCsDIQ_xeY(*K z!g%S|uLC`%p;t)wyG%HXe=$FE3oa29mZBmMHVB5Zu)gAg<>-ISx^dCeGq=K!^Xn+z zguTm~5DFo*kqtI{I*h-WL>JY9Pr$~Tbj_mMz)lDL)xY6)vP>DG6$BZ5SiSexf8^Vy zE1)_B*#qEf&G$i3>fuzyhnE_Y{A9sllM~H0y{gF*i7q2jbnfH7DAnw`r-a(Oc5AL)a5q!55v1@{=~Ly)0WS!tX|J*;TQnJ)7)?hBTE|hi$UaosN1v3;`JMvH;9n-hD|PXLw>J>w z5tT0EB8JoGAqp7iScAZ@mlP7h$N_#Z?JH7!qo%<|NhQsk-g~Ky_X6)8UcmGu(gvWU zC977kF}6Mf0}tu;G2HV}ZD@-8Kp0}Z&)xN)x7-JMbNe*7@K@JmKcOcO0>!<3D0Pz2 zsJ$!=b>W(!4u6E~Vbu0dJt$Ii-Ylomr|$<^RMn_PIPll5N&32$fIn2#I)Pi9?mt($ z_R#P>KNxClW~Y`0REOY6i5nC2@QqL+xEbBcb#J~@KW!s$k$U+eC@xSK(YpJ;vZV!4xss72~tLCtW=zP;}G77+LRPoGZ z!GSa7o}SW&D)J?0Ra@qdU?ZsDw!Ga??MOLTy|go7z!k5~(-s z{U*lJMaA2N#emp&d_!O>`v=yoyI|va@?;{Qx5v$zceMxW$S($F^#4J&S*7yvC^o2Q zeWz+^A$dtap@FdR(vz!cmRln49-B3Dru#SKi53sr4jVbLZ|~l_QS*6r(F<1==5Y=g zCDdlY5n3&{hRw<2R*vS`S72s>)Ne8d5tM&aI&%uH&Ny@vg$gxBJylEJ<8-v(sx;pK z2j>j;GMymU&kgeI2gAlhd{IdnytGf=6?$OzLhob8JR-Bdxiso;dbJFkqbT=0+!!_lnTDz%!ZUhS%HJ9%_CJRilvm^3s{DzV#y)VORh zgJB~N6RfLm6$LCaKMT;0>r1o3n#8V(R#! zIe%r4KutJfiZ%KAmNT|&GyZ(C z|JulYMOAvQo6gDl_I6VImRiY$Chu!5Ex^wN#h-4cH6Cq@&ESIz>$&ygrF;a~zMV4kFDWzd(k)%?HP?8W*6iEnWOBBPDtx|m- zuQB)c{(gV=+~;@B@BHQ*f6Po>uIqEXm)GmLz2vzFlR-z197j@tmE@&Hj5w9!MZyy* z(WGe|WdjRxIdoB0)6iT0)bKp|MuJTx*U2W$y+27P9oirCokfOd( z@wa^|no0L4W@ml%6FbJNp5H`pR=yD!;wddIkmV6KFu~M-?fk#254f&R7pyN~#uh{= z*2-kB>LoFA%h|?w$Eae@tgF$3#GhUDx8CFs!{HjOg^#1FDMQxX#PqZlsVBeEIV2;7 z;Pym=agdA0R8=xua=uN6jVDAW&@|RxX4n9_D0Wn{T|-tHu}HF*QUGG2H0fERKoQzs zW?x%1e-CBjyBi}*B{l$I)K%Q%EnBs^Z6izyoX>#7BN&o-Hn(DDYQoL?;)pQM6OZ#4 z9y*Lc)Hm-*3tP%PZ<>K>vux{;_}A$nKP3&opLQVRyZ_eTT0ZeMx)T^jgfGi_F_*s4 ztT0!8%gk~EXAe5c?+_Ol?Fo96mGwNzXa42iS8N>Ack^T3k|PPa$syhRMRee08IqBf zbiUyB5JKG^zAe7w?bGwaS9O7|zi0iiTNS0)sD`>0>+jEJI)MZnZ{D z)$(1SsDW1kHE~u*c`vbG>dW79+=-6_n$n+YaT`E$|6JBs7W@T@ zdk+2MsLvelOT;gtfi3MOP>Y%qh})7%H^z=bt}{Bz&fJk*s6Yo;eP_oOak};581+?#Gj!~2YDQUKIzS(>MQ0U z4&c7jDa<(CYW@ObL1sT=e(Nvj@v6=YcqM39hq^^eUn791lrAK39DVntOC2ggnSWvo z2$w|!tuYJYGVg>(ONlofJ@*7eZFbb&ExDX46n^vR zgIgLg)UoAvn*noTh;#2it0Q0IQ>ru5p74jA`41N<1&{ZzGN!^;$cLTlC^TTRySoB+635Y+865q`4J=B z?-Q)Q50@MYqq=)#tt!UF?0J!UXqc`U#puZyUUy&A^?U77l3~AiuO^Jsw$6i;O^fCT zE|yeuV8w+K6S2X;)Fh=i1tXOJz}B5P=<4OmE8i3kXTYlcfDdC@qd!QvUO4~u)clow z|G`C%*(Uwc>5N`?HvQw})82YFT7~ah6BTm?2!ae}8QKF$OLcdmWQliY!=8Muz92=^ z<5r`CoNTz_yTTL}RddHnmV7$b6TMsjdtGW55dVZ#VPDRT6!Il-Y1)51vCgzUDh?8lX+94sA_aLJAM56n>bl4MS@aHf8HK ze&J1?|DmvzU+#qqPg28AwF^N88hrJXhnrh`QPM>+w8nY%$ZQoF_==wFXw_bnSz~AQ zAfIgkmb#f1lU-+}{W5{kN)^6qhQ{a+nWwzb=$&Ej?t=-G<==d557`^ou}njqwUkAd zN`rKFO))_;^jN8hbkC{~B<6QXX`4s`a1b{4RnqL)!}bGNKB=f!vx=dJxb&#>97 z9Fo6$J2-j{*gLf?$}#5sedd#&0xOZI zwR~{9!ag%!|0wzFVy15B*|Fm$uKTU4PH@{B%w7%O%b|D@w+X|*10MF~U#gPgL?w>C z9)Kbj$%t51$v_lUc?t>@F>ClUQO=iBKNulf&5cv6y0Yit*%IHUnLT%t@n|SEV87{0B zfYjT_-33w8uzCOJ;X}!z-MZl;q9eft^bcB}44r?c8nvo`Qx|F2anj1f9h-P*O$cup z-*fo7vQTSmKJ8QUReYEJJf-Do!UI#i>qqHYaz@*xuU@&|!0t|z{$Y$BePF!t+`u#u zL&u}e29*AEo?NbroTL$+yHxXs4j&tH4>3fDsWvcrP~e-AbH5>Y!culwDhCufbK+r9%Nyb=y`B8_cyfVhj5*?gwj4@T$DwzLFVsJva4oa`U>ItujROX7=V#O(3jrQh z3@yb64#$C%W`5FDdUc+S#V6}Q?OKHEl{K}$*)ww9xiz71cL%Hzq$Fc=RFz|^5i6MF zO-qUd6UacG*x1Zz3DA9@hX!1x^XL)#Zd%uVUX#d(h=|Fx+aPVg!6K`@O>4L#xs^Mj z>FKSdwSffG$VCbpb>IM&nbGb&9a=c=z3O&`(pGvu))rNnq!9t35mTTOYAPm|wr!i6 zp1jA&vI&&~U0_F|Is|;$Kv6Rcc7}FqcuxNH>wOFiy88I|L@sumfQqmO;H3KRmUCqTP<5rV;>&UYXEh>hlDa(qsyaJuk6%n|+ zK5(tkFAr~_#Tcrmr!2{QXf_M8i-)*2i5wiC79l#+*jSM`u5@>Q&ZHzI-L|?37YVf3 zl5@G=;knL^VFw7Xf&}XaR3<0OY)|SX^?eD*`9y8E@;VthMwgt@m{yrL%FORjRMx@) zl_x{)MCq1pEf{Vq5_r1gXLj&doZfDIUjvNerk}B9jZo`uz4EwZI|8YZdY{9)5u*XP zi_x`CE`VAzUz`-*yFJfVbB#ckEFuj+q0qj23$468!k2nPnAx1{(WQmT%!qhpd)Fqm zj)>*IW!=+Nl{xVJ@^G(RaD-}P{$zZR(KPD?M*`x1kA2^$x`7%z-TQQMWU_8fV_WXJ zU|X|ROhwCQ3(y;e#WuxWo$6J6=*UkpsDb^~b?BnaTNAl3xSz_X6PpR+MsE15rR!tb z*y$%E>@?IWF@r3o5I*Fe@;rW`Xm7SxZg8xD8L2@PA$Rrg&IP9_ zTX3M|TyW$o!DoGP`J>uj9vm8^WT6|XvHlrwRL>f3-H9rJzO|dxOgkMN(3|N*NDud` z0*D?hcm}PHseL!s=e1QY@m4V|Rxn*60k)aO^n$`dOuX!#ZYMRQ>^R4Dsjs3zH2Gea zx%LZj?|^(>!jLI9Cnsd((o--su`~a1LU120+2@lg!L66FU(&IIiMW6(>zY$H0Wxuj z2-iv;JJCvgF-pNaDG@77gLp-sNY+CnDxwi1cs?0%HxHqelp%CT zMrJQ;9+Xr?G=2QKaMBcX>F-FKl_VG@HmZdjc|y`Su=|vZ5wvDdn*2)i2ZL5BL)3!% zI88S|+N;%=SWyuce`(kI^JTcH4&uK12O(}W4NfY{9EFmgY!mYh-FLt$z}h8jPm(Hs z<}8x50I=^PvpaS)ogBsu?Nk3DtjGld{ud5^D7M~8QYi>xujr*~pSB}D?bGb8p{k*l zfBX==XgJ7MQEd|F>i!)LuIGF%W^{gy(plS8A{5p@9HfLFZHwyEM!8RlZT-pL%-=H8 zBbdL>?o}#Q4gfpTHJ{%_t$U4tG?;H~uJw(MEh+}FIfLmQ-Fc9v!mHDH1Sd6|7*#mA zv0MB0-=(Z5wNE~EYBx`!_jE`%qL0Jsav*d~DcpAh*Y=^ns;Op~nev+ixR@&xJ9(!4 z?%%sN72_5-cx=4oY2pD3F(*6Grm5$#Urk_nf>FOMrWHleZGtUtr~Jissl6m6i^e5P zpEBtc)paOfzI#bNow~MB8f2cGAFbef!qP+!4sWuPjcn~S8voisB2d(>Qqc|OeOOl7 zyZ8gDOa*?qQ=6pTrHe~S;*C!;@7+ybf3Drpq?QMrjSYwNDh}V~=hvKc2|AxGkkafK zpJVhMQMN)qN_5(pbY{BOyF=_-=*$f6L!&jk=tN7E z;U?#TKejKFK`Ek{|AI;fj&L`Cz2&`3sq}|Wn%C@#U!Xh zp#jAzdj&W(T(Nw49?3XObPpy-Z;*^sZC?4PB+7*B(P@>fcx|z`$|#(dFAsl66TKqt zWdxL26V{GT{Nws)J81|Gua~!pU#aJVjCiGEBXqi1RFHsb{!&NHxyOGuA&T6>0e-o~ z#cAgACh3@zE9Olu4kt8FNKZH?r-8N80O1&u*ERecV-MJuD2>)Wt$p_N zskmqnvm+asm}l1a&+aDjh1Vj#%2|aK3BCIFr#=eQ=%1ixI;`E@E<_2AXP5$CE|}t0 zWHLh;AZ+6Yx*SZ^FK8W}APKxB>EY;3osYAii`#H)A$;70kn9O6LL@CNPj{;*Uzq)z zK8=o~CYmNGs zM~$kwzck|7-PAK@etiFOmJ;A<7fFC30}ri8&ob$g!<+s=Lfzw~>~D+gCuK z-3`~SUtdga0&MIvJZWGS{Q?c0W}g@`crfFH4M==Lq#)6|C|cEjA0MTl-oAz~&L(4> z0p&5L=Ffc11pwS)vxTQu4Ov{-h_%GMFJ&cCBcw4gGrI)eN6HIbL=B2YUM~iyBDu(ch7nk}582=pB4?Js2!T)p05pY?nhL`}p>t zG{~z{=!Q}}> z-JodB?O+JTD9LBi+|p}`$DSf}L-5#@e6uiO`>4bU&?oS=pSz*ry*{qtkG7Iw^mFD6 zt92Td=A%%9bu!LWi{-`caX5 zDk1&K0xwY2|Nngic@fQTCM_vNu`grUFoTRoL4v{&Bdt~WdWw3sYW9sAcf9r|)hRI= zCuquLQB8r2a{WF=^h9605oLo*2;zbn1R3UyQdPcC?Png>hvJmxRV1NkStKG*QE=1~ zMJe5+cio$jtVyvRFFs3oFEfPbg}g)tNsFuK6|{<-N}AuGySpaBm;owt4$|E$#pDHx>T8e^&VW)b8KFC*DMV-ysgt$|JLXQya5P z_e$7`iLW#gIV31C53PiS4CFE2uaV{qeuxWaS5S~ha+Dr9f24TpM}`620*$(E=wY2) zp8t>T?njcV3;+CVj`;`mj4zJc7}+q}GPCXni_XV(e;iWQ^lWnd46o5frxK^B*s6H? zcG>gy)p=jB>L`-OLLjGIOd8D&D?a6#i#npU5!eFOiRipq(;oY1*xcC7Hd`_bK_IE8 zElLKRz%=)NFU`S-ni~CkalYx;k-h6N)p0~lNwi|!f?gNwRUd~W34?+Jlwv2EUsip` zLsOv_I=A*Z&1)(#6x%(;!NaE1>7*uEo|qeGd$h230f_#Gr2np8~)Uc<18%4lQyb6*|%(zu!jbYsZF;!hALrBv z&-uXl0kmu~L3?Uf=X;ffs-4ZwUF7VX!-+Sb`^aI#kc@3YOf;0w8kzOWnDwZqEc)0s>_E^|&`nTB`WQW<49_ znf97Oz~zI_s27Q9+~v_L2U3oJ{i0zWkLdKd zo&8^L!w=*=C*e+50Szh+7O!`Yn*hcVCuotHbT|Zg1${o*s~6FeQ^mhS|7<;VXZ*GU z2YPX0U1EuuaL^GwHJXy=$f^3P5uB8k0T`T2A`IjxKPn z#ib`Qx%J=c<1h9q%HtocLOTL7@C9IBqcoyVxAh*W>+43aW`sw5wi{-~P;65PSGHQW2wb}LzVmV+@}%}O2nthTg@emXay&+2)AJ{U!2Gv zOX@^PBuF2jKVsXXN|lh_vQZ~PYi>=^JnnLL@a};&6Obz_^lCp-U|);&h7x;WbrOk}ZRc)@GK9X>ATCp@rfb%KbPu*D#I; z(MfCw&KS%D=x6Kjgo>mIK6SWz^E)!ut=9r|!ww$FTS2lKWG`phAHXSYWUxYTBg=ip(vm!P)H9Zc zXU17zZ8PI9M>ocZf^&lK^Jw|@B=HDv2-yo}-W=>!j*l)vNO0C&;iUacn=968-5(<0 z1(?>Jj714lfh^ig+B$4bQu*_@LFqnCxohvh6PLIL-cC?Rh%wI|MU;9mO!bkVX^Odf zNIwzhr4SJ_$JVGwN{h?lkkiMGi6b7w>U>UV01fVZi++z2)o{#>t$o>>;y_?p_=nxv zYsJk(TjE6Y77I~6hA3vW>)FJszGXfd(C9(h3^?s3kITv?O`Epe?kcfInGk?Z9Dol? zP(O;Z_2b9B+*FWxi(Fj;DE&Et+`7r!R~e1u(>RvP5zz)Vg-ncX222!#BwK)*Rq0E0 zMB{Tl>8?sP$fPKROpOOfgu-mYwG83TwLGxV=azc*#A}E5{;N@J(9}}4x)A+tP8(~F z!U`YyQE-OI*c(=(`;o+IoI+ktoB8?q4I`Mzzyv32H9)ix_n|^Z^cUTSj#>A4Cjlhl z+?24}#L94<>tcib6c+`DrguYsgg5;$;Bh9ji4r~J^3(a?+uea1YwppQmz84| z0XnYj9qNUWpI8DT7S-?_XYp<9-1$!Dd^1XgeUTQrVlU5m`YJP5mMzjnH37Ot5Yz>AUw zBX1r}F8f1-tcA`VTdr54+w8#lx_tfmcGf1K*d+uoSbGi*)QsKsx4op&sHRMnSZ$SL zXJTj99b%EX@LIWXrta!aJ#(ML@31{b?+zTx+6OwzM8+&1HDY!67{*nAuc8?_e(KaA zC{3(y*V=F8ldVexU!e_BHQnk%yFABfkE8nAsKryiaKbBrMyhjEh>^gQDxFx0xNtFwJ(1vl;eNX$a{`vc@mhHlP2#OpWZKCt46ZGm;s(U)M zNr_hD%=d7v>xAa0>1h_b=W|2UM~`aqHd>GTJtTGwJ;aX#1II|oONbu#5VWTVp4Z5U zcr)9Od6EkVwP+&)P{o}KGj))Y2LyUA&uli6Z{a-z{>|LbB>9p$8fCTQT>#YsLJFK_4yjEw{xsgbzOK|{6 zF(ryU-NleCVS4sngU z!sU6IQ}M~ThqrdG?|Em?>@E`$%(PaII6Nb>?r=!!?q*H%3NjM8L#hlYM*_wkP4A)A zJR#<`KeZDJM`EjS$0LtL1MhOA)YQyO{E}3tO_>WvWSTM1M(7*wPD5YA8i-*EoMGjU zKSm;r`GRV5!|z682MjQKHkM^G6@vQtTW$x7uu&_|2%P}-X@C)(GqbsAQR^?vfoo#g zJv_O(K22Q3wCBN7yopcEMCDX%{06`w{&fqMl^fzhyf#237nsQh9L#aWI|Pc_85TB$ z8}7$ds~iA+QKtZkO=f+``JhPdABnUI(BwBXZ!#nq8vwDSi=k7M_)*dSCo|bXiD#_U z_QJ?zH#bO}4RfbBL7RC!sl+mT5q&myR5?CV?}K_bu3y*D)h(Fwn^Itr6D4MOVDk8- zPMJ0u_d-36L7?a#^vZeAq^d>QSBsfQ-$YuhT{#mSNB;SS4?~FW%|{xoB<}4{Yx^fO zIegJigR&BHn{BgHt@>Y0?&8qa^ERflp|1=hhOal4Dwl35%C6vsVCG|MKfRs*jr> z;duIzhXxK!yr~q893}!FIyhXCr^%+<82qG04oMs$3Yu3=Q<9m$sR zDjGh@yoc5zLD<{HZ zq`8&(BmN!48Ee8;*;V3Q=lY7h%l|TGYK=ZYK~4l@F`h3#hVi}Pj?{2m3vt3>R=|cW za}c$Mk`sAfRmb_7P2nN@pOd@I-7}R^F_=I4;6<1`TnY014X(uFwgEk;ooq zT_SGn-3aWWdRn7JkA4sa54>L!D;2RrT-uwP^#`O}P z8@pFg%iSb)5)stk3_rY`>z_z(W2AvsEGnb_oT0JLVD>`mCH?6a7v)qLj8|< z|E5v>#CK@~u-`Fi{4e$Oa>a6Bq?2q+}9Hjd_F`3vkAvX~bcjI(YNMzbXL&G!%4B#X}-DegOF z4Eql*(tGiPWYdp6bq`8O^l@ABje~;&?Q?vOfc+%r<4#@HeJ;TYTr$e;Gh=$kPs< z<=Wdtz8KWoMoeRHG6`0B$1w-C_8UN~Djkk(-nQy9;H8`X>XwHs%4&h-XD(|s3sx~< z-ee{-L(yDdgeFYcxLIp?WVd4vH7%i5FS0G&xqtt3)Cb}o;$(f((eZwl78U+qn{@8> z1G|KJC9UJOlyswua48#{|<&{I)*30H5@6Z++GMB z8Sv&g`RWqM06&v6;SnVkUU)Z7EIAfokv4Xy&t`kG&o)qdr)PR|euyKVrkK<`B^h;y z5-(=wDU?>qL(DVh+Sv{K^au^QNGk#F=ozZAt{qkNO^dt|+X<0ppm`i*R`06g99kVg zENRT8t%44gI-4GPGkBYW6K=j`t)cNI({U=-fi$oy z(*M|Mw*(%Lilz*CQ}Pd|23yv|Qya;AP<i2@?+m5Eq1FX(pQW;XBU%aitq;`CCF} z#5wom<=8fSNJr9PC`y#Ioq7YAQb=-mQo&d)TuS@5Ry9>?qmklMp+_dSST0~!&CBS( zGca|uw@+61)Xm+}pqLw}rd^xDk|F|cAGp}}FpkKl)k2>4I!o(K%^)#O6h|Zxh;6DY z(lSc%_}Me*uTES&9P2Phb+Sw@e(bC+Km4gINY{LRAb$Ud-dFc>=YxbMe=7PTt*$|=caw>SWS zbvtTm=2KmQwGi?OsI%kXN<*2EvUGoF+@sQTuU%ZS5;#DGcA0bXdCC+c zRrSwE=DEya8>6!Az$R%+zo2;mbw8Uiw32pJRt-ESGU!A0+ zlENl*0*W8Ig@au08y!u4d}7^vgv3*v2MyW`zX=b-JvDE~4zL}xU4ODiN|3GJjT*HV zKh3gxwsYo4Hb+K7t&5V7hO|B&MO`#B)I!`lV*|}XsY|6({qD)c``7$;?0CWR4YhnZ z1q(W#PGa@gz>+CdRXjuq=2mVOydim1`AU!CtI9%OCx~wZeL(|oj*@otO3VbI`O?Hl z(Amwg{wJY1K*yM1y@Wc&?I56U|F8tBgoH5f1Nx~+bAFk@IHI~wEG;sua+N0lR4dD{&>7o7(J0yC5-b3b;5|zdWN_gDvm72vW zH&Rx9%*@XInY*&8raS_jUdoG42?IZO8Xxg^4=DxK1y``<9YlRHzp|!QfIV#^rb^5_ z+doBO$YQv5s+>kn6ks%tv(tRZk{7p^`x_}7&;m_`^^rn;Ks_!rky54A=2s}@)~~R& z-Fr}>a}WZ=r8`EhuzmaY$G}qoqs-8#|Aooj+}__&eZQht<6ZB<0X{%lg#t9PG3-?< zTWi44LIU@$aRgNq#B6g%jKnYW|NeUgidUJd5E2nF1X9j~sA}mjo>x@p!l%i*050EG zn6ZBCHJD@!PP@o#8$i5;3HACe_xf6omOBYah!*Pj;^wMyhld&$9BJIaA1*91X*P!81=UIbq0SJ8Yr-NBpUV6KOv;e7g0oLjHS9IEcHDWiMt9+03&} zf#~-C67abcIak(q{5X8YQQu(q7NOjtbKXwb0n}HyzMBiVGrJAn^vwpOvd+Gy-Og|b zH=sel_L@Om56l6Yu?F8{BVV;Kx3X`$A~Jd&8QwptZhw`;FC$c ziB>-dxJWFIp=Z<0=ZjKl9001__xP3F*)ren8j%f zGoz+3daCHM_nq?_KCzxRL6 zd*1gw=j|Lhb)V7!~}E%2!ar!)Rgt%cP0FIT*8IFAC5dtgkSg` zYNp-@Leh)*!OG+(p+^uF1f{HC7?8J_A87t~?fl%Tq+wJMRng$D&q2y2T2P;kvLkvg ztm$XkCw$krk9)jd)GE=4#`)lyewN}R^=Zov`6FK))pu0r=I6=%ffJ$C z%c1$lVb9mizxj5|eiKA#Y1y3~?eEsLhMm&c2G)gWWo92cXt1$8N5*VaoG1%>;wSi& zV<^jR$CB{tSCkqU;f9Bw>yL|xi4{~l<(0hZd`0e%<_lqrO^TDyS()Q8(Y*= zt<8mriHRZebjto(wl@U--wJrV8I6>SUa9HmsNT7AC-v|8L>YVK{#O&y;N>C8rsie^ zV`FM{b#-BJ@!nFsm+`LFo{0=M$jRey>gwtcgrA>Z++p;l8Yv-R&w~qikCrkru3%oj zb?cU{kx_JG>#j&A7vC=i?6NLKMpWh&7OCm!4|B!r70t}(Q&Uq- z>TEBHii+0S^h6VUYj&9uy?6gUHd6okwMft(2O?Tg9E*2;7ZD=*>qKyIj;I~M#>R%n zQXer6F7D#*FBP!~2}*8mZmFVCtoU)t`cCv$Em|Ix8I%+{j=!pHXsFz=|3_m~V@Zqz z93Kdto$TrSJ3Q=~oNO9?r@Zp%c}z(Ow~LF5aQIosz=sd)JUo}=&;GH~U3ZBsP>T7g zyvMKOsa zy3aiu8X9sLe?{#6qeUg{&;C9qV%g#o$HAMaZrTwRDi?Z`fjr7K7wXsY zvgg6Z)Wq1B&C6SlX|7yRzJ2@l^wd;nhE7OqU7bjc#k;<@?sHUuZNY!F2aMTCj<autQ&wjA(C{`;>R1$Mt(7yjZIgL&BlqH(6OJ06R~C;E^y4 zOir4lUCAqe3(RY+u`t(eY`CNe)Fm476~lhL^V=NCKIPvMMA2bv(sZ4&qW+8%o?CGe0+V2q4?+8g8Pe#IQV#Z^~}tk zLVf35bEcxCq{NS)rKO!|50%Ce78Xw72weXvh&>NgtfucVS)%hCy*6Ib8vOU_@xi9X zjT<)>G{!1T#TN2Xenwzj;7L{cx3i#xDGM(zFU%R`h}@;2qZ@+zhRh$%g&jXeB;99a zp2>wi!NtYh7%w43dHvn`fzx@g`Q7{c>~v$UL!Ofy|9gX@f#W%gyjTq9;Pf6$m8LA^8=%4t5Czi|b1R=YN7g6ZN_X#+isqCt094jMFRguKRL=M#1 zP7f(gCzN~)2Q4F`7D7ZwxRfPm_Q)y)dw6*GQUny%((&JIfG?#+*Y8;z&DLGm*z@ov zYG>=UQC9HWCu=3oA6cbF5mJ*Qe>cDP!?`&*IE)SsqH6u;JF!}tnsiM~a}n6A$zly^ zxqzJr4o62v6l{G#J1otBEmio&ja>Fyi7W_{OhC%Lux;~ER>OH#fS&_o zi8LbEs>w`I%4`aN&LW{lJ|X*GjMcQX-X~BCJ!-|r$L~Imi;F`LSJzE~sbJWXlarI3 zmFMBu1MD`6b|CY^iqhcIl)?#ZDy41-z^Jq_gV8*8G`BOIXSVdt*!c>RDE^X zD{#uo%S`~$;G?jttgKeo))u~2nMnry;dye+nd^@Oa+#bQTUAwcrX!pgkTx4_af${hXh;RQt{rPRE;YJ|JbwZDgk_1Ilh`S`RH(Og`J>NPj!EugyDxw-KGsn0lM1@sLJ zOg}qMH#pwD9xWTN!(w4>J_&sfkXeUH=VFlZ;h`WWR~t&Qk@i{bZ1G)3SJbpGo*w^2 zWy!3u4d&%B_^p3^47*9$X9y^_)cN2-Sxt?Oii(Ppv-4}HuWp>;Cef&MjzNG35*pzM zP!=zNBZ0?8$k=b`>glDPot*)7mJ}CrLKCj7tf;1$zjb4*s;n%ntkm@O_O3Q>)-QEm z>U-=0HT7j;Leg);L`qtk0s+kyB?E=eg)};hDgHVMm5k0zPk&imeHF-sC$A^+y0f!0 z1;Wn8cJH@IqYJHBqYLWVwQFB1jFa`tGQ{jZUfHm}e;?h?99~pVP*AJxz1WMNc32^0 z@Jh4b)hn+3KYyBn_MQ0n_>87#z77n;LJ?DPWky+jdL~N|Qs2jAVW&4=d;T~4+?f49 z?jkg>sF*jLX0FgB6x0DZa{g~AIl1w!tLw!O?L6O0A~$@#?CB@~vBofJ`|O z?o0qo6-ReNyyT=~PWAQl^t!4o-tCO*$QQsmORYNOqDdIz;q)&IbU0tP?Y$)K_!-B> z#zxn`prZD%>FfIo({G$jLhjwvlZ0m5=!v=K8SrJphON zx6kFzPYlY?l$_k$CAT)Q3R`uHvRI`m)v6SIOj7TtD^misAoi@5_uvMMio{B=5pbgM6UG%>&=MevbxbC+G(Z zgN~uo&47GLJeNu-gxR z(dT-Bm}sc0W6c%v@bmHE$Q5$fntsC%bfU@4&HW@d*K>FAy=2S`m@*vPPEG#UvpNN;KwY+^R(f^oU6?AH&<9M{6pPx+d zfdI;DbNbE3*h{=0KYm>N4oLh8Kub_i(9zlXLzUUvG>#Ijr?>q5|FW%YW?O~vz6k|o z${^v!prxhd=;rnjfM*w&h-2^l*K{teLg+ORsco&T{{Vi|4j2FIF7?0mT4B;lhPiMMWtb*;g&pp(E1{k4a0*%SHM4;yDg~ zf8lp>auNl_%Rx&`-H%I5w*z(A>bFS;ChYKF(=6>L9G>Z0Hw&9jQE9PBNw46+E|b;T ze_~>-@0y!?4%#|K@bd|0C*hjuj3)Y*RH8NmkYg2 zMTH9zU#(bQSw#g4@!Oh-1C6Z2mzm{cW@W_;aMJTi>uCzm4~UD!Wcf2BrDNnX$jTQW zUXY!=JtbH;h%S%SQPw{jQxtS`bO?*``!M{FjGiEnMZCQDC=_b-$2$oOi)CaOI*B`> zN-HYPzvrAYPZ*7fV9-p;XEoxw>-0^w)Xwp73NR*;o{P#+-}hKAj#YPdn5|PMRuHQ0 zadC380_|Y7V;!JeQMneX5#AN+rw$h$DU1wKpH>H%%q%dbWP|uKQpV9 z2t?oO%6k1;%<%SYSi&Rlp}Bt45~!*w!-NPkOH0dJ;XClqzlGVY-Q1D@$a4RxDJm!w zeDfsRuw#RAxE~%D+L#dHz||12U~PKY$jA3LOMueh_wg z#Cqcf?a|Ru4k&sV8JYNuv5AQcQw!cnp#_Z>ce36P5fgi!9{D1N<$s_7E4qCL1_u=^ zEt%ku_{3^rV(>6JAf{*UHPdDHyW&b_f@O+IVn5hpq4AdGFn`g{2L3L4i?GcY8AJZ1x0_5D5Z;LV#iqhtX= zL2Tej*VfjM2=GdnixC9CVPonw9xpF1Sk|7;#Tp+PZkv_*kiH8&K49B^%p^+(G@%Nc zJN821g3sFLiy(^1b=%Z8yM?+5!fXwJHQL2~g2VzOsZs>}6lSjd%kP%3Gk&u5LGi|}t(07~%i6F034Gphw zY3IcP2(SwYk-}lszIj85CZZF+G#7p@+uhUi!I$Ld?{@M_)#UDpi7S{#jE=@_bo)Vo z<7GOxPIq4)E_@1Hz=Y(7%juM!VnLJ3@cIGK?P{)|{v^qXy&`HRBA`&dJGP;o~EK97E-^++cLy8_M`Q z^Pl2BaXB?gHF+-K;*v0!*dEn%oDoP!yrpwV6`+@J>n&7CP}iJ$=Pv|RR53gYzI^nZ z|2Fx!{Qe;isZ~SI9WygRv*B=}^=~ybEqzyd=DQw#c++~@G$RvOJ$@)J`4g6>8jF6# zf0&7Nh_FJzl7^9y*wxilQcB9mvF$kpGzKUw-N)an8hYZ<-GxBM-6JDfO^=T_y|!j< zNZz>drFCIwi}aZD1EEg7)O!%43Ir8Kh$KLZtV)q6vW9)8jZmuDO zQAJTAA|jOrB_z*fgKvq3?=45hgfhs7JJRx=0*4Em|DIU)90@8kVv`$d948)-b76pLc$jAsVKm`;9 zOR5@6rh0;lw^e5Z)&<=X?K3_{;P?cYj)L;b%TdLb85oFQMUeUw>b<;`BNHfEUtf

arV#M&X zJ?1=Ve-bE40HO5e+NiN_-(r%JKdJJ*5)cr;85G-PY5WHL-b8hAt}9(Ef!Q&5wo+i|6E>XWnn?c3od|dWOvDHbsXnX=s)IU86wn3 zp$7H62>!JX$S4(*a-4D`WQ5j`zyMJzs;ONX9vJ~`m;{kzcYi;gQZx~7{q?B=B|ID) zoEOG5mI3Ey|1t2c)8bHZ8PiwI%*=d#PvC=O!bO4av;{*{TUUn_LB0-APFEVI#{AkE zWRa2J>I+J%aT975(OpuCj7-TdS7soO z{qHy$tq7-90fkc7TIjS|qMoah^26T!^3JA)F3tou!-|p%Kg$Dbo~gTwH+Uk{^56lM zRa?+|Z~?pPH62&S{Q~!EeIvppZXBm{k7Y&Slaf;V^=d$@0HpS!wDb}sWhMcCqk0-O zGEJ04B%-YtF1mxkc2LN}PefJLaGu`#->txfZatD<7$3tc_| zp_3gy4^RD@^78V~X9N(D^Nso01TH|}1`R_-OKW;RAEK2q@<7&<8mrNIenl7-qt%`DH`#9$ip-SLF-QE7t z3S*%L$8lT|5)w)8Ux~vj&xLKUA%cqm=`gr~HZfHWwBe0KcQ1l;QkZKGtqVQ&TW|yC z`Qsj1Gf$EX!cRp2iCc*@4?yzVj&s$+oCyCga7Su>K5=kxFme-k6T(%2kTd92$W<8= zs06!bn!Oj6mL7sW=BpFLEXF2E=!1m!f-Va5s|R{M+Q)Z3II$P zuElU_czF15zVzGAjqo7n2$(J9pA@?)6>pRS3k0qS3RRM{JH${fM;(Un1={$skl-u- z@2N({jc5o%XiiQ~oeKro&U-S%X-`tTv|8dRI%8u)2!?znwezLoBuJFY^C9=n;J0FA zIiL0Lgxp>cg(~}fhm%bon*+iEy-Fq}5CXAGhdi>Cv1+#ss)9_&QgxzMVU7{+yE{!}ji7)>O3@phsGvA?rLAy4AnXGc%JyBjx4g5oBAmhcpj+dU=To z2nu>aF0KBiOcJI93#+RpTQO3`+}D_XSv-Z&jmrJ|Trf|7&?d68^QOymLs{SV-JgRL z(9Hv_62L>4lhJy5y~-MC1_90tntjbJc_4n`Y zuV0OHJ1=zB+kLQhbtNt{#9;W+Kq|Z99ZgLlI1d{~$2gGQwqVxm8f_q_S^Zi?4~94r z7_}Q_1oy27XmLUpAkr$Bh z?4Z$#*4Ea!-(KD+OA5uuI5to`v+bc~rTx>>PdEa>c0iaT#>)EOKXI|IuWx(6ZX{^f zN=O<0ZqMnY0VCamhIw>EDBoNpTpX3q5wsuw_0XSC;NN`}@kjhb2RTa1~DS}ZM$i2lSlvnp7{67Z=T&6*jd!U!6AVY2s{+k5K z07ynKThOczHsUh!`t@sCGBO1U3XGpg<2XG%ovOBw#*FPaZn(`z9&FD&=Lp=HSD>Sz zxwMJNK2J|h9xcIXjraG*aO7rZ_rrL^ZL;*}WHCO>^j z4?COt?Ab>WMyXMdsHGBIT+u;6K`Qw#2uerWaX9tTdO$AZOG!z=#H0Y?%WLA|r7vG9 z!2_lpl1K;aShI%P+OlC`;%<;VzhcSQ@BJ1N5wTHL#sQ7tXk){gejOC0c8>6adut?S zO*7zQ@grbYR{*TQx?fG7gT+D|cpuv5%a<>?>FGUCk3iYkvO#~WU0fkziwy>=Ul9l=SjIh9{C8$rJ7mQnno#{RnvTS8RtDR?_HtQ+I#rlzJ;7Gd_+kdl*Qa{sA10kw|0x}vRZ;m$bj&vWJApdifX z5tK|*z%Cn%N)n+{+2rJy!0tSJ_KYbnKi`hcoiLmWG6w)rV;V&UX+I*U_THxw?kwEg zG2r(u=@38`lZM}R=J6vK#x9V^W#h+atE+cI^X+~R>bSIBR$fje9j&RY9i5bv)pYgK!$QGn;@Wke%Y!u7P;Np`b`-+bqQ| z*Xp#8)PK!_Hqg)@1kKnTP#yu3OC=p0Qd3h?&R3xV;9zTOYdb;NC1`C!f|SH8p9FPc z3xRA?__-XFfC&Pw*Jpdyg3DcBKdm;xBB#FlnXiw}Jvn0tori~R0uy6jxPUQrHeA&; zHOWBg_>4+6kO|-ZDI2HE=Do4LP6*j}Yv3L(xWe~EsPtNhr;$z|&-e`sy9Y+59{_ zYM1aZUXM%b2@Z>Vp@gig#pHw%Wc{yJ80A7FBOgA*`gx899~r?RE-sE)Dkcm?z-?fH zdqRFjZEfwz)<7{YZ|~h-BlM6kX#euQZ*RW@gMHDqz{dttC}U4Rb4Z2bHh>l&Nt-HE zA+&7rP*AgiH2LXuS9P#om;o8Yepfz2iZI#Y>kM1<8Bh~^JNajI`kqFoFY1zK9#+*b z9~$rKdH|IxE+Vo3SsXO7l4y8qMPZ>LoK8VViFUq&ogF7bw)h%fBFF_|A|i*ocY7dS zgNgZLa9%4wUKl6>O;!)d)5Q4r5@bX?4JQh?yk@SzY0 zbE4V<_oA;~zwR$g4bEe1a4=5miFg4d^6z}tF{qlt!7Lx9>F@84xfeoj zCMG861FFw3{=ncG=;x15C29tWG>nbk_Im5mmivC@LlP$&VlbnRBegToz^+*loZ z8HMiwvfZx<1(1FWR(P}+aIc? zV4{GTV8CgYPvA81UEZ&?x&)om1oABN>lC<>nRouANO`D)XMB)J>hz=17|KI7-n~8r zP0d7_YyA3~hNy`R;0%TOUK<7Y&H{KWP_QPuR8-|k0zz3;p+DlNr>o)5CkDnR+7_%zl-1%L~tJ77Y@Dr z;V(i5C4FZEA^nPd;UsXAG9btmL|IN++x_ios)v!<;aQtWWm&I`a$cF67K)5jfS-_% zF2X93Rxl-BU%;}9R%q6S?z{Kq8_Vl9Pvb2*UWZ82(%VG(M5(jN9Pb_di|ww=TUF>| zT0C^0P)v1}92Z~ok=l2bT-^2bLnS9C2Ze>5V`Jq^+LZJ;x~%p_#AiO@>&fHOn(m^V z&dl(zTD06Om4@E`^G4tC#-S+yUtL$%Z$4scYYTe>{eZZ*xY=~$3#SCmVQqaSB?3}L zF@NSep6xoH!rJq;wtJ*z*Bj14s;jHJPCK(Y=hi&Dc9vd6qODpQKE%{9hX(b26eekZK9Pb@4< zyI%A22?_?*)ZE(H-JMxojryL%tDC&2qgVEnywJGr$N=3QSY0iSq6puxnyBJ8sC*WM z{+`(JNWs>Yr{?*eb4*N3LRS5F1%{QazrVfwTQamIO92bg-r0#cL>jjjd(bNs@quu+ z4tp!3Td0D>lN0ZXr+oppZrw7fdCn>NY@(e^>Ldmcd;FE4x|87IMHKQ*+&KhQZ9gU1 z`t4gRikOJ#Q+9US^t35!U1g;xI|X6G!EfScV`bq}-rFP$!q#%m&d$^{G`cC-671~k z!WDmZ{tVzXKKkO?;X+yzn4C<9!^guDX=Y}I{k|JFZV>v9SK1fxpM_I$e9Fl9T46UX z0Kd2SnV#a-WUs5xQK4XNB(9zLxYAKkSUQu@1Uik6c!66McZ@j|p`&Gqgg59>SUwb<{ zBk1Yr8Si)sT_B;CL%O=UEE;_O5%>=mKBDX&9~n_MG<*Z)7_gbh0e6lZ{BoPx{2ES) z*Z4~6R8OqlaaQ5nbgjqs0hBH!l63PC7h{9h{>|Y6!!}}?n=w4Ac$VF7l?4R_bMx{B z1_t8x*M42qKSIB|<0V3J@#4q_dE$_e5KS$uxcm3-7gtihr#SS-#xt_Aw)#FQqRvEBX$37WDm$H?9166Az@oiH4)&+~;!v}* zvxNSAeSH&UR&g8OHA4~-sBoYwk`50KZ6|BR;eu5$*ge5Uz~sRLGGt?8ro~`5yPzNn+GgfwfngQYuZZmk;^N|hhmSvV zusN%Kp99=3ECQ{Et!lc%Clr%6KK&gZGl( zU>o_Y2d}UE`a(0?_KIfgeOw%_ot@oNYwO1y81^gSb8{By|E^uT)@;I_St&Ssq+s)_ z!B6VkxpNNFjW|juin3?F=mjmi8ok!*Lc6+DB|LYOl)M(ZnP$%7<1Zur_4U35%U@jn zQeS)UF7oWS;S5*ZGyUJcfBdd1dPrjwgJ^D7UVc8$i65LTC@3h+ye%34z4`Rtab7{? zO6#-HQhaD2F}F2FfV&X5iH{!J3yA;Vpf>Bj)$vO7)+>5pA{03lRdB=U5ixL$BR=lt z&Q4HvHplskwEor3iyweQMk?$WpkmUBipY3*dB1-9HUkCXpOQi!a*^&FLO@2=2HUu~ zF(dmaH@ErQH+)#|0Qha8NyE)DlY94w;S!Xf^MZ+K9H0@)?8YB1DRqv$$6x|57>sq1 zqR*znq6hSK$+KU#Y{x4|Uc7k0Cm_%au2PNqr=M z*azjfYeR`sRgUIJ<4jBF=Hh!l?6+%ZXed2+&<5AuTVZF2t%HV>En*=dq26*ET?>F;CL(HLE*MOnUK@d(Lo3>s#oQ}N<>6t;rT8Rz{fp;C)C#gA~2!vq+!g zJyt0xmO8Kf^N9COpWJSmbA9Aa%>JFeD3DPfh^3=6IwwhDj>GQg{fV;ULIX}85wf2va+NMBC1s(XuF@o z!yHI!Yinox=D-7~61W^-kH>M>)UGF}9IjSQ5$!I{&u;?4rsd@1@QphkY?xs(Kg$ke zseLRgycrc4NlQ(wprbQXDX`!(+iFOOZatnlJKc{O+!tx@=!o@bc5`yV9G1pdXlq}_ z*=S?&^PcxySzR3kdR$msY;dC6O3Tkbc^FyQRL`8{U7~(D8YCVq9i6nA8VR6omE-Jr zPy*Z%wwW0jpe}J=3)@id?CfleK6yV>6Mb;tzA{!$Ov7vZ_2h6nJvSHNuJ6jz;?`q( zd0AQ9+pa5(fN6x#S3-7Ump>{*HGhzQi6B5p(s%D72IbblOG{6mT3NxV^gmn9z&U97 zALD^ec{rTiYZ@~i8kMnh9;Lair>A%2=1o#dOG|;{&!wfk`TBzTX5DX|y$w@(#7bWj z*35=|>tFgakS%BxC0Zd_)BZ%4mPMwyS$-doq?K~5?m3o-8qTD3m|0BL9Q#K0?D@lLVxWsXm+W^Nv6H(t@9(>CRI76mey7-ZIz0%)MQPVOz& zPlB^|KnL{q_s`uwn+aukyx5)Ul$k2-oMl?8TWItmH1t9ZR2l0dV`Ju{-M^s^BoFbx zG3b>%#s>+(AteySH~9k&}~4gU)y@Vn<)&woYneW5Z)o&xlO_{rmFoaM4Hj z6_hh^ijY-+Y$$2dz`$o21`yAaB+G0H&|r^0ltq>$#hbqDKM_12a#1=Qt~1-HFa7a z2LaJ6{YJ#j^vRRZXTNG@x{?K(OUiAAoBR7IG;=OXOG_{HeY^nlt84BlOWFtLf!sl~Qg0!Ve$VKJ9|a%gN2{oR~18rlx)vW_}kF zO2%Rd`VGDJu(^PA3oL6sj8{LYIu~#`s5wgrQR3dVHN@3xzt!_ zX_Y{K18|jOWCV40cLN$Qeg6DeUsJOggg;h5qdEZFi045W#vC0TO#mk;Z^30_g;^ZO z12LPQJiZ%E7lbQ>Z{L2?+1XhOeW|@5}UJW_C6x%3IT89u*%+boW zwl&co$pt?84LBIA&Gij99YKKZKv%s0(TA9BOgFuj@DPY*z7ui0zup473oD8EV?_}F zsFO)jNUIGAgSWSLOk!e4S((tz`V)hPmmssIE58n?pjg1+EajTzK{`Be7piSLSY;5d{7q}OQ z9N8!+Df>#y6_bUuvQ(QuwL`D#%v7gy+1lC`TMuzfR6AdQ{RJ*3x@lZX033I4e0)`0 zT>k)s7lE&@Z|~4hLUK8d#iI?XC{JNyuntC54mgOqwsw$--@o#o=|ou}DQu1-0ZEe%8m2S3P%@aGpGQ5)%Y=&GJVI{)Gz{kVY`By+tNcbBl|zIyzJ) zKD$()(bCe>Ux4mw86Kvg2*<;{Kq?0fvAkk5C4>QYOz#p+Ow9wzGvyQ4F%8sd03qcy zZTgWpJJV;+qL-GIR9FTR5)#l7>GMCgH3zpMYH^n3d-B@B{gAhWkmPM0xJ~(R)bd#o z)JE-rhtqM-*%FwXoIF_jvc6naUo)M`XYA$WWk!d{Ppegk^7E4;^j*d2B4N1#K{pP&Ca7guw=&++v9JU)bF$fdcwGio{IjJNSg z6p3{SJPe^pN&H!vnXK&W@(P#(5Q+p+^DUudG(oa((@kOISFQ8E0KbQYhc^LEVYwFA zXSS%}lwz5fl$3he35Yu@%QBNfNj_2Pp+a4KhC2hM9Ry;sPySV93y&OhGDTh&EhKmj zT_Yp3A|fIOU}?B+WZRZtz^BfDw$%ILT41yb1k%{jf-5gCe=wh9f(6!$?Ccge1R66} z+wG(juhcfYz>gT}5nouD4e|l}p0Kbm04mNFpefR|fCS{9KD`cbgo9v@&bpsUgg7`m zx2*m8f`wp+Q1bOkKD5?cCe)xf3`jx6{yW}p1B!M8*9Q_-XVhE-G_IqgBNl)I0s_=E zH3L{>LmK<~G?ccn<{Yp?R#i39XxJ2LTg+h^;kj|6?~}$==xkF^0Ej;n#w@(BZ58qI zWqMH&Z`a_#;o(es>{SN`2mi!G>Z}LvZ|eF)1knC8A(cFwqkNr`@*4owZ(Pme1_Z&q z;1)A7GTQSSM`J#z>G@U9ZvPb0J+fDfUawMOYNTPsSr(EkVw) z=9KSo!Tmb#BICLUu-3XBCw9hU8a>ApMcn-P>uHQv6(VD7I#*mcrwBPQa%Eg{I?4Z| zx7k$KOw?Ka+vKIce_Muz%I|--Qv&^9K2`5ypZN^CPBk%d^<6;a)2pjDYCHdlI)N6c zs;;g}?VQ&*8m!E<1>}N!K{PNh@Xx}60yj7JO~VS+>of>Nq=$ct8n7Bi6&PGw2ZWMH zh5eNAJ1vaaOmi?8I(`xo5^Q6W>X82GmhUh{>YE5a~J;t->R#>G*BE9e8~iFe@wR$Sh- zy7ELrg0Pq^g+}k>q;+$j8ijB;LvMe7GbkK>w>6`Q zdLIVhH7t9;otBp|}-S?{q;1&74|If^}BQqOFI zWEww-GtJf0*m2}af7+!`61H``51SF!d9e8R0j0Tli9MDVUPNIMDl8floGNU27&+qx z-&C0PNdD;R!bTFIUU0sX?6c$8z)u4i{|5CHZ!r7vf+5UQJIQ(~x zsn;kcNFtj9LWgb;)kEjx8&zwr9nDL}%XPlE9`5b@GGO>TeDcBvRH;)ZHU1RT&IWZc zct!!MPF^DBOP8+5wH6V}DbK;nVm0TLe3MNe90$kd-`Op>?rwLfoMinHT)$k#i;equ zW0dT%rPqJ6jV5f~U-DqsY9583OVuNLxIcUvye3&Bw(!4WusL7T+aSbcWMq~<-(X|Y zkyLu9P+-aM)v-uPR_594YTw7u1B^_@q<({M-GtRQ{{IaJ{!0k{d($jxJ?`LmZwgAp z#dvMp;KemgPD0RQfCiD2;bOvdC5TFhebwy#aeN4^3B$9$Fox(NQfU;P63Sb z!$<%^(VFhRS{fSC78a=1Xr}QiYc8pD>!s-L4iJ759kWRJM#40(5r$~d(a`~=EQs&X zAC8gnaapc}=Fw3)@IExr>?jmA4h45C|MzD>iS1}9{rDvi&v2kAc>JZwy4(2$1ts2x zPBZS0AG2XcWI5UqAPQL_XuSJ}gx4M~^|o7Unsi{$>gH@4kRct_vX-W%Oj|S)zxRQ| z%48h_;sBDV>dTjwi3vs!U<5=&6bo(JTU&gNzvW&hCpQ5lgMTU*oVp<-ba`)Yuf4tf zuCK3TKwuzif{Gakgml@^-;l~e4)x;YOJWE*u&M!iUdr%!P9CQM)fa-wUvmfC5X&cx+agQwv zGcVY&o&9|d<;3`ShsjzGqXyqQ%2-MRL~{4DSh=xEC)Pp|+~ zR$5BYsivfq78|P}fAtgYq~1gbj7|F+8~x9pKd-H&^)Wh{6b5J@X_QL`-4!EgSu-9e zE3+b5+1bu8#JWg85X0F6EDNbgWJJUVP@i2T8XpxL;ciiRqLW*PTie@&{*b@ULF8g( zXLloRa%$@R=O;au&_KXt`r6uGfhqa;_+nsB(3+YUhy1j(G#CTM$8P|R4-O1aUKE0< zmxqUk3=@209(qX`LrO{t&hTo>!FAwUK8qmNLfN4`Mq3WKT#!( zMx(KT4WBV2*f8!Q9EW5B;y5&ja>x#Y{=v4hAwa&mBbC7ZFe^z#p#y^BnYit1fe^Gc zHGjjXYR&k?34-9`W1j`!o(LSy6lpy+@HA#&VS!ixLA-r@_+k3*?(W{6!4Kts%Io~i z_vC=Te_#NLAKkzF=MO80aflVDPP!p4jlp0v%?SF_sA`?vJ;=v#qeI4lUzr@HGXx5k*X#@oQX&h>B2$c-px7+Bx$oS0WEsLLDaj1O-LD|4gE>4Q!RSg6 zzPE(xbUxggCprd=(d7ygXHXHFE2Dx~V-EmC72x;wmP@XT?S(Xs4;+%!nxnP4JLG@7^&(L{#j&ct2hASDlwAn3?l17v5PJrG%08!N2_} zoOsXkZQs6iNXQLQyScf+h>}R73er0AOPBlwpL8SFg(pGTd@L@;-ulu=$yJyLgo9Pm z<(tg?)IsG9-cGODi5;9oY-%cry}f<16$gMXj0LePLqI};uYUBB8alJ8{cLaC{`D;v zE`QCQ1<2i5kqDR$slI}|=4nu9DDL%t@}B$CMJpj zi7wO7%t8o*HBVh0Q24(A&jspE45i;WhDngwCSc+GezHKY&(TgggxllgHf^wKgl$*= zs(AJ*1%{a`6V-yR7{%Eb?*T5r;|CxNuvn&(_mHqHmth;SOz9C{@$ONqxc&WG21Gib zmBZ1_A093)HvL+&+uJ+r>0Zb^8D2%QP66pa6+9-8ng|yY4jDV{-N1;gn|uHFahr*j5J0s)FTIS( z9Ov~J*ww4>Tuo=CEjn&)NJCv6JH@MJxVGRYy3Grrx=c`eZVdNVPW7X`Pr14s33Z`` zJZd@`E%VY{ybCn4ZzE1@E=B3enUQ1PVnLtOyI#zOs;PPUGEAu)n>kACgp=7m_6_bh z+rl+Wtz}Nk)_|E_(U3cT!|OBj1;nw7`$O@G6cttNpaH!)H9RqeD9hiME0i$}_&?V} ByJG+V diff --git a/doc/src_intro/img/components.png b/doc/src_intro/img/components.png index 6c16d7e5060551f1ab08e4149f8a6688f4836934..f71cd3b042700c28993b395811e396461197ef8c 100644 GIT binary patch literal 14314 zcmbVzWmsInmMsZEf+x5KcL?qf+}+)+ad$~@5AN;`!QI{6wXw$C<#q1NH*e;CZ|2VT zesuRaed@@r+Esh)wbu!imlZ>V!-0cw({r!AMph3cgfcOR>AuOQmmVUbK>V-DH(sj9MCB;S*8L&Z=?KhL=H@*zJ!ku}D8)!P||<614yLhbdP5?|zR7X$`mmQNXCU z;Xj%t#q|B%MWH7N4g7mRTl6dZ-vdn%q!@n>*kS*77r>I_f*`s&;&Zo=2>uq(^dXI( zKy8L7MDfR0cm?WlZ)>N2{EY-OWuOJ22vZRW5&h5C`DFroxO1Tel5LQ7{0&EK1;}oVK>|z|}KXp4hE82|rm9|bsriRO0d5Kfm^1J8XmNXsN=d8 z-lyR{f*!f2H^bJc`99rsL_bM>SVvzG`GrXj9HSey13Of`F+RLPl!=4sY;^f6MNreo zwFcmH#Q$`i0}m}!FFVk?+h&cu9JPb7b*TwNNDu9ltCwZ^u%8cXaD=j*l#)R>>WSjD&n>};*na_|z0C{piy+$1 zHkA;EF@NZFm>JqG|EF~V6Y(U73Hq#o{DY1C#x2;dJv|aUZ@gLMm)WZ%y(MinEYaRx zC@@-g0Fo3hqEAJ{>UsDyHX0)m#EsUJeBm>w&K~DVZGS{hdvGQHp#$a z8a;$bKa`z25?%~J?c9f{Y)cq`w_E&#e^z$fuX}NgpJbA!) zmR{H0zVb*~DGhq@dI$QvcN>V&_}giu_XVO(Z@daj@*0}_WbNKMvibdkRz$hcC(0f? zWbSvbdxFahHu=d6;n*HFiXLHo))ZyC^<});JKXNqrkVxQU zFIO)+!W|$}c%NZ;w1W|gIa&k!CwQKdw1nwUT>p@X$+(3d)WPKs+?E(3GHtZwSm+0asE zBl;bRYC|R?2LfP~;L!=UJqqG2`I?O1_|M)Phew)UhCRLMuX%4_2)Vz3l#-8SczQ0h zBHZ*ueW!BZxS}nvnasx^nyy6joLYDfwWCvqofNp}F7i5@zT$vT z^{lnSgB@64ioa%i2%(JoP9i7Dn7GbI4%?^=iq+wT5`wTwS$^2xQ-gkkV_k@1g*F8S zgr+LBCI;GGVWLMCHI`*#pL!!}p+^Pdf<>qyrLl!DI2PvOQQwF5-`W-S?I7p`lR4o- zglR#orQHs!0lwL|uEBUT6Uf052|tpD_RCC_gNy@d$!LtJp2Ap5rVhx)tO-P?htb@@ z*V&7s{k=y#k#DYuAxnJuO2APRJi#7U%@2jCl=kiu z@6$g>xOdls)q&^T1Ra>i!>7gAnDDfvrUkJ#P0|op*bf^CnL5+mnmvDQMT4{;oIsjP4;znd29T zlIujJBXt{o%xZJjL!1B(TAOlUjA z9-T*S{45!BCRLaZO(d7JQFM+&OH42#MT7ErR0CXejLH@vHIhOIDjyZvXhsW4|K5ZJ ze3PN;4hs1-UJ0F>8I`JU)5;Wg#X?JYNIH*xxk3kf(HmgrVDLrDg9)2P?B9|N&@dFpXM)K3Q?5XS4V?1 z8gDIm7-LZOviW>A{yg$3{C7lfXN(jg)^J>UDhw!Cq;L|a5Y?k?dN67jHVaB}jnQwv zmd;4hZ=(vvlgFyBeGF^G+;2cOvU&dg+nbsBc^Q(!P)_G z=-qL4RYzg4z5$*{*n&7z zi6oheAX!+S6>UYRK;{7`;)V*Pl+f%qKJ(MhDhwd`07_J_dB0f>7{5K==3%YN^Sn-b zs)?Q}VQ09i+MDF@#|fG)3K2$R$-NM~VmOFHD6``f3l zd`ICPj00rOa0&zx(O^#;bFf{@01#$D$%r_vOqXjEgFbW2?#L?v!F~%2;r3@fL%V}7 zn);(yrBTFtgz`BHvG09ZZ(6O?7d}cbWHtQn6a0~zHqk>jv=cf2h381>zcHnTk=!9P zT%cGPbc07uR7Q@rn#)X)MZ%FFZ>CJ^2ZL>#pf<95fBZKwQLa)mC~5FQWGX>1D*pl5 zJuwhMBsd2Ec1heF`^n;yv=5>uy$*+R<-rTv;yj)r_F`+;R%Z7`rJI!jA2D*RVmUF$ z1f&kea%*l*9@%p4c9wqnKWu44STM#H)Bx;HeuOZ|O@kQcZG-QHW=n1cWXDd$c4-_h zlZNvv+zCB*1*Yo0hA4*o5&IghCDAH=(PNUXKqKGi?MSVlZL17TU4J6(9c@^u8?qXi zt8cTxzG-Uag$2UpBiYX5>+6^giZ7V0#@p~qjnV!n0H?qf|19f3N0SOE5c2?~xrBK# z;N8o$jawTYnfA7A_=Do<)*`41DP1DRYSSlzv=w=ruqg{#*Mb^`NFRW%9_Nl%&L^0nDkCfmk z+%wHKfMH5kUpVwCY5onU5%){am3Xyr@+qRk%fFbB5yMy=OG|PoX02L zUEtL1ZFu{{EeAdt|Cz88k-O)__Lhg$h;n7}6^o55&e;)KflPifih{pr_|LYJLKl`d zv}dgX6e&7H<|h|`)LtN)2jaQNdNGN)MeyepSAJeg5k{kvGPkn_hI&;DqD);H_m@16 zmzV3_ldPq{crTKXV*AjGUanf4fq$wM+8kf5@51y@&t+6ctjD~97MZMtOAm&HBiCxDec91j^ zJ=I9`Rff8D?x6#D+R}f9k)!5J>aP!^v}|TB8hQNlW!g_dsN)3gpC+gIYip%Y=TxJ& z+=V_I$~#dX6}Ts=MZ(n8y}r~NVkV)9FRqwQB{3nI@lk1L}B(hn(v_Z@!w);u_Y>wQ!ks5;?0 z+a(#ri8d+kc7+J5xjVW>8sQZN&JdoMC1GE;7rl zNd2k;E8=(gA_Hq#n^n<2&|AW@cpQ7VC`2|9xmycOxIWR7IaepW4^gj3(NRXBOvzD8O=xB2E(nocc!DCN9kTy3IsOX z!B4Kvz?w$0*(1e9KgAT70i#gmbyRd#~wo;@@`7d7PKK zYXZ!7grXd@TUB`or&b;5QW)e6!+c09E)Q<57?u~z*mMRaOqZ5IBfNQ%&#aw zkeIULPbE;5Aziighi$CGP99DlSLBoR#mMXP@bx!vB%w4iX9Ob`iryOnoNPM=Sv)ZS zlC-5{_~Qmbj_O_8ls_p0DY3ybhcX_CJ-RKf0xiPSk!TO`z4GZ8fyBJqL3ZDpkdY!-r^=2o-!Vg^B;#Y2-Xg4%@r=Awl1jlau!1DakX z47UMK12^vWINp+6QBsmxJO#@4pm(&@yPa|^SRzSW30mQ1_WSy2GW=g)Xu-Byit?W* z7Ga5+en)cRnx!*5m9KwucyMs-5#3$L(qMWQQ#}b6V}4LNKZABNqF^S&HyYos12O&n z33--t#F~gt?UFca_2xqU{^~$hB;h@*HGZC|N zq0y0i53l!L7m$@myOZ!Cf%8Vex1}Dp>tNN$KGC@N?59)K1=_varmQ#mGMFaXp~fqr zGT!j1dR~npA;C|BKc1xp8SiW7R%j@RI|}SoMln{cF(!Ft>bg;8V?`V?&>@*$kX^hD zd)0U_l6W;-FBii+n#+A=FfD8{Xwhk*asYEpA-~M2(skK>`dI7gx3=f|e+itK;jA^M z<@M~4DVEBlfVu3h#hNvwlro~zUbQ3bc1_Wrr;9TS0drl3` zZQBy_vu@ML2s^0)Q#{<9^=7&xecF?0w&G~i+&#p1g?eX(RJD%o+Y5#aiqbNpF&fvg zTuPpm=xjM&-Ua{BWwe-A!G=uT5ei$MuG013&pKfH>CS)|GBw&y>T0Mi7q8)R*UMRE zLt}8;aT}4?EY^tjoKWcp3s-N&0%MxaVG(txG@70v zX=Ib(G}~Iv%aQBcDULehsPg3gaOAb_b|HR~^)@l=sS*;Qr;a|=;|lZo+_>Si+%=`y z-sM)3pb=M&rA`p#fT}-ewUo(YPjRE-zvWz96D0Kimz)cM)qzWm{VcyW!l7{I#;wG9 zbA!3bGfQt{x{r)}{0Xv;<(x~REmHrI>8DpsW#M4|J|W*41}@aJk}o^Ox>yM}Q0E@Ye?$8uIc&?8;*i(gDSPA9k zNS{P@FwG70s&VfTj{|I_H@tWGk*dy~Vp8;=Dj*APzoSywu|PI?xc_T?=&!^nba=zUeP2_bx;>D#J6GXtF;! zYfmWv;^x6{xwfEIxFTob9t>Wo#98Er8-pC9t83-~iE>T2kW(drJ=>e?aduSnqi1D< zms9W4phjd3ZwE{>oJvFM3*m+UEDN2HvvGOZ&9H!>oC4Hl1GXyZ^kIh9*vnha(O+Uu zR|?{)l}r}t>x5wi3a(u2mA&{GD~ipA%pQoH9*Q{wwA;5SM04lNA$%G1SF;bxpNc#b zd(S!G`84}E$HTekGG17{>BZ8wI4=Jyq2&-nEkgHvDKK(<(URzrob9c8v=FuvTvPRj z6*V2k?D8SFrtZ{{e}9wE=x(2M=gwy|0&{c6SD<9B*gcWcNRMI&PO}GK+R+@D>Mc4` z=0Y8VdF|@2rOLC zot&icXDOlIywn^*+-d3*XP^&@cu$X#myMSw%XU&z>bgz?b296Cq;VTT0fS{umf!yi z%BoOyFD7G+pju!^8?Gldq(;b zX#i;!-@~p?<+`P#8azb8kWsKiA0+bR8kCc=<#HSGB5lS4997DL5Ba`!3&ZBZD_cyG*hZ_TeD#_T}nW=*FjjPK0ov0R`QK zpm)7ckRnEBSXR)ASmm5>yqeyoOI;Ll0w@-ytqSoM<(0yjm*8pCL==CBb~HnDWh((> zY9Mj_5Sslrl-H}0Nu$=_UWxSqO-FXozWaG<=I&ap1I#mx<$ec@kv9ab*juvwCUAB# z);QtFleJ%vtwg?&Vky^9O|Oa3t`?g8$j5r?!OLM3(!3Qg@UEJjOtV#aXm@Q#aqNYI z^E)#~p#N7UE8?mOkdk`@bdO5}XGFo(BRQB^QCn+Mz{G3jEt+-ioc~ z$3QS@AkNJRX7Fn+XB#_CbXSn^8(S!qt?wY!3upTav#RZqn3E`0Fp}=Kw;@?sQZf6R zEcK&^jPdFKSFGm;G`@`5C~b&6uHyQdXxz1JD{D@02+bQGf@ zg(#RnJ9-cbx2wqS9BlL0bNBWvjL0j3!6Ym0qN(bxxD62pQ&>CY}<$81Z@}KIzQ2Z}Izq;3@v~l}i z(8)G(=$3_0{=tKtab01`cR2QI`m6EINKzPKt=R1VvQeA96PNmPMI5$p^!C;-mF5R) zSA6_xwywav>s^oB311{MA3S#>`sV9wr?yIKVVl>`{!Q<`^iE=h_2a3lj{Q%RNVFE8 z^UYN(R!mTkqj7{sX%=o&LpPZ+LQy;Q<;u|!T}z#Pf*SeK1gbPee~?&jCbjWwTeAfg zZ1=^rc)#^NXGs@YPgDmbwnRf!@l5tCH6UQGAUQ6Xx|r~E#e;f_&!Mwp@L19$CVl%R zgb8t2EQH%9GVJwU>4E`wW?Ola%xB%?#x``MQK=w2om(=(jz>PCF`tQj_J5SeCKnE(!w7hN4`lls44m|3l zS-1XxV9w`38vZV)CimTxVTJfVixGL|gU+ptO$RLL6NuNW=ZHD_4z81LHB)yZ*Du;- z>tKwzNcPSt|6sox+PszpLk@8D4lB{gGCXpA&4`j*-!PrdS(J$4l1gocW~FxD=R!nl z)8wCIZ_Oe))&4Ym###)r?Z_R~yR;e4+dSF*qV;up8v6kWdpw!OqYmwbOAdJOs?>~y zE}B~d?OcX4yOmhG(UJ*Zid=URBiCFe-#6fhXzt^q7i<4?i@OP4R<8; zVe#71(Dlj2x(DY`1p(3F-aS! za;{MQv%zp=b28fz+Fh1aRiq{5-nsGlAdueu~M$N>UJeIpJ zG&_i)sBZQd4~V^g{G5Wz)$zp-N8<*g{3nI`*?D@Pe60Yq42(Zl9!~D zWaKm8$vx`j?W@pP<>X;i)OMfb!-RFZ#Driw%GgohwK_JQQeT?xXK*i&$&uUY#)YQp zP<%JPH7nQr+EY?W^LW%qeQ0=aDcp+rU@@!!-RXoW6D*xGcvZFBL=oS|7Ou{l^HuT$ zXT!~$6rNnRV16PH!JIXK-nFA=ApRuP86DSgGx;ZrwBEUqsxJA7W${(z$&m-&k5wsjXeCz1Aki9MGI$D9>EG#w=G<_W_n zbkT2$?GHkne=Izj$C@CB{M#+S-aT=yITUT{)3XV}0bBt(Jb>_tr(C0fzX>0$EolKO z^r|m6m}avRwf9A~%XmOiqeVfCPa=ksB_gA6+XoVI%+Ixx4^~&Gv`)U^=bL9Kj)T(d zTzs!^_%gU|6^@W+$81rNDjw4v0Cehsa+ChIPb_0~_){?NL$>afo8S46CVG@I$-r)5 z5}=Llkdk?HAF&_mDSF-a3?`vdqg{E&2b&w_usi+efS9{0hEP8~9}Zt1X4{WdZLxB22=HO9cdgNBCr$aTUbi-&}6#dgAUtO)Kb zPO{KI8uQP1npXrga!)(9h=$v);h*`^RAv-HS7Y|@DCGJa#<_=2%v@3d04Zdx1>_#*}^N@erwq8N>HNW{FOuxzfX1V*^?053k5p95F%rx>@u_15Cz; zu$n4#ln1UTPYS-!z9u`5oi0o@_8%HI>(foI8<`)^lW0OuYm>Jap7h&tmaM>`Ersmb z*SNpKjm4k;_RPkQ-GxbMhH=44HjN$AzjZ;&zs6M*`RRYqyT& zQaTw!ec&fAbX}EdP9#ERWWj|Q$p{KW51B3WR|D1Pmy~j!^XsQ;WT1k%J7lEj#LhSX zx`mB$7dXxP`wTUc*!&Gnbwk+-96|6W^Znqhj#$$!=xr|s+XgR`AO=NbZQo+#3hxhQ z8@aE>lK8)GZ%{8jbkPf*(B~Ct1~W!jp7rN!ivAh+9@bbSmmlnDf2Jfhj}(0^s0u5^ zR!%*E|5@P(ENv0~JnQKWETJ^#+gLo&u`An55Il*Bo#r4OLRrhBfEYfx(mi5qA%OJ^rpN1SafG?bWkazJ)|}u>!8d6 zN)=sr^vB~!h+w8D?Ae)tx-mX#l~Y_L7-<9X+YPwiwp|Mb%0Zb7F zh3@RQrc)2j|0yKw|A4h80|RPGROKBZpB?|f)!7_({(b!Sdq^3nl?hCvr|bQ&?@Y5o z8dv+PR`>Pn%`O4xOz8AK2Sz zOTMj$y~?&PttWo+8_~(qo;|2FvtTi4{lVUzQs`~=S0VB%VTRB1?|BMW`@(JN1!y^A zsgRfjkrYpJb8&r0$bdjpmxZ(<_>!_$-f@r%o9hW2UnJpPebQpJ$&QcJ6T}!q7^X@a zZxawy!m~C6-~T5~F6%YY;~JB>y!0agbIza6-FJlB3GwaMgj)D|Cc8Sm%4+o9Hqz!r zC$AWX^-FvTe@DoMdn)Iv*7atR9_fWI{G&r1yX1aW+nNW*HRgM7@uJqO(-4{m?R#pZ zr=WyYZOA+-bxvR9c4V;VAN?I=%~S0m2w!Z-FCT4~YL;FuIl%g_fF^P%xp#=Q1YcD6 zeiY>vn|j@boy8R)WI0 zTmMa%s;Hj<*jsgn@mu|{Sh*I1T#Qmcz#gjdPsxV~BfX2P#)dBsL+|!UNgvJ4E7h?S zBaMJ3?_bN=4Cm@7N__p3oQ_J74U}yekm%C8#XOI{XRjB$ec+uxo)^ff4%)-5(iTw; z*PD!WJ_!4+tkm`&5NAew^!(?8T3_iK~u4Q)K9`BD=l^7Xk_S5(HQsHze_q(o@5Z z;>p@Y9?AZWH6wPqE`Ri6R@FBFm1&=>p{eB7;@v{XqJ)S(SXn$olK!PEUf&m_k|g(At}s?Un~ScsN7!z* zCVBc=%O({SP8Wp}t}eFq9ljfX2W?PdKo{f;RO|;=t>of9p;Q2VfU803FYA-(PJS&$ z7;=19FdxDor8GZMX{w~UxJSOXGlwK5E!-@`a<&|eemqiasHK4}r~M|o zD6cWDX3Ii$ne(=0wATN=kl6*gG47o#Gv{ldDTL(ztVO_0X=20`-3gf9)ZS_hi6m87$dG2n3(^KWMximDB>AvUnC% z?9n7`dTAuN)jE-O(=i3(P1wDgLE!#wC64+yOcq@ErSny7$Mq#>xQfdr0RUVr=hj8k z{JGPDMC0kf1qg&|YAzq3vCse+$)FdFd7^k=5pIVMN#A% zBCMW3(i%z$O(x&T*GS-mR;Q(>Bo8Lr#9r4NQXkB#i??q&w@txEMDE6H>i&AXu%D%; zT#iL%j4BM^Qwt<52CwQlQITu5t4R7*y)D?Y*pAp63g z8cU;339Tx7yEC`Ki@1HL_n^-j9jUJXT+s-tU|&%z0j)`;ico(YUxMyA8(5)L6#-yTN<_It4eT0EJ4L@2JPQCx;BEh#32eTkVD*+Mwz<751hhs79>y91{ zFD%xl4>--6PcBaR6!u4H??Pq{gPrUCA`jsRg4ccc#gq{0#BZi=Ekem>*!|UPZgsuVczqt2mSGzSW#LA0P>Bq(?R_AGmq^Y>Ye=^|B7yyuSYq_pPGW zTuyfc>$Jj3r8`VGdND70#(G(>S<;_l`STZNN5y$~lf-nFWY>L2u$Q-aW<8^Jd=)Tu zkSBo&gL>PwtOvy_J!uuFK^G_K?Nj;KApWSGd43?r^`P_s?;H81wN!4d?I%6Nli|7y z4G#EnX8&Xzy{n#w#YYb*>UvADi_Pw;Khq!Y@;0yb9gv@*2qo%Odfm1%AeV-z^V=w7 zS{jNpf4~!XoM2F(bB6w~Iau_P=<8vJ)%zYf)Nku(b88m(V&83VSrWX2WkptPLrRF~ z6Iu_V!qd5d%OgmeSj)CElneagO6vP;e3~Y(nSy!9Q;kd@C3-c}GIsK`qk7d7UonTz z5%kkpi6f4-_ghl&fzMuw+MV5C7ZCy|aqNJ^^vX4iqMn8TSmvtgpn6SQT@g3WFmBM9 z=XdR}Kvjxff5HtznfL`PbG0r*xKm&H{B}fR<=vn#SnOYfSqn5EDdGc(8y|04>{e!X z0_`);FX&M_x%xt|PtCXN{Tg09W(Mx@?iW(WYg(UXOPYV>L~{FPiWhB6vCZ9Gn|394 zJ2BoB?fg{XX<$iy3yOv>zJ~49vys79f?E&1%gxK3O1$St(C@dN;ED18Y4F(cH*l>N zXJJd^uEeI|!%qv~G<1 z<3Q?CUh$!wn<8NO@Z&Si4twKJ0NV~deZ`K(d8DfpfFO%M*Z27ok1Gd;TX|m0t;9Al z!J*<(WW+nfI5q)3%xS2nNz;Ah*_K|&bksI37HRQ1F2DG_gW+`=XNC~bbPxd#rW9de z(*a+^To~hU3)8Q-;W-%MZbTT;iW~9)DKBuu0hFIjzSmTL!S+d{)tc!0WCT%ProoAZ zDOakcIU(K|!*y%<+hw0v&1+J{>CmBF;K&IMsg-2%1On0-XRe1JRYXwr%aL$!uDN+? z#!~Vpz>RObJ@2}oJx`pHAWij)3|p`BcMll-8>A*ft%`1?P|Z6Z#uJ%f*`nNime}0c zJ*RN=H9pNFUDfv|+-+ojiCWFG^1n)>fGoIRYUr!`ig;Iy9@&iEshNrpYbCo@?&tuF z=5jEx7|ry++ZRbbUi#-U%{{#iLh~c{JDBHR^b}v}h@?dC5|EA%z2B%{?CH!pNgXJ7 zN1u>=z^37SYACX9ESqy*E@+WvvDzIb)O!JylfOnxH(uSo+h;b_kG}7|*zE=3LDf&%mOs95@{J#LXYc!PSi308Kq9a-)glGI zuSos^Ym-#)Ii&PsEkQup_Abd2jrJ%vM0sm z0l@&2#T*234Cu4W2dGKTjlImS)j^f%;Ci&z#3Ehe<$`CpM(qiA!-7XJGC^rq zAa5&Y3c+}HyFy>^x$*n5Fp}-2*jQlR32Y=8;GIpjz|tJ^zUJZB{e|fq(&ygSU*nZp z(MVdr*~6a5jbR&P2D?ny8|W_(KrVVUxuK53fB%65_$HLrmAJNgPlmKHpGGc<%LtXo zADm}Old9!=unyX+<-J>&B)YKW_Ddu@DLhNoaAQAH-gTzCX$E%umRySR79PMie9qz6 zL9#y3*G7AG#oyja)F=Lm^v7L`!y@%3#^Xv6@+l5Gu~D}p&(o0_9+_WWIG>SDyx^=E zpT72*){T!F@hrcVR5DQpiB@#1<{5=O4(Q@V+T-Q=qt0`**$Srbmy|d=(DALI-@9Ta z-UVgc0iI}y)6d^@j4X6pZEdXv)1z#Ry1c|h0Yj&SHfbB)S8IlP-^wmjU|FqFFq{bX zX$Blww8$|sVD^u(b`|o#>Dzr=oBN^n%F)`TUF)B?$EPFZ8e{eEZXReB=@PXj2F%I! zG*DETymT>RL%r&86Gn0p*`n_U@N}L)`vY4-PgRVtlBmDppP0Nn(j)qF(%CV3)W_aaVab-Z7~M`(2v@fn1bF}p>BJTG;}*% zT{#V~3OkqSr6WiG>ifYa;Og7^f~CBQauI6LMnrIlAFqyD2G<%dZ8P^sQCR47zluw-@t$M#?}jec7+WEWvO8u R_~kta2@zT0NywzwB4ZbefxxJ#k9yAx<}cXtg=(ctcG!DZ6-z3<%n z-MM$}tZ!yb)*{Kt$+4Y%_WnP=|ML*~MM)at4bdAoI5-Sh83|Q5xL3@u_jj+6Vb6%f zwtBD^R67}MM>sgl-oJnFiAL;y6||E3 z`jvl(40f)pO4zGcVQs?x_j9;t{>Gj*w}td!#_;bEtKj5fF(+HzddLEEt?Ne~q~XM6 zWPT(BK8oV&LCmj@Qay*pmUc5zwR^Y~aj;D*;Tf{g35c=42&0y{1$Rc=q!ADjWPE`85sm22|A3{5x!cQu5pM ztpyFKzusqVYHCVKN&{uo@Q{!YHxU|U*wO|xp%S(f0#WORE&X>Zr+#kcer-u0*ULjW z2$iw;9Uv*!CT3{qGg~`m!iVQ}f0w{gx}OQQ754ljA;D@w^zPmNy9@i@Z<2p)X_S_) zJ^3kQ>u=+n&vS`~mp-d(7T{_xOP0|?!e#6UczlR_+eM0Vdt&4R%5o9jGRO+k$S7o!|`S9*T-!$9lnjOL$J+)}8=1zN+IA?4_4=)+I?1ajw+1 z8nWM-!!MQ7+S6P(*iBckFH&UUs^u zG(B*7`zAKNQQb zI#$vUSq^RcrjJWq02inCJW4;oKQ0Lbl&wGnm7M0SB{;BOj-C_&Cb9k>Z5Y6Zk)V<#L>s(>W?I(Gw?9 z6|Y5&2;Vi}?#3G4dU%L6i>$m`^%BeK>S~idvpA6NatK-4K)D$kMPg;5+`xc!UH?#v zw5?~ZY!}NJmY%Hmj_qtTcAPuU`-(Zs-3;Dz5v1ltx_I#i{n}FxGYzY*cS;SYr;``S zo^ED7==pvA>jRy!yJcfOUn>av`&aSb0?lW3oidrN>x`TQ?b5#G7sMHP*tIx@`|^5@ z`X{r@IfRD1XQ5$M9TEs#Z2tj8F`lb;VtBxb3(>1jqB>94u5u77%8!(CjVu5@hF`Tb zWBj!B4${|jDp(W|C~(dzS6*@Ch=*KWCKQd_?bzU{dqquOb^jtn&p>|fitHX*NyJ4JSesU~_4g7OAG2Xg`pD4mV$ytenXxg$Z z@W742P$dh1MiAf`zM5(`-Wq)%sBt10E%muw92ZG3G0)$uy)$Xp(g)0c@fB7g_F>+> ztFKT4o(KnN*8ND8)d>oO^F?S_41+pVHuV~2SMP>UFsBHYqv0{cz=odl-NhU^LG&hx zJtDl=S5<4oZ)0w_U8#rL?_-w*Y>PO&(*9i1@{u(VN6(PIyvkU|Xz|scw2Kn-6j@3Z zbonq9xOjZ$%0FC*vz7&&^yohxfE^>I`mQfq7bKaRLT`l4fIcgAMR3V1;-JJAKgR`p z!{QN8<$GsazNeM7=D%VeubEkJsI- zy?)(Aq=zj(AExz_(U`>$N7qf?dfmASG04v-!D)`tAr>|p4$y$F8acS8K5(&EeV(+} z1H0_#%)ZmY%t~Xaf>;K&X;>ZA>HJg=7LApUY_Fqq(7w#2U7M?a3$71@(|RR-Znc8; zQgUxpF{RPQMw$FtA9fyjVRSs8+HFJZn`f5Z_Qm9pff*XoxRCchV1l4&OKTX?OGFYy z^MU_RCkbt9sUfP-^&y`B7~4(=jpH*mgEeeEjg=2Gy3E_SWEx8`7gRmZ?Ol@%?ZWkZ zyBk}^A8ieGHbnzX_j(;F7;+(S(L}|lWEtPy;;ZjbI$;0fipI|{dJl+0>bw-aEbIC^ zpe)+J6xx$s6WF$0?%!~tY|!k;=98>Q35A}wdLM7-7Y_%GBlINR$icLNUOPI1RTHDu zuzFX;U}VBE6!GL%+|>FG1H7|pexFjJ~p-WiIdBnWJdrR*q$Q65*Y$vhmQ zF~fJw5j%I2O}x^r>%aYK5kd2zG2k~Y!!qnrWQuU-_6?Re9%OV=AF#f8OvVk|dh!zb zj*E(n66ug;St?el+eGlx63u3ZX$@&~5)r%+eI~drEjYE*lFhY)&Azd!!hS~Q z#k7(4S1`fV|9Sm6s7<;LUqh{a{POmzmChtZs0{C4dz#Jq!U5aBTPw6P024XMZj-D|GOCjeNQKm9xCkgk7!84Wf)-M5^+!1#UxgdZKzpN zLJkc!ARl;NkNkEicO%tmU!qcow?a=L9?IQh- zAr)UucO9Ipf2}1M77y#LKvUWp*IDr^%RBOkMDF-rQ1S*p|D<-|t_uW9FF(pf?H5nmW?VNTt%zU`7D~jN$aHl&OX=}AF7FnmTfP7A} zmie`mSca;5M<3ma^;6hvUuX^4a_4+N-E{;Rk8M#rjVFcC2tL7PmgGgTqe`%fSKnin z%53}9EXkX^_hea|{pPXbns$P=9!E$p@uAvgqhh()Ls}pEjeo~tSEJqbXUTi6godv z8Ixmn(8non;|C$h*PEO6`}vn1esxhKboR*Fn_|4VjYyE0WfoA-dcrBy#{HOVM2aeq zQ1e`qOwl_)r4ehKPlkuhDJytJbt?MIIrS`;uk^rZ?cwrzTygQ!{Os}B2ti+Z_|%}@ zHRVe~9X7;ZHRTp}Smx}9kOQYl|FdG|$g-;TN_ zF!UQ0IC(vW-^kL9^5aq3Kg0Uo?Uf4TSxH}voq486Z^v}87aTQSGzD75C+`v8ss+vw zZ-6s^%={&;Iev%yp|lA?(be1G&I#Fw4G`I+?0lz_84zv$C$xv*qiCp|_fxEbm+1S$ zF2y5dxt-fs1;#5|IT~FO8_&7|RHd{tUX*v40ZOR@eo0(~W+?I!jt9ZaBOEAnhxtA| zE7@qe5I`TkW)S9o*53Q2_wk3@dO?UTrK4;bu^TGI?~)>pePg(7Mzp6`;JdVbc2@;_ z?bfKWoqaiLo-5| zchft_r07*hq7quWjQLp!i+&FF9?8}86Yya`dnN30fXz#!jeMC5DEraxU|5vhj?+Ne3cxer@Y;?{dsWzbEDTh5 zP%U)^*mZNRDPcMhYd?*!M#(#rZPQXbk9m?xvT*v_8^VM(Cpe(8 z@*hRMf(A1lS`Zb2G)Uy~KdSuw|D^Ii-z}KkI$ku8IKi7!`YLCQlI^-Du^9C=wT-B~ zjK=$>(x%v6`-rBoW$N#(@FPZZ;Y9BXJjB!fh$Mni&efR?4jymzZ`yCVn9XFUS7hoq zkDKTN7U>+K*>+JJN?xS#6vvv-k+I$T8C6^5)Uk#G?Ich8aNClvW>#ZOpBk`L=HKySg0qTbbzP(*A z@eynwWGK%YtNSkw3wQmRITRow9Z$=wl4wk>qPl*2euz2MX6rqfMKEeIyZGHAsM@n% zXykl+%g&NomzTUC)l5JL2XkH9Hv^su%;mP#6G6}(Hdba$Ql0lryD7d0idO^Ovma4! zArNp7_C9Sb`FOaXvpp@Uk|>(!5DGkYacQ1)p!OkW(l{y54o>54wi5OZ22}V`E+hC1 zR-uzSTt#XUw%&>f7(WHq>Jq)pw#8?V3bIIZ&mYPpe>$qZr&+A!S=|++cB1eq=FLA+ z9A8_kq$0?B&=sn%_3b$5(~h0X z%^b{fO>XZ@p!_nf_iLw~KCMWd|1~EFY{7-)VW3|K*+!pj+!n-vsW`_pNbzZVcm_j>3spx z`;nf~7OrYR>l5A}2hBuRH*vRPc*6Mm3cbe+`N0@i98lQ`_`a`cghCv1fS#&i>kaY9A zHMtiL^@dF^g_^3F+i!P0SvvfdPfg#um*-d?3U;I%J>$oafZCQF4TDIkJdSyjhqa63 zw2tZ)zf~;LLT(fQQnP2{>n!|OK(MDat;3>jUVDKg99QT- z8SQ@vAip70^8N;=0QO_$??f*1Ve`$0i{i_Odz@Rqgjm3}Wgy_@6KCT#_Mw7@V)xk%N-%8c;!&0ysjn3}hVcqz*0zgmkDlG#~NH?@8y1&{Tmu!6O- z6b+w9pEaR_L}YQ3qp$OAPbY+zTSA7iT!ps_T{oYEeN3=te2bV4plp7tksE4Dpua>CNi;mA;{BPVq?e3C%;QVdoO&Xui#2cnC?5= z_G5pr+3w~n$+v(IdG@02tZ4GBm7N*$C)_GT&E5@sbUI(wPL1+6uvK9I3YbP`#fBX= z1{UTm4Jgap9kZz7dq?b#47`ZLLIc`&t_r3g$yW<2QfD?mT;p8WMJ0=h2yYo{*}y_F zYFv<^>{?w9hu52@AQc#V{e&w2s}eaFhkK8w+i>}F(|Y`w)q=h&T4+efdrAycT*@B4 zw;f4O)u8-Cmv!NGG{BY)Czee=X&o_O8g%LNyBx-Z>5Ui!H5T_#CNfW~I24x{INaVv zugiwQ;*y_qG(=OeVX6C_PWhW^m&I`rIxwKk#9+jr6y(QKNC^wRXh>m)8laJc{6E0U zYTc^L3M8_!@7LC!@O!-}V{ytUi}hf8M1!4zB?ekKa>~yP|xzSQvwU>RjQU-y%>1P5e*GdEmnHDLKJ_ z@Cz6UmKO{#Hfkmz&>&}@9(%_SDW~7PAscEs8rKsrBi5Cs4(~)b8yh1ouU+|_>%7Zm zf4KnHNW%_X3OK(Ip*FppDwXE*cX=79_SFk8T#mnXUOGy9LGv7P&IQk?SAuww|H|(^ zs?(ki%G&p}oa{fY1_Hf=e9^9Xd-fpBucZ8p|FgX3=p?O+64N;9S;v>G7Sv>2_|I75 zYLfDxiK)hCq1zl>d1ri%)%_2MVOI+4N&z#Scm~9}eI9e&#Xn~Xa>emtKYwjbV>IWC z?TFYck_KP)1Zi;^|CU)24Rys!DmV-=`f4cbj}0sZSG~yhw|oBR=flX>Uw9$7>#abX zy{>e7q^>81Cy>&%4u0-ZDN|(~eDm>x^J3la&rRk|q)rGtUY+r+fr&zo-xsL;EN+Cs zh89Q>WR)!dEI4lV zvo0q@CY!(-(zcTK!mBliJb8{4*W4T!I&+5RzIud$Tg1cmafgwn8<)SduxyQeRXM@Y z)RiX35}36apIC&nDAUx$OpUP1xnt#Hm~eL6o%wIdsGKLjFrn{7?Aq0_J$lQtk32i+ zyob|7k}wG@v#+)ql+}Z&M?OrmFVco^L2*M%LS(coJ(=p$c%K9RlqPGg_z1Q4beO6? z1U2d`DXk%mF8UjBoWG~XV~>Y$y|kQ$9`S`S72nnLZte^`|9orP)tG%3o*?>n2+B7c zn7cx&4|9eA8rjG4qoPA2308`{$3@Emjb+Y9fjeEyW;m|cj)IpUV2>R0!-hO1=?}V~ zx(-&lF+{6OiX|OaRyJQ`&4x1(*O`9^!C+Kcx|ej*Hcn-w5xyjHZEkmNL&26mZT7Fp z0JLONAATDkwj?oAtRUKLo;TXJa5GaU^JNWTRH>K3;DtJ~-!FosB^1-k&9D{u?gY<} z7dv)yDLD#h21?01Cun8LpaiS#aO|yjsa8{#IjQC3UitYIsSo~t&_s>L{X<7&JpS-y zVtFp{N)ZHnpjqUP{323U=67AT(}TNO7G;weQiRdx>sIRfY8E2WIh)!wTuHBQI9+DRe^Eye%@xoW2F%H88Se2t(zmP5wcUGg?FHNwG$kM%(rYwH}|w8!LIUhb30* zbd_Bc1!O`MyJK@4dn#{Lc}s~a%JqIu?L;qMeDFRIg`VIjEME2wLXbl822JsnW1`k~ zqh}nk5Hdw?A9VJ(0bE!B{>uBiPH~M=4H%%F=-nZbXTJ{D2Ergp?3Rn(fcu(Sh+Rm5B&Hs z$^u#R`MD{f&R8U|tMT6?%K1nBo&wZ1vJ-jImKP-IHvq8lr4V6oAO6b}l?t+pSce+L zHu-QM6cnx(hyL>6$a%rIVk)Uq>1It~4oUghjF%Vl7Fhkh9* z6RO(nz)>2x$FZaBk>EtKre6i)%JSb{KbHZ!U_i20kw{^uyhEu2kWYsLRZx2@--|d+ z6gjt=M(wGvMwMcsY*OilkyN=(9`SJ*EjR@*>LlL?g?A50<@|ZsBBtkP$zSrPTt^E7 zl?dYaA)yJ>Fw&%2e9PB?>UxTh`zTCt^Qv5dLJgEoO0F@VIeT&#h?#^fcoV9sU`_kY9tT(gkW7-K;gSL%TP9tPg z{*neVZC{oMEh0g@TBqT1AAN z__HcW&kkVMYi%^s%|ifL{uFGP{CsyZY3T2zO^;(h+Myp$;ONK~Byz?P`#ginruzm@ zUqa$dYGgI;aJ=XXgVgomm^aQ&rH})iZu0m>NfpALJCtWh$mPvpjy?@h-ot>Zd8=^P z1DSWU`UL1v%np?v7hvNlgE)Hcl+%uDt>`h?B8m9v+8DF@4y$8CTY2!Ln=%>eCR9SH z5l)X9+#644&S?FwT!7SLktyt9n4c!YQoC6jO2rTw@wxbTb*{^aIyTPzHL>DFP0 ztb*V+kSE(4!W*E&{B@r_gF^gt>ly{L8K{iMeiK|!RJ(<0+hPQl1yo|GqAybyvOA2y z)Kfx0O`iC@)nhz-kY6(|m)*h|2*r_RH?k)&uNv3ga@eFahccmC2qa`}D9B`uH-cO* z)xOR)Fq!lSDcm~XEVdJMJ&~Vudso$PDOb8K96KEg#Af1qPmYnb{5x9Zz{R)p64=&) zT(Fh!KyV7%JjnZfo@gNgcxMZ3Y&E=Xb5sw>Ms@;EE^Z8sK{RZ%`_hn0NJWj-+nFRV za#QN_N^+?v-sct+u%jVZP7B_(n^j}%AxQwd$dP}E-G1xDtBce9U0{oWY)_3`j4RL^ zjqbAV$~m{;i48}Jhsu7F*(c?kE8XOf;}**C^?n}8d9!%A@-n*98GFdKglQuw~& zUjD~}1m(UDMM71ROq6VY#b^2g!EFU;=3q>r*CpzSose)$wg&Rz!k~ zt8nqq=wyF2rE^Nig6P5bDI%*r{~IkCCGD2fiB~1L^D8)Il5~KA(Yd{y^eNr!Y>aKr z$;SQb4r@oH?X0F3lM`MPQRIXwQV}5|F==$r^wXorDX}@Zb=MPwd}GsfH)eLzh8DBz z6c@6c03u7OX_QfpG+(a0NqOo4dtJ1IU*CwzuKvMoeONpFqI=rJ5kD_8MLYr(3)qi*|SY)AiQK2Hlo3REIBm)%VVC{*pJ=jT1DIGRh393mFg} zP7&CDxwZEu0SOy}D`TE4o(WNsIB&wSZXIR?H!jfW6ZO@k&Ib;sQXZZ@Ujue<$=y^b zwV{`)&+|`cQ~9hro$X5pS6fwjhXOX|Q-^8Lld$zkK+Ilyfz^d#5EMW{in;RiQYQlIkjfTM1?d9N=S zV5IRJ{dLBmuPw>I^m0Kzj@taKiy`Q-gn=r{Ehsq4Erw~M0Vm#D>q?I!MfOM^iesoi zFn%?!c5B%bAHwJox2f7{Zkqj`j#)Hd_E6yv*+;7z_-*T{!A^aX_p0LTsmxysoSFhb60uGOy3lF+_Mkb1P)`qrty9`acqADD;3MeM;h55?;!mp?d^yI8NymLK~iP?qx4# zBkKy`yJ+5FiD^F8QTe6E)r{Hfmv+6h`M|`II$+p;KAp39XC%&Su~@*d9}T1KKz>gF z2SbR1Xeq_7gu0a60#GMnhSkdUF-u}mW>sJZq;!MaQ{(_yit8oaP?o!^ZCl^qu8G5S zbur^3Lc|)GF!zZHvQwd-^W}rW?Q9mvRZqSWp5Rlh+n%<^9rI2m#D}sA@n&T(!gEz} z9L4s-^ecicy_ro9MpL2TEG}gKB8WSGCeeH)qW}m)fheUj)F=oL+(; z`~LAkVxQ+Z`?Y}q17vh^p?WpK5TKQyzM&u6t~DTw*wRDXFjbG+bz1OQs|qXFaGJ2} zh9!K~sD57|6{`04o}0kU=j5uP@)nxy;%|?lvATYjWu0RHY3IgjSeKg{95S2uYMauP zb|-XZ!xQ3T!?>Haw55H0CA$CLSyij?Gup%NYW(_!uVc(H^5wMP%+h(lzEi+brBcOY z5L8CH=?72nXA7Z9s+m%4mWO{?ReU^@HZw4fY7rLx_Eo>M%n6uLqUeleCy_E^j~0d7ErlzTmV3r~biXjr2aG*={^>73YqtWN zZ?%pJ`#7fyV}<=M<^l=xjUlb5A=&@wEWB4>R6QTc|61KQQLpKlww8+utlEiRG8W^S zbyn*z0>+R#wpXo{u0$f2Z&IgyY5&2Jm2rL?%_JUtT~?%Hjsk&pU>x=9qG{$$^2`&5wCrkJ?+hg#T)X1pWH{lV1cDZ{JwwxdD0~mk z8RK1+Jw?v4SBUxC;U~#|46R)mO?Vtm zV<6G%NS$7QOqHu3VmMf6?`{b^Be1nLW`vL->@Ty1MW46@st>|{MO_(72(1w~Vvv{E zSZlT#xwUuSa9of8-07?t%olO7uNi8~m-vt@LU zOeS+WxIcY~f=uT`tWz+sl4+`bX6*seMn#}2aDf7Pk37pG9gHZ}>^Hl_t-o@U@q^D4 zeK_8CS<;)r_*Y1J;~v4IPVFzh@zm3d1#N}Pqh;C#iwz8=x|Ii&VNB7#ozM6Tcqr0P zF<3PFfFUv0rQ!IxN2hEvzR0t1wjL?bKkaX-R{8NIN%ZoOX;5|}|oRr1(ev|7pMf$P|w zI$CwG{JqmYZY;;zxaw$@*K#`i8zhdVHyzGan2gUBQdC~4wheQDs1Hlb3+x}PWb~l; z(jsuI#yRNa`%A*oY;v^0*Dc>yp+mx+n*U~@kQo<<4JD7UIsr-i!KtC(kz+DT9EG2M zblm%%fu(f^N$cZ-s}6sVQbHd^ym>t@nu7+7yX;KY2I_AC{eT^Q$8GhF^tP<%u__W| z>|Gs59NSGh+nrs%(dTBd(X$=VABk@gyU(qkLy=Ibqj%G&OYbA0gLvH~nte-mRARtU z5Wi>0LM66tPk(|l5HPwBV4XgrX#AP7T~T+k6a4vm-~|EQY>khnfe`HHaeKLD5kZwV zM^62b8tZc}kGXc9ks6<-L}xqolTO-dFh1$?LeZwmkg<Snt5yYWxgmqwhCtK<2}4H*Kkp0yk>2({6!u&4J(G%r88AK%9vJtF5EI z!^Sz9)xMn6@G9GVhk8Uw0nJCpv^MHlOr(#DFdK_wc)hu!+b%d>QhptQ&dKDXOy9Qo zhy<%q%~#*?bLb}5aILf3NA|O?mCm_3xE&hTlZlLtskgi)7XY=NvrV2J@S-IO?AmBwh=#jW*QGBbz&8Z%r>8f3J_Uu~hfugi3^uDFsm#iLw& zd6J!ws4%SY~_9su@4W;nd!<+oaJn-8EBx{ok?;CdKd9hwv60_k5{97;A*Vy`Grfw#5!|e~T zn+2Hc`%K!+yczIV7`eZVemOLxTkN-_?^h@rMI&@7EQc$ zbQJHBWJH2gHu5)nAa^LFk08_WYbqLdQ>Mz<`2d?pdior&2Oj$ivhb@VtZr;7T3g^E$aLwX5PGF#SnCp%~Q0H z)77jmoc16c%o2^C0bWpSHddw#kQuEL|G zs-=n^oge8T#4Pm@J&VCD!OdncJR)+e{_420$j-P}K)H84VkF#oOpl=HxIygI#^#6qhWgiGV`mBAO-%Y7H zZ7NMhKw-ZxovT=jKgP-gLDV`VIB8iBbU$_ulGU{uTlUN)TCrO{&#`WeVpP`%B* ze@*M-696Xj2~W0t1|=V1I}to_0EKl>N|4AN9T*9749%}nsF4i}{R+3k&%9w#^xoS5 zcmkf&oyeDCz*P#}-s&}48gJ=vA_j8;2I|g0MZEU>+NW{>O?2~DLObol%IO)68LMZ5 zS03ms`+}6O!b6A$HRq9dcIx^~| zdfZ*CrQwrhrhoTF;CzaBmfbd=o`at6=4l+Ow^B^-aZvs)*^%#*Hm2Vh7&-Y_DI{z=9+ zxcf07l0HSh$sy`h#(T5kN>|3TbwmyQN3JWM8!XrLIg(f~ze1|E$ zj#(mg_rq7SxJ-u)lrfKX6KX=Dh?zY!O671QCHnPPG?q{w{LXQY;G{Aw;34;7jjJm` zAX5><6y(5ta7n55(CXIClsiYTBfwg^_qYeRr_tp~J4J@<(mYUW_=*IyDhuU7U_Q_7 z<*~{gek)vG3s#yb$Wo%A z)a4$b*=4%nzZuYN@Mb;!Rq3gw{5H2$3A>B!N^MP-1O_v&%xNtM@m@V*ECHBvP^6=h zT)T#LmYLS;%51qpVa6!CiP;+-Ac4Yo6tu<`H_=%0Js2~yfmQLZm;4E9Sdx=#V1S)t znNEg}LI$ONSnIrDMW8Cn$#pH&>@qV;%;g62nIB*UiOM1!a9VfqjyI6};@R>(?? z*`B;$m6?~Xnz2DtYq3mLfk((S-%PNM63pCq!~GBr3iG_vper%f7gKyMY> znj$M<%VRM?74bCe>eyE_+fs)u(l0C@O=5O4lKwf3X?vs^DOT4T&==P!7XD08tH~tX zf)%GyX1=}}WEjH_!*YJ_k{mg@zfZo%_CwkBKW@d@iWd?%*u*GZ@S9yZgzN#0kD^*|cnN0DW^a!2?i{4NBWm2a? z7m8!Nf3nUqpaOx$5qwv`*HS5o?Qf;K>V{n#?QUcnu4P+Ujn?)i|Ky`g#i@d_VS2+C zk`IO4-(G7XWz|hcnlO`vSd}GaokxZ zE@)>@`Ucs@2;=)|9mX#_G<89Az`!4&rYFB$xAl0Wk*9SFMizJfMO%W--E=jyFNV+d z_;~+UI{P~X;5DU{DYX5HW7_VeOm ze}pAjCu3uA2x(NBE*yGY^sM%R#$;6gOQiL5fx9cXLgP zg)>5ZU49?RMjHXRKVtBzTauN)6&kc>$an}t7aCot>&kl1Te0ZJH0}`>BFbcowhoEN z{&~vi^FkFCrWs%YAMq!Dnkscj#KWA1>AyyF*Sj*;8JZ)s`xXpGDNx^$+jX?|6vu#j zal?(!bOi1D4VmZ5Y2s4MqtP~#tY3;trXU|5WP6b5HSjSLxat$Hy{f!XLql7Jyz(iy zlgGFeW5J5jA|ktmku}dE5SK(*$7;$w^y0;Z1uu2y5wMAriZPQ!y9{ zSP3;*cy0A3ls9td8{F(!ae$dM04$16&^3K1oS_tHt>s^Cw&zQ>brLFevG1$1vnXkW zftpv^M=b(HGzURz^Bq|2O#=R$cX@tK5X{PYkr|QW=7gL}E6^cx4>#}iHtp!Itf;0g z5bEA~jxs)1L2_)rabI@mD+Ma;;?#VS87*nL53^(T8QtT#z|-L=RE&p5XdLngs1>9l zoXjJ{t}FlL+7M)FdzZd^^5MX#HSyZnTFdHY({I9cvd&TLB=d@+rx;vqcX2~9G9O7p ziLdbYs{1VmpX;vQwtXklwQ(-e-(KAh8r>b)>RibX63ZGB*QBksy#{!3Inq>-p`;d^ z%yBSlu^>x*5f}o2w+YH`wcJgDT~q#XmqwJeh6yI8v{*7W%-wt3%tZQG>rxM%ZX4WE`K1 z!7m|RpC<@DD4KM!2QDdb7g4Qj(h#lv(TP3Ybq9?{Iby zIh>9Ng7i|mm0xadB*zxJc5tl*DrYyEqoAxu8yfOv9#MOJx;H+983R7kT6_7M@wm#g z@5$nD;_cL8nVPRYY?OM@?Ne@w;a`#*PJNcqf))Ds!m2Y=Ltw+QgZ6+a7+i7bX*@Pn z82IPSHiuFv;K>C5%5ph<{xN|ylC#qmZEv$(x}Fs7Z5-mcn(W2D$xgAHW$t#l1neHm z`t%3Gb)sOB*4&HT&kWwXk#%p{Q-ksA8*t4X9UjTRN}^F*x z24zV0b?j`w{>9T0}eaaq`hgn{%p0m;YX}| zRNG`GT|%4@E|aU=ycieDnq1}`NZv2>)(Wg&bittt4a8@5v-vo&ucl&RLKwLnPQ<3iQ1^D)cxkB;>(o*VR?~(raj(+I0r@6pRf2tRU6%}i8WES1{ufal5?oxL? z;3H5h2Q2*QrQYyQt&x7Y^|xQvGVIbmnIl8USd;a~A8d=yxwuZ+!)(fgCJ&>mngmU0 zJ48I0)alw~A-NT|7V$XAm&Br}2GK@*`WRLnJBwI8v}2pJ>x&b@4wbaL06_+OdsAe- z^=AAR)6dcQ0U1PSoH%nFH_IeYJ!y%Lv|z|fucpAJsB=A7F0(6VuaPkmUU5v=RQtaU zi>eg)`EOnvQj^1TN&siWwS(4n{*E)$vhCi%UNi_8BEQ7u*W9`{{L zgct4wrjBY(K{g!Bs=pmX*S5BZDKg=Krwm~UZLmB}4~<&4vax8Ne!w_7%RW0R*2!06 zOwt}wjd;7Puc|Cv34_l8kP){i33qzKGU0Y){te8xz_QQVZ-E35yV#^1+7F$4Hx0{l zA)+MVD(ytLufnTH&804v*X~@fDif zYRgzk{k|4z-)xb?j&s*8l2APJ@-)R)ikukEQ2RLl`ZYgzeMl!LjAu;ex3L+EZeW_3 zJU3$Oa9TO6;-%?}IWi$3t@%Cbh`jIF7hq@4%lQ3!{_}in@Uy|xPIsM8^)y-_K zsi@#8WJDt<2EG4+BImn!cJa?=Z2k+&45+#H$y9{{*9&MjyYi#sX|wJ}{g)tCO3J3G zm@f=94?Qi~-T)qrRsHxfwwtYi@zZ#FuhTwFYtXk{K*MC=G9qsaYkMdD965?YfgEjhQcZ){M9X+slFu8Kf z`)~-U*F`~nNtx1x#Sq639RhbaxYzIg{$GIMD}jjp3b4M~KvbETo-f$>y;p5u*sq&v zdJW@UaQXm65DGbobcI@AZk`4w`{XAnIZ;238;+Oy!wK=03>62_7x@xe?*7j5NbP}! zmpG&((SaXr)R~Hl7loKa!>vtt9vZvup**o2ys;0OojnIUBUxgBM)1iEF3wGhbDI1~ zM&YxQp3~^$hGv_c?qF}jhycX7u=;ZsIWqVLkpcfI?^vR+!P^4@Z=kKIbbjis^v0h4 zLNlwkGi%i8%8+eICan#D>nNEl5LKA2T4r9wzsEFB>3HOgo``UwfVC3SZx#IBY^%|$ zh^TzsG5n)K472`aqiKLOMGbRGDB1?WZ!1TP6-TuCk@u^{yE=O%Et3GI*ZzM>ha)QK z`-o+94CJmvE<}Z_%*zBerI#= zrcdUq(G_gjyN!!q#ALRVb(I~ihRv8ggi|p*-+xAdoQ*9FwpLC>O|tHals+8j8@M^3 z0#Ac!-7p*74+$CrMzb~LD1DbKrE6@d_ve=bRx>*@?66iL;rkz;w{*gH!4;^Pi66TW znTCDOIrpLF$jI9@jCYQ5Gh_i#-;Fn?4hOE?nvj$6CdVOjTh>dO_W?+s-s(8TV&n0( z%(fy;aS~?7uU9D#v_m>wnV7xEpU6K)eh3!r#4$;}7-{}F;_FULvC|fjD(W|Ik{3Z( z8Ss0c=#d#cLj}41{d^OLXd1DmqP;LDJC{*}i=#=HtTM*#cz$+?8Q z?Qd;a`%JVav6bBxke^rMr+ywcq8^btf*jyBvbb})R^;69*CMhWDXRUeQH;>y?B>k5 zABH0;Y0dC@=nq8)Fx9kz9cxk zRK3E^%b18S{o^Et@fy!)mH>4QHWf>Fa0EO--p+02arq}EXXI5AE1pKBkzQ2)HI!zV zo{itXYe~{`%-}=X@t^Mb2aAgHMbEeyKbU-5i+P@7B>FC5`++KpZ;X2QU0BO;v5E*n zF#1OZ2UX7n`7vXmUC{@5nYf_*CIM~j9w--%Hh+`*fGKwNOuMJS3RhKfA-X7mFwnjP zT!5LYR_UcwvOC7j1XsKmnr|@DO+=_Y`(->Mow^QvS3jE-I&bZ9Dvr7QK%nwd(OLsn zE_^tkShF@@$QdfY7W(*PsxC2?v zmnW8=#$c8B)GiL(&Y#c#iKW_Df`wL{sgG6`0`ydhG;;q*v*xy740G_a`f~WOGzI4!VwbX0Y>?#mS%F6UmUh?w z5%~fJ{kWl#jEjGjiijA7FL<3b(HSgR{xK<^tt0csWh|Rv#+tR8!;R(a+fzYR$v5O4 ztLEU>xtyrX=bQX0%5yR)YShr`bNFb@JAAldC13PgLh{s}^q=20=PNuNRLIfBVzP5j zVBMF={+e=fv#f+C{e}6}FEV=QNN&IDSq=`5BWQ27m)HtCH$*eSv58k-dW+1;%e%U? z-=v3$TDgm0OFXinV+&|>XODX|pKQ*i+`5m9gH@c&%OLM$IXS!X$xHi|vg$liGmdgv z(=(!7UGBsZ5k}MdNhCh^CIwnB2R~R%dHf0?e8YuPGcgoTeb-FpWRip2a}S zQ?GDG?ys3}=fga|I<=*723^QxW(I%8qcaov?fOFWeXH2J!%9TET2CW#nD4PSx9#o) zK@hGGNz*RpOkpIPW`xYPgyl$YxWkxh~DsghMuC>c9k;TDpqZNhK`Zzk<>F zK+MM0gYdrRRB_lG=)0MJbpB0q*>UMj1YE&3QgJkLYJV!H_NU^kslZixg3yJ3qsL8_ z3%=&!j=Ozb+;%&X$%I~Y(&RE=4wL~6r`?I(WB^5n&JXWeiF;=KCEGa8r=4y!7j~B( zla$UAVXqRAv7MxWGH5PrcA0Kw36G*ff3{X$uECDP3W6Z`fiCttNy2DuzsIU%GLOVrKQ>Nctg0P7b4&SotaZfD3J_-_hrNrqxog^)T1Yv7i=|VILIIDgO>Z5Cp+r zbjp;FAP9mW2*Rb*MHbx(f*=Tj(3OdXMGyo*5Cp#`8Wuqi1VIq|o@iJEK@bE%@Oz?R p5d=XH1i|l#hD8trK@bGL_kY*qziJg%JKq2R002ovPDHLkV1nhfm|p+@ diff --git a/doc/src_intro/rs_driver_intro.md b/doc/src_intro/rs_driver_intro.md index 7dacca5b..09d96e7d 100644 --- a/doc/src_intro/rs_driver_intro.md +++ b/doc/src_intro/rs_driver_intro.md @@ -1,4 +1,4 @@ -# rs_driver v1.5.1 源代码解析 +# rs_driver v1.5.2 源代码解析 ## 1 基本概念 @@ -8,12 +8,12 @@ rs_driver支持RoboSense的两种雷达: + 机械式激光雷达。如RS16/RS32/RSBP/RSHELIOS/RS80/RS128。机械式激光雷达有控制激光发射角度的旋转部件,有360°扫描视场。 + MEMS激光雷达。如RSM1。MEMS激光雷达是单轴、谐振式的MEMS扫描镜,其水平扫描角度可达120°。 -### 1.2 线/通道 Channel +### 1.2 通道 Channel -线(或通道)是机械式雷达的概念,指的是雷达垂直方向上扫描的角度数。 +对于机械式雷达,通道指的是垂直方向上扫描的点数,每个通道上的点连成一条线。 + 比如,RS16是16线雷达,也就是16个通道; RSBP是32线雷达,RS128是128线雷达。 -MEMS雷达淡化了通道概念。 +MEMS雷达的通道与机械式不同,它的每个通道可能对应一块区域,比如一个矩形。 ### 1.3 MSOP/DIFOP @@ -43,8 +43,8 @@ rs_driver主要由三部分组成: Input、Decoder、LidarDriverImpl。 + Input部分负责从Socket、或PCAP文件等源,获取MSOP/DIFOP Packet。Input类一般有自己的接收线程。 + Decoder部分负责解析MSOP/DIFOP Packet,得到点云。Decoder没有自己的线程,它运行在LiarDriverImpl的Packet处理线程中。 + LidarDrvierImpl将Input和Decoder组合到一起。它从Input得到Packet,根据Packet的类型将它派发到Decoder。得到点云后,通过用户的回调函数传递给用户。 - + LidarDriverImpl提供Packet队列。Input收到MSOP/DIFOP Packet后,调用LidarDriverImpl的回调函数。回调函数根据Packet的类型,将它保存到MSOP Packet Queue或DIFOP Packet Queue。 - + LidarDriverImpl提供MSOP/DIFOP Packet处理线程。在MSOP处理线程中,从MSOP Packet Queue得到MSOP Packet,派发给Decoder;在DIFOP处理线程中,从DIFOP Packet Queue得到DIFOP Packet,派发给Decoder。 + + LidarDriverImpl提供Packet队列。Input收到MSOP/DIFOP Packet后,调用LidarDriverImpl的回调函数。回调函数将它保存到Packet Queue。 + + LidarDriverImpl提供Packet处理线程。在Packet处理线程中,将MSOP Packet和DIFOP Packet分别派发给Decoder相应的处理函数。 + Decoder解析完一帧点云时,通知LidarDriverImpl。后者再将点云传递给用户。 ## 3 Packet接收 @@ -71,7 +71,7 @@ Input定义接收MSOP/DIFOP Packet的接口。 ### 3.2 InputSock -InputSockt类从UDP Socket接收MSOP/DIFOP Packet。雷达将MSOP/DIFOP Packet发送到这个Socket上。 +InputSock类从UDP Socket接收MSOP/DIFOP Packet。雷达将MSOP/DIFOP Packet发送到这个Socket上。 ![InputSock](./img/class_input_sock.png) @@ -194,7 +194,7 @@ recvPacket()解析PCAP文件。 如果是DIFOP Packet,处理与MSOP Packet一样。 -+ 调用this_thread::sleep_for()让解析线程睡眠一小会。这是为了模拟雷达发送MSOP Packet的间隔。这个间隔时间来自`Decoder`,每个雷达有自己的值。在`Decoder`部分会说明如何算这个值。 ++ 调用this_thread::sleep_for()让解析线程睡眠一小会。这是为了模拟雷达发送MSOP Packet的间隔。这个间隔时间来自`Decoder`,每个雷达有自己的值。在`Decoder`部分,会说明如何计算这个值。 如果pcap_next_ex()不能读出Packet,一般意味着到了文件结尾,则: + 调用pcap_close()关闭pcap文件指针 `pcap_` 。 @@ -371,7 +371,7 @@ MSOP格式中用一个字节表示: int8_t return_mode; ``` -但驱动并不在意是回波是“最强的”,还是“最后的”。因为影响MSOP解析的只是:有几个回波? +但rs_driver并不在意是回波是“最强的”,还是“最后的”。因为影响MSOP解析的只是:有几个回波? 如下是才是rs_driver关心的回波模式。 @@ -667,7 +667,7 @@ Channel的时间戳 = 所在Block的时间戳 + Channel对Block的相对时间 在MSOP格式中,Block的成员中包括水平角`azimuth`。 -雷达的旋转当然不是匀速的。但放到一个Block这么短时间内来看,认为旋转是匀速的,还是合理的。 +雷达的旋转当然不是匀速的,但放到一个Block这么短时间内来看,认为旋转是匀速的,还是合理的。 所以,通过Channel占Block的时间比例,可以估计Channel对Block的相对水平角。 @@ -921,7 +921,6 @@ MEMS雷达的分帧是在雷达内部确定的。 SplitStrategyBySeq按Packet编号分帧。 + 注意SplitStrategyBySeq的接口与SplitStrategy不同,不是后者的派生类。 -+ 成员变量`max_seq_`是Packet编号的最大值。 + 成员变量`prev_seq_`是前一个Packet的编号。 + 成员变量`safe_seq_min_`和`safe_seq_max`,是基于`prev_seq_`的一个安全区间。稍后说明它的用处。 @@ -934,8 +933,8 @@ SplitStrategyBySeq按Packet编号分帧。 MSOP使用UDP协议,理论上Packet可能丢包、乱序。 先讨论没有安全区间时,如何处理丢包、乱序。 -+ 理想情况下,如果不丢包不乱序,Packet编号从`1`到`630`, 只需要检查Packet编号是不是`630`。如果是就分帧。 -+ 那假如只有丢包呢?举个例子,如果编号为`630`的Packet丢了,则可以加入检查条件,就是当前Packet编号小于`prev_seq_`,就分帧。 ++ 理想情况下,如果不丢包不乱序,Packet编号从`1`到`630`, 只需要检查Packet编号是不是`1`。如果是就分帧。 ++ 那假如只有丢包呢?举个例子,如果编号为`1`的Packet丢了,则可以加入检查条件,就是当前Packet编号小于`prev_seq_`,就分帧。 + 在乱序的情况下,这个检查条件会导致另一个困境。举个例子,如果编号为`300`和`301`的两个Packet乱序,那么这个位置分帧,会导致原本的一帧拆分成两帧。 为了一定程度上,包容可能的Packet丢包、乱序情况,引入安全区间的概念。 @@ -1008,7 +1007,6 @@ DecoderFactory根据指定的雷达类型,生成Decoder实例。 + 成员`temperature_`是雷达温度。Decoder的 派生类解析MSOP Packet时,应该保存这个值。 + 成员`angles_ready_`是当前的配置信息是否已经就绪。不管这些信息是来自于DIFOP Packet,还是来自外部文件。 + 成员`point_cloud_`是当前累积的点云。 -+ 成员`height_`是点云的高度。Decoder的派生类设置这个值。 + 成员`prev_pkt_ts_`是最后一个MSOP Packet的时间戳,成员`prev_point_ts_`则是最后一个点的时间戳。 + 成员`cb_split_frame_`是点云分帧时,要调用的回调函数。由使用者通过成员函数setSplitCallback()设置。 @@ -1176,6 +1174,7 @@ Block间的角度差 = 360 / 每帧Block数 | DIFOP_ID[] | {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} | DIFOP Packet标志字节,长度为8 | | DIFOP_ID_LEN | 8 | DIFOP_LEN[]中的字节长度 | | BLOCK_ID[] | {0xFF, 0xEE} | block标志字节,长度为2 | +| LASER_NUM | 32 | 32通道 | | BLOCKS_PER_PKT | 12 | 每Packet中12个Block | | CHANNEL_PER_BLOCK | 32 | RSBP为32线雷达 | | DISTANCE_MIN | 0.1 | 测距最小值,单位米 | @@ -1257,7 +1256,6 @@ RS16的处理与别的机械式雷达不同。请参考前面的“RS16的Packet RSM1是MEMS雷达。这里说明RSM1的Decoder。 + DecoderRSM1的常量配置由成员函数getConstParam()生成。这个配置定义为静态本地变量。 + 成员`split_strategy_`是SplitStrategyBy类的实例,保存分帧策略。 -+ 成员`max_seq_`是一帧内的Packet的最大编号。`split_strategy_`引用它。 ![decoder rsm1](./img/class_decoder_rsm1.png) @@ -1272,6 +1270,7 @@ RSM1是MEMS雷达。这里说明RSM1的Decoder。 | DIFOP_ID[] | {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} | DIFOP Packet标志字节,长度为8 | | DIFOP_ID_LEN | 8 | DIFOP_LEN[]中的字节长度 | | BLOCK_ID[] | {0xFF, 0xEE} | block标志字节,长度为2 | +| LASER_NUM | 5 | 5通道 | | BLOCKS_PER_PKT | 25 | 每Packet中12个Block | | CHANNEL_PER_BLOCK | 5 | RSBP为32线雷达 | | DISTANCE_MIN | 0.2 | 测距最小值,单位米 | @@ -1289,10 +1288,16 @@ decodeDifopPkt() 解析DIFOP Packet。 decodeMsopPkt()解析MSOP Packet。 + 解析Packet中的`temperature`字段,得到雷达温度,保存到`temperature_`。 + + 调用parseTimeUTCWithUs()得到Packet的时间戳,保存到本地变量`pkt_ts`。 + ++ 调用SplitStrategyBySeq::newPacket(),检查是否分帧。如果是,调用回调函数`cb_split_frame_`,通知使用者。 + `cb_split_frame_`应该转移点云`pont_cloud_`,并重置它。 + + 遍历Packet内所有的Block。 + + 从Block相对于Packet的偏移,得到Block的时间戳。对于RSM1, Block内的所有Channel的时间戳都是这个时间戳。 - + + 遍历Block内所有的Channel。 + 解析Channel的distance。 + 调用DistanceSection::in()校验`distance`。 @@ -1307,10 +1312,8 @@ decodeMsopPkt()解析MSOP Packet。 + 将`NAN`点保存到点云`point_cloud_`尾部。 + 当前点的时间戳保存到成员`prev_point_ts_`。如果下一个Block分包,那么这个时间戳就是点云的时间戳。 -+ 将当前Packet的时间戳保存到成员`prev_pkt_ts_`。这样,Decoder的使用者不需要重新解析Packet来得到它。 -+ 调用SplitStrategyBySeq::newPacket(),检查是否分帧。如果是,调用回调函数`cb_split_frame_`,通知使用者。 - `cb_split_frame_`应该转移点云`pont_cloud_`,并重置它。 ++ 将当前Packet的时间戳保存到成员`prev_pkt_ts_`。这样,Decoder的使用者不需要重新解析Packet来得到它。 #### 4.8.6 DecoderFactory @@ -1343,9 +1346,9 @@ createDecoder() 根据指定的雷达类型,创建Decdoer实例。 LidarDriverImpl组合Input部分和Decoder部分。 + 成员`input_ptr_`是Input实例。成员`decoder_ptr_`是Decoder实例。 + LidarDriverImpl只有一个Input实例和一个Decoder实例,所以一个LidarDriverImpl实例只支持一个雷达。如果需要支持多个雷达,就需要分别创建多个LidarDriverImpl实例。 -+ 成员`msop_handle_thread_`,`difop_handle_thread_`分别是MSOP/DIFOP Packet的处理线程。 -+ 成员`driver_param_`是RSDriverParam的实例,`difop_handle_thread_`分别是MSOP/DIFOP Packet的处理线程。 - + RSDriverParam打包了RSInputParam和RSDecoderParam,它们分别是Input和Decoder部分的参数。 ++ 成员`handle_thread_`是MSOP/DIFOP Packet的处理线程。 ++ 成员`driver_param_`是RSDriverParam的实例。 + + RSDriverParam打包了RSInputParam和RSDecoderParam,它们分别是Input部分和Decoder部分的参数。 ``` typedef struct RSDriverParam @@ -1360,8 +1363,8 @@ typedef struct RSDriverParam ![lidar driver impl](./img/class_lidar_driver_impl.png) 组合Input, -+ 成员`free_pkt_queue_`、`msop_pkt_queue_`、和`difop_pkt_queue_`三个队列分别保存空闲的Packet, 待处理的MSOP Pcket, 待处理的DIFOP Packet。 - + 这3个队列是SyncQueue类的实例。SyncQueue提供多线程访问的互斥保护。 ++ 成员`free_pkt_queue_`、`pkt_queue_`分别保存空闲的Packet, 待处理的MSOP/DIFOP Packet。 + + 这2个队列是SyncQueue类的实例。SyncQueue提供多线程访问的互斥保护。 + 函数packetGet()和packetPut()用来向input_ptr_注册。`input_ptr_`调用前者得到空闲的Buffer,和调用后者派发填充好Packet的Buffer。 组合Decoder, @@ -1387,19 +1390,18 @@ init()初始化LidarDriverImpl实例。 初始化Decoder部分, + 调用DecoderFactory::createDecoder(),创建Decoder实例。 + 调用getPointCloud()得到空闲的点云,设置`decoder_ptr_`的成员`point_cloud_`。 -+ 调用Decoder::setSplitCallback(), 传递成员函数splitFrame()作为参数。这样Decoder分帧时,会调用splitFrame()通知。 ++ 调用Decoder::regCallback(), 传递成员函数splitFrame()作为参数。这样Decoder分帧时,会调用splitFrame()通知。 + 调用Decoder::getPacketDuration()得到Decoder的Packet持续时间。 初始化Input部分, + 调用InputFactory::createInput(),创建Input实例。 -+ 调用Input::regRecvCallback(),传递成员函数packetGet()和packetPut()。这样Input可以得到Buffer, 和派发填充好Packet的Buffer。 ++ 调用Input::regCallback(),传递成员函数packetGet()和packetPut()。这样Input可以得到Buffer, 和派发填充好Packet的Buffer。 + 调用Input::init(),初始化Input实例。 #### 4.9.3 LidarDriverImpl::start() start()开始处理MSOP/DIFOP Packet。 -+ 启动MOSP处理线程`msop_handle_thread_`, 线程函数为processMsop()。 -+ 启动DIFOP线程`difop_handle_thread_`, 线程函数为processDifop()。 ++ 启动Packet处理线程`handle_thread_`, 线程函数为processPacket()。 + 调用Input::start(), 其中启动接收线程,接收MSOP/DIFOP Packet。 #### 4.9.4 LidarDriverImpl::packetGet() @@ -1410,27 +1412,19 @@ packetGet()分配空闲的Buffer。 #### 4.9.5 LidarDriverImpl::packetPut() -packetPut()将收到的Packet,按照Packet类型,放入相应队列。 -+ 检查Packet的标志字节。 - + 如果是MSOP Packet,派发到`msop_pkt_queue_`;如果是DIFOP Packet, 派发到`difop_pkt_queue_`;否则,回收到`free_pkt_queue_`,等待下次使用。 +packetPut()将收到的Packet,放入队列`pkt_queue_`。 + 检查`msop_pkt_queue_`/`difop_pkt_queue`中的Packet数。如果处理线程太忙,不能及时处理, 则释放队列中所有Buffer。 -#### 4.9.6 LidarDriverImpl::processDifop() - -processDifop()是DIFOP处理线程的函数。在循环中, -+ 调用SyncQueue::popWait()从`difop_pkt_queue_`获得Packet, -+ 调用Decoder::processDifopPkt(),处理Difop Packet。 -+ 将Packet的Buffer回收到`free_pkt_queue_`,等待下次使用。 - -#### 4.9.7 LidarDriverImpl::processMsop() +#### 4.9.6 LidarDriverImpl::processPacket() processMsop()是MSOP Packet处理线程的函数。在循环中, + 调用SyncQueue::popWait()获得Packet, -+ 调用Decoder::processMsopPkt(),处理MSOP Packet。 - + 如果Packet触发了分帧,则Decoder会调用回调函数,也就是DriverImpl::splitFrame()。 ++ 检查Packet的标志字节。 + + 如果是MSOP Packet,调用Decoder::processMsopPkt(),处理MSOP Packet。如果Packet触发了分帧,则Decoder会调用回调函数,也就是DriverImpl::splitFrame()。 + + 如果是DIFOP Packet, 调用Decoder::processDifopPkt(),处理Difop Packet。 + 将Packet的Buffer回收到`free_pkt_queue_`,等待下次使用。 -#### 4.9.8 LidarDriverImpl::splitFrame() +#### 4.9.7 LidarDriverImpl::splitFrame() splitFrame()在Decoder通知分帧时,派发点云。 + 得到点云,也就是成员`decoder_ptr`的`point_cloud_`。 @@ -1440,7 +1434,7 @@ splitFrame()在Decoder通知分帧时,派发点云。 + 调用`cb_put_pc_`,将点云传给驱动的使用者。 + 调用getPointCloud()得到空闲点云,重新设置成员`decoder_ptr`的`point_cloud_`。 -#### 4.9.9 LidarDriverImpl::getTemperature() +#### 4.9.8 LidarDriverImpl::getTemperature() getTemperature()调用Decoder::getTemperature(), 得到雷达温度。 From 4f43691839d9479f61f7957e77a803977b2f0cb8 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 19 May 2022 17:06:11 +0800 Subject: [PATCH 264/379] feat: tag v1.5.2 --- CHANGELOG.md | 2 ++ CMakeLists.txt | 2 +- src/rs_driver/macro/version.hpp | 2 +- 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index d7ba5da9..b4f9c195 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -2,6 +2,8 @@ ## Unreleased +## v1.5.2 2022-05-20 + ### Added - Support RSP128/RSP80/RSP48 lidars - Support EOS lidar diff --git a/CMakeLists.txt b/CMakeLists.txt index e1db28c2..2ae8876f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.5.1) +project(rs_driver VERSION 1.5.2) #======================== # Project setup diff --git a/src/rs_driver/macro/version.hpp b/src/rs_driver/macro/version.hpp index e85056ad..9e3e92f2 100644 --- a/src/rs_driver/macro/version.hpp +++ b/src/rs_driver/macro/version.hpp @@ -1,3 +1,3 @@ #define RSLIDAR_VERSION_MAJOR 1 #define RSLIDAR_VERSION_MINOR 5 -#define RSLIDAR_VERSION_PATCH 1 +#define RSLIDAR_VERSION_PATCH 2 From 7abbc16db9caf5366ca815e37a4945ec1152147f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 25 May 2022 09:40:19 +0800 Subject: [PATCH 265/379] feat: check overflow of point cloud --- src/rs_driver/common/error_code.hpp | 44 +++++++++++++++--------- src/rs_driver/driver/decoder/decoder.hpp | 7 ++++ 2 files changed, 34 insertions(+), 17 deletions(-) diff --git a/src/rs_driver/common/error_code.hpp b/src/rs_driver/common/error_code.hpp index ff46c01a..96ed746f 100644 --- a/src/rs_driver/common/error_code.hpp +++ b/src/rs_driver/common/error_code.hpp @@ -55,23 +55,27 @@ enum class ErrCodeType enum ErrCode { - ERRCODE_SUCCESS = 0x00, ///< Normal - ERRCODE_PCAPREPEAT = 0x01, ///< Pcap file will play repeatedly - ERRCODE_PCAPEXIT = 0x02, ///< Pcap thread will exit - - ERRCODE_MSOPTIMEOUT = 0x40, ///< Msop packets receive overtime (1 sec) - ERRCODE_DIFOPTIMEOUT = 0x41, ///< Difop packets receive overtime (2 sec) - ERRCODE_NODIFOPRECV = 0x42, ///< Point cloud decoding process will not start until the difop packet receive - ERRCODE_WRONGPKTHEADER = 0x43, ///< Packet header is wrong - ERRCODE_WRONGPKTLENGTH = 0x44, ///< Packet length is wrong - ERRCODE_ZEROPOINTS = 0x45, ///< Size of the point cloud is zero - - ERRCODE_STARTBEFOREINIT = 0x80, ///< start() function is called before initializing successfully - ERRCODE_MSOPPORTBUZY = 0x81, ///< Input msop port is already used - ERRCODE_DIFOPPORTBUZY = 0x82, ///< Input difop port is already used - ERRCODE_PCAPWRONGPATH = 0x83, ///< Input directory of pcap file is wrong - ERRCODE_POINTCLOUDNULL = 0x84, ///< PointCloud buffer is invalid - ERRCODE_PKTBUFOVERFLOW = 0x85, ///< Packet buffer is over flow + // info + ERRCODE_SUCCESS = 0x00, ///< Normal + ERRCODE_PCAPREPEAT = 0x01, ///< Pcap file will play repeatedly + ERRCODE_PCAPEXIT = 0x02, ///< Pcap thread will exit + + // warning + ERRCODE_MSOPTIMEOUT = 0x40, ///< Msop packets receive overtime (1 sec) + ERRCODE_DIFOPTIMEOUT = 0x41, ///< Difop packets receive overtime (2 sec) + ERRCODE_NODIFOPRECV = 0x42, ///< Point cloud decoding process will not start until the difop packet receive + ERRCODE_WRONGPKTHEADER = 0x43, ///< Packet header is wrong + ERRCODE_WRONGPKTLENGTH = 0x44, ///< Packet length is wrong + ERRCODE_ZEROPOINTS = 0x45, ///< Size of the point cloud is zero + ERRCODE_PKTBUFOVERFLOW = 0x46, ///< Packet buffer is overflow + ERRCODE_CLOUDBUFOVERFLOW = 0x47, ///< Point cloud buffer is overflow + + // error + ERRCODE_STARTBEFOREINIT = 0x80, ///< start() function is called before initializing successfully + ERRCODE_MSOPPORTBUZY = 0x81, ///< Input msop port is already used + ERRCODE_DIFOPPORTBUZY = 0x82, ///< Input difop port is already used + ERRCODE_PCAPWRONGPATH = 0x83, ///< Input directory of pcap file is wrong + ERRCODE_POINTCLOUDNULL = 0x84, ///< PointCloud buffer is invalid }; struct Error @@ -97,11 +101,13 @@ struct Error { switch (error_code) { + // info case ERRCODE_PCAPREPEAT: return "Info_PcapRepeat"; case ERRCODE_PCAPEXIT: return "Info_PcapExit"; + // warning case ERRCODE_MSOPTIMEOUT: return "ERRCODE_MSOPTIMEOUT"; case ERRCODE_DIFOPTIMEOUT: @@ -115,6 +121,7 @@ struct Error case ERRCODE_ZEROPOINTS: return "ERRCODE_ZEROPOINTS"; + // error case ERRCODE_STARTBEFOREINIT: return "ERRCODE_STARTBEFOREINIT"; case ERRCODE_MSOPPORTBUZY: @@ -127,7 +134,10 @@ struct Error return "ERRCODE_POINTCLOUDNULL"; case ERRCODE_PKTBUFOVERFLOW: return "ERRCODE_PKTBUFOVERFLOW"; + case ERRCODE_CLOUDBUFOVERFLOW: + return "ERRCODE_CLOUDBUFOVERFLOW"; + //default default: return "ERRCODE_SUCCESS"; } diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 662a471d..d38e78a1 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -388,6 +388,13 @@ inline void Decoder::processDifopPkt(const uint8_t* pkt, size_t si template inline bool Decoder::processMsopPkt(const uint8_t* pkt, size_t size) { + constexpr static int CLOUD_POINT_MAX = 1000000; + + if (this->point_cloud_->points.size() > CLOUD_POINT_MAX) + { + LIMIT_CALL(this->cb_excep_(Error(ERRCODE_CLOUDBUFOVERFLOW)), 1); + } + if (param_.wait_for_difop && !angles_ready_) { DELAY_LIMIT_CALL(cb_excep_(Error(ERRCODE_NODIFOPRECV)), 1); From d32b3e4db21fa61b21244825d977445877cdd4dc Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 25 May 2022 10:44:25 +0800 Subject: [PATCH 266/379] feat: add option to receive with epoll() --- CMakeLists.txt | 12 + src/rs_driver/driver/input/input_factory.hpp | 10 + .../driver/input/unix/input_sock.hpp | 6 +- .../driver/input/unix/input_sock_epoll.hpp | 297 ++++++++++++++++++ 4 files changed, 322 insertions(+), 3 deletions(-) create mode 100644 src/rs_driver/driver/input/unix/input_sock_epoll.hpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 2ae8876f..10801e54 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -20,6 +20,7 @@ endif() #============================= option(ENABLE_PCAP_PARSE "Enable PCAP file parse" ON) option(ENABLE_TRANSFORM "Enable transform functions" OFF) +option(ENABLE_EPOLL_RECEIVE "Receive packets with epoll() instead of select()" OFF) option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) option(ENABLE_RECVMMSG "Enable recvmmsg() to receive MSOP message" OFF) option(ENABLE_PCL_POINTCLOUD "Enable PCL Point Cloud" OFF) @@ -92,6 +93,17 @@ endif(WIN32) #======================== # Build Features #======================== + +if(${ENABLE_EPOLL_RECEIVE}) + + message(=============================================================) + message("-- Enable Epoll Receive") + message(=============================================================) + + add_definitions("-DENABLE_EPOLL_RECEIVE") +endif(${ENABLE_EPOLL_RECEIVE}) + + if(${ENABLE_HIGH_PRIORITY_THREAD}) message(=============================================================) diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index f761e214..e2aca5bf 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -31,16 +31,26 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once + #include #include + #ifdef ENABLE_PCAP_PARSE #include #endif #ifdef __linux__ + +#ifdef ENABLE_EPOLL_RECEIVE +#include +#else #include +#endif + #elif _WIN32 + #include + #endif namespace robosense diff --git a/src/rs_driver/driver/input/unix/input_sock.hpp b/src/rs_driver/driver/input/unix/input_sock.hpp index de989d2f..b6965b64 100644 --- a/src/rs_driver/driver/input/unix/input_sock.hpp +++ b/src/rs_driver/driver/input/unix/input_sock.hpp @@ -227,15 +227,15 @@ inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, con inline void InputSock::recvPacket() { - fd_set rfds; + int max_fd = ((fds_[0] > fds_[1]) ? fds_[0] : fds_[1]); while (!to_exit_recv_) { + fd_set rfds; FD_ZERO(&rfds); FD_SET(fds_[0], &rfds); if (fds_[1] >= 0) FD_SET(fds_[1], &rfds); - int max_fd = ((fds_[0] > fds_[1]) ? fds_[0] : fds_[1]); struct timeval tv; tv.tv_sec = 1; @@ -246,7 +246,7 @@ inline void InputSock::recvPacket() cb_excep_(Error(ERRCODE_MSOPTIMEOUT)); continue; } - else if (retval == -1) + else if (retval < 0) { if (errno == EINTR) continue; diff --git a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp new file mode 100644 index 00000000..5d2fb3f3 --- /dev/null +++ b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp @@ -0,0 +1,297 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include + +#include +#include +#include +#include +#include +#include + +namespace robosense +{ +namespace lidar +{ +class InputSock : public Input +{ +public: + InputSock(const RSInputParam& input_param) + : Input(input_param), sock_offset_(0), sock_tail_(0) + { + sock_offset_ += input_param.user_layer_bytes; + sock_tail_ += input_param.tail_layer_bytes; + } + + virtual bool init(); + virtual bool start(); + virtual ~InputSock(); + +private: + inline void recvPacket(); + inline void higherThreadPrioty(std::thread::native_handle_type handle); + inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); + +private: + int epfd_; + int fds_[2]; + size_t sock_offset_; + size_t sock_tail_; +}; + +inline void InputSock::higherThreadPrioty(std::thread::native_handle_type handle) +{ +#ifdef ENABLE_HIGH_PRIORITY_THREAD + int policy; + sched_param sch; + pthread_getschedparam(handle, &policy, &sch); + + sch.sched_priority = 63; + if (pthread_setschedparam(handle, SCHED_RR, &sch)) + { + std::cout << "setschedparam failed: " << std::strerror(errno) << std::endl; + } +#endif +} + +inline bool InputSock::init() +{ + if (init_flag_) + { + return true; + } + + int msop_fd = -1, difop_fd = -1; + int epfd = epoll_create(1); + if (epfd < 0) + goto failEpfd; + + // + // msop + // + { + msop_fd = createSocket(input_param_.msop_port, input_param_.host_address, input_param_.group_address); + if (msop_fd < 0) + goto failMsop; + + struct epoll_event ev; + ev.data.fd = msop_fd; + ev.events = EPOLLIN | EPOLLET; + epoll_ctl (epfd, EPOLL_CTL_ADD, msop_fd, &ev); + } + + // + // difop + // + if ((input_param_.difop_port != 0) && (input_param_.difop_port != input_param_.msop_port)) + { + difop_fd = createSocket(input_param_.difop_port, input_param_.host_address, input_param_.group_address); + if (difop_fd < 0) + goto failDifop; + + struct epoll_event ev; + ev.data.fd = difop_fd; + ev.events = EPOLLIN | EPOLLET; + epoll_ctl (epfd, EPOLL_CTL_ADD, difop_fd, &ev); + } + + epfd_ = epfd; + fds_[0] = msop_fd; + fds_[1] = difop_fd; + + init_flag_ = true; + return true; + +failDifop: + close(msop_fd); +failMsop: + close(epfd); +failEpfd: + return false; +} + +inline bool InputSock::start() +{ + if (start_flag_) + { + return true; + } + + if (!init_flag_) + { + cb_excep_(Error(ERRCODE_STARTBEFOREINIT)); + return false; + } + + recv_thread_ = std::thread(std::bind(&InputSock::recvPacket, this)); + + higherThreadPrioty(recv_thread_.native_handle()); + + start_flag_ = true; + return true; +} + +inline InputSock::~InputSock() +{ + stop(); + + close(fds_[0]); + if (fds_[1] >= 0) + close(fds_[1]); + + close(epfd_); +} + +inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp) +{ + int fd; + int ret; + int reuse = 1; + + fd = socket(PF_INET, SOCK_DGRAM, 0); + if (fd < 0) + { + perror("socket: "); + goto failSocket; + } + + ret = setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &reuse, sizeof(reuse)); + if (ret < 0) + { + perror("setsockopt: "); + goto failOption; + } + + struct sockaddr_in host_addr; + memset(&host_addr, 0, sizeof(host_addr)); + host_addr.sin_family = AF_INET; + host_addr.sin_port = htons(port); + host_addr.sin_addr.s_addr = INADDR_ANY; + if (hostIp != "0.0.0.0" && grpIp == "0.0.0.0") + { + inet_pton(AF_INET, hostIp.c_str(), &(host_addr.sin_addr)); + } + + ret = bind(fd, (struct sockaddr*)&host_addr, sizeof(host_addr)); + if (ret < 0) + { + perror("bind: "); + goto failBind; + } + + if (grpIp != "0.0.0.0") + { +#if 0 + struct ip_mreqn ipm; + memset(&ipm, 0, sizeof(ipm)); + inet_pton(AF_INET, grpIp.c_str(), &(ipm.imr_multiaddr)); + inet_pton(AF_INET, hostIp.c_str(), &(ipm.imr_address)); +#else + struct ip_mreq ipm; + inet_pton(AF_INET, grpIp.c_str(), &(ipm.imr_multiaddr)); + inet_pton(AF_INET, hostIp.c_str(), &(ipm.imr_interface)); +#endif + ret = setsockopt(fd, IPPROTO_IP, IP_ADD_MEMBERSHIP, &ipm, sizeof(ipm)); + if (ret < 0) + { + perror("setsockopt: "); + goto failGroup; + } + } + + { + int flags = fcntl(fd, F_GETFL, 0); + ret = fcntl(fd, F_SETFL, flags | O_NONBLOCK); + if (ret < 0) + { + perror("fcntl: "); + goto failNonBlock; + } + } + + return fd; + +failNonBlock: +failGroup: +failBind: +failOption: + close(fd); +failSocket: + return -1; +} + +inline void InputSock::recvPacket() +{ + while (!to_exit_recv_) + { + struct epoll_event events[8]; + int retval = epoll_wait (epfd_, events, 8, 1000); + if (retval == 0) + { + cb_excep_(Error(ERRCODE_MSOPTIMEOUT)); + continue; + } + else if (retval < 0) + { + if (errno == EINTR) + continue; + + perror("epoll_wait: "); + break; + } + + for(int i = 0; i < retval; i++) + { + if (events[i].events & EPOLLIN) + { + std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); + ssize_t ret = recvfrom(events[i].data.fd, pkt->buf(), pkt->bufSize(), 0, NULL, NULL); + if (ret < 0) + { + perror("recvfrom: "); + break; + } + else if (ret > 0) + { + pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); + pushPacket(pkt); + } + } + } + } +} + +} // namespace lidar +} // namespace robosense From c685538da0658112733b7b6825636aa27b37cd80 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 25 May 2022 11:10:36 +0800 Subject: [PATCH 267/379] feat: change timeout of waiting packets --- CHANGELOG.md | 4 ++++ src/rs_driver/driver/lidar_driver_impl.hpp | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index b4f9c195..f58bfea8 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -2,6 +2,10 @@ ## Unreleased +### Added +- Check overflow of point cloud +- Add option to receive packet with epoll() instead of select() + ## v1.5.2 2022-05-20 ### Added diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index df2c4c66..38d4e577 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -325,7 +325,7 @@ inline void LidarDriverImpl::processPacket() { while (!to_exit_handle_) { - std::shared_ptr pkt = pkt_queue_.popWait(1000); + std::shared_ptr pkt = pkt_queue_.popWait(500000); if (pkt.get() == NULL) { continue; From d6797ff6be33e90632294c80d30ee9edccc4f85b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 25 May 2022 17:26:20 +0800 Subject: [PATCH 268/379] feat: support jumbo udp --- .../driver/decoder/decoder_RSM1_Jumbo.hpp | 255 +++++++++++++++ .../driver/input/input_pcap_jumbo.hpp | 307 ++++++++++++++++++ 2 files changed, 562 insertions(+) create mode 100644 src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp create mode 100644 src/rs_driver/driver/input/input_pcap_jumbo.hpp diff --git a/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp b/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp new file mode 100644 index 00000000..110bff01 --- /dev/null +++ b/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp @@ -0,0 +1,255 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include + +namespace robosense +{ +namespace lidar +{ +#pragma pack(push, 1) + +typedef struct +{ + uint16_t distance; + uint16_t pitch; + uint16_t yaw; + uint8_t intensity; +} RSM1_Jumbo_Channel; + +typedef struct +{ + uint8_t time_offset; + uint8_t return_seq; + RSM1Channel channel[5]; +} RSM1_Jumbo_Block; + +typedef struct +{ + RSM1MsopHeader header; + RSM1Block blocks[25]; + uint8_t reserved[11]; +} RSM1_Jumbo_MsopPkt; + +#pragma pack(pop) + +template +class DecoderRSM1_Jumbo : public Decoder +{ +public: + + constexpr static double FRAME_DURATION = 0.1; + constexpr static uint32_t SINGLE_PKT_NUM = 630; + constexpr static int ANGLE_OFFSET = 32768; + + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRSM1_Jumbo() = default; + + explicit DecoderRSM1_Jumbo(const RSDecoderParam& param); + +private: + + static RSDecoderConstParam& getConstParam(); + RSEchoMode getEchoMode(uint8_t mode); + + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); + SplitStrategyBySeq split_strategy_; +}; + +template +inline RSDecoderConstParam& DecoderRSM1_Jumbo::getConstParam() +{ + static RSDecoderConstParam param = + { + 62152 // msop len + , 256 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x5A, 0xA5} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0x00, 0x00} + , 5 // laser number + , 25 // blocks per packet + , 5 // channels per block + , 0.2f // distance min + , 200.0f // distance max + , 0.005f // distance resolution + , 80.0f // initial value of temperature + }; + + return param; +} + +template +inline DecoderRSM1_Jumbo::DecoderRSM1_Jumbo(const RSDecoderParam& param) + : Decoder(getConstParam(), param) +{ + this->packet_duration_ = FRAME_DURATION / SINGLE_PKT_NUM; + this->angles_ready_ = true; +} + +template +inline RSEchoMode DecoderRSM1_Jumbo::getEchoMode(uint8_t mode) +{ + switch (mode) + { + case 0x00: // dual return + return RSEchoMode::ECHO_DUAL; + case 0x04: // strongest return + case 0x05: // last return + case 0x06: // first return + default: + return RSEchoMode::ECHO_SINGLE; + } +} + +template +inline void DecoderRSM1_Jumbo::decodeDifopPkt(const uint8_t* packet, size_t size) +{ + const RSM1DifopPkt& pkt = *(RSM1DifopPkt*)packet; + this->echo_mode_ = this->getEchoMode(pkt.return_mode); +} + +template +inline bool DecoderRSM1_Jumbo::decodeMsopPkt(const uint8_t* packet, size_t size) +{ + static const size_t JUMBO_SIZE = 62152; + static const size_t PACKET_SIZE = 984; + static const size_t PACKET_NUM = 63; + bool ret = false; + + if (size != JUMBO_SIZE) + return false; + + size_t off = 0; + for (size_t i = 0; i < PACKET_NUM; i++, off += PACKET_SIZE) + { + bool r = internDecodeMsopPkt(packet+off, PACKET_SIZE); + ret = (ret || r); + } + + return ret; +} + +template +inline bool DecoderRSM1_Jumbo::internDecodeMsopPkt(const uint8_t* packet, size_t size) +{ + const RSM1MsopPkt& pkt = *(RSM1MsopPkt*)packet; + bool ret = false; + + if (memcmp(packet, this->const_param_.MSOP_ID, this->const_param_.MSOP_ID_LEN) != 0) + return false; + + this->temperature_ = static_cast(pkt.header.temperature - this->const_param_.TEMPERATURE_RES); + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) + { + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 1e-6; + } + else + { + uint64_t ts = getTimeHost(); + + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = getTimeHost() * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + } + } + + uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); + if (split_strategy_.newPacket(pkt_seq)) + { + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + ret = true; + } + + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + { + const RSM1Block& block = pkt.blocks[blk]; + + double point_time = pkt_ts + block.time_offset * 1e-6; + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) + { + const RSM1Channel& channel = block.channel[chan]; + + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + + if (this->distance_section_.in(distance)) + { + int pitch = ntohs(channel.pitch) - ANGLE_OFFSET; + int yaw = ntohs(channel.yaw) - ANGLE_OFFSET; + + float x = distance * COS (pitch) * COS (yaw); + float y = distance * COS (pitch) * SIN (yaw); + float z = distance * SIN (pitch); + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, point_time); + setRing(point, chan); + + this->point_cloud_->points.emplace_back(point); + } + else if (!this->param_.dense_points) + { + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, point_time); + setRing(point, chan); + + this->point_cloud_->points.emplace_back(point); + } + } + + this->prev_point_ts_ = point_time; + } + + this->prev_pkt_ts_ = pkt_ts; + return ret; +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/input/input_pcap_jumbo.hpp b/src/rs_driver/driver/input/input_pcap_jumbo.hpp new file mode 100644 index 00000000..e33bac56 --- /dev/null +++ b/src/rs_driver/driver/input/input_pcap_jumbo.hpp @@ -0,0 +1,307 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include +#include + +#include +#include +#include + +#ifdef __linux__ +#elif _WIN32 +#define WIN32 +#endif + +#include + +namespace robosense +{ +namespace lidar +{ + +class jumbo_ip_packet +{ +public: + + jumbo_ip_packet() + : ip_id_(0), buf_off_(0) + { + } + + bool new_fragment(const u_char* pkt_data, size_t pkt_data_size) + { + // Is it an ip packet ? + const u_short* eth_type = (const u_short*)(pkt_data + 12); + if (ntohs(*eth_type) != 0x0800) + return false; + + // is it a udp packet? + const struct iphdr* ip_hdr = (const struct iphdr*)(pkt_data + 14); + if (ip_hdr->protocol != 0x11) + return false; + + // ip data + u_short ip_hdr_size = ip_hdr->ihl * 4; + u_short ip_len = ntohs(ip_hdr->tot_len); + + const u_char* ip_data = pkt_data + 14 + ip_hdr_size; + u_short ip_data_len = ip_len - ip_hdr_size; + + // ip fragment + u_short ip_id = ntohs (ip_hdr->id); + u_short f_off = ntohs(ip_hdr->frag_off); + u_short frag_flags = (f_off >> 13); + u_short frag_off = (f_off & 0x1fff) * 8; // 8 octet boudary + + if (ip_id == ip_id_) + { + if (frag_off == buf_off_) + { + memcpy (buf_ + buf_off_, ip_data, ip_data_len); + buf_off_ += ip_data_len; + + if ((frag_flags & 0x1) == 0) + { + //printf ("--- end new packet. ip_id:0x%x, len:%d\n", ip_id_, buf_off_); + + ip_id_ = 0; + return true; + } + } + } + else + { + if ((frag_off == 0) && ((frag_flags & 0x1) != 0)) + //if (frag_off == 0) + { + ip_id_ = ip_id; + buf_off_ = 0; + + memcpy (buf_ + buf_off_, ip_data, ip_data_len); + buf_off_ += ip_data_len; + + //printf ("+++ start packet 0x%x\n", ip_id_); + } + } + + return false; + } + + u_char* buf() + { + return buf_; + } + + u_short buf_len() + { + return buf_off_; + } + +private: + + u_short ip_id_; + u_char buf_[IP_LEN]; + u_short buf_off_; +}; + +class InputPcapJumbo : public Input +{ +public: + InputPcapJumbo(const RSInputParam& input_param, double sec_to_delay) + : Input(input_param), pcap_(NULL), pcap_offset_(ETH_HDR_LEN), pcap_tail_(0), difop_filter_valid_(false), + msec_to_delay_((uint64_t)(sec_to_delay*1000000)) + { + if (input_param.use_vlan) + { + pcap_offset_ += VLAN_HDR_LEN; + } + + pcap_offset_ += input_param.user_layer_bytes; + pcap_tail_ += input_param.tail_layer_bytes; + + std::stringstream msop_stream, difop_stream; + if (input_param_.use_vlan) + { + msop_stream << "vlan && "; + difop_stream << "vlan && "; + } + + msop_stream << "udp"; + difop_stream << "udp dst port " << input_param_.difop_port; + + msop_filter_str_ = msop_stream.str(); + difop_filter_str_ = difop_stream.str(); + } + + virtual bool init(); + virtual bool start(); + virtual ~InputPcapJumbo(); + +private: + void recvPacket(); + +private: + pcap_t* pcap_; + size_t pcap_offset_; + size_t pcap_tail_; + std::string msop_filter_str_; + std::string difop_filter_str_; + bpf_program msop_filter_; + bpf_program difop_filter_; + bool difop_filter_valid_; + uint64_t msec_to_delay_; + + jumbo_ip_packet jumbo_packet_; +}; + +inline bool InputPcapJumbo::init() +{ + if (init_flag_) + return true; + + char errbuf[PCAP_ERRBUF_SIZE]; + pcap_ = pcap_open_offline(input_param_.pcap_path.c_str(), errbuf); + if (pcap_ == NULL) + { + cb_excep_(Error(ERRCODE_PCAPWRONGPATH)); + return false; + } + + pcap_compile(pcap_, &msop_filter_, msop_filter_str_.c_str(), 1, 0xFFFFFFFF); + + if ((input_param_.difop_port != 0) && (input_param_.difop_port != input_param_.msop_port)) + { + pcap_compile(pcap_, &difop_filter_, difop_filter_str_.c_str(), 1, 0xFFFFFFFF); + difop_filter_valid_ = true; + } + + init_flag_ = true; + return true; +} + +inline bool InputPcapJumbo::start() +{ + if (start_flag_) + return true; + + if (!init_flag_) + { + cb_excep_(Error(ERRCODE_STARTBEFOREINIT)); + return false; + } + + to_exit_recv_ = false; + recv_thread_ = std::thread(std::bind(&InputPcapJumbo::recvPacket, this)); + + start_flag_ = true; + return true; +} + +inline InputPcapJumbo::~InputPcapJumbo() +{ + stop(); + + if (pcap_ != NULL) + { + pcap_close(pcap_); + } +} + +inline void InputPcapJumbo::recvPacket() +{ + while (!to_exit_recv_) + { + struct pcap_pkthdr* header; + const u_char* pkt_data; + int ret = pcap_next_ex(pcap_, &header, &pkt_data); + if (ret < 0) // reach file end. + { + pcap_close(pcap_); + + if (input_param_.pcap_repeat) + { + cb_excep_(Error(ERRCODE_PCAPREPEAT)); + + char errbuf[PCAP_ERRBUF_SIZE]; + pcap_ = pcap_open_offline(input_param_.pcap_path.c_str(), errbuf); + continue; + } + else + { + cb_excep_(Error(ERRCODE_PCAPEXIT)); + break; + } + } + + if (pcap_offline_filter(&msop_filter_, header, pkt_data) != 0) + { + bool new_pkt = jumbo_packet_.new_fragment(pkt_data, header->len); + if (new_pkt) + { + const struct udphdr * udp_hdr = (const struct udphdr*)jumbo_packet_.buf(); + u_short dst_port = ntohs(udp_hdr->dest); + + if (dst_port == input_param_.msop_port) + { +#if 0 + for (uint16_t off = UDP_HDR_LEN; off < jumbo_packet_.buf_len(); off += 984) + { + hexdump (jumbo_packet_.buf() + off, 32, "jumbo_buf"); + } +#endif + std::shared_ptr pkt = cb_get_pkt_(IP_LEN); + memcpy(pkt->data(), jumbo_packet_.buf() + UDP_HDR_LEN, jumbo_packet_.buf_len() - UDP_HDR_LEN); + pkt->setData(0, jumbo_packet_.buf_len() - UDP_HDR_LEN); + pushPacket(pkt); + } + } + } + else if (difop_filter_valid_ && (pcap_offline_filter(&difop_filter_, header, pkt_data) != 0)) + { + std::shared_ptr pkt = cb_get_pkt_(IP_LEN); + memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_ - pcap_tail_); + pkt->setData(0, header->len - pcap_offset_ - pcap_tail_); + pushPacket(pkt); + } + else + { + continue; + } + + std::this_thread::sleep_for(std::chrono::microseconds(msec_to_delay_)); + } +} + +} // namespace lidar +} // namespace robosense From 1e7e5858f7f34b3468b32fbbb55c255de32ab992 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 25 May 2022 17:29:57 +0800 Subject: [PATCH 269/379] feat: support jumbo udp --- .../driver/decoder/decoder_factory.hpp | 4 ++++ src/rs_driver/driver/driver_param.hpp | 23 +++++++++++++++---- src/rs_driver/driver/input/input.hpp | 6 ++++- src/rs_driver/driver/input/input_factory.hpp | 14 +++++++---- src/rs_driver/driver/input/input_pcap.hpp | 7 ++---- src/rs_driver/driver/input/input_raw.hpp | 10 ++++---- .../driver/input/unix/input_sock.hpp | 10 ++++---- .../driver/input/unix/input_sock_epoll.hpp | 8 ++++--- src/rs_driver/driver/input/win/input_sock.hpp | 10 ++++---- src/rs_driver/driver/lidar_driver_impl.hpp | 3 ++- 10 files changed, 64 insertions(+), 31 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index c35bd3b3..fcdab106 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -44,6 +44,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include namespace robosense { @@ -106,6 +107,9 @@ inline std::shared_ptr> DecoderFactory::crea case LidarType::RSEOS: ret_ptr = std::make_shared>(param); break; + case LidarType::RSM1_JUMBO: + ret_ptr = std::make_shared>(param); + break; default: RS_ERROR << "Wrong LiDAR Type. Please check your LiDAR Version! " << RS_REND; exit(-1); diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index d4a804be..9e6d61a0 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -42,7 +42,8 @@ namespace lidar { enum LidarType ///< LiDAR type { - RS16 = 1, + // mechanical + RS16 = 0x01, RS32, RSBP, RS128, @@ -53,9 +54,15 @@ enum LidarType ///< LiDAR type RSHELIOS, RSHELIOS_16P, RSROCK, + + // mems RSM1 = 0x20, RSM2, - RSEOS + RSEOS, + + // jumbo + RS_JUMBO = 0x100, + RSM1_JUMBO = RS_JUMBO + RSM1, }; inline std::string lidarTypeToStr(const LidarType& type) @@ -102,6 +109,9 @@ inline std::string lidarTypeToStr(const LidarType& type) case LidarType::RSEOS: str = "RSEOS"; break; + case LidarType::RSM1_JUMBO: + str = "RSM1_JUMBO"; + break; default: str = "ERROR"; RS_ERROR << "RS_ERROR" << RS_REND; @@ -163,11 +173,16 @@ inline LidarType strToLidarType(const std::string& type) { return lidar::LidarType::RSEOS; } + else if (type == "RSM1_JUMBO") + { + return lidar::LidarType::RSM1_JUMBO; + } else { RS_ERROR << "Wrong lidar type: " << type << RS_REND; - RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS80, RS128, RSP128, RSP80, RSP48, RSM1, RSM2, RSEOS." - << RS_REND; + RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS80, RS128, RSP128, RSP80, RSP48, " + << "RSM1, RSM2, RSEOS, RSM1_JUMBO." + << RS_REND; exit(-1); } } diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index e0e0c240..a2cfc1c3 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -39,7 +39,11 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include -#define MAX_PKT_LEN 1500 +#define VLAN_HDR_LEN 4 +#define ETH_HDR_LEN 42 +#define ETH_LEN (ETH_HDR_LEN + VLAN_HDR_LEN + 1500) +#define IP_LEN 65536 +#define UDP_HDR_LEN 8 namespace robosense { diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index e2aca5bf..a2ff07b4 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -37,6 +37,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #ifdef ENABLE_PCAP_PARSE #include +#include #endif #ifdef __linux__ @@ -61,11 +62,11 @@ namespace lidar class InputFactory { public: - static std::shared_ptr createInput(InputType type, const RSInputParam& param, + static std::shared_ptr createInput(InputType type, const RSInputParam& param, bool isJumbo, double sec_to_delay, std::function& cb_feed_pkt); }; -inline std::shared_ptr InputFactory::createInput(InputType type, const RSInputParam& param, +inline std::shared_ptr InputFactory::createInput(InputType type, const RSInputParam& param, bool isJumbo, double sec_to_delay, std::function& cb_feed_pkt) { std::shared_ptr input; @@ -74,21 +75,24 @@ inline std::shared_ptr InputFactory::createInput(InputType type, const RS { case InputType::ONLINE_LIDAR: { - input = std::make_shared(param); + input = std::make_shared(param, isJumbo); } break; #ifdef ENABLE_PCAP_PARSE case InputType::PCAP_FILE: { - input = std::make_shared(param, sec_to_delay); + if (isJumbo) + input = std::make_shared(param, sec_to_delay); + else + input = std::make_shared(param, sec_to_delay); } break; #endif case InputType::RAW_PACKET: { - std::shared_ptr inputRaw = std::make_shared(param); + std::shared_ptr inputRaw = std::make_shared(param, isJumbo); cb_feed_pkt = std::bind(&InputRaw::feedPacket, inputRaw, std::placeholders::_1, std::placeholders::_2); input = inputRaw; diff --git a/src/rs_driver/driver/input/input_pcap.hpp b/src/rs_driver/driver/input/input_pcap.hpp index 4bbd1593..34016b33 100644 --- a/src/rs_driver/driver/input/input_pcap.hpp +++ b/src/rs_driver/driver/input/input_pcap.hpp @@ -42,9 +42,6 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include -#define ETH_HDR_LEN 42 -#define VLAN_HDR_LEN 4 - namespace robosense { namespace lidar @@ -178,14 +175,14 @@ inline void InputPcap::recvPacket() if (pcap_offline_filter(&msop_filter_, header, pkt_data) != 0) { - std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(ETH_LEN); memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_ - pcap_tail_); pkt->setData(0, header->len - pcap_offset_ - pcap_tail_); pushPacket(pkt); } else if (difop_filter_valid_ && (pcap_offline_filter(&difop_filter_, header, pkt_data) != 0)) { - std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(ETH_LEN); memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_ - pcap_tail_); pkt->setData(0, header->len - pcap_offset_ - pcap_tail_); pushPacket(pkt); diff --git a/src/rs_driver/driver/input/input_raw.hpp b/src/rs_driver/driver/input/input_raw.hpp index a589e322..cd4a283d 100644 --- a/src/rs_driver/driver/input/input_raw.hpp +++ b/src/rs_driver/driver/input/input_raw.hpp @@ -49,15 +49,17 @@ class InputRaw : public Input void feedPacket(const uint8_t* data, size_t size); - InputRaw(const RSInputParam& input_param); + InputRaw(const RSInputParam& input_param, bool isJumbo); private: + const size_t pkt_buf_len_; size_t raw_offset_; size_t raw_tail_; }; -InputRaw::InputRaw(const RSInputParam& input_param) - : Input(input_param), raw_offset_(0), raw_tail_(0) +InputRaw::InputRaw(const RSInputParam& input_param, bool isJumbo) + : Input(input_param), pkt_buf_len_(isJumbo ? IP_LEN : ETH_LEN), + raw_offset_(0), raw_tail_(0) { raw_offset_ += input_param.user_layer_bytes; raw_tail_ += input_param.tail_layer_bytes; @@ -65,7 +67,7 @@ InputRaw::InputRaw(const RSInputParam& input_param) inline void InputRaw::feedPacket(const uint8_t* data, size_t size) { - std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); memcpy(pkt->data(), data + raw_offset_, size - raw_offset_ - raw_tail_); pkt->setData(0, size - raw_offset_ - raw_tail_); pushPacket(pkt); diff --git a/src/rs_driver/driver/input/unix/input_sock.hpp b/src/rs_driver/driver/input/unix/input_sock.hpp index b6965b64..2f134cc8 100644 --- a/src/rs_driver/driver/input/unix/input_sock.hpp +++ b/src/rs_driver/driver/input/unix/input_sock.hpp @@ -48,8 +48,9 @@ namespace lidar class InputSock : public Input { public: - InputSock(const RSInputParam& input_param) - : Input(input_param), sock_offset_(0), sock_tail_(0) + InputSock(const RSInputParam& input_param, bool isJumbo) + : Input(input_param), pkt_buf_len_(isJumbo ? IP_LEN : ETH_LEN), + sock_offset_(0), sock_tail_(0) { sock_offset_ += input_param.user_layer_bytes; sock_tail_ += input_param.tail_layer_bytes; @@ -65,6 +66,7 @@ class InputSock : public Input inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); private: + const size_t pkt_buf_len_; int fds_[2]; size_t sock_offset_; size_t sock_tail_; @@ -287,7 +289,7 @@ inline void InputSock::recvPacket() #else - std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); ssize_t ret = recvfrom(fds_[0], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret < 0) { @@ -304,7 +306,7 @@ inline void InputSock::recvPacket() } else if (FD_ISSET(fds_[1], &rfds)) { - std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); ssize_t ret = recvfrom(fds_[1], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret < 0) { diff --git a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp index 5d2fb3f3..8af4a45b 100644 --- a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp @@ -48,8 +48,9 @@ namespace lidar class InputSock : public Input { public: - InputSock(const RSInputParam& input_param) - : Input(input_param), sock_offset_(0), sock_tail_(0) + InputSock(const RSInputParam& input_param, bool isJumbo) + : Input(input_param), pkt_buf_len_(isJumbo ? IP_LEN : ETH_LEN), + sock_offset_(0), sock_tail_(0) { sock_offset_ += input_param.user_layer_bytes; sock_tail_ += input_param.tail_layer_bytes; @@ -65,6 +66,7 @@ class InputSock : public Input inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); private: + const size_t pkt_buf_len_; int epfd_; int fds_[2]; size_t sock_offset_; @@ -276,7 +278,7 @@ inline void InputSock::recvPacket() { if (events[i].events & EPOLLIN) { - std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); ssize_t ret = recvfrom(events[i].data.fd, pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret < 0) { diff --git a/src/rs_driver/driver/input/win/input_sock.hpp b/src/rs_driver/driver/input/win/input_sock.hpp index b4a2db49..0d6292c5 100644 --- a/src/rs_driver/driver/input/win/input_sock.hpp +++ b/src/rs_driver/driver/input/win/input_sock.hpp @@ -46,8 +46,9 @@ namespace lidar class InputSock : public Input { public: - InputSock(const RSInputParam& input_param) - : Input(input_param), sock_offset_(0), sock_tail_(0) + InputSock(const RSInputParam& input_param, bool isJumbo) + : Input(input_param), pkt_buf_len_(isJumbo ? IP_LEN : ETH_LEN), + sock_offset_(0), sock_tail_(0) { sock_offset_ += input_param.user_layer_bytes; sock_tail_ += input_param.tail_layer_bytes; @@ -62,6 +63,7 @@ class InputSock : public Input inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); private: + const size_t pkt_buf_len_; int fds_[2]; size_t sock_offset_; size_t sock_tail_; @@ -246,7 +248,7 @@ inline void InputSock::recvPacket() if (FD_ISSET(fds_[0], &rfds)) { - std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); int ret = recvfrom(fds_[0], (char*)pkt->buf(), (int)pkt->bufSize(), 0, NULL, NULL); if (ret < 0) { @@ -261,7 +263,7 @@ inline void InputSock::recvPacket() } else if (FD_ISSET(fds_[1], &rfds)) { - std::shared_ptr pkt = cb_get_pkt_(MAX_PKT_LEN); + std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); int ret = recvfrom(fds_[1], (char*)pkt->buf(), (int)pkt->bufSize(), 0, NULL, NULL); if (ret < 0) { diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 38d4e577..aa498fb2 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -186,11 +186,12 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) std::bind(&LidarDriverImpl::splitFrame, this, std::placeholders::_1, std::placeholders::_2)); double packet_duration = decoder_ptr_->getPacketDuration(); + bool isJumbo = (param.lidar_type >= LidarType::RS_JUMBO); // // input // - input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, packet_duration, cb_feed_pkt_); + input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, isJumbo, packet_duration, cb_feed_pkt_); input_ptr_->regCallback( std::bind(&LidarDriverImpl::runExceptionCallback, this, std::placeholders::_1), From 956ea25e815d7649e59c45c7093be4c59a4c9ea5 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 25 May 2022 20:41:59 +0800 Subject: [PATCH 270/379] feat: support m1_jumbo --- .../driver/decoder/decoder_RSM1_Jumbo.hpp | 36 +++++++++++-------- .../driver/input/input_pcap_jumbo.hpp | 7 ++-- .../driver/input/unix/input_sock.hpp | 2 +- 3 files changed, 27 insertions(+), 18 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp b/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp index 110bff01..971f4508 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp @@ -51,16 +51,23 @@ typedef struct { uint8_t time_offset; uint8_t return_seq; - RSM1Channel channel[5]; + RSM1_Jumbo_Channel channel[5]; } RSM1_Jumbo_Block; typedef struct { RSM1MsopHeader header; - RSM1Block blocks[25]; - uint8_t reserved[11]; + RSM1_Jumbo_Block blocks[25]; + uint8_t reserved1[11]; + uint8_t reserved2[16]; } RSM1_Jumbo_MsopPkt; +typedef struct +{ + RSM1_Jumbo_MsopPkt pkts[63]; + uint8_t reserved[160]; +} RSM1_Jumbo; + #pragma pack(pop) template @@ -144,18 +151,17 @@ inline void DecoderRSM1_Jumbo::decodeDifopPkt(const uint8_t* packe template inline bool DecoderRSM1_Jumbo::decodeMsopPkt(const uint8_t* packet, size_t size) { - static const size_t JUMBO_SIZE = 62152; - static const size_t PACKET_SIZE = 984; - static const size_t PACKET_NUM = 63; - bool ret = false; - - if (size != JUMBO_SIZE) + if (size != sizeof(RSM1_Jumbo)) return false; - size_t off = 0; - for (size_t i = 0; i < PACKET_NUM; i++, off += PACKET_SIZE) + constexpr static int PACKET_NUM = 63; + + const RSM1_Jumbo* jumbo = (const RSM1_Jumbo *)packet; + bool ret = false; + + for (size_t i = 0; i < PACKET_NUM; i++) { - bool r = internDecodeMsopPkt(packet+off, PACKET_SIZE); + bool r = internDecodeMsopPkt((const uint8_t*)&(jumbo->pkts[i]), sizeof(RSM1_Jumbo_MsopPkt)); ret = (ret || r); } @@ -165,7 +171,7 @@ inline bool DecoderRSM1_Jumbo::decodeMsopPkt(const uint8_t* packet template inline bool DecoderRSM1_Jumbo::internDecodeMsopPkt(const uint8_t* packet, size_t size) { - const RSM1MsopPkt& pkt = *(RSM1MsopPkt*)packet; + const RSM1_Jumbo_MsopPkt& pkt = *(RSM1_Jumbo_MsopPkt*)packet; bool ret = false; if (memcmp(packet, this->const_param_.MSOP_ID, this->const_param_.MSOP_ID_LEN) != 0) @@ -200,13 +206,13 @@ inline bool DecoderRSM1_Jumbo::internDecodeMsopPkt(const uint8_t* for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { - const RSM1Block& block = pkt.blocks[blk]; + const RSM1_Jumbo_Block& block = pkt.blocks[blk]; double point_time = pkt_ts + block.time_offset * 1e-6; for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { - const RSM1Channel& channel = block.channel[chan]; + const RSM1_Jumbo_Channel& channel = block.channel[chan]; float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; diff --git a/src/rs_driver/driver/input/input_pcap_jumbo.hpp b/src/rs_driver/driver/input/input_pcap_jumbo.hpp index e33bac56..337ce21f 100644 --- a/src/rs_driver/driver/input/input_pcap_jumbo.hpp +++ b/src/rs_driver/driver/input/input_pcap_jumbo.hpp @@ -275,9 +275,12 @@ inline void InputPcapJumbo::recvPacket() if (dst_port == input_param_.msop_port) { #if 0 - for (uint16_t off = UDP_HDR_LEN; off < jumbo_packet_.buf_len(); off += 984) + int i = 0; + for (uint16_t off = UDP_HDR_LEN; off < jumbo_packet_.buf_len(); i++, off += 984) { - hexdump (jumbo_packet_.buf() + off, 32, "jumbo_buf"); + char buf[32]; + sprintf (buf, "jumbo_buf %d", i); + hexdump (jumbo_packet_.buf() + off, 32, buf); } #endif std::shared_ptr pkt = cb_get_pkt_(IP_LEN); diff --git a/src/rs_driver/driver/input/unix/input_sock.hpp b/src/rs_driver/driver/input/unix/input_sock.hpp index 2f134cc8..b2c476d0 100644 --- a/src/rs_driver/driver/input/unix/input_sock.hpp +++ b/src/rs_driver/driver/input/unix/input_sock.hpp @@ -270,7 +270,7 @@ inline void InputSock::recvPacket() memset(msgs, 0, sizeof(msgs)); for (i = 0; i < VLEN; i++) { - pkts[i] = cb_get_pkt_(MAX_PKT_LEN); + pkts[i] = cb_get_pkt_(pkt_buf_len_); iovecs[i].iov_base = pkts[i]->buf(); iovecs[i].iov_len = pkts[i]->bufSize(); msgs[i].msg_hdr.msg_iov = &iovecs[i]; From 9689d4eaa9b204f6977cd526e8c1e58b38f51e4b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 26 May 2022 09:56:39 +0800 Subject: [PATCH 271/379] feat: add jumbo class --- .../driver/input/input_pcap_jumbo.hpp | 112 +---------- src/rs_driver/driver/input/jumbo.hpp | 180 ++++++++++++++++++ 2 files changed, 186 insertions(+), 106 deletions(-) create mode 100644 src/rs_driver/driver/input/jumbo.hpp diff --git a/src/rs_driver/driver/input/input_pcap_jumbo.hpp b/src/rs_driver/driver/input/input_pcap_jumbo.hpp index 337ce21f..ebe478e8 100644 --- a/src/rs_driver/driver/input/input_pcap_jumbo.hpp +++ b/src/rs_driver/driver/input/input_pcap_jumbo.hpp @@ -32,10 +32,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once #include -#include +#include -#include -#include #include #ifdef __linux__ @@ -49,92 +47,6 @@ namespace robosense { namespace lidar { - -class jumbo_ip_packet -{ -public: - - jumbo_ip_packet() - : ip_id_(0), buf_off_(0) - { - } - - bool new_fragment(const u_char* pkt_data, size_t pkt_data_size) - { - // Is it an ip packet ? - const u_short* eth_type = (const u_short*)(pkt_data + 12); - if (ntohs(*eth_type) != 0x0800) - return false; - - // is it a udp packet? - const struct iphdr* ip_hdr = (const struct iphdr*)(pkt_data + 14); - if (ip_hdr->protocol != 0x11) - return false; - - // ip data - u_short ip_hdr_size = ip_hdr->ihl * 4; - u_short ip_len = ntohs(ip_hdr->tot_len); - - const u_char* ip_data = pkt_data + 14 + ip_hdr_size; - u_short ip_data_len = ip_len - ip_hdr_size; - - // ip fragment - u_short ip_id = ntohs (ip_hdr->id); - u_short f_off = ntohs(ip_hdr->frag_off); - u_short frag_flags = (f_off >> 13); - u_short frag_off = (f_off & 0x1fff) * 8; // 8 octet boudary - - if (ip_id == ip_id_) - { - if (frag_off == buf_off_) - { - memcpy (buf_ + buf_off_, ip_data, ip_data_len); - buf_off_ += ip_data_len; - - if ((frag_flags & 0x1) == 0) - { - //printf ("--- end new packet. ip_id:0x%x, len:%d\n", ip_id_, buf_off_); - - ip_id_ = 0; - return true; - } - } - } - else - { - if ((frag_off == 0) && ((frag_flags & 0x1) != 0)) - //if (frag_off == 0) - { - ip_id_ = ip_id; - buf_off_ = 0; - - memcpy (buf_ + buf_off_, ip_data, ip_data_len); - buf_off_ += ip_data_len; - - //printf ("+++ start packet 0x%x\n", ip_id_); - } - } - - return false; - } - - u_char* buf() - { - return buf_; - } - - u_short buf_len() - { - return buf_off_; - } - -private: - - u_short ip_id_; - u_char buf_[IP_LEN]; - u_short buf_off_; -}; - class InputPcapJumbo : public Input { public: @@ -182,7 +94,7 @@ class InputPcapJumbo : public Input bool difop_filter_valid_; uint64_t msec_to_delay_; - jumbo_ip_packet jumbo_packet_; + Jumbo jumbo_; }; inline bool InputPcapJumbo::init() @@ -266,26 +178,14 @@ inline void InputPcapJumbo::recvPacket() if (pcap_offline_filter(&msop_filter_, header, pkt_data) != 0) { - bool new_pkt = jumbo_packet_.new_fragment(pkt_data, header->len); + bool new_pkt = jumbo_.new_fragment(pkt_data, header->len); if (new_pkt) { - const struct udphdr * udp_hdr = (const struct udphdr*)jumbo_packet_.buf(); - u_short dst_port = ntohs(udp_hdr->dest); - - if (dst_port == input_param_.msop_port) + if (jumbo_.dst_port() == input_param_.msop_port) { -#if 0 - int i = 0; - for (uint16_t off = UDP_HDR_LEN; off < jumbo_packet_.buf_len(); i++, off += 984) - { - char buf[32]; - sprintf (buf, "jumbo_buf %d", i); - hexdump (jumbo_packet_.buf() + off, 32, buf); - } -#endif std::shared_ptr pkt = cb_get_pkt_(IP_LEN); - memcpy(pkt->data(), jumbo_packet_.buf() + UDP_HDR_LEN, jumbo_packet_.buf_len() - UDP_HDR_LEN); - pkt->setData(0, jumbo_packet_.buf_len() - UDP_HDR_LEN); + memcpy(pkt->data(), jumbo_.buf() + UDP_HDR_LEN, jumbo_.buf_len() - UDP_HDR_LEN); + pkt->setData(0, jumbo_.buf_len() - UDP_HDR_LEN); pushPacket(pkt); } } diff --git a/src/rs_driver/driver/input/jumbo.hpp b/src/rs_driver/driver/input/jumbo.hpp new file mode 100644 index 00000000..eb2da112 --- /dev/null +++ b/src/rs_driver/driver/input/jumbo.hpp @@ -0,0 +1,180 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include + +namespace robosense +{ +namespace lidar +{ + +#pragma pack(push, 1) + +struct iphdr +{ + u_char version; + u_char tos; + u_short tot_len; + + u_short id; + u_short frag_off; + + u_char ttl; + u_char protocol; + u_short check; + + u_int saddr; + u_int daddr; +}; + +struct udphdr +{ + u_short source; + u_short dest; + u_short len; + u_short check; +}; + +#pragma pack(pop) + +class Jumbo +{ +public: + + Jumbo() + : ip_id_(0), buf_off_(0) + { + } + + u_char* buf() + { + return buf_; + } + + u_short buf_len() + { + return buf_off_; + } + + bool new_fragment(const u_char* pkt_data, size_t pkt_data_size); + + u_short dst_port(); + +private: + + u_short ip_id_; + u_char buf_[IP_LEN]; + u_short buf_off_; +}; + +inline bool Jumbo::new_fragment(const u_char* pkt_data, size_t pkt_data_size) +{ + // Is it an ip packet ? + const u_short* eth_type = (const u_short*)(pkt_data + 12); + if (ntohs(*eth_type) != 0x0800) + return false; + + // is it a udp packet? + const struct iphdr* ip_hdr = (const struct iphdr*)(pkt_data + 14); + if (ip_hdr->protocol != 0x11) + return false; + + // ip data + //u_short ip_hdr_size = ip_hdr->ihl * 4; + u_short ip_hdr_size = (ip_hdr->version & 0xf) * 4; + u_short ip_len = ntohs(ip_hdr->tot_len); + + const u_char* ip_data = pkt_data + 14 + ip_hdr_size; + u_short ip_data_len = ip_len - ip_hdr_size; + + // ip fragment + u_short ip_id = ntohs (ip_hdr->id); + u_short f_off = ntohs(ip_hdr->frag_off); + u_short frag_flags = (f_off >> 13); + u_short frag_off = (f_off & 0x1fff) * 8; // 8 octet boudary + + if (ip_id == ip_id_) + { + if (frag_off == buf_off_) + { + memcpy (buf_ + buf_off_, ip_data, ip_data_len); + buf_off_ += ip_data_len; + + if ((frag_flags & 0x1) == 0) + { +#if 0 + printf ("--- end new packet. ip_id:0x%x, len:%d\n", ip_id_, buf_off_); + + for (uint16_t off = UDP_HDR_LEN, i = 0; off < buf_len(); off += 984, i++) + { + char title[32]; + sprintf (title, "jumbo %d ", i); + + hexdump (buf() + off, 32, title); + } +#endif + + ip_id_ = 0; + return true; + } + } + } + else + { + if ((frag_off == 0) && ((frag_flags & 0x1) != 0)) + //if (frag_off == 0) + { + ip_id_ = ip_id; + buf_off_ = 0; + + memcpy (buf_ + buf_off_, ip_data, ip_data_len); + buf_off_ += ip_data_len; + +#if 0 + printf ("+++ start packet 0x%x\n", ip_id_); +#endif + } + } + + return false; +} + +inline u_short Jumbo::dst_port() +{ + const struct udphdr * udp_hdr = (const struct udphdr*)buf_; + return ntohs(udp_hdr->dest); +} + +} // namespace lidar +} // namespace robosense From 27500f929180e17fe1150d0db7d21f207aafafc0 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 26 May 2022 10:30:35 +0800 Subject: [PATCH 272/379] feat: support jumbo --- src/rs_driver/driver/input/input_factory.hpp | 31 ++++++----- src/rs_driver/driver/input/input_raw.hpp | 10 ++-- .../driver/input/input_raw_jumbo.hpp | 53 +++++++++++++++++++ src/rs_driver/driver/input/input_sock.hpp | 17 ++++++ .../driver/input/input_sock_jumbo.hpp | 23 ++++++++ .../driver/input/unix/input_sock_epoll.hpp | 8 +-- .../{input_sock.hpp => input_sock_select.hpp} | 8 +-- .../{input_sock.hpp => input_sock_select.hpp} | 8 +-- 8 files changed, 125 insertions(+), 33 deletions(-) create mode 100644 src/rs_driver/driver/input/input_raw_jumbo.hpp create mode 100644 src/rs_driver/driver/input/input_sock.hpp create mode 100644 src/rs_driver/driver/input/input_sock_jumbo.hpp rename src/rs_driver/driver/input/unix/{input_sock.hpp => input_sock_select.hpp} (98%) rename src/rs_driver/driver/input/win/{input_sock.hpp => input_sock_select.hpp} (97%) diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index a2ff07b4..e5765157 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -34,26 +34,15 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include +#include +#include +#include #ifdef ENABLE_PCAP_PARSE #include #include #endif -#ifdef __linux__ - -#ifdef ENABLE_EPOLL_RECEIVE -#include -#else -#include -#endif - -#elif _WIN32 - -#include - -#endif - namespace robosense { namespace lidar @@ -75,7 +64,10 @@ inline std::shared_ptr InputFactory::createInput(InputType type, const RS { case InputType::ONLINE_LIDAR: { - input = std::make_shared(param, isJumbo); + if (isJumbo) + input = std::make_shared(param); + else + input = std::make_shared(param); } break; @@ -92,9 +84,16 @@ inline std::shared_ptr InputFactory::createInput(InputType type, const RS case InputType::RAW_PACKET: { - std::shared_ptr inputRaw = std::make_shared(param, isJumbo); + std::shared_ptr inputRaw; + + if (isJumbo) + inputRaw = std::make_shared(param); + else + inputRaw = std::make_shared(param); + cb_feed_pkt = std::bind(&InputRaw::feedPacket, inputRaw, std::placeholders::_1, std::placeholders::_2); + input = inputRaw; } break; diff --git a/src/rs_driver/driver/input/input_raw.hpp b/src/rs_driver/driver/input/input_raw.hpp index cd4a283d..da1b793f 100644 --- a/src/rs_driver/driver/input/input_raw.hpp +++ b/src/rs_driver/driver/input/input_raw.hpp @@ -49,16 +49,16 @@ class InputRaw : public Input void feedPacket(const uint8_t* data, size_t size); - InputRaw(const RSInputParam& input_param, bool isJumbo); + InputRaw(const RSInputParam& input_param); -private: - const size_t pkt_buf_len_; +protected: + size_t pkt_buf_len_; size_t raw_offset_; size_t raw_tail_; }; -InputRaw::InputRaw(const RSInputParam& input_param, bool isJumbo) - : Input(input_param), pkt_buf_len_(isJumbo ? IP_LEN : ETH_LEN), +InputRaw::InputRaw(const RSInputParam& input_param) + : Input(input_param), pkt_buf_len_(ETH_LEN), raw_offset_(0), raw_tail_(0) { raw_offset_ += input_param.user_layer_bytes; diff --git a/src/rs_driver/driver/input/input_raw_jumbo.hpp b/src/rs_driver/driver/input/input_raw_jumbo.hpp new file mode 100644 index 00000000..1c9ca0ff --- /dev/null +++ b/src/rs_driver/driver/input/input_raw_jumbo.hpp @@ -0,0 +1,53 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include + +namespace robosense +{ +namespace lidar +{ +class InputRawJumbo : public InputRaw +{ +public: + + InputRawJumbo(const RSInputParam& input_param) + : InputRaw(input_param) + { + pkt_buf_len_ = IP_LEN; + } +}; + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/input/input_sock.hpp b/src/rs_driver/driver/input/input_sock.hpp new file mode 100644 index 00000000..daca9851 --- /dev/null +++ b/src/rs_driver/driver/input/input_sock.hpp @@ -0,0 +1,17 @@ + +#pragma once + +#ifdef __linux__ + +#ifdef ENABLE_EPOLL_RECEIVE +#include +#else +#include +#endif + +#elif _WIN32 + +#include + +#endif + diff --git a/src/rs_driver/driver/input/input_sock_jumbo.hpp b/src/rs_driver/driver/input/input_sock_jumbo.hpp new file mode 100644 index 00000000..cc197fad --- /dev/null +++ b/src/rs_driver/driver/input/input_sock_jumbo.hpp @@ -0,0 +1,23 @@ + +#pragma once + +#include + +namespace robosense +{ +namespace lidar +{ + +class InputSockJumbo : public InputSock +{ +public: + + InputSockJumbo(const RSInputParam& input_param) + : InputSock(input_param) + { + pkt_buf_len_ = IP_LEN; + } +}; + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp index 8af4a45b..6b527292 100644 --- a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp @@ -48,8 +48,8 @@ namespace lidar class InputSock : public Input { public: - InputSock(const RSInputParam& input_param, bool isJumbo) - : Input(input_param), pkt_buf_len_(isJumbo ? IP_LEN : ETH_LEN), + InputSock(const RSInputParam& input_param) + : Input(input_param), pkt_buf_len_(ETH_LEN), sock_offset_(0), sock_tail_(0) { sock_offset_ += input_param.user_layer_bytes; @@ -65,8 +65,8 @@ class InputSock : public Input inline void higherThreadPrioty(std::thread::native_handle_type handle); inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); -private: - const size_t pkt_buf_len_; +protected: + size_t pkt_buf_len_; int epfd_; int fds_[2]; size_t sock_offset_; diff --git a/src/rs_driver/driver/input/unix/input_sock.hpp b/src/rs_driver/driver/input/unix/input_sock_select.hpp similarity index 98% rename from src/rs_driver/driver/input/unix/input_sock.hpp rename to src/rs_driver/driver/input/unix/input_sock_select.hpp index b2c476d0..592a7cce 100644 --- a/src/rs_driver/driver/input/unix/input_sock.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_select.hpp @@ -48,8 +48,8 @@ namespace lidar class InputSock : public Input { public: - InputSock(const RSInputParam& input_param, bool isJumbo) - : Input(input_param), pkt_buf_len_(isJumbo ? IP_LEN : ETH_LEN), + InputSock(const RSInputParam& input_param) + : Input(input_param), pkt_buf_len_(ETH_LEN), sock_offset_(0), sock_tail_(0) { sock_offset_ += input_param.user_layer_bytes; @@ -65,8 +65,8 @@ class InputSock : public Input inline void higherThreadPrioty(std::thread::native_handle_type handle); inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); -private: - const size_t pkt_buf_len_; +protected: + size_t pkt_buf_len_; int fds_[2]; size_t sock_offset_; size_t sock_tail_; diff --git a/src/rs_driver/driver/input/win/input_sock.hpp b/src/rs_driver/driver/input/win/input_sock_select.hpp similarity index 97% rename from src/rs_driver/driver/input/win/input_sock.hpp rename to src/rs_driver/driver/input/win/input_sock_select.hpp index 0d6292c5..44497545 100644 --- a/src/rs_driver/driver/input/win/input_sock.hpp +++ b/src/rs_driver/driver/input/win/input_sock_select.hpp @@ -46,8 +46,8 @@ namespace lidar class InputSock : public Input { public: - InputSock(const RSInputParam& input_param, bool isJumbo) - : Input(input_param), pkt_buf_len_(isJumbo ? IP_LEN : ETH_LEN), + InputSock(const RSInputParam& input_param) + : Input(input_param), pkt_buf_len_(ETH_LEN), sock_offset_(0), sock_tail_(0) { sock_offset_ += input_param.user_layer_bytes; @@ -62,8 +62,8 @@ class InputSock : public Input inline void recvPacket(); inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); -private: - const size_t pkt_buf_len_; +protected: + size_t pkt_buf_len_; int fds_[2]; size_t sock_offset_; size_t sock_tail_; From b9d5eb7d22e5d7384cd64ef5e41a7a0f39b17b98 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 26 May 2022 12:12:44 +0800 Subject: [PATCH 273/379] fix compiling error --- src/rs_driver/driver/input/input_raw.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rs_driver/driver/input/input_raw.hpp b/src/rs_driver/driver/input/input_raw.hpp index da1b793f..201e02c4 100644 --- a/src/rs_driver/driver/input/input_raw.hpp +++ b/src/rs_driver/driver/input/input_raw.hpp @@ -57,7 +57,7 @@ class InputRaw : public Input size_t raw_tail_; }; -InputRaw::InputRaw(const RSInputParam& input_param) +inline InputRaw::InputRaw(const RSInputParam& input_param) : Input(input_param), pkt_buf_len_(ETH_LEN), raw_offset_(0), raw_tail_(0) { From 126e90ef7f42fe4bc391bc700bc0caca6ce9b6c8 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 31 May 2022 10:49:29 +0800 Subject: [PATCH 274/379] feat: disable unused-para waringing --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 10801e54..b5449f32 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -65,7 +65,7 @@ elseif(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") message(FATAL_ERROR "Unsupported compiler.") endif() - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++14") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -Wall -Wno-unused-parameter") set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -g") set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3") endif() From 3f2031037a96c4fb0ef0d48e7bf48a9ea88ccaec Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 1 Jun 2022 10:01:27 +0800 Subject: [PATCH 275/379] fix: fix test cases --- src/rs_driver/driver/decoder/decoder.hpp | 2 +- test/decoder_rs16_test.cpp | 155 -------------- test/decoder_test.cpp | 255 ++++------------------- 3 files changed, 37 insertions(+), 375 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index d38e78a1..71e539d8 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -390,7 +390,7 @@ inline bool Decoder::processMsopPkt(const uint8_t* pkt, size_t siz { constexpr static int CLOUD_POINT_MAX = 1000000; - if (this->point_cloud_->points.size() > CLOUD_POINT_MAX) + if (this->point_cloud_ && (this->point_cloud_->points.size() > CLOUD_POINT_MAX)) { LIMIT_CALL(this->cb_excep_(Error(ERRCODE_CLOUDBUFOVERFLOW)), 1); } diff --git a/test/decoder_rs16_test.cpp b/test/decoder_rs16_test.cpp index 536e00eb..2ce99185 100644 --- a/test/decoder_rs16_test.cpp +++ b/test/decoder_rs16_test.cpp @@ -50,158 +50,3 @@ TEST(TestDecoderRS16, RS16DifopPkt2Adapter) ASSERT_EQ(ntohs(dst.horiz_angle_cali[0].value), 0); } -#if 0 - -static ErrCode errCode = ERRCODE_SUCCESS; -static void errCallback(const Error& err) -{ - errCode = err.error_code; -} - - -TEST(TestDecoderRS16, decodeDifopPkt) -{ - // const_param - RSDecoderParam param; - DecoderRS16 decoder(param, errCallback); - ASSERT_EQ(decoder.blks_per_frame_, 1801); - ASSERT_EQ(decoder.split_blks_per_frame_, 1801); - - // rpm = 600, dual return - RS32DifopPkt pkt; - pkt.rpm = htons(600); - pkt.return_mode = 0; - decoder.decodeDifopPkt((uint8_t*)&pkt, sizeof(pkt)); - ASSERT_EQ(decoder.rps_, 10); - ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_DUAL); - ASSERT_EQ(decoder.blks_per_frame_, 1801); - ASSERT_EQ(decoder.split_blks_per_frame_, 3602); - - // rpm = 1200, single return - pkt.rpm = htons(1200); - pkt.return_mode = 1; - decoder.decodeDifopPkt((uint8_t*)&pkt, sizeof(pkt)); - ASSERT_EQ(decoder.rps_, 20); - ASSERT_EQ(decoder.echo_mode_, RSEchoMode::ECHO_SINGLE); - ASSERT_EQ(decoder.blks_per_frame_, 900); - ASSERT_EQ(decoder.split_blks_per_frame_, 900); -} - -static void splitFrame(uint16_t height, double ts) -{ -} - -TEST(TestDecoderRS16, decodeMsopPkt) -{ - uint8_t pkt[] = - { - // - // header - // - 0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0, // msop id - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // reserved_1 - 0x15, 0x0a, 0x01, 0x01, 0x02, 0x03, 0x11, 0x22, 0x33, 0x44, // ts_YMD - 0x00, // lidar type - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // reserved_2 - 0x18, 0x01, // temprature - 0x00, 0x00, // reserved_3 - - // - // block_01 - // - 0xFF, 0xEE, // block id - 0x00, 0x00, // azimuth - 0x03, 0xE8, // chan_00, distance - 0x01, // chan_00, intensity - 0x00, 0x00, // chan_01, distance - 0x00, // chan_01, intensity - 0x00, 0x00, // chan_02, distance - 0x00, // chan_02, intensity - 0x00, 0x00, // chan_03, distance - 0x00, // chan_03, intensity - 0x00, 0x00, // chan_04, distance - 0x00, // chan_04, intensity - 0x00, 0x00, // chan_05, distance - 0x00, // chan_05, intensity - 0x00, 0x00, // chan_06, distance - 0x00, // chan_06, intensity - 0x00, 0x00, // chan_07, distance - 0x00, // chan_07, intensity - 0x00, 0x00, // chan_08, distance - 0x00, // chan_08, intensity - 0x00, 0x00, // chan_09, distance - 0x00, // chan_09, intensity - 0x00, 0x00, // chan_10, distance - 0x00, // chan_10, intensity - 0x00, 0x00, // chan_11, distance - 0x00, // chan_11, intensity - 0x00, 0x00, // chan_12, distance - 0x00, // chan_12, intensity - 0x00, 0x00, // chan_13, distance - 0x00, // chan_13, intensity - 0x00, 0x00, // chan_14, distance - 0x00, // chan_14, intensity - 0x00, 0x00, // chan_15, distance - 0x00, // chan_15, intensity - 0x00, 0x00, // chan_16, distance - 0x00, // chan_16, intensity - 0x00, 0x00, // chan_17, distance - 0x00, // chan_17, intensity - 0x00, 0x00, // chan_18, distance - 0x00, // chan_18, intensity - 0x00, 0x00, // chan_19, distance - 0x00, // chan_19, intensity - 0x00, 0x00, // chan_20, distance - 0x00, // chan_20, intensity - 0x00, 0x00, // chan_21, distance - 0x00, // chan_21, intensity - 0x00, 0x00, // chan_22, distance - 0x00, // chan_22, intensity - 0x00, 0x00, // chan_23, distance - 0x00, // chan_23, intensity - 0x00, 0x00, // chan_24, distance - 0x00, // chan_24, intensity - 0x00, 0x00, // chan_25, distance - 0x00, // chan_25, intensity - 0x00, 0x00, // chan_26, distance - 0x00, // chan_26, intensity - 0x00, 0x00, // chan_27, distance - 0x00, // chan_27, intensity - 0x00, 0x00, // chan_28, distance - 0x00, // chan_28, intensity - 0x00, 0x00, // chan_29, distance - 0x00, // chan_29, intensity - 0x00, 0x00, // chan_30, distance - 0x00, // chan_30, intensity - 0x00, 0x00, // chan_31, distance - 0x00, // chan_31, intensity - - // - // block_02 - // - 0x00, 0x00, // block id - }; - - // dense_points = false, use_lidar_clock = true - RSDecoderParam param; - DecoderRS16 decoder(param, errCallback); - ASSERT_EQ(decoder.chan_angles_.user_chans_.size(), 32); - decoder.chan_angles_.user_chans_[0] = 2; - decoder.chan_angles_.user_chans_[1] = 1; - decoder.param_.dense_points = false; - decoder.param_.use_lidar_clock = true; - - decoder.point_cloud_ = std::make_shared(); - decoder.setSplitCallback(splitFrame); - - decoder.decodeMsopPkt(pkt, sizeof(pkt)); - ASSERT_EQ(decoder.getTemperature(), 2.1875); - ASSERT_EQ(decoder.point_cloud_->points.size(), 32); - - PointT& point = decoder.point_cloud_->points[0]; - ASSERT_EQ(point.intensity, 1); - ASSERT_NE(point.timestamp, 0); - ASSERT_EQ(point.ring, 2); -} -#endif - diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 78b174c9..377a8818 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -88,15 +88,15 @@ TEST(TestDecoder, angles_from_file_fail) TEST(TestDecoder, processDifopPkt_fail) { - RSDecoderMechConstParam const_param = - { - sizeof(MyMsopPkt) // msop len - , sizeof(MyDifopPkt) // difop len - , 8 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id - , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - }; + RSDecoderMechConstParam const_param = + { + sizeof(MyMsopPkt) // msop len + , sizeof(MyDifopPkt) // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + }; RSDecoderParam param; MyDecoder decoder(const_param, param); @@ -119,10 +119,10 @@ TEST(TestDecoder, processDifopPkt) RSDecoderMechConstParam const_param = { sizeof(MyMsopPkt) // msop len - , sizeof(MyDifopPkt) // difop len - , 8 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , sizeof(MyDifopPkt) // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id , {0xFF, 0xEE} // block id , 2 // laser number @@ -201,19 +201,19 @@ TEST(TestDecoder, processDifopPkt) TEST(TestDecoder, processDifopPkt_invalid_rpm) { - RSDecoderMechConstParam const_param = - { - sizeof(MyMsopPkt) // msop len - , sizeof(MyDifopPkt) // difop len - , 8 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id - , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - , {0xFF, 0xEE} // block id - , 32 // laser number - , 12 // blocks per packet - , 32 // channels per block - }; + RSDecoderMechConstParam const_param = + { + sizeof(MyMsopPkt) // msop len + , sizeof(MyDifopPkt) // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 32 // laser number + , 12 // blocks per packet + , 32 // channels per block + }; RSDecoderParam param; MyDecoder decoder(const_param, param); @@ -233,15 +233,15 @@ TEST(TestDecoder, processDifopPkt_invalid_rpm) TEST(TestDecoder, processMsopPkt) { - RSDecoderMechConstParam const_param = - { - sizeof(MyMsopPkt) // msop len - , sizeof(MyDifopPkt) // difop len - , 8 // msop id len - , 8 // difop id len - , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id - , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id - }; + RSDecoderMechConstParam const_param = + { + sizeof(MyMsopPkt) // msop len + , sizeof(MyDifopPkt) // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + }; MyMsopPkt pkt; RSDecoderParam param; @@ -253,7 +253,7 @@ TEST(TestDecoder, processMsopPkt) decoder.angles_ready_ = false; errCode = ERRCODE_SUCCESS; decoder.processMsopPkt((const uint8_t*)&pkt, 2); - ASSERT_EQ(errCode, 0); + ASSERT_EQ(errCode, ERRCODE_SUCCESS); #if 0 sleep(2); @@ -285,186 +285,3 @@ TEST(TestDecoder, processMsopPkt) ASSERT_EQ(errCode, ERRCODE_SUCCESS); } -#if 0 -TEST(TestDecoder, setPointCloudHeader) -{ - // dense_points - RSDecoderMechConstParam const_param = {}; - const_param.base.CHANNELS_PER_BLOCK = 2; - RSDecoderParam param; - param.dense_points = true; - MyDecoder decoder(const_param, param, errCallback); - ASSERT_EQ(decoder.point_cloud_seq_, 0); - ASSERT_TRUE(decoder.param_.dense_points); - - std::shared_ptr pt = std::make_shared(); - PointT point; - pt->points.emplace_back(point); - pt->points.emplace_back(point); - - // dense_points = true - { - decoder.setPointCloudHeader(pt, 0.5f); - ASSERT_EQ(pt->seq, 0); - ASSERT_EQ(pt->timestamp, 0.5f); - ASSERT_TRUE(pt->is_dense); - ASSERT_EQ(pt->height, 1); - ASSERT_EQ(pt->width, 2); - } - - // dense_points = false - decoder.param_.dense_points = false; - { - decoder.setPointCloudHeader(pt, 0.5f); - ASSERT_EQ(pt->seq, 1); - ASSERT_EQ(pt->timestamp, 0.5f); - ASSERT_FALSE(pt->is_dense); - ASSERT_EQ(pt->height, 2); - ASSERT_EQ(pt->width, 1); - } -} - -std::shared_ptr point_cloud_to_get; - -std::shared_ptr getCallback(void) -{ - return point_cloud_to_get; -} - -bool flag_point_cloud = false; -std::shared_ptr point_cloud_to_put; - -void putCallback(std::shared_ptr pt) -{ - point_cloud_to_put = pt; - flag_point_cloud = true; -} - -TEST(TestDecoder, split_by_angle) -{ - RSDecoderMechConstParam const_param; - const_param.base.CHANNELS_PER_BLOCK = 2; - - RSDecoderParam param; - param.split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; - param.split_angle = 0.0f; - - MyDecoder decoder(param, errCallback, const_param); - - point_cloud_to_get = std::make_shared(); - decoder.regRecvCallback (getCallback, putCallback); - - { - // not cross split angle yet. - errCode = ERRCODE_SUCCESS; - flag_point_cloud = false; - decoder.newBlock (35999); - ASSERT_EQ(errCode, ERRCODE_SUCCESS); - ASSERT_FALSE(flag_point_cloud); - - // cross split angle. no points in point cloud. - errCode = ERRCODE_SUCCESS; - decoder.newBlock (2); - ASSERT_EQ(errCode, ERRCODE_ZEROPOINTS); - } - - // cross split angle. points in point cloud. - { - PointT point; - point_cloud_to_get->points.emplace_back(point); - point_cloud_to_get->points.emplace_back(point); - - errCode = ERRCODE_SUCCESS; - flag_point_cloud = false; - decoder.newBlock (1); - ASSERT_EQ(errCode, ERRCODE_SUCCESS); - ASSERT_TRUE(flag_point_cloud); - ASSERT_TRUE(point_cloud_to_put.get() != NULL); - ASSERT_EQ(point_cloud_to_put->height, 2); - ASSERT_EQ(point_cloud_to_put->width, 1); - } -} - -TEST(TestDecoder, split_by_fixed_pkts) -{ - RSDecoderMechConstParam const_param; - const_param.base.CHANNELS_PER_BLOCK = 2; - - RSDecoderParam param; - param.split_frame_mode = SplitFrameMode::SPLIT_BY_FIXED_BLKS; - - MyDecoder decoder(param, errCallback, const_param); - decoder.split_blks_per_frame_ = 2; - - point_cloud_to_get = std::make_shared(); - decoder.regRecvCallback (getCallback, putCallback); - - PointT point; - point_cloud_to_get->points.emplace_back(point); - point_cloud_to_get->points.emplace_back(point); - - { - // blocks < split_blks_per_frame_ - errCode = ERRCODE_SUCCESS; - flag_point_cloud = false; - decoder.newBlock (0); - ASSERT_EQ(errCode, ERRCODE_SUCCESS); - ASSERT_FALSE(flag_point_cloud); - } - - { - // blocks = split_blks_per_frame_ - errCode = ERRCODE_SUCCESS; - flag_point_cloud = false; - decoder.newBlock (0); - ASSERT_EQ(errCode, ERRCODE_SUCCESS); - ASSERT_TRUE(flag_point_cloud); - - ASSERT_TRUE(point_cloud_to_put.get() != NULL); - ASSERT_EQ(point_cloud_to_put->height, 2); - ASSERT_EQ(point_cloud_to_put->width, 1); - } -} - -TEST(TestDecoder, split_by_custom_blks) -{ - RSDecoderMechConstParam const_param; - const_param.base.CHANNELS_PER_BLOCK = 2; - - RSDecoderParam param; - param.split_frame_mode = SplitFrameMode::SPLIT_BY_CUSTOM_BLKS; - param.num_blks_split = 2; - - MyDecoder decoder(param, errCallback, const_param); - - point_cloud_to_get = std::make_shared(); - decoder.regRecvCallback (getCallback, putCallback); - - PointT point; - point_cloud_to_get->points.emplace_back(point); - point_cloud_to_get->points.emplace_back(point); - - { - // blocks < num_blks_split - errCode = ERRCODE_SUCCESS; - flag_point_cloud = false; - decoder.newBlock (0); - ASSERT_EQ(errCode, ERRCODE_SUCCESS); - ASSERT_FALSE(flag_point_cloud); - } - - { - // blocks = num_blks_split - errCode = ERRCODE_SUCCESS; - flag_point_cloud = false; - decoder.newBlock (0); - ASSERT_EQ(errCode, ERRCODE_SUCCESS); - ASSERT_TRUE(flag_point_cloud); - - ASSERT_TRUE(point_cloud_to_put.get() != NULL); - ASSERT_EQ(point_cloud_to_put->height, 2); - ASSERT_EQ(point_cloud_to_put->width, 1); - } -} -#endif - From cd6651cf3884a3ed914c7af3893c5a33bc15520b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 1 Jun 2022 12:03:10 +0800 Subject: [PATCH 276/379] feat: update rs_driver_viewer --- doc/howto/how_to_use_rs_driver_viewer.md | 28 ++-- doc/img/14_rs_driver_viewer_point_cloud.png | Bin 0 -> 66986 bytes tool/CMakeLists.txt | 4 +- tool/rs_driver_viewer.cpp | 142 +++++++------------- 4 files changed, 65 insertions(+), 109 deletions(-) create mode 100644 doc/img/14_rs_driver_viewer_point_cloud.png diff --git a/doc/howto/how_to_use_rs_driver_viewer.md b/doc/howto/how_to_use_rs_driver_viewer.md index 7965eead..2da41b95 100644 --- a/doc/howto/how_to_use_rs_driver_viewer.md +++ b/doc/howto/how_to_use_rs_driver_viewer.md @@ -4,6 +4,8 @@ The rs_driver_viewer is a visualization tool for the point cloud. This document illustrates how to use it. +![](../img/14_rs_driver_viewer_point_cloud.png) + ## 2 Compile and Run Compile the driver with the option COMPILE_TOOLS=ON. @@ -20,10 +22,18 @@ Run the tool. ### 2.1 Help Menu -- -h/--help +- -h print the argument menu +- -type + + LiDAR type, the default value is *RS16* + +- -pcap + + Full path of the PCAP file. If this argument is set, the driver read packets from the pcap file, else from online Lidar. + - -msop MSOP port number of LiDAR, the default value is *6699* @@ -32,21 +42,13 @@ Run the tool. DIFOP port number of LiDAR, the default value is *7788* -- -host - - the host address - - -group the multicast group address -- -pcap - - Full path of the PCAP file. If this argument is empty, the driver read packets from online Lidar, else from the PCAP file. - -- -type +- -host - LiDAR type, the default value is *RS16* + the host address - -x @@ -81,13 +83,13 @@ Note: - Decode from an online RS128 LiDAR. Its MSOP port is ```9966```, and difop port is ```8877``` ```bash - rs_driver_viewer -msop 9966 -difop 8877 -type RS128 + rs_driver_viewer -type RS128 -msop 9966 -difop 8877 ``` - Decode from a PCAP file with RSHELIOS LiDAR data. ```bash - rs_driver_viewer -pcap /home/robosense/helios.pcap -type RSHELIOS + rs_driver_viewer -type RSHELIOS -pcap /home/robosense/helios.pcap ``` - Decode with the coordinate transformation parameters: x=1.5, y=2, z=0, roll=1.57, pitch=0, yaw=0 diff --git a/doc/img/14_rs_driver_viewer_point_cloud.png b/doc/img/14_rs_driver_viewer_point_cloud.png new file mode 100644 index 0000000000000000000000000000000000000000..9e99ad5f0c8abb023607bb6b47dbf6b5846cd0a6 GIT binary patch literal 66986 zcmbrlWl&tf)-H^@I|L6Jd~kOQF2UV`1b24{1SdEFg1fs7?iL8{PH?vYzJYVkd+(21 z_5HYAH8srMyI1#K>**y=H{X>NrBRWHkRTu+P-SH#R3RXsnIRycun^$DS3db<41>QA z9b~kfAt2ED-ae2&8PGmJK#)VoN{Fg^WFD`2`cS!Mym;@qP{&B!bTd+k z|M=Hq6SjG)JF?K*6~BMIvaR*B_4G5}X{oU0-TuGRm!#*C!+@VUX74}@!%6I#C=(PS3=p1@#u-13OGHiU>BMzQ!U`5Twq*RQmr^OZ*EZ3m01&Wu+k z@GvfQ|AYMNP_Rykmce3uC^ zwYD~~m8d!O!6FcYU(-N}@mRI+Km8-62*UbCwswLthnuzTRzJs$;(6&&zBgzXV-6KY z7=D-_a=Po(|0n|v0ZMHh%M}-yQ$hay3e7l_#!nc=n6$p3m(1}AgN*M|AB+jGq^e?+ z#xdT9FsszTME7{wvSY41Hkb9;_*Utwoe@n!4cZVP^sc=Pxh2E;BL-ay*fmi7_3YRSZx+x)H zhVtT~a+eyM{8Fj4F#aWK;H8zd^>Dr`Vo09L9(vyQnfbKkSx(RQa^dUil6jPt??3u- z#_SD8)34{ZN>9Zltidhyt)m~LnmLb{ck2v8A;EgXgy-U!aYW}AzkI#;MT07 z&+m+;Oot2f8KYv0>KuzpOeiT$EwcMEgl>2f@H6}VgkI4#)Vh!^jbAAV$&a2iIUH4G z)4nnYbYA|{bJi!Z_v!ai)WM78gBz!-LtWlG*LOFKx z$J3JAR+semL!n0pH#AN57x+@z#cQrH^f#*YVQH;Ko-nF4 zvIM&}Vo2*t^`$v&otIT6E5Z=0;~tYi?_t&3=d;5a{`%ygUww2AXxHap)Nn)pFSVAj z3$}P%dx-WibDQ!Oi__ z!6=<3v`N9WTKBy-r86cpCdzw++jFnPXU9Zsn}&xMts5=Y+izVmE(^$ug_&j?hO8)s zY)#VxWuU*ve?GyQbM(Tm<*@pd!a!_aa2+ZKRO=3SZJl)3`EY0|D!11ErDLVJ$z*nY zG*{bSRlgsMXqM6Bs*dm@yEUod+8NI$;a7e#uU)YT?<4c_hYN-FW+71%TSN^zhV`eR z8_->Ec#bva*Iyl}_}QbVOPVpXT^D|pZ4aKul3y==`9EWk@%SU+8$5d%JYHp-YY&9E z`^TZTpO`2bYL86gzsii>+3gH0lkGbo^i6KrlKHWuOnS$kyN`qRvC%Z2XQZ3A#v01C zYU4_4<8Db}o!6OO`~BB1a7dnC`TCUhgV$Gw-~-pBJNw#%K)!CFQ4YeFh?T|kw8tLl z{GFHPon42#x90mbmq{tkMCf%)5GK8uMBY0WI>>8d_>Cp+nPyT^BK?Z6}R)clIZi$pT+53 zP>KQY3z=}#44z-y5xbJ}3TM?b)qo;UAUTrdU>uaY;>sfw0d9 zf?ff^B)ICkON+uhF}Rp%kjZ^v+2~WQXLmK#ss5{9A$Xj&g-N(w%ex9{YT%haP2gh^ zHWAQv9Yw8xvUFRX_nW5ATg?}`jY%Jdt1OYp?^e+7|DpfdEN+NHbph*JJMfenJ#)@G zsr*F{M{##pmaf{0g=TZa4KE3neN^Zb;q^RzXoAqW38oY zB090(9WIq!I+xvHg0+3pmCaeTt;C`ik>wpo_I&cC{iecxXT*P1W-{RG&G~}<-BdEP z_m`mgEH$JghrJ^fQw7HS{R{q z*jzUl#GHwFjJ^La_iO{m zmQ|1SwhaBE%;87XsErM1(ActMGO0oH6DikM@#E5)Ol?6uf>|Xy?pWcP42Xl2gW>&sxR=8bkxYty^*;iT%dQ!P?oaTz?3RXNg&Zk!E zP5NF}S@HU8)24ypSnToK&@1G>j_@=x+9W=w&W0K9IC|Ol>We=4#@c5ORUkI^>R6|{!QeyH3p?K= zbMVB|;=M9_reN4}G?N8(JYgZmYI|fiIHmN}ero1Rxg1^NHB*r5+%tE`8tp6}uVhoi z{;0k|NeM7+IdMNPu!xN)rGMTt?eHqVDJCoZ3Jc96onX0z*z^YIzI z`Sj9FX5BaZF3^qhHCEhcC=g1cJTv@e!Pv=^(EiTv)*YtW5*(ddP@d9!2eaoZl@=V!w6k0`oz_8Z3u z{Yj^f)a#wkynIk}+Vzo=g8YlvsoA6KOm{WUf@hnv+?|*`6&zmfwa)qpOHpfm1&xyX zRf1e3NP~^Su*{Tos%)?{Gt+|KcqpoC@lMG$@9XXjE(o<@q)<5sF*bz=? zAHUotIJ$cMN8^wzpo6Z5O{6S5al{yF`A>7(^VqTNJZ^#TN z3k_BumCOle1j>!>1Xn=Y?vAJY1|v2f{D5V`YvQth1wJ2amFRYj54aI%)dQp!nFQJ& z=&ITrFsp2vqfyBY3qc2y4+l>#QG<2ME!%Rhz0`&ehM7$VC~Gg1hTA94gY{=c#9jyN zpu#6u5WZ8$*Ku0M-f@uce%k}cet^~BMP~Hb+w)3S^E@)vKRi2ssRo~!#DOme|7@#} zziQ9luqItj_<_XlvHRI2g()}0@4~=fUwp;uiM{=TWllu}(s(}@w9!};Mn4jJ+x4ty z*ZFkfa|<41czv~RQphFZwmJy*r#=XDR=H7^F;-Tmv?@2+Xyak;`eWq^{Tw*wd;EA~ z(Q5eodBkeJ+t7B)0b!Hij+PRjkAx|*>Xq{YT;N<+>|((YgXZr@<}V3yuGY?`7k!Qb z23y6WbkUQek5b=4QreGSOg>FDq2hs({k&&;=~oQZ{EbtfsBjOrc}y>{5B&4PFZ3tG+!dSx-ReqI_shmA_=6MgnK4CLEJvaA9M%mMRwzY1VNy6 zp>d`R9o|%iuNMh`7~;c1ju9jm;VY7t(`T~n*R>Z2r85BuO)m0f-;h<^*8umsyyGZs zjCNq`%SjaII{t)s*v-Mxf0AHuxf|N>0p`_jkZi$i;kWgo$%xlo-AT#%RmR|5Dv(N` zuaLzr)&D-bZLz&0_`YYC@rQfO-2;=r^+p{r(Yb|F{mXsZH*55OfR3(5=DTAeb0=Mo zxajPzU$Oot%%q;17>k#ojC3c)lg>)DWliNQ5hH^Ag6_i7Tqp}S8PNh+$ctUmrq1p% z4(IbL4Hr2N`3~hz*qCXOw-&ZUcR$hFog;G0n+H2vnlgPCFG49b6c$SzE)E$6Zz%s$ zQ=&7S5%ZXTL-F&e{!w*OL2z}2{%ujRK)>>>S_3x#o8hWjcZ@;C?4Qa`E7RTsM5fM~ zrc8dcX!}U5Ur_k(QqroyrRv4eE!J91aYj^`SL_j2Ba6)y_=26F*1(ISBKnb%8aS5+ zH?z-Lz>$Q20ygaSn$?`xBP=eoe9nN zKO?gM%w=vPzZ|f=|B664{E?zz1j)6SAQt;xj!T%yd|11nVb<0B zyy6F%KlcBQbp3uK{~qM{O8IiF@HGRL?zyp1ELQq`h#j8MXEzfT!@Mn@|4hTg7$La; z_#a`B^O2lah>d4JG(~^O+`;#$Py+IuHAr^98wyEfdVUEdje4KSP+a5MgY&PYKi|Ko zHGcYbvZiuy@t-LY7ZrZP{pr?X{lDJsp8kK)0l$m>JIa5R`+un5|M{U?`lCsvYl8Q8 zl#t5*@tJ-HT(6@8zTnS|RI z^Z%ZT*;ns2Btf`$BgA7azBnu4dZGMh1|L-&JKvRwBe?9j*!q76XwPq-GR1iBLl{pI zA{a^<{2y~f99JmW(*N)G|F3obH^}~?3B@3iKpaZLd5WKYFF=utBEZ-#2*L&o`lY=cWrXzOFbdD^Dff>)M_-2A3gg+3* zf$$WRl2W}mD|--hED+8I-jkSGijd_D1gH*P#3y{%{+Y9;6Ob|tDY zAxBE)g5&pyF{$@A0*E%?HK#6DGdk>xUjbw^6;3@AUBE6b>iDCup27Q?ACpm_zz{oO zjrE2!GZCR~-c=U-j<__ON`Gq~E$+0{hKZS0qYhR#04+LIsa-8~%O-8P9fOGAVO>lO zFB6R%Uf~2=I2qdLa6KzxO#jV<1KpBpuKBU(`O=;-^Qd;{v&&Oh0o>iD=1@b|#cFB) zeTo9t_E`)~%!1}aDYV+qnF9H}G7#WQm1luU_&g?2m=t*>2^JM)XZ2VZ{r$%PdZ4+5 z%814DZq{GDoavxeF?0ztygyY+nDL0k;;?@JZloK#z*q&wWlDBAnvg;ti-HIhqAx`b%|;EDLLD$)vx4m$ zQ2A=d5PdT^yMYYsDw&w!OM}Jiht#c_J6(fk0Iu3h&Na<%m>XixA1D@ zN`IsT)GZ$1mqZ|pi!kUs=oBWK24Y9qg_8aNgY>KJmDAfwmg(mG@!A83M)XL)_NW*` zH9$z?sfJjI{C+lA18krm;RZvog>EA9_RS;YZ(vQ&4VoE1SW9^-Fj@HG&j*Dm_dhua z2!|vSHz(fzsOHSBs0nOd{Hi19Dq)5ex!=mEDKF6%+oSOD3sG-0=U(!w zF@9J+ey)G&azTC%Pc6JVYJ=m1N^C=D7jIWbccDnMan|(3Zfw-PYnKtc6C;4OS}lS;9;IC7~@j$CI?m~ zR%0ABQ-I}bMB*9s@4OhMy6Yql-;hPr5KxhH3WKtPXANZPMZJ{Xjl=%tvj9If0rXZm zo&KV7FGqx4zFl>2PA^C#oyHek_oXLS3#gITm|(d^02_Ni z>K!_C3Whdj0qRL{=RGYMnGUS`)Y?-jVAr6R^VXGM90f)F5?PVP$!J%;sR*SI$E?zc z^=M%h*Mk^5{*x66K4!e}&UQSJeB71^k!_&1OdLjacWf|ruzHF%xdXE!>mpuu8t)fH z35iHUKN9@62-Q2(B(6Bsq#@@#OOficfdy}3apWpu67wFtW|+vDEy2!dh}B0PxOLZ7 z^_{NH2(nRoiz*SiHMQoAhm^2@dKV*OT+8Iw_0*1`BNo#jVmBmK3SVxZcJ#;chDnDW z40|`v@o3a8kU6~cMI(JGnGr< z#0AM23d+5ByGPz;)#q}eSv|vn4NS=Xyodw7_rdnrYN1KIKA-@+P=BPo%RkSv6-+!M zPDae7LAGMj0M8j<@#gZvHY9avml`FO^Uaa2uI}2VePxl;x2K4M_f-7q9&=lUkGG6o z1bJXdLL-Kb3&5c>p5i`L%t!c92z!-C+#xT&#bvuOB^kEyw~n!j4qL2(LhXNAXyzfQKrt!c??10K9TvlfzNtAN~W@-v~jj`O_G1a?)ls*U2K@7Hvl5$4$O{Xx;)3pB#=3rP! zO?8uM+0c@V3sY}Wf#yTc6X!+)$hkD!cg!2Udu!f!n7k@)Q<4|a@0u{tm`X7|m-f`B zf$_>=f)VCs6>(&m`S}AV&rc*ru3iojLl*(Vh2#w`+i@_~Y>?8rF4@5)yAFY27=J#( z5SK8_ z$Pq&06x4|Te1BN9NbMj*^iRLl%?RF+D%Ll8F{H93f8&vd^i)Kh|xpv>Mnl`NXUu<8#^Dg^DTuP;i%gVIWGCz_cFKtpzncMQdgG5crw zVYmJ`NBL1ATxJDud*k*Gw|`Ii!#+4k-~nUNOzNC|jP{ar(BJ7qT9@{bkNrT54LjA! z*0o?`5Qxg!Wm}ip|H)aUB5DffFVcg!fQEerqu8gf6Nh>~W4aU9Lr(sli(qLySwO0j zLVg}|zJ$Eq@Q(touNkKy_$`{4e`?4H3<2XZpTzYlk`5U~Tr@ z%JvCQLdIgvkC+>N_kVK2GoetVCGwU37f99Be<3{u5wI-nu_Kfic@>3nhEDa2q3QrL z$yfp!Mbj|+OK-a%G66>T^*i!Ys${N(SA_=zGvl#=Ppcn&5&FCPAt%9lKLO=hy>3F$GTRkV4NzVtiUK;~=S?O%2}OGxZYCw3$8 zPjG&-1?5tZV34rADUN0+mN{S*qn$27Wz*MD_Jr`hV{i;f2jUO!#`(qF6Rj6HB_*sy z>)(c5tW5%l-D1p5Y)dLp~@3qPl zL49(Dt%BxkANeE0&d~}u1kt_wk3@0xjp!0#%Wir6k1({Xi@`ebY#uslgE5Eej|9I< z6sPA=J79^D!2XHg4Rjg~ypFbZB=T%RcvN{1VZ_QvA?POBeLQF-r$egf+jU zxd$g?DZ_c~!4BIrXQw@43<*s+Ry)qV_2JqT19~jfgRmN-9m#Se-BmWdkau~@WUUUl z883v3L+4{>ezjOJV$50C?rj^MU<2EK&jRdn>J+Y4y_HkB;EHSviPXXu`4xtE6yDl& z`nuZk8B-Y90KVQuoQD7W!Hzidb7G*QcL2tpU_9N-1Dk}z$uV|DA@BC|7W3u1!|+xA_)=DH#7sX z+0#amB1z-=YgUEc?AcI6B zGd!E-nJBT3rjFB#hyHJ1R}G}r4?$#zd}=MT0ykl7NmY6mK|1-v+20Pu zS@9BC*Da%!(m%wg5B>0opvv9iFCw_YqP}?0JPy`H5=6m_zd+23k}E@CW53=1{RK#2+1xw(TRsH3eo17^$1sr-f8!>3_%y%g!tfeD$e+jh z(5KJmO!6)~8L=I%>H(0h&Qk52x!-`I1(hV?OzVJfz-9yHKV&W<$U5vPs;k~|<+Pe~ z*0Op2={r9J#hA`e`X@)cz#|BjRM)RGz2V!1p$(xM+Uy^fq2eA37F!!zI3+``hY?Th ze+QCNi_jOAX%p_Xzn!F@|8%kP>(5)pZ?+OiG4m(eCappGPvBu3u9UtTd+@J)vJeS4 z9+>ejd!2B|f8Yu6$?A{@fB6Jf6@Py!4U_hw?A zho#)Lo_bkks{f`D%1CWy)e$n7PORCFZP=i`j%h$vIo2ld?^Kpku_64L&k!-}mU371 z8RcTEhRdClA-ch=&nJ$qnf~hY_58Nn=V%lUWheodm`5x@%jtt*@=NlSb!FeYy;l6bIFZCSUSk2*Th6bh3FS(`u`9nirS6;u`-vSg z-)SQ`RR@n%xQcfbsRd;L(k^$9f)Wq`j+klFE0#wJn?k*3{;bY-lB9WM)1l@a)0ZWjsaX`>Ip%OQ1u!mfXStY3($&y$z2MA~KV zZO@*g(@lsVy$WCJl#Q-+i^9KE(3EQse-^MbfN@Fn-DPKSR`|UN0>`k(=>OsI z9Kp$;j7`$tV#FdlML)mCDKqAmEP{GwxKFIMu6Ga&0l^~pR8Y>F0=PP+Dz_$xQ^rBf z$>2Oz7s#O*)gG(NngE3gV?Nqz?4{Ul1t#LGrRt`Qjc6-cqaIqO5&AI4*SM@8LmO@eP+}|rZgGxBWd)i{p6U@ zy|JBl5m2pcFs^C4aV`OQz^m!3Tu=MKAiSK1FF+@mRj9PA-m}RwHtxx=#^aSSaOID~ z{uWHOALMPNy5SMVlkyPHKEnIK^PGsFDdco2J4Z$vHcVMowFWVAc&2b*#(*UCRYgX}RJla9p4~s) z1*@2|eJL+j$6^*pZnW>Db$*{e`d0iVG+9b+LeBiGHbqtm;Wb8?fSUWz%4{(gDti;u zHtB+DGlXm35eu$#Hn#eo+48(ytc+tA5(wh48H6`dVm=} z&qEDaXnM>c|BL#CT!5g5 z`q5qGjDGy>OS2P1oMAeq3yvls&p~3GQ?Ec%Y`4O*;>m zujr94un8|TkdZnn;Sq7Z#vdUvU-3i3YRhH&F;{m8;1n!b>zuGHp{%$7m#H=Hv=XXy z3WRwfPZuv*QpTauOs$Any@SbbL(vxWd~s|9jtTgp!E&rNF6K0!#&LXF~I=U&I{J`w$-vIFUaWddY93R&t+A3z%AX|#~tf|&hL zE%ZGby6VFUz+oQhHBeh^uUFZ5it$m4&JP{BR{2ywo=FatV{dFB)6V%tO6Q7(5dPbh zK^8?&O)IPlT>1Ple+y9p3v_zmLLb0J7TKB&*~)9%zXj|J0^Ssi=+(`=>`t>eHwGNU zYJ2KbMEBCS;b@4e1NyJQP{r6<11@b-Nsw2Z#`svdXq1QH3Aqa0sI$$7(&o97Gw4+n z7CRf{+YRbyP|Z;+Ih2P2s3-Y@2xm-yVXeJ!-=(8bBcR$~r!Kdqs+4q;ZPLoI@Hk+U z@t?oQxn}sbK2OAF2Zz9)VigOA%eww9i;h|E*}44)&Qrf;U46Z9xMI>V2NziFm-A&W zj|WjvIh)4kzW_|JGgmotTv?S6D+KpNfo-H7gbrlqI2M8lpwhGM9BB14Daa5SXDAC2 zEa4Fu55c&~h{zf5K)b7zmniwhf!}`*qpI^XyhvxOfIm70VRRHul>Pa5+5(xcgjA(t z{B83{8hV+biv(KPA9FceL~X}rZ!nAT60Si6iOv|;rMKxq5wpTxeYa{RcdO{6yo>)Q zi9}ugn?;5m-p#a@6>^r)#?hKjhaqk{?J~RdpjAZ z30(v+2`$XFnEF_1$%nnMZ$ncU2tB*3k{3XkbO`&It%1kU2)3F43k5}IB~?4WwgxJl zA*TiB5A`1BAYX_!IKx}Qg|#Z!6B0%~<~r(Zc2xV2INJ`58BZww=An=(aT}(XXaWh< zYCru;b%i(x3F8kS9ZRaQb0(wUSSSp=a5)!aH!mMQb>FnhxY9sTU5#6c<&}oGC~gtC zwsj`%L9#S}8smVzJT|II+vYGM5%1s9yx1^MFPJqDhD4oAZ_x7@l{eqA#1U|jKZA-F@;z$h zVCj)Bu?`Q@yO1Zj5|bf;UFSAzlDZN9{*spTLe{i6?fY|s6qY-uN^X%$jh!RFyl{&I zdG4DfeWMY0hcWDJpU)yx42JPgba{J01cit+d~7ce-TYBs-J1e>jy>(uaANK$-4x`6 z*O=rBSs;0O4<3%v6ckPKKYxQuWOF_UZU|wRC05ZC)Xd1?%5Q@(j1M`5ABz7ytsMax zWSFwz_z)(LEIW|yN$$M|gcac}nczppuIrQjnM+70A}HX3Q^FiR%vrCq_74Q}=8`q*wVePqTa!Od2)r+*hvCphFosC(XwF2%EC#D|iJSYs ztMXtebv2Ftv3$cdZL=%*61t+fvPET@^R`9>ftR^Cj~fdP6Y8W zzY%nqiB+d1-1YM&OZk}6f)JCN(QQ(_Q5fUJDP4x z^v;Hj#dX06K^N^mXb%yGNg!(pDr1XKhAb21?3x<+BYo1@{L@=qi3CF46!$kstpQ_W zM{8dX8=c$#YdV9tq=aIQ&y;Ee=jWBgoKp@5@9sr(KVA>| zPpjoj9zAeLPE)!Rcty1NW8c^xdgZT|3148tOY{SG+&zT{$&9}Mc-!=!mZP7WA#vUB zl!&3ReW|QY8lrlh>ACEK3r$fcl6&-wfP!6);_>-fEnobx;ZT*PDjpB-r^wwzyx9ua z(wt4$^B8#ta#Qfup|Huov>swoAZOsuohbbbbX&yxX%4a?UY(D$@%FP12-W`S=$|M7 z;eBm>O#wmb5s?w{Z18ncd8VRBb@$sIoP%S2)=t>S2JIvp-Wwg3K{$8XYM@`kfogaa zB?;^ego^Zq0sg|x3}Z(&=z+SB>LR_YXEnbL1kq;xek)J-xshy41h+HB)_XXy0j6B zb2}o&e1xXrs_fH@I;2c8k1}Ql$@Dtd|{iXD}xQ%XS1kY*UbX>w2v6+j?tH?jMf6mF_62E*j08qS$=r`-uJPmMV zD4BwxH>S1_9RZNr)iNtkD}%|}t8Q&OK66hNF||5Gx0T}Ud6)K-Ick-Pan23TgiDKx|5@!E+v3>Lb7LBHr@$|uAcIRz5 z%*fH&KtNhNl}NpvyeYNCO*!Kr6h6MpuOKVg6}Y6Jx(S^7HeKMd72fwgxH9JmQzg|c z3~am;CF=;0j zIM67=Z!LjO8Pt9-Mbsnu{VfVxWP8&OU2DqB*jlBhc%mEbb6{v{aVd0W@vl&@pJV*q zX$M_Il)!b*5+tlJ3j4$h3$(Sv8rT}$;8Mf>DO zkJ)S>0(d*N@jjl637+GNyhNc^r`i`t4+w_e$wS!1^Fup1=08j)C9+3~o=Dmd$#u&5 zW7GH&sA!_54!^?vatFW}gxdc>7q^6t z+SYx-wK@XAI`=Bt<6&2=pNnB1h_OATp7QwU(M2lguzAeq^puE^A24PnMNbK!Rhaqe zK?#`Wg%xPTPp7=w!|{j}*>cY78eobxST?oW{-O`}3$>)O7!|M~wTL$o(66i+-9m)M zO44pJy^RlnOnyOljxN4!-|dOWBOPchV_e65r?J3v+qiwcCmk`7}Da-U1Dco?y0Y zl;1&3zBv8-`U;>c0aXeq~Sg$Knx>4BH9FKRtyI=FR!9rTg#ub$$D)W)zg1MoJg;pOZE-G??jQ;mEY0L^brQ5++tB_qyV!Br@Dq zP2DNh9!ak)Y+u89bj)U+R9JeOtCLuK<60K9YBCQbY=`n5oRhPj*>(X`n7C(YBf-Ax zkj4+2$w%GZSc((rocjMd(T07Ak#(BK%Ab0KfA}drcI|hN#jf33RnQE~|n6pE4{LTrCwwE8*0` z{P4E@G5mRVtl~l4QV4-5oLo=>RqoZ~s+CS|hV_8=q2+ea7Ycl;mX2GeYhX0(P^`gR z#Ar^|@dfWn_YO|J@MHLJ`!W0SxmfiJ5rVM||LiMa^#`F<6z*O04O1vQDALx-@qpZ0C9E90X)GGvPRabN5R! z1|Oh!-!8Mw^fTnf-RNOz!B{Z|3OTd=I^<0I`2u+Ev;#B8Ppjb5bHuI*rG&GNWt*CV zWHYga&Gj%AkJ@_yh!zQ7fPaBp;1cdifP)3L2SUF6ZvXkYhCNG-`Alz9nz7{ zzJ*M1oeTZF%lwdVzJCV26fl3cdR87d_XJ#r<4jTPZ)37!-dm3zoFbI3B2n#7)`dOX zwXpszoHCDr6|Vx`i;I_aX4Nn9k!Ogm&tN?Uh|{6>DfiT=xe8IyA76bwfOF(`!9$6&z57N- z_$GYE`CqB#F4)d2$RnB!_Bd@D=CRnTxWjLIlHJ9L>t`@)_PM;%kJ2v~i(`)m>((Zz zB`JP$9AU-!mf+021Nx{`LIUoM>`dGfXkHFJdq^7eC@i8@X}^Tq$jg0gvP9d3^m$K| zpl1ojMMFdymhoslnLF*Zhf8vNxGf+t*O7%odmEjO7&vUgykqKnw)hIca|QIoN+^Qp zg55_O@_|v66gaW+hx3EVbPq;^YWqAU->U1C!xv)qvVW)Iunzqf9g-z{Nz$PNdNWUD zV_J!ikL9^-tA(rm)-wX0^$f@3j=uWiKUTMFbi`#BYG`baR-0F0Z+B8dP5pg;kY{4O z?47Tnlj?|~=v=L=od^y-9=@LPaP-H@?czM)Ceg&^u>&5Y(-`*D59&r{BAB>16x_!V z2y_MIC$hSq>0Q<{c0n)qzv5i%t>^*2=C>V5_t%^!{p>T&o_vI|?`XA@_ATO2P){vd zW^rAW8v8X7uKqR|5Y z0JrH26Ua-5hZ-S8RRzyRQF#-j}a} zq1iEeJiyC!d#Z%-B?QvaiZFCDh-5`JRq2r9pAxE-eF1IB)AX;^Sp3Au2+fJFT4UI# zec=vM6fRw%u$(yin6An)wprVUIH%-yuFUoYw;ZLDeZy2jVqNn8Jquvp%RQWpS2$1= zZhDQ+tP-QSK2b5~)Ein}T-bpl#87AzG+D(jkiU!@Q?NO50(uD#*FLFFNpXN=2&TTf zwKQppJeE7^O^T0?uVDaeCV;=@``keJUCjC~puwj@E8mlhp{@`3+y9u5kDXV$3wa*T zPZ3j8zoy=XJTzgfMtvb5kcW80ztbcOT4qB%60|p{CW2El5Z}cLo1|`Xt%}RU$R(tj zwMm+J_8K`u#~W*t%V!C~UM_7cqFnV4;=R|4AadEK6J}A+Tt-wNEArwSPr*1dMx8+3 zh30W5P65S0DjBow>SwZLJjAMi0ORXu^V*L_5z76D7uz^?#yWz%_>NN~^*;)?Ifz&a zUEoie>^#d=(G9%-?JvIAiLnJ*_%JHo{0fKe$-+sN0tKnJEymib8uVeDtD9>BEbP-* z_IT-y$=GLM)1p#RQUeBRYP==$9;_L)^cl5>k{RF~js(#Jv40bQCQy)4}4%jHEb|AhQ=3t0}&vhDRxvU@TKAE<}V z9YBTC2|FUgAhv{uU@Ae>gdHtefLuZn)i4=#6xQ$vJk>Bi)o=>+@Br(sb3#OZfnGwA zTtZp`ZXFeRm%-&Ix{S~R^04l|9zM@y;rWW9i2U#QR%K`ThtLT-{0TcAvQC{;o~~ZZ z^Kz|cKdHXTCPYz1EATIzsms=iBrqmO%-pTpA7|JmNYBfaVhuMqq>t#u$N6( zrW%Hm{X;KX88@5#v86@9X_V!$@pZ~)*c*FT^DIe#*YMBkN2^w?1YukFu0z6vheT@G zpH!Y@RGt-7B`H+TbM{_|R1eyz_Gd5BPls#m1ZpovvH-CJ_0I_aS&F+q*=k(oYFy9j znbx0Zsijd$Woskkz`FLMI2EOB7>|X^{&aFw|Fp?7`<>F>-S1;Qj=MiGc|qu zon7IOlxOSkSg2PlzNm=iC&zY;TvGPYV5O=3RNr{5kzzJZ0?~0vlZGhc^h%MU4}io_ z6G@@Ox4!J&Ze z>ihtDAxnB_#6%s%Z&Siu!+ujL?huYTn?GO3te2d~##3^>y-MnC#CrZ(2ByrMJ?40a ztOKJD1v*~2qmk`Q8a$mG*Kf_gI>`hcDQ><>8f(v_H2IfX%FtD7CKD+OL>DB@O?6h= zcl^=QOPpx>UBT#Tb0mAmCdjy+efP~iqA<=UaAmx&KdUN(CC^qQLjAA#gfSr@AxoTm zvzeLMu`^OnKzXq}#%hgVQN?P$xkNR4rLLkCHm<6H!j2>gd^layj3yiyCIwMt@KFoX9qw<7KiJY0NAJF$0SALItc8PajqA&MoQsVP zMFrS@XmcAQ^uA1<971pl?(Xgm!QBZi!QBZCli=$2m7kMdabJJ>h9T8bkfmuygLIPr^xL;bw&?kg($vC z(+MqblvQ2D5V$!sG;VQ2r>((8-90Wv(t)zQCB*gJBz1n4~?YdxXB9{;pDFXpQez6^X()GWp$)@{W)yDu_Y4j}Hh7B@HW7ejgxxou*F(fc&JwCzC@>rAnZ}r#*ti6dj1jxdN&1 zvq_wis4~cGDw7&x68w&^6BCpY(G00Z(AHmkS0rb|XX>La3XgWk_f8@uUB6MZ2`2nj zp~^YB9ZD>6xA8gWq#i+*TUAJAad#C_)Sw)hcStk_r}^w)DQghOh%9Ze)sVQWA>Tpv7Id%gIX1w=*ib6*}*$H%gjui5 zq_v?}q!B}@%jdz_l$}NiX8}1_IlZ5xH6?o|eCg&042Ry>7B?Ud(|r69u0-R%uC8HW z4hrC4BQ~{IjWn0zAQNw@Q(Bs$0BRuXBW-65X5=y9Gc(I>^I6xdLTC8)eD)7yg*0{k zU!#=lkwDZ~09$7)ZSeq9fgLmM;<39+2l|TR^X1hG$@ul38lp+YxPzbCs!;L}wS22^ z*yIYEw_J4cc1M2VDBV}JjhD|pp&A|(B+_Uhjre)O^%~bUZz;r5Y&S`C<1|JQgdTvNfhH_1by@4p z5hptt$u<#6lsOb`2Nx;5((8YoxEh;7%WpLZ;9xs8Lz@IQY0edM z3N1BS$%-8I+>#wH^h+I7%hbwNYY*f0$hQ<^ zLy!V@<}8?R6^re;+BQu%);a0y`uI9C*1ki-m2m5hxEMOhqFY>Vj#(Aq{Y_j0-Bz_= z2KjP$_d!hhe2lL4r9=I*_6{YF)goGy5>*_w4(7(7sVNC;I<=b z#dT?@r8jrWh0nS$xsj|3KLp<-9v`Ko8>b-xIH2U7+keZ@eajrV7%X;g!Au2)_ZYTw z;lkDkNq8W2`NX5abY1dK%1-Nba(8Gb*)oSMHl=)){-E5ZKv(jNclYMgzg6_{?c*7$&#GK;?PGcxVgUZh7N4$yfAU-D|0MSsFhFY(v-_Ikv zj7y+%WtF7|+Knkod&UTL?D&oGdapYQ2M~1&yLvqGq(40<`z%53+)|f4w zyP9l?lAhv=1(}Z{z~r~z`D$^k-CntOCz;*=KLKbSU^-F11?uZCZpdDviMh`ap$Cs; zArX1n;+dm$rJEDI&4aSJvwv{cIP{qZ{17PZj+iElsG;l*+b5(ulVZ@)kA*Ig=@9_e zuYA18_0adqNEBY-1D*p!+!>|KD1nsx@oNpB@Ghh{wU*==7*;5eG5kD+%pT-b=5bb% z#%vBznq>Ts@nzUeMkG0!^JT)3M#stFE6QR|6dc%O$=p#OgLE9ehd3=`P*%j+1I%x(|rX&cMB*mj}L0R{w*HDVtGRVq`Fk6X*AA7T~PbYQP zMrR&S>QLrg)h}=-xft`0HG3_si_8R2ZXjvIzOVUcqjyGxudbCM^{*;1`g}|HXAezG z((bvMH%c2J)_@pKsgZ)uEoE?u{bvcJV?*WzBB>!Us@WM10U(rHam(B{R2hDC>{iXK z|1z`_dD|IB*24Y+KMTv=O*^>(iVQs8{gX7ZF3~4!GuyAmhrg5VAFu-B3a`QXeH2y` z+@#G-b%p@R=!G~~fr{B>x*u5k-TKd%{5;EMM+_O)7O%)h(M7*1QRxU3x^MuI7ydj) ztq2V@U6KaouN^%On=kxbzL6MFMO%o=-=)CNBS8xPX%u5G@`O|)`J7fc*~-i?EBcM5GatyW{M3@hHn3$g zL>Cb=L}qs4K(Ob-jFz8Jmcnzc<+fvGG=DXDG$eSmzNKe!mi8ExI{ z$Ompu7+DJZyriiNMpMhPhiQ{x{|QXL7R2KNUJpG^A9z3alL^tFTJ?Wsh}()!k^l^k zoY4CswO#RH9Q@@CH4oM3kW%m)=4_#zL>IbzLV4S0QQo>UF@h>> z)*pndt+oIRZ}cx2G%s^>TRn$<&_5^gZ1MfLXX3zQUA+-#He{!#5DhsOoxT;z45*Dm zi+`U$_2if=|5ALUAfMggb#WD?i<)_f)!`JAxr^&}Q87c4F0s^IM&m}? z%g!#Evavljd88m6k5hxs(wl%S>5grg>7-Q#Zz3Q&s)nr_$Bs^4N=EPuU^>`wls*VG zus+ps;okGSS`+(?KiP|>&XaRDpFK75^T+RXEZ{2|5z(=&k1P3~dN!IPWSj56firiZ zF9cT7#4El~-Ndfzn{c!|I~WFTz;4NP$<7=Nr+Zx`!!( zhmh;@C=k>tt>qRd=JSt%0cHS)u<$Oh_n54G6gNR192|5QiP!dXGI$M+PCqU@Q=*)- z)_-fp8G$8#PxHEgPHUR(jNL#b>bCK|}mVF|WkK@=8Vx!8Dh*+wDfwnu_vCC8?B zT)BcMF(Tpg?xoBb5)c({Xbe`s=w7DQPTmd}ymDO`{`SVLRNe}QB-fBF#!Mq;jr8}4 zpZR`KyJL{{WIq%m5#+)1loBm{{+3+zH~JxTcisN8i*S*Hq>qdOFRWy9eqj0P{( z+3*FueO)HtF&5CYhZKymr#4`qs|h8hr#hUg`l`zDTdar#+cqg@(2lZ?l|&Ji|8Bv%D@msg0G# z{#@#pt+pO)TgZ*~aYnAD^lJt6Rdz7bD(p)9F0ZQLgz;(w#{HnSP~H!>-i( z(|nQEUzGGS7#6a-&YGvw$t;xve$*Dn7q6w-Ec@IKGgalWB_`)G40jU&kdI5*%A6Mm2w7 ze*R^Jd%0DL=TCrYK4m{jf=!{Rfagk#))VW8ALG4!G$7n^mFynzz=&$9reg!)qYae zBYmwbwD(I#oOQ-+eL1I>_e8dz50kd^P>l3%rN)B?A4JKcda47BRu^6smqk)uAKUF^ayqg{>+}% zvo`6rZme7*L9>X16N8G`z2H}Y0pZ5An9!LYjA;J!r>D;1-7A`(f$zs#c72Wo>tYYV zCTvS9N>@^`&Gx-2HSV_q5BT2S;c)x&UcGE9@!6yBDRsGn_eE#DXc%wYV@ysB&YwIH z?fUNcqozHbw;Bx8{I*IlMQ3qS$iq{!R_Tm`fPd9_dA7K2Z+Y4H4B;EFBeX&SBv&g* z8LHQxWffLwK|&9&U8~>)td6oXgy#Ke&8^M9Br{XBPT+FU+&A`Iy1s{C&9V2z-J|3=H%H>dN>cnNEZ|XVsDKpm#HJ%a0agoXR2pfJ>={%_#+kXy zMW$oR1MXEp8_S(Yn>ZydVl9j<`lO;osQC<(HiwP>zTaoFKO)bgS!XS|;%m+g2gt5x zzm<$`5BZg2U0j&GRa&>LN5YiwjILxcmwNZZ2GEV(!%Iv{8~*$H_Q%YF?z5KEbB9D{ z>W`$18_gB;O&_Ee?sbKl=p=p*C0DB7axE9PjZ%TNl|B$|?pf}kwt8ityrNK7Nv zZ1SKrd|OxuQDdVBi@}Yoys%Yl(4gxn5}MJ^514DnjYxk4!B0^EJamG+5|g#y^ncc>HovD zMlgZ5E61*8JG1hB)1`+kI;yg@%Icu$1Ek0FWARB_c@8CTJNhFsk&IAwsFQ{s$wG_| zUs+Vk`dE3PjS(rZVyKQSGe&1-blez$V&_JaOYI6pX!K*vSF|D8eA2PQ;Gr=cJ?Z(D zGN16t8+yX81FQJcgP@1{cFOQytzog6Mg1edhy=Q{NK)VC^{%(R9<%{MSnTTaQ+_Ij29xfjRf)1#mXMi#o!*FDwQHT!&O&<@^X#*esb}3AHi1 zSai(N&I`)FzSu?Rh0vr3k}t{)2=DIKc@vS^?cRIHKWrZ)law@myCoMDs6x|II$;g2 zonj0g6mbXkqduj7laR}K*xyZiy zAQzhE@Lf8#UW%$KWK#ucI>S+MK$puvtULvzc#Kg+2^51O5YSG!P+n0)+Pp|_Rq24k zHs!~(*xnLNLO&IS+zy0C(O~vZhQ*7%V ze8HvMj1^W)V#{-3Qgrg9mGqW*<2;rxj=I{{v0~a15wiIKZwy*U&yu(G>hBSbtC)=r zF8sk}gdfejvKo}M(M<+WPfu%}<>IBJGz0%1`qa63ktkN|TWkiMZ?XRR5r6@Zx1e#& zWAGGrcQgooZH&42dqc;MV}MhniVQ4|>+Q6xVBQd}hCiyni11K2rY?J2!Vrh+r+4va zkDAdpbw||7=WhJw4l`!z*cy&-7Y&Fke~8y)eM)+F{sU~Qi7H377{Kmx`5`^ z*qN+8rESJ0Vh8g?kY8(IgYsVh3_Bo$$AKv7zD4&jk{wv6L=v09vYvKq{bjo^I z^8DkrGZR>N1f2XcCT=bnvHN4!XW&S2JBhA1XlZ3OoMkYROtUaUykhNFYr+#?;9wYS zkPR9#vuLxaxWjHjI_(EuB-k4Zs`6y5VZD4xy}U4|AOK+Bcbv0@j#HQCU%5yoyEgXZ z#QBNbhI!wtKHcAdG;U0K^Vlslacauf<0&OdmbMI?Ze%DTP4Q@OENlEZF~nhBMy3Po z-*Nv|kQMoHcWB1hY4hh@@oprAXr+Z2+BYYwGhJjKDcN3y_CqMyx|?{7j6}TjKbdJ5 zqS!_<7Vb=no;uRyluCQzW9mfG0Y$Y*Zv*M>#z^JH3Q)Z1<^FlegBfSWeS7^%?uyNm zUEbYllVNhI3(B^jwH=-K_MtuRr|-6?X4j=bh7TLHbg|{D!r!J>HyT>QhUkQ4CX{?z zrvnPy8Lxc%{Bp0jv`+h8EX<+A|FQoUc_p-2OrSM_5^f`AuU3*Gujtni_l%ugh zycmF#<;W{FrYt!!CKPSYu+!5g|9Ak5HLFzRcHHIDKEZ@plLQbpyJ2laU|z8sC<~>Q zaZ1{_qQRHII?)J_;)ZFq&uG#6^w5Wvv&Dl+WhXwgZ;H7hVxQRyWsBKJjFwT%jjkD* zyS4dCu02pL!4CNU815mzFaM4)(?`HCyQtepO=(s$@?W#1HkKYUJ%7YH3+tYDb;ujtFzlQB@hPdcIHjYZ z>3wQ-Q^HdO6G#hXSX}HcEV8}92N1fsDQ#X6!pmE6D(#77&uQPzH_5KoNs3R5nC3$) z0X&EpS#$q1H#4Q9$Xe4Q2}}5lpe=hm4{Tb^P`hif-}=n4-54+|d;tg&wLffpJLpUH zO^*F?<#-ETPUBME0qNRz{sh7zLxe|2Wk(OQ$Mf>(3hi*PH7@ytVIIX9f6UTVl{gEG zq?Mh~c;fGWK41xAHw+h08q8QCqF~~|Sf?$TQbO;y=02zG2~FjfoGs_?R3Q^{;j{xE zTx0+4=3*iwWk0M0c`ig;VQHy7Y^*O3u!hs+4CyliF!U>-xdo5BhefFgSFZo*rstH6 z?W-C2Ovlx`CszCmT*QXeTIU0Q5T9sY@ zmVe`$U9Ha-g1Ipg?yBq^y8l*kRG(uoXEf!@+8lo08B`y~)|v$DlK^MToUjTpKY3UOdwWP|@4z-SIqw1kq43X(;AC*|wm?M8w5@mrOxM~!YItoDSi{QoB z#1;X+MOfQd|Foq|NL+rCcu>^ZB(cpU&>I%Tf6Bw7xCQIVk6GKMUU-T6N*JMUQ_r3C z9qK9wJS`bk?!U8t_lw&DxbK7a5kh{duQ@+v>|TMiGDh%Na&Spb zjvd-SV~tWdXN)V=(pN5J>vnIWr(M5F@fR>G3M2eH>o6X)C;J8;}27E3*D|Mvskiv-{?XQ>c&aMGz9o!M-P|6@2D76 zr8pA%4%naEwPN})y(HMawmz+rr#La=5|U3u6?RErfCxLa|Nncr1Gx_QSknmFNqM)Wjd27U7si$E?vKZPPEHmRzD_Iv#e!Ld^^G1V+o+IN+xtDUx8- zXVQK<>#}@HYUVyV&37x@bPh8`^@ifKWoedHFK@3W(7D`~+hr)WW$a&1h2}p`1!20i z(Q0&1c$3FidMog<{cb1O2t;)4ZN=eFGrx!!a;(ozP8@vq2ENbeV`u4%<#q0F@p|MK z^ql4lzfKSm$+`J5$V9Fy1?H=;`pZ)yvnralKxNK&gxVWRm;XXj!K;p^vZc934WC&b z05f#etf=dgI)W68RgXwcrP*6R`>YkAdPwnVJcpA;+@22IXDf5`306OI zT$}1Lp=dvXXtoZ5L@}zc)LTrMioA%YKVM($$I-eSk!QCix&e!PKAe2MU5~6=U-}A# z8O+9Gc_Q9KeqIQYn@iR33e8f6pKgrW5MTWz1QD^kbxRa@4!lf3OOK1X{J34Ikq2cn?khX7d}kmalWuUPRQIy)3~5|FZ?iN3|pK~xE$w&e_UsE zxZ+35hGPm}*9|sC?VfZwRboMYE{dMO<(RFPM9!Ja6e6PtiK(8FqBo7(p^(lpd3SaQ z{%&|_G=^}~Z>K!q3`G%Sc*|pZlg)=>$C|_C0oG zhmJs2-4G&9qww1OppXOgw6lF)Bm9Z?p62KE-ge3$&PAEDc>TeCF?SRTXPH(Wg}yfF zp6^gamPh7SSiqpc`xXOFMl+xg^04MZ+V=c-p4RF@0WcEBV!wI3rSg?EQgCD_j^L7P z94}$}ELRp~3n0*50pYgQrq?vOsEqe;Juuh29XJaE3+rf$E>fPj8~oa)oG~_EosKt0 zIBy9iDN+7AC5ylsiSl#Dvgvt@<%XRgIXLRi#p z@4k{Q8WHwr;MT@dQ`yAraNzp|Mo)4%?}7}W;2IvX;z;e z$aB#omdU=yh<5B_4T(*AAyiL&cY-SImys+fT_*6R4aY$B0rT;Yk61o-)}tVif<2wy z0_tcl=C+AlY0j-NJn?6&>l16cUaZJB48)0iwsdeONfQ5w>vq?nr&@c|vWkX3b#cu$ z!GI%!X9#^*hgooF5b1Z%YI1!!i(I!k48Mq3>{2nmVZ_2sZQwhYw~@ec;Q#%{=~p-uH{L zW-nAu=q4@R@W=i~{m(EyBWbg#sQZdIh&|In*F` zgTzr-DIy9IZX(h6ejoldxAf~jRte)|1btwUk&2oI$VV38@|vx`ztG(JnHG5J_pv5P z`u*3-88v-zPW~^k-NO<6QL~oC^92H0v zWiHB$$+I9RKI)Ik=nO@&OaP!wP#@E}T&{Pt&vvK~g_WPrx%d9nvB_b!U*1liB}F-K zqAWaip)Hxx!=d;ofkq7>BB9ljx`~0lU)1v)vuXJ!A=#Kkhg@ZM>B5!iT;;8Thqd5| zU}e_M&Z*Rr??y)Bef*4=c+W0#i7GM5yLtE-uCp)3$)8o<;9*Jn_mx6+i}6&BzRUAo z3{3b&L^ytlCcEFdAb)2iZ#e(!L`$Vy`51x-1)n~fI3LcpT+N*!rM>nOemYrJo)k>J zdcz*vg3&M6>zzMv1G&dS@UINIMW`h8W8aWa%406dUDDH#=(P;38KyMXUfC;G=%SWX zWxhB)d%Kf)7S*r{nGGEP!6Dsr?VldX!|0#!EiMYSj3qu-$sjI5Gb2Z{{15x_`;EJnIN6}|0e3)76Rpd^1K*>G(CQ*x?bIIR38$;vNRXjZ z`N@BSb=!3#|B+JQs4X(KLC!V$bo+^1jEF~QBs_u27(wcCKMctB;#S+S7rmr|FEQpGd{7Q*#nd@kN64--V(1-Jw^ zZx>qJ7OZvhc6Ixm!J4aPImw;!3vUbz}D;xAG?AO3hV@(EkI_e1rA80QXc{BsX(@~MX+0Va~7uuX?X3^m2q zNJI-0CbXA-lohweC|m{kccbU$Wgq|b06p5LidQX4D2i)pDLz&r6SpWvfN1<`7EB5?8F?^iy{K}+mG-;tre=IM$2Gxlm3gN z08&rl!Qb@AzM0mTkbJJq!IDL{{ZFy4LMlVM-EBL*P*XK|I?-qVYsjI2&6m_#d$tGS zJ~22>M+R{Aa3i(5!6dj_*#w6~?xI&vy!39TT|#c+qY4M40qY!v{(D!y3%Vz|5~Yvq zqbaZtCSCE?*0xmDIL{2OT92F2#*XF0j*jy%2~ z#s9{_b23fGRb!)!^G|{ySD}!?n_dnt&&NGVAywS9f$ek|*3tm@>5MXJ0btL@u$s8u zO3+Jl*FmoM(DkS?Q?U(g%rj4sjrnR+^VeGvU^eOG7Q~`2FsDia^xQ%M7VZAb7`&Y+ zp(_-1#hcWbBes_f#e=CazfAcJpc3jLg?@x8mlc+wGK*@~9yw|eg~+7ek|`Hk315@Zi++p*)hiB!s3PHgI+G;<3z;HWxc*=x<}%h`s!% znggT8Ix&PiH-&E#t&koFUujjF=qFrM`SVABeCe{o__+X)tmFNkGX-o`lxOF9e#mD@ z5UfX;oMiu-ZVLJ@GT~|ZNW-%Ar^e;bxjM2Hpz{7APVrZ{r~!Q~6aKe_(a4Li{r%iW z%*A{*&fhC+aj7k#r3=NhE$dDI4=Np>4D>pCjLLI_f9TH<7?M|*l2vYw_s1bon%kd#zvaWx=JXDox+x?=8eW%xU=3D(|C2SXmNO_xPx^1dF+*B*2Fu%)kmpP1*6!-` z>+}c=Mw#m^*6R!;dOuZJrw#&7bv!wVFUOw8GNr4V-Fq%H2S@h1Y=^Z*btISE1HRC7+uhm+d|A^eN%e!HsNa2>(EIBXhDJZH#XE;wzRJ4SWC(1GM+c z4!+aFpZ;~CtN+gurIqfRZuAS{Hj`seKd9`=Yy8zJ>5eUbfD4pbos(DS^qY+ z^;Ubmq@{DHpnq0znBit(PAIWhG}=nHWpT! zCop#}y3lJuYG%=S^NdZtsh?~N1gh{(WKCms7aHZO>64t>5;D*^4ngPxLXU5j zmiqT6qL;#1G2TL;FMJ510Gk1M07DAI-gCQ@hR#s-PLy@JJ9b;1ocOfVuQ6gpZ!&!Z zf4(0nq9S;MEhin_w!8rGTBRV0KFZVobbHn$5G2@EC#wxBAsuQlkHOml`%9#u#OZxf z(-SF=k@>-l(W9UQy)ybf?&t9Dq+U+H$@v|qSNmm;L|r;QH$Lv|g76CJ&Y47Tp`GvH z6pnkC|ERrO_(kc7&w?MF&SNU`ddG`YP(}cSFb3{#i<{Hh-`>i{$9Kq~u474fm;zHW z62qQnonPM!VF|3%MAB$Q26}5wp6zYMzq!p=EA*@cdSPG5v*`4VDDYdrq|P?PmR{`t zwI#>W_!WfrBjAuIV2Lc&4|NZ@;*Tb|)9;uyCZe&+!p8w~WeCj%E0eI~%X@yyie z8c#fve7Fxilgj)z_V-_jD@Yz8Af~yDpbt7wZAh(Xv8qYFbPV4)Z%LImIS{MF?H3Vd z{B-h5f{tpo7OirlmH1%Y*%Xd>7rH4kDoF0|@AY3c3K^jbcsVIS3`Y02)0xv)BbR-~ zwe-GDJb+G8e`IsRIThs#BS-4nmLKOmsdfTmqL!cn)dG4Iyr`fbN;vBp;}dkv@rdPrJKp$Y!qUkqt#lUc-TsDzl}N<(%6n}9kN=W zWpFw$)JT8m3!M2A4v~7U&$IrDMTmaZ@p4yMg~Hq@qHIF3fG$dMZv3yt<^4a6>op%D zzIaa_*f--iwSTX-Eyo6* zK9E3rxrzjtdZvFhAKOv7C}48fT@qcX*B7F_g_PyLZ+{?_`!gb)<9xog&=ii?0Ug^} z)n5_~q7*#C(`eTptI|Njf02IQaY+`PlsPXw7570cJi!ED~yjwkQ@Mng&^$CO`4gLe((%989{jlIX zmnYmA$NHtxtiUQZVRcRld3w|V%@1ySzFRLou`i!%YTphq=x7oi^ipMEA zOsWXCG;lHFq2L_l`=L_6x;yz;&c6Wmcw^A;CIjc}wQVTM<`JvM$!v$Zvz?`gL)pGc z3o^^M^p#d}5l7;6OT^N@FK0iWbK~LJu_w|m0aWYXbMdaD(*7UN!@2#f9S+k(&f5LN zV!sg zH0ZHfT!hk9A%(==bs?KSjXa`33D*6tZA84W7ITJcRCd<{(>swl_i+Y1QW6BSt+R$HZ&07S6i`l1qNgmH6uu@Px?9|4>F({H7xgkr3x9W`a){ zbO}7u>gk2PSzUDRoRm#M<9ce^cWHR-cM1}EOM(#c;hrNC<-a6`C{gMJnkOl-W}VWQ zBz!uh=~!0Uyp{YSCrd8+k4aL<*D36ruYYc1rJG$Yl(cd-Ne>W5q?_5l6At?s)!bzI z9so1=t3>aXo#uN0_@B#3nz!?qNYxpk%Y<7h!G%7c{sZe`zF`(PxEZJd*$t))!yz z8h3yX`$l&2si!05f*VaV6})Tc8MTAUlcwUwfyV-XIxy#;XlY(g<(B1wq1bam*PzJ` z%KPA6j<1HqO-Y}e@^Tp8ii?V%4haM-^z`)4(d{ZB4(Im=07WwiYnbR9eB@Ng$Dq`s z?fTql*FCqm9AixJiR0tI1Dc9I#&{2M-Tq!>BXzL($Dlx;Wi%>EY`hgi1YbC)g zCwVlXgMXaBrHneN)g(2SwhN~b-y;W6Z5s?e?DkuaJMU%J)=DsB(xJ4wi8PgqSDM_@ zPex!?w$4=Y==;mx4j3C0VYtBTL?aAgwGR6JhbUNP*aP!ry_?&hz?A#}p_`a0ay3eI zd@ydBJ8K^0osYENiHR{iG2Xq!a1gwHOJAe}#X0d`sk?_>1UP|CDA~3a6&0Ow zy0&nV6RuROAqfs$WYUADr$`p8vq;c3(tk0Wn$??hh{(+H%EkVL3b;CmeepIxgB2}# zVeHF&+cxId@o-#@a7iIf%LTKkguY!;qIQXPI(Dbxs|_n0;^`~_B0*u7Jjy`uLY=vE zT}AlhP{tMQ6B@aO669O@pWq3_*3Sw$e)w_9=Jx_6TA^#ewncR|mCMv!*xc>l)M~Mj z>>65SUD>|9lp?U&?2oXng^rci7yE$k$ zoh-&f^n5TX+e3Wu)*adT?*~{sjwAaz3tEt_3@Xv~l1 zEWibjG)30kM)l+`-)36l*BIn|yv)sO=Yd|KXe81va$+nUCb)w>-}=qY#3s)3j)@=a zx`7s92Pib-gt*UxDBd4~F_`$U57d^2+t;Gn^aW`uNG5dfSRX{pZ9~=5ki^?zm^uX7=_2*$| z61aFV8nSz8Cv~KGbB>TmtztK>4|N7vpA=cZy&owIjkfc{YOdVr^;hGs8p8Bc?^-7+ zkQ2JcDcQ><$>oniL68Ak+4CAIfbtZEW*&aX52?Dq8Jf}MMDafgz%J&cf)=;pK=OQ~ z``_4-@O#W>Y!yvkI-GIij7Nig%U_ve7(XZ763V9=XV<`RppLcLI6g9Q7JxDnnMG1m zJEBX}>tWs$knx!On^8yw$pJe~lK>AsAnImPUEuF;8LFBG2v7T}Iy7Y!XFCRIt!Yoo z-t^~`pH7NC6+-5{SZK@aytu8qKk@zhPp+Rdt}}FmBk~P)UCXM7>#Pi>na=;U-nfHAh3hml;ePO zZ;cVh0R{n)VJqc;>H|xE7CaW`W53K-O02g^;jGuqX%E5)K{Y3WynCU{0FVO`Kjf!_ z=vWm(=$Ps#rScQj$(Ka8<<^kEFO~stLx26`E9)Xk1Hj|#=GRU7_5+52zrJkg5UDs~ zI#l`HdnG=o&P)`dbiNSyJd|1i{8)-~HT{ELzHGb6k`(jcMk-0ez|v@&YQg`q)fX=a zlxZnrF7YSpJpBNsY3zS#bf-j+wskZyLWI=lFc>s`cng}&wvZ_bRe1jeju`mY=zPnL9a+Ce&sJtR zzOL%kGfLEV){$#dXEF=5wYmyAY*(kld45msS4jT_Qy(3rgDKkMqG=BRD%+m> zIrh})cHe)d5e~(;b+G(~ea}f(X%NlaNE{eOCzO4tpInV1#m~8kN|MZO6?)Da5Tmfb zW-FZA#&#-rEQ=Lt?!S(;HZgah))|iiry&&b0L6rR`6mq?>GoCCx*pQ4%Ed9NYFtk} z=RN{ox$lRnpa70vOAYkfP{gk)2ECDi;k|_l`}qF2GQ{;Jxu(Tva1^gdtvGSNJ% z#>+UavPN4Nv&A=(+`)hTrd?Kw7Xxo3QfwbUwTt7w@46s5d<7V)i_+1c!Anz>@Ob|> z=C6up3H`jEbazjexfBtb0%@d~7%azr8^)bw#nra`JTTFA>YLcyFY~;0+&~tzXCESWz()F|(FdhEvyKYm5WX z({So+X_4xaP!U#FNleCf6pwL$`%abyymmfEzDOe!h$Yi)sm41SZF7bL11+k?M1$4n z4NF{!pfUU_%j3zsOJ!7JDp`I?pj6{~8X9OhN5~d~4cD-jrrC|6UHiyak|W<4cq}N6 zM@a7eJAlkv@Qrv-Zll)Q>k`P55+a`U6w=x$l05VBkZcgvIrS4JxV93$MLi%X{y?2P zIH77{Gl|o)*c?$8;M+1?%y!te61Nhg9d=H?x3cHzCj%psh!X)Yt`e8cAI{*4E zko^jwfZE`Vm?U>}d_Mb93d#?d3^;Cwvuou_)-Yzk3l|27`~Sgg;Ks@pauIslh)^cC zqGr{cg5uh?Y&%#Ft(zDOnrU?di~~AT1YcwCd8RcpHzHIJZp(&K|--Uck@g2IKmk?5Tqnr>~C+l$P9e z#c`#C{O-)tR;toM-e7|8AEX;WwErUgAOB`Y<^1JH5lkaKNFl=zw7V;;A=!c$HWH)DOcg(7-?i889cftCk@<*qq%Cao+p@2C9 z>62+mhq3|(;`Nv80617P*bA6m7#Go|hAXx9LH4tRJQl6%JoJrunbmLO{DH4(io_FZ z521e7YeVALzFmR5MPba;>BQAp9l4K@=z6?vJ(rDuBfJ9kTOf{jrk;<@umXV$ex~$3 z=1tVJ%9_%cWo8H5gNwtMs-A3pKRPF{Hs_=^1y|u2~BdcqXqsqgG*EMay znf|q^D$A)sai)-8hn9PqBnBiPS3TB(^X*G6-&=8xD7KKyo^z<53*13A$-e^Ht5*kCB~t~Z&GmwdK^3kgl#+0_w4u?Y_fINz*Ce3Fx`JYA3}fI%xUN8&_u<`LVchO8m< z%2N%($YG4wd~j=Z{o;}rzks=uUz~mSaXSWz9pcu;(_%HaiG9-_ziFdD_|3TRN`0I5 zew2cV2hRJMh!}0ysG&>upocoNx2#yf;KA9G~c(J$qlb>F3~QU^P;%aBlE^ zl3icWjVV-M-{DM*?Qe4q9-SaXOY||Lb!3@8UGBpyZgk;AK@w!AL?fYVM% zI_Cw}+;8c4A)ZIJ9#?XO3-i$=9kJv2CsNXE3C*u3htRBUw%2y3V90U}91n0^f{t2`jEV&1)Gd!@z3#vhKh{4G}h4W%EQ`Yp&SHMP-)%j z4mPCyml!xDRaBQkmDKdni;M^nJ=fD}fuq=Y&S`sC>i1L`VxNG9usozWmEO((>Z6XOcmVr!JU%AlcQ7v#2w_-8uW-^KO}U0D+5ixK$k zr85sM*~~)iU~t>D+__*_)d6hS;INZwJ0H9^^H5ow+AX)OsMIa{IHd>`o^#BJ%{iwI zcUM{jr;e7COzMDL+o56r=dK8M%Kt~xTL!e*HC>~)1&87m+@0bCDNx)?k>XO^iW7o+ zk)Q=iiWI3pf#U8CMT$#;Q`{X+?&m$<&-}YGd(EDiHEU+$9F;wNVSckB`TqAS%->l% z9;VhOoML`yw_;*uXVwmVz`3%@)ZD)xKuN06sozAcA%B!pO#<*y83_FRbok@4Hv`=xiYMdrD7y@ zaC8J?!@g0>AnODt^b6dE#-?5;?%rv9WOlpqD?;L5$15|-lg3u~`PJDbbLpc;=m0LA zbgl$*GHj{iTZ9QMr$zhu`8W?A&_Jg(6a5(9TGjVyJJlajI!9Qqi|S=&CMO44@tkLgcisz-pS@ETik#)$Pw6%d4Pj%v5&I-= zV70pI{X#sL&w>Mo=^$kddXFbwPfAbs zFH$ZO7!($0!0wdHP9i{57m~2ITZXVFt+@^v9JhT6{9QL0ve3?;g)AHj*pao{Q#~g! z1)~y$AD^0_srT(Q0WJahH?^~~j&k*nS=j_$nm!}vBBnJQe=fwl8w{=&tfexd{hryM z8so(ua$G>5Rz%IZtjsC$-uu_y$tFD;m3P$0exyv74concum^&i z!0s^4V=bp6LTj6eLZYFQ9Y%Fw;(vZGuXYeRXFC>zIXS!hgj{@JV}rL;-C1}H-E!P= zw{)bV1FSWG_e}-M>efdiyF*jgdUrm&!DKuI@P{6*MiietZa6Ui&d7OBI0V=+x7XM`qfAOZEZFgPN5$H zIr))0K);~u@kEs;EZ!n~|D%3d@BT|&cZjzdPUYx&3Yh1V|FSQ}a8hph%`)AVh=sRw_6ev$+k)|A!{4S4zs+o z?le#5sNQX(5>W;Y29wHN0Y6x#`F6M1F9ddY8V~}!&0%{iyZ1DScS?Lnvi~{Nj^5V8 zp^MA)$9CMpZQ^fFrKi|i$DFYx2#E~;5*Y__pOArRz09>wch1FhH4C~dBe#jArq2Z7 z9sZtpXN>o3GSNSelr4c`JfaOL^(umHz`2x?+ZV7}Wo%>auHFypQ04OAsQ|`vjz805 zGfp4I@z|o-1xj{#2LH4tT*44DKJyp&98VnA^rLCl8(hQOTr;)&9$NUzvMZz}(;~`1Eu;l^T_GcEA`8A-MJBb2NK6cCV{YE=x`dCOOlQdqTPYzq@f~L-4m&W*+E&J}3CsIMd`Mbe~3NDmXNr=7wb6X2R(pT7ps@ zlBzkDm@iGv_nN-7H)M68sO59I7L%=3S-sS9)|}knD@lRtsbAZONCB8boWym zVQ$zI3mD#AZc zjP$Q4cGNXwW@Fp>tBl08Ol)$Lgw`vaK(;?L-fFAoD&qkH{sVOPX>Kj}VsD+#fp42Q zoKk)PTOlVX?wnfyj+03AAyIrtQ!|m<{nJ|e$esx|fZ9xPo5?wa^%`gLS@(C?zc}pK z>JUQP=j=1-rfq2%xx~v66Hn&iV98CDhxmSR_*xX^X~hrNXwugV8O=QwbK{4+&{-d`4Rh6$9}g zCTn*54+9teBp0Zx(cm3BjP-m-D&A;3nGs)%5NX=sMUqw9hZp>gwp=MX8{1R5=$lld zLBw;m-h#bFJ|`x;urB4=QrMoft{{^%{7S21I6HaXCkGlhWA{1mtTvx9SNz zx^(!11`Tk|gj&PDg5UC><%B+WtdV+BfI-_Z8bOmAa6)SDI>Sfxh|@_3sUPn%m!D zxRxQ=`BwZPzRiEJja$|UFE;^vZ>Dd0cCLQ%68t=*t~Blao0l_9nUN(`c6MU8UL9i1 zH`38`zP~y@%mM1FBg<(^>qy!l5~<*{>DG5Jj~A#$;3wR@HSX?e(D$Nx=TYR3N%}?r zQ5jXKpWJE?a3^ar82Ofsir3cU5%Z2iWZmi8YS*`Fg&)pZLPlg!dZL{0Xp?NSzci#jSN(W|=0UE9)|Ht)S1Y1SI$!rz%uvWJS# zbLZS7r~Y~>olMG;pEQ)x{^AWKuKb;ACnW2rud9s^>y9cV0mohL5An_Wh3LgdVn%Mv zr}OTPTUN#Hw#~!3s|-AO`mHeAFv)-5)J1W_thy-$HU21S?^>#PXm+7-_hXYp)H1eV5J?{!$Lif z$XofvTT0E&1TQp@H@na8 zokZFJS-UG)0=+}}6l%?lIpNUl?AN+s_X z?f9?M)6wgdGfsi7ZJJt5;PWu=q=lfij(O!KW$;pW&virCSs<1*?xjTf=AE zrnh!?@2Z&x61EB(ku!OvI`RPeJf(8PXy$S-drl`;(9ja{e+|5w(lnD|7|E4@7g&e*dMV zVE^Q9U@xz?e<5S@=IEp78ZCtr?2-I9h=nMBfO^EFF6uoN-&*k#G4Ru!lV;fg=T(as zr;#j}*_O25Ur?xu{qnp_(jW8g2JRGcEmb(Yi4j7Vy+KG`>rF$}0DbpDQL#aQiJD{P zgF#D{z)zO*xzxlzrV5p;Gh*5Lo1g3+y`+Jqzi&4HtdeME&94!YuH>vWDO>4W@O1%1|s}xj);E08*H_xaf!<5 z;FnQ(=y=5weM`As*ZZvcn}JBbE)NZez7e0;Q&+U|x+q0@Zx?@$Hz6{+W{Z0}G~(0q z$G>!7v7_!Xe~5X@2vox3_vY78TLql$uU`UdQ}Z&AmjCwuEbj|rut>NmdP6uSe5a5A zQ9R5*0K$$EmdCo_72j3^I~H$8VLBQk^$1D8+@IQ)4?vk}9Ds>zd~I&yH}`>l4JWsG zKQWIMh!UNtndU9~wpLMj#FNPFB?s31M{Yuw#h(&)sH<0Ebkr1|w6OKX^%{YIg{rJE zz>N$2ko2eNp{_nd&Ej7vO=AJVh5?|GR97cC$PVT0?8ZXE^$^B~7>t|S+m5FmY5@YB zKM$9w9Z)`I^>SI*B1j)OOz`;>W3f3-d^=^IRB;mTJ%35PONU)MXpd4=dm z#Q}4H(gkI|JN(O54=rDvYK-J21B1m;pw6FVN*N8aW83aH!OZr#)L?>!-iHGVDeoBu zohvG!s*`5uxSNE$@55TO($Z&@$Fr z0k!Ftm}7As+Qq~+3#B&JJ))(;`xK9y3>mL~gREQ`GOJ8#4A~d%P}kk8hmj6KNM*!p zVY##-=V2l2Z@aPgaXPf_JF8j?YtyT#I^CLTgR}X+&^mt&iWM%C zkSe<^(;)*Qb&7ZV3;F51<}6L%?{i)om;97C4t&~W0ia}CFnEY6DJIHEi9>c1s%<1-C!HyRMQ8ljc2ni0FMXM zp&P72jSuZ;YWkdN?CQ`S)*&b8>Y7G#RoX>|HgrY}%C6>JTk>oM^}U2fixY}qK{r*Q zo6c(bZP$?RLwIUy&T7~1pkroi9crx4xv!JI(H~3)<+9$Uvfj$)_}sr$J3}siHB}RS zHx(MiO3mWLNx$7-!mT#UcDMv4()(J1uv43sW}BR$6pvl3WgGem-KhBR!n4n z?VOS+Itmq~1IDYordbtmVs@IJloWwpDXJ+s978yqG|U#Cu1tORGB!`n{;^*Eudgmt z6n9&PsPND@hd(8{bl2})&RDz_CG7}3I)%9tETy!*{xrQ!;oY<&H`Y-bSlhSb<_#xW z(CxhAO4|GCN&S%#VGN?RXxm#c`y`Zhti@p=`XIK!#>=aWs%5$8E|Wdo9u-5BE{k*9 z{fSLn=>Fj0{+1V%Tx0Rgop1<|Tmly@h4nR8FK6(b%=w1Ymsq+pxPgY}n5lz)G8b9A z*;Kl0f7;jGDGJ3PEPJxv&Yn6GC3v?q2E^SNxtzQKTwoH7w&G9f|G;0RiibN5HoOM` zWs-<%u0)Z&+*b$#MZPrK*X(I~JuZ&8`r#|TSIc`7&Sq29OC5@ zcg$|AEz@g2Hjp0_^mNI+?N<1*`|UQp%7^#F7=wrK{4|77_kSez6=%f&o12ryQi1b% z4fN@ix9$E3OuUsRfYr2$@#$Rc5DI+-9Xe_fs&6-jhG)SFa+?Q?gloSPzkVh`ZpAxjsd#O=eJY z4mCM`r=XtX3D8CG;&yXd$sVs-kJ;6@j9KD&LG2G#NscwVNJo4B{?Gq+qZEB*_^){- ztF5YOYa7s#Tw?xbch2qp zq}QKE^!Am8(rX~a`&K^&fSkpiFTVF1WT`#0Fn}IH`xn*Qe#v-2Q{T{&AEasB@0GWa%72Zw&ui1mcb&0)R zjx#kUmdOoRW9v=E^(VGuq zA&LC)7j z>aB_cIQabM19M$ngx)Dt0RrGS?IUGx$zIE#Dtq0?MWQ!n= zE480rFQi#xr+ox<+QOCU1%W+W;P`aPtH4cELKpkM-l3dyPxoF-Y-<^h&>Y9vDf7;4 zufj?Vo#geXVuxQSRZY-E5f7a=XVs8Zw;Ki2O%WOTIeu+P|GU zO_VUE(8An=W^11bZ)Ga?Pr2VMmYgr&TlhpI4c5z{z!iI>5=i=v&7o(f`;(rVjbp(_#y9{b8VkUU)Lt-ih zbOZ1)&6F61hK0wg9PLL74XEF}zVFsGe5Cz2^G?MLcz)K$Sse1D%xcM43SAt-qQ61E zrAB{lzsJ7z{SX^1`-<%q;Jog&bDTCsQZ3hLGoI>tS;nfyHY9#^wAl9T%XoWL@7Xxd zg71}~1#2T3uXtx#f4Ib8?2W1ugTzAvW zXzS~+&kh9)t_+&R*Tp{Ym$W8~G7g&e=UFDUsA(%Ia8Bif6x4{Psl661^t9Th#yc+B zuWJpIieBq|Vm)T7jen7DA}2=0ZGeqsMpIz;@yH7NqLx|xo{QHigxoM)2b3*_+p+fr zNJ*G@Mmj*UO<5#w`b)yl=nAFSM<=vb#N*3Yh zfUaGv&MEqjyxvd0y@4Q`HQ*!7HdHn&fO_n?!42kUBi9@=>LR&iW(cN^{*mJJkU|fT zKo-+Tu^WT3+0i#*J1u>EwCY2=;Y0Q`Vip0VkHqd2$J>&oBi#`d4*RQoQrTxyWY3>= zcXy5iOywt~wlk;6qw^D+WzCf$;7-5?_Of1?)lr3%7_bt=`KOV!nTY1Qw8Gwz@_S)W z$LCsyKSB{V!rn^BBNRdqYLH_h{?G?fqowhdNZkQeVe%hIBhDXoi? zUY#DW4`FnQ@V@|{+(F`n<+jLt+yB!7B*b4V_iu7gdtuR@J}>4xu-6#Hl~bv0Nh_Am zTY6`-i_gqZe>y3gJ54iaL{N|CsNI*h4%o+0ZY>lgpd+l+o-R>tb*m3EYt}6sMp+pY zy3~slfmKBrPt!vm(wmYSGj>U!6?7LoU1TCj|7KSmo(f-`53SVxL7dP>OqQ!px z^_;>7dW~mWa^ES*i1oCXC3(h@N@tVPnhv|8ItQmXomnQ34;@lVJ3Y9nnA zA7~teZlxPx;%pzr?M-4xsPWdQ#v9IxetnD)qFR3?Xot@}Ie<%#e&2is7DhbvJ^rS^ z+885sCYAM| zMd+Ae@o2&CS?nioVnAbF@zM6Gc5W3e41C6DapyH-tS8MCCuj(|n}UIm-O#Nq&D;&> z8I(-5FLx&e*kCWn66`-1aFzWj$jst)Gs^&ibH44?(&6UY9y7%KZ38S+qd>74pmPbo zpNdNnH$W;GG%FnkEPBR}{m+ein8T6e%;)g5S0hRmsuS2v4+`G*X|m}BUKy5s<@_pg zqloKuUh_yob&$?pkks0c!B$e9`YF-E+p)NT6Up`cxKg}5&~$k-hJTE2=#Z4kkK$n7 z;&#ow_|{`ZZtk}xg9*+mpNDfgbZ_16%CPe)${EFDB|kSpOZ61=zWo$It{U7@YVo`B z5FW;NuPu%uOTqc(#*TOwF$wL_tY-~K7)57Ie@$5UP~Mv#zWmA7$wL0AiF*mMlyqEI4_!EwQZSmug+P{WUkQ#YODR1} z9?JDL6TsCps*ZPwg|-#uW^QZm57|; zv{3iMoa9a#UR#sNb6-Dc(&ThpKNFlQ6a}4!bj-=Bf|Un_hTK-0=89i34rjZtthz62 z-MXy^4v3kPKm8Q7Xx)%f430Q>dP~wi(I_7G8%e|J7CpRNjkSG^Bxq-DXSAP;wg2k` z;~E*+?M&&{orm`P3_k+L&<>keN{zXHBLNgf?|1~^e7@wJ%%u3}&U0uhS|}6-we-zpqoyc*gl&k&~jQnLpU2 zF&RI1CNQ!q6?5zH_0T={+5hI)+5@_e=e;0ZT#>&xa7r}u8#L!xG3F5~V!k~=6fI9H z5IU&@UY%jknEn8as!G|`id0rDcCw}wSPkA#3*4G!%}^?@-e4}};u44|TE$ke-D+o0 zMJ6&lsYv<-NFB11o!K7V& z%Tw*2t}k!03R#_HDTKNS!iZel)Th~*W%0wV=amX0=Pog*XL2qYyieq)o?K*mf(r#P zX>401;l+&Y`WmkG+g5hzvCxaJnTnx6Zq>AFAt zY?vb}$V~qV|Im{sTq1ay7QRR7BzN1?E{cqD?D}Z z7D%i9ua|svF9KX>za$0P1p@kUtX*Sc?)7~%8ahPOjG$CExZebjRPjN?Q*pQcpx1i&IWg4q#-A!u!{ zb`YMkrF>RhtYq)wQcObMt$FtQA73yU33h`DcVcv7G7Q-zD=o@u@f zp#(7RS+FQrZS~cIl(Tbn#6k6Z%Jz4^(ABmvwU=h`$&0=H4$bR-Vp#mKM-rQ^-)JjT zf^S0gfOT6DlZ!9#&X3eoRFV?rscN|h?{nv-vi>(>BtV8NRFU$ul<6tD#Z_j80KG8G z-I4EXhfD&+wzlI5r%RR9j@s~cmHwX_joL*6)#%l&-)UpkV6xGr$5GLNV|kylzk)`R zoXCB3Z(xdVXPkfQO=�aB&t{0ojC#IpFTg;bcP}nOYQ1)OkxFyk^^*MqfLkZ7~E? zI55B8-uU6Z7!wK|!ZmyQJMDC52lRSgAhJsT#EmeDdP(a&_O$?mpf2>Jna`uM_pxxx z59qdfWnANOwj-gFs?~1(YcV07TPYxu_PuHR&m{^{u%suLy&A#;%2V5M3OV4)+9_BP zu+SV!T`xpxaV33LW`2^jPh=M6>=$f`U5-|M{h7>>8|iK8eqNdUKf)vU|MdIclb4Y) zN|k|gh&tF!jAKUdIEZfi_nszg*PY&PUXBJ@ytO*j=?@7^JHhCaFr=QbO(czYGS5+~ z*qkw5q3~wqx1?85t*j?8GcRxj)M7ND;qvwIta9ik?4P1|?U+z2G?{>cxN7rc$gNom z+4ICUk(8gkgI)YvDE*D+*!Nl?GOBDwzI@-fjns@DLqM?eChomep8_5uV;HP}?`&=r zPlo8OGTQOJO#4x+(TfTe#ppx~*d~>X0pZW^_E#yC^)j@Tq7#carJ+<`@R7S!aLIHR0r-kC1T1Sm zVZjxd#N0k)p6N2ze_9ZKfVWKMJr}3(x3Z z-wD^+`ga|-(mA9kUc*p{x+(c1cQV4nnXO$6It2y!ww!z3=^n;Zs^OHj4s4Q-z5_g; zW_wPE7hbpus)jShns@vVW9V`0N9?dvm$^`AA3&!DDLW{VI|$vmMIYaIPz95YqUbOD zvkW^1f^96Yu4)CZd^xpx#5zz0R?%UhJo?PdJrV|CiVZRr!%L)B!*ONyqCI&bR13ke zrq|I&TPF(Eb`$~~1Q&A}Wz+yYJ+?)5qp-#geosU0fHz@k`U;UH`{1%Q$N$Nu38v7UI27o4}zGE@D{k(d<-b^F$e0eb_p@!aSn zR}YtR9kgI6{+m;Rk38YSs33E4qQylF4_TaZQbvEV;&A4cF&D(ms%{6KdYr{rVmW&<2>cN#dr zz#7)Qdq*XU^;d%}Z7mCa=RSXF zG%rSQFUL0*dXGAP9x(4uewQ2(EG9_MrPP@owuX8o|Br4Ngt{USkqsL<6W|}&Ooz`Z z_U2id!FzSOKd+o*m%)b}hn9&XC1h}AEh8911n7dqFhs0C8*csm>N7v89L&0!M?o-|Jv8=gytRt`Y2?xk8!M--1o)`KVG z!8Lv#N*FWl!70U7xNFquvEp0B1eph!R$t1H`!>&wysVDx-z#)xuJ)Hc9L8>ITTe(v;oT!J#5{VHi7N{lt6FA51{u%A>j{ep^DJy+=7Me7vQ%dQ*T%>n2?=Gf^djy*ROLf zj8rC++(ElL+XAx(1aNG}PC1Bm>_F4k!3uVHWN@tu%`Zp$8$&w%w|TDTrJ<-xR<~Ox z?%)ORqc8|_GW#(R>^bHFk4bu<8V{GmZ++39BL5)ZVp&B`t{th>eS+F}C3jd)-0#N)$3MEud=X z(cV>VlD zA8$USm%-uqC!7!cmnNa>+*Bw}59t)aEuw$$i8>2JUT4-oBAKv>+8Iit zCn?l9x$;o!*`bM~?kdMGG@TkM@DBRyw!ov~uiXalzRCM@PdIPu8L*^mkGMJ zHDb*Zm=pG`VI85=2+k6)7Vc-pxomND3N>xRYZ1*RRJqYJBb^yc*CsdZWLC*N9iO8{ zYdar_M?-XS9h!H57WoDz;vGbLmf<(wXrFnv_3tGs&f*SB&QZ97tdFuEZaLZltO=G zf{|A47)yfJ*u1S?!~rCR_hF1-|I&fJlu@c-AhhxD+aKl=?(nt33l#Gv#)x36?d&^b zxvL>bCqatM4k!1V&88}d>0&*3mm`U7*-lU(j7@3OwMw|HF4&*#W1-wQ(@Kmo`BgB0 zZcijV>K6qpL;k7ZQ#zhaw2@5~JNu*T73zz5OEeX$2fx6_*?_HmGi9o{0HFL)&)WB& zchzDJoc~>`R^>aXJY%le%s0qic@v3Gj5i15o}}wbR(9SSKFvLz2PP-m?@or8HBAR0 zC`EcV|303idtgc9LZs0I3ZlRuJiASe$1@DpZKl_XXD|fd(Q_*sev%Rq%q_EssoD7$ z3(r-^(UPwL$o(hm#t+b_8(ucK>48Pu$W;%>v93&)RYgG_@ysnL5NFup*CHV!k_U82 zkM#PuBgQ0v`w;5Qrl9HZKx@TEnda1XUi;hIH3$QL5Ke@SlDoGr!lp88DlttapZgah zo>Bp zi+txL6AE3FsBr?}zuxrmg>i&fMCp&tl8EckkD;&$EXNQj{p|$5K_-U@Q>KQE$OGkN zmcvqlkrLsAiO}W=v|zthUvH|u-02WR?V#@t*XY{bY+66J>g@Cth;FNj?)7>N#=|ve zrdhqEqw1hgfuM9lpw5F06u|tnmz>keySLPEx!q?qs$gb(5MexPc+D1Qh0Z>*M2Bu~*fE*g4uA00J2%X@R;fNAXQoI7H;lXa`@Gnt> zTDMJ3!WH0p5;CZ2=%7oqfb>X9X}mV$o(rMfM@+c-V5p&M9DlebUd1E+3AQ|S<)es% z7j;qy#zC>ga%0d04f=T#Jy0+oO$3`&xkUGC!L#0Z`%Qn=IneF}qq9-glYm#x<0AKb zS-96zE=_E>KN=&d9AR{Zfa;317?`i~KAaVwA$spBx0o}brdSVwJfa%BkMZaGh?RTz z%+vN9&2OvY$eTmr6|`)E9$D0U8T<)+#AY5m5A$XfEO-`>b3;LQ7-`XI!D7^NLpJyr z4Xfp4e*Y419Do5`!{W!{H9z(6?As`m_=pn=ELj2n6mr14g%z>uItMavQQ%N$v{8Tc z6_mps{Y$n`%z<8Jbwc$jTcLh);-})>+-CKD_^H{$c^MObM3V{W<3Q@acl4@Zz4NF? zyCG5LdGV=)%0hxuZ#0mWH;w-DP1yYb!f@pA>Jjv>Ypv_lx z{aMNe?=KDrpb$1&03HY6(Ud*U&J9}fj#zVC2}M5`|CcSg^j-{2YK!?l1+NlKfcYP$ zbh@yg3vYd=K-dygHxdt9AO#3!^4ow-znp@we}Wj6;louu%Oc^z2a8 zcq)Kj6aiv92{i`)hX<@8#;6Bhs}6wD z>A#)Wl*sIN82RD;`4KzEk*7|aqQIboC^~F1&ueVpqq)TSvFF^x@VRl8RSjU(G-?M8 z1jcBdK}?)L)P|=K3$}E1RHyvP30}0PoQ7OJOeKZ!;htcoi!C?A-nv$?W*I z0#;GyvG*sQ-3jGRc1~0*HNUhHX@|Vv4;G4=K&=eh+zGRcwxc;PK-`d?=XLrw97ia0 zUPMU7+2w)`cpz-$*~+1V&&yhmkTmKNYda++b?FVvvFR`#;3JXXA|^sX@LEX@mF4?| z3a&qD2j+!50x^D8KQlPiZH4JQpu!23b~y2tcu@cHhd+^*+Y}kZ1kO{L7ACBZ5``%mt<0N0ts_l=lz% z00^5BgmyJjlM>1qbHwx|Kr9D0R_zY=JHdb)oa9yG42DJo=G)eWe*aXMr<`M-SZgRo zjr=zDR#P|KuMv*@iI>^oB-u6WPlWC$J(`X4r? zSP@%-FR@M|d0>uVQ^1no2bj`>?=Nvh8C+YASHE3L6lcGLBaX3a%@k+XX@NoHuHqrP z+EfoOb}Nygmf^Cu$HtHO>cq_p$o;wQ@C-lJB$TWffiKwZiE;&y8oN1~KFZN)!F( zVLy<~&9$`35AOpPwV0o=;+i`dqSGK1#(z!EmQ8aqbru;w02cq3`MPoCDolX*Lm>jQ5)*5cdvvW70zn?0Ziu-^W%K4kaW27wG;Ac{Qx;#Njq8isAa%Yp|jJrv(^^ zZA=w>B$mZ(R63LGw&q-J?Y?~{kGF0y*!Iohs=-K;g^NuU3(f^Xsd}82nLHuJY6L$V zwn}8PZ;O1$6yQZAW8hBrI4+<*8{I`uBdn4X_g7?3JoBi@%^>Q8u70gZj9ly*xq262w8Hj!*Luf7Vi!uh*R^zF5-_Ci;UZ)4S z#i1MRDelb1Ywu7qkEl%zF~PS6MR)Jro__>ccnQexWBMCeUt8b!{f)JJhqjERhf<81 z8dXjC%pSe(VU-Q0b_9$qWD-Jyziu)h(w`5evh}oGenCT7_$#_w&=#r2Xs7oh9?5PpAnOl}s#p$o;Sg_JX1Z4c~ z&`X#Qm~ZA88h4@BP$@TV8W+qYW1+*&C`PQ!^fk8Q5xJJOBVYVTN71WVp^uq~CpCxEiwp*`aVh;Wvep@D%J!s~h@ zjI^5@km{f0rn(4G-4Y?PM2h3&S|g?WMp>$Bf+vDAx&O669T7S9j*M``t5)L%YjQep z=Q=pYKj2V4N&~+nZK9syi1KcOA04}Z2=TL>d4Ux}mHzo+8)$KAT)!%R zW>W&xbVD!rQc$}QCf_}s1R0j1I?nFKsLvE{`{+r~&1ReyfteSMsy=ux^IOdYnMwVQ zEG$sMXALq!Vr)vLZmcrl(_f)Tq-;`QLL4CnQ1V#nt%K?YNqMs2uNV^jb!Nr?k|Y0c zu+mA+EJrGjl0w*>7-BF?`5Y{M9CXARJ;GA-1w}Q?1a_Q(@oh?;wAaVxktS=F(zQI( z#iD{ru`FFjor>YbVAB{SKhq({hL))+vcURYflEp7!XShGbv><$!4y@MZp>8Q*~1_G z73{pvJ_2?@T?NsFL$mWu(`s*+ybPO1JsdcE%}|d{Y(EK#83g~C*Q}wC!b-}9$3Ak& zW{-Q%B{DTPp?Ji0a{wPPpKUVPg{-s{Z(jW>1GfA8<#D#Vx01kY;^MSmp1@qXxv%?x z>DKoJ6paatdS_wR5fw;Z5O^?#z$Qv zgZ%-MsG+8wAJa$RJ8LGjzZ;e9YVQD(D4W+TvLL9g1o|F9fO|dd*Th#CgrCm{$mTi^ zuNCLOo@LSEc8H7>40JR3mr7GV;qIJyp6J8lT2%DDV;ugVQa!pY>02<%v2 zV@AN7aF1ndf$XkoCf7u#;v9+-Diw9_5#8{3Ikh9hAuu3N(lE@8bpDS9fEOA+LcbMp zepYvq@3(QzES7I~(lMUpFhy}SX)axo{9-=g_MWY8VsPFm#E$NWDr#bW`~@EZI2Z!* zq$3<1ii=J4IOqVh;x=Mwdib2n_T0G`{J8;XUW{(LC5-SSQq1wOoS~KFgz2Lw^Cz7R zk64F8Xk#FaHn%>N33f=>x~l$XlX@X`+?!v&>VnYUu+W4d7~&kl(n*V96^sqZuZs~A}F_xsAXZ67zOxOkIZkH2m=5oFRk9R z`bD#Ew_Xs)Q?9#JLrHnXf3>J*>wz^op;Snxr}?5J!yN#MWVUL@kfEeP(YIQ~um$1Uz8GA_MC^ou_SO6k5PO5zy`N6{#6-%&=8L);LN`mLawc&c4y^eNDr1TUN$B*tKbkdZ$ zlZ19FOZ|aVKc|rY$204O&M<$g16^-q4VJ>}Ze4X}iX-74NU{gG+FC4T0e9uEE_Mg1ZF`?iSqLA!vdJCs=TML%#p**|UdbXL`E3 zs&2{c=@FucKNK4y*XVT%K7=9-%;)d*yLhts+#>o{>?=w_cQ_A*5f)TGWGzvt2#>5_ zO))$oLw3ToA2qG7Bn{pN7SbYDuY^9@0A6VLmtEzq%a-%lGgl|+$^uCMhlbe~oJ(&u z!q7QLF>?3=Kk4^)B103g5z+ztyE&f)o_m2|y-p7AgE(G|+mn^iMLaCc z3CDgD{{2T}088lj3E$$HiBIW)9@W>lV_|MG*uAJpFy*Yf9U>u2c375yVz6+=cYUlr zpJ4z#s)neju~t+vlJJlxjzL8OY33`KS6IaPGW}R}|$}(Yp0OsQ* z*s=%=?t}UGlWDkbV(gxksMk|3#d%*%!Jcp)dCMNZ3t{5DVIJh+>+CyZT%hl6Yzxj2 zff6-uGE`oTU4bt)kV?GiMs};cw-Jx8@BiUdI1B3xe_pM#^+4Mf$P1qqBna;oc~(J~ zbjXBpEw-o48V8>XGdoPd2N%jKBV1piqnnZ*3vwDU*e8)UfSnS38jIB~1_tMX^{;HO zs^GykgE}Ghry~CO_`R+!>{OHp8>&(kPROtL??@BHGR3Vpt$BfW<}z_ig1>y!SjovC zUbpNXX;gH9P5UKU@l6*BW~?d9VHb0uIp%_Nah+klPeaz~9oelQY+V%*SouVUaKHPX zZv=)kY0`s_^F_=p!x4B2s^|c6;z!}1uv8Q$kj}j4RE8i&LC36a%caY!SkB$i0W}14 z^55|_Fdrb2E}fYgZFsXzR_zO^2RJYuK2MsUTSxB3vOahLrKCe{v8~|KW+?y~KE72F z=FE|#%__6(c|$hfI}qvWE%d1u;Z=s=Ij^zF1Gc5eA@Qu@0bARAeV?>z~;O!OeOj zuZ3>}Wlm676n)g3)?a+ysbx3qI;-V(17_)^a@)=~dfUAbiCA;*z0mp`7GNV}Wn?rL zVt3P$pOF#ivXgg0px^nugf&^4MS*VJl--2(*f+x_4ZajKF}p_>+21n_3`tEUggt8G`B5>NsS`>#cUc9Tw~NyD6&CkP3_h_qs;@6H(0 zIV@i4;2URp5IKE1KZ2ebf&pr1oc$C#B`T`C&a8wg0RGf(Y1W+9&m8*}SdzdCf(R#q zx&6hL*zc~a^@@T_aEQE6Wl<%ZaThy@6rf43&M5 z2X~BOR9X#d1J}P2TFO5qI~3tltHpVCB3_|ds$Fm<2|}$ln%(_#%^uj{P8PjY4BU&P zTIf>tdQa4&k^kf*6BC?+r6g|zH>CEasJ)hCKtT(q*eX-jWEp6WD}1ilFtLYH1h#y~ zah$Agq`PsA9T0U&*|n2$9I)UZYL1g~;Y#UiZm{ta+dAK;{sl>go?jPK**3x0+D_YL^0{3iiG^?)}Y>Awoqe+LTu1F3&M9C|dCrvqsu zo-tI<=q#UIb?MvblLbIhiDQOLe-r4`!?_GIuzp4YhoNCqiR8pFsRBgfCIPIlR9{)w z%uN7>0>6>C{;dhaCnx>Z2?#-%mLVi$KK?JsY8`YSQmvwHg$0ZO`$t2|dPO)uiPCaJ}}^z z?dRtk1AWu!ff351jyJLvgFWgS>=q)Fk@jkbtBDrn@=f*PepHWtR`Y+_!TV57Cm(+` zY}>RoYDY+uiXhq88tJB;4-^uB%;v3(Wb_gJ5sI#ot*9b7@z@T1cTB$rqA(@Q6Iw=N ziOU@UClDWBD_ZndKCy)f9I8(>0yduhE-k$;<^*p13+hNWga`jJHmiE-45_5@6fLHh z;a9@ohSLUdWjCazk8J;ZC8sPK#+J%e@<8QeI~$AFJHx47M~H+PM)RQ974rm#%2RD- zIYOR~AyJ{yVfdV^mOv$E*+l|xi&apkdpOr4}XR6d@YvLmjB8y7B=&d4G9bCP?QhSr9mLCJMcwTrvWXHL= zAw(;FIXs0E5$g`O@&_)pL6~I-+iu&F6VCd4=+6zTnaPv-%fSP$O5-*+Lmq9*&=B=Imw|is)inp(6}=2cbmKF;uxMCQC(IcZqksB^iq? z7TGkA!jiDK2w0lk^8%w$vg;k^T?~H1%K}bW`~?Qz6>5EMzh%jqtmpIj zLdR?9_$MMBA-ErB!SWk$h~W!<&!i#0J}Q9C5*W5++0-^0Z*%|3A^v6!L`Yoyj&=Z< z1T~MUz|notU~g3uA^Whj&#jFapHE9@!aVia5a&jk6;VJvpk9(vFFDmDG2qp=dF1Ta zg8+{EJIbA<@C>ZNSa%)k_ZNe+S?2G4w)8azvJCy7uKp}je^A3I_WVbma0V*MIHVLm zRG32D({P_2Q82?rp!NK47Y7_S{tanZwFTrW(jP{cX{mQH)V&Iiu5RAF$~RjkvIvg> zS{IEFyCvkg;&Qa^(JutTXm08-qdp$XSh=Ya_7M-{zDP))-pivRQr6@Vr0tlBzo%*` zvGteK%AtesCM=EGH)#;-$20NyB#)sqKB6ipU{@70Im$D=Ru6OWkopnF4D$^uz8fM0 zDjR11?(ei-Pg&*ewvwnsscPh1f&SZbfRj!?;&Q(~4doAa0&D*Dm~@k==a`%anpl)e z8S*NNJ~3X1De}=o=!9W4G$b@9MNz$Zi)h`W?Qjj=u;Ax`9i%5M(gY5p8Zs>sJB}F# zE2L>+m%%vFy-wB;BSudM=*}(De+llM-!Lb{u5a$Uaj4sJ4IPLla|eJNSn&|5)L}*g z_SW>E+WaJ64l9yDdEco~Cx5-u0_*-dqI7Ywj&j3KhV5oMoXUX;EHezk=sBg+b}IU< zs`-v?_YUFFLV3lGzCkPk9KE0DugahlR%z@-l$#?|x^Ic6DEg=oDa|6dIh5B;py;m0 zcJdF42W65m(916h2B{$7106!F;w8MXFx*C+OiOrc0MtH~c7B_%&0585?1xw+HB273 zi?0fdmoA)%{HGO^lVHCSsjWF=H>CTLrBQSGaP({I10;KBR%Z+r?fz5>Z)>wG#WCb> zFd@xyue6W%HdB|b$i-sV+*Ncsl2t3#SoiKKyatW<{*6rftDGK6sTIu@gi{>R9Zbqd zK&34;qouRVfeS~{ir`IdRtyv>bqsJ)&2&?~)JUi#C&Ssc`UO-2kmF&^101ZoWYV!L zFko%G=mhGeUxwl58_$w=`TU!gi0KT;_m7A`sFouw@Ef=hkFuZ(Y4&H|%wz!ziNM14 zTrb?$j?a0#`Xd28EA5LN#Uo1EyC_p7{EeV7)V zt}XK7sF#vV^Tmc;mBs|pYbpmKIppEky?^x380(f#t9g}NI*ZA=oS5m757qAqwQ2xDG)uafh`l}Fxd+7&5jp*CWZHG)Tzp-|0G{qs=YK;KdUOw5OIzKfHGPNv$IF4p7GicwmsT~sPz zi^A``sge}-KzdpD=FWjP#HBA-0f{5t+wzbFw@>@>fo~5Tx~I2w8a1Qz;i(ydot4FU zu0nNg4dsNdCi+*OwJDJCk^YMonh|!wCHqB^rw0B)%Hro~tz#297`|YV;hAHJAW1zM zwj%dg84@DwHYt!5edDT~!Aq>}R63#t7(D4WfsElLh$i~a+cNfQ0gH?3tnd}=_1{;l zb{JtT!Byc03$vxky_66`6CZ`UCjr(cUpeD#eBWV8EHN+(D3 zUpGFm>tT?mx&+xh67+-*i1pUm)#k7bPys?K4W&O*^cY6xZbxG)B*c zI0$Ij`353l-_^>&4@&6a<6^IytiXDRCRK~kD1+XAd`%>`uhRn(M!f%o831+sD8-}D zyox1hm0OE^*&Y}b!jD(N?NF6aA5ln$sA|+mvGCaz4US~nHGlmtCT$R{MBmc(B!`l6 zGMdPL0>vgxHhDTf+W&G#<1_vqT6Ixr0lM%PD;Gn~cFI-RwOT%ui>O!97_|<(GDO0w zAbNW|ai$i&)!nZe+yNQx5G$zGgO;8}ZUKtGwO`hq_`DUS#=eZSg?LTN8k z*E7T?puxm)>va{zzofAvtf#uj{;MOa)YP2h%LM@vDO2jB=oh)P*s~$`u1mCOrIC|6 z(4;@?WY2|)Ck;U+jOOua3eKYmD%MJp&hfQv7){-Ab>Ky%9t)PUtNSzGvk~ z-qi0kJLP?qz*;1?MNpn4X0ZO(bgB?UOe*D|hw6dwP_xc}Q8&>pq8NWt@-s;Vd=d7b zTr8@Fss?4iM8(Aif&Mqg-x);+|FUP$4o5WY=Ur8s=KV^PevLSvbHG$DW2=IzFxc0> z)8Sq^$>mC?O#b8ib7OPja(ZwiL?sKRen=<@?XSM`ku98fh^!D@SR^%kREd!gv@Sln zZnypTQZ8Us0?nKFR=7fh5Zy8C0+#60A=tZA?d*1}DtfYQ>BOm$zZFK1ps2C_j6t*? zTA#NM=1a@;z_-8XaH=Y*pH>^C(8r%Yzw#6t)gX<2=3NvP#20ae8e>!4!6PcClav0p z63(vQvXAzR58tMR4T+p+O_u;cqINf-w!kTm)o#spLvFy5W9CP#PU8nWbz4hb{e&6u zwat{#`)+8w^eJHXCP2wh{_ADT(mS;K^Azo*;cF}?PlH&xUx7r+GY)fnp3Zh8roOfx z5aQz<2Bir`n74TTJF|}_rk@ib`nsMTaiMC)FvVFm$IC z`#HAvoCd1YAanpX%bd+yA`hH@Fu_55MP6&{QiRCS&iMc&F|VEG>_2ueESG#<=t98sgfez)#nPpRlDtyxh0*9HfCPN)oX{!Vey4sl9O2iax(SY|a zLikh`#yrZeQo?dF?sxa=6d(E%hMs4et)3IYu#EDBhwN&_0TmN@iz}2mA= zu-gyrJ8C9U?M2nNcDfN;6c_Vi;~mb2HQVOWjq)w)7$)9x9+KS^K-d6#fc`m&MMd8y zSNIW%qP90EuVAq!S~bus^93EWC@dW~Rf=SRfnHGjo>UOfVcJNJ*V{z5wKvM0lC?>( zw#H9&_3QYc%cv$g-iqzopz~atV`(Y8+#|)>#?N~=OxW1teeBJ|ITo0seDgpZp&0am ze&b&c67rLH?-ratr(zjYZ~e3zlBCd03KuUtZ7y;hC~X0Z-DLp?;iBf=JxMJ!(`kTL zQ8S?9y>aSkwOJ`#DGW7u9rQ!)<148<-_aBF!v}h67_|4y8J7=Pb2TLgv^nN)Y37sq z;Vp>I6~Kg;Vaijk?Gn9)BRhWf`7z%Nn|gZH1*~}R1onvqd=H#cU`!CS3aaAYpQ}lk zg)qq~@rnUV!8tZnRjGS0Vl;@wq;#(0R@}+Vfu&0N9FP*SropeKn=|)I;j#oY6k8fJ zb&Vi8z0j}Q8|_S{rF&%;TZT=u=?o@#o)Z(Pnu~-V1|6lnOpM;r)10ukD&vYvv$$|# zs`45FWv6+V7O;g4?J?1Ap9%YFuSDS_WIB#1oM9vUC~R4fAi@PMt3KcBgAaPTeGyo- z1|g~L6Gq+|;bT_s_QvsQ=R>a0&WDgJtAmpdRf)gw*4`5I1;j8fwC{5h;-}4kYLLWS zc@m07cf#j{T~H>KM!(0B-)NDIz$b^iaCyGpW=6pNm=2jZ$MzHIVxlCoD_~G;9;gil zZZSu+b#^vw-9gg+ktO8p7226~W7*zN2fudwbP8zaNs z8N||DKM*JA%NDR?uhv>IeLIkpjbXvSxciwJ;5Fx0mH7j1?2|zRjxTIG<{QG>V!VC6 zEfH`x@?jp9@`^c;h}kGIgEF9L9rH<7o*HeLhFB4qs{1t()`dPaEoKgKgsm4BLM9IB z>&GAwfr$zJD{F{XDv}S?j)H>UPbECQGArHtgc?I^a4RU$zRROMFC;s9FOx>$jT!R? zjssRf+y#$vJ4RvH5=Wp|7F|7!t!J&X-TCt&I?a;JR}8&S@*5ue%Y3sHdr zIErDMQMLutr{TDB9q^D@Vk`lR<3|BTiGQ%+Sp?;w}q>p?#Z)$BG8%*(Xg2qCsdSv(`+M!*?0l5H2x z4O6>}z;ZeJd8-IS<%vVnx0H zqKA}57py_XkC|Cm6Pg7*}f#n0Qn`L3ZqK3Uw=VS}~j99EV)K7#TV z<20nsA9LGUCGvk$^||Q^NBB&{t_yAPdBKoapQ}1V`f3opd%rlzeV(T0%Q8{ zMB~rmh%)EgQ`A9Q2+isQ#7-f&XPCUmZg8J%o+@$=@h%c`!)EO_{<72Ov2|kT$Ao;F zl$(WEVrjBiHfQ=K7EF_bB$Y14v$V zIU;T(Lg>W2&x^N~Wg-I9eUxj^p(_tkLO0-^iNHg6?`Hi38_}Q_`V9^0_@a9c)b;2& zzl&O&sfYkJMDi7kZS}yrn3gTh?cayM6BW~tq)t$MWirgJrz;>7Y8$^%6UMv3Pxmep zO5DsK(m@gjvvDm^ww{Tfhs5=Sli^%wrq9cnxo`OxA!)Qh?N|3nwl7(H;)-Or*_3;9oGrNjMa?d9!hEyU$E=&)BRSeu zRZKNS?W8=mp_3M)Qj?8My}NI0?aLL^p;1k?&z$zX5A99>_0sznV)KFJFAHnF9)Naq zsk8%N?z7Sn(Puos{Wyo7qS zJ3%iN2(8=FyFu6@G}L`Iba+`d*C@VXWBwAQ%FZYF%RiDgw@MRoN|dMC!@}8 ztwFqTD}i1?&(<-#D*{7`*<_Ua1V=y8tWkEHSu%CK7rb@Fig4`mZ-RmyBjLhxBu+wg z(qXK9b$woO&(EfjNGtn@QPLY z{1jUIF5k4D{vv?W7@|C$pO)xO`{0)c2*rJ=o0^oDHf7}Uz36VJ2#!p>{{k!(Ioj05 zUl2_%&GY^r*pCA6$&wu*hz4HYb;^@M)g($)i$1S7icJ--)tq8qXFyItK2rD$uz zTV)HdEsi!B)tx~u0oNM&Cc!PKa5NGf;V8XC$J3xis>PNG z=Dch&w*aPN0&0iu<0Kg0v`b2gVHI@dti+-l*3j{rE!`H~Pph#EdXWs&PZmji-=T#9 z{cEUZ!Vz`ri1xjF*&pq**M3hcj_nxxC*}FuomkhlObajVES+2nyFYp#4C8t~@4!^2 z_oP@yUf<20N~bNSohF4G#D_-C7O#gr@@$g9x2lYR7?$J4(LHqF9sd-Bh7xJ>7W8zV zyqJcKm5b1+q8 zw3nlFUZiulX*H`dS+QTYR0~KFmFUTMdTg8JY`P{AW@#r>YK-jhX{Tp;?YG^@t?>|Y zTIp7o{4af&>%~y{E_WldCRi>PZ~i2nq`$c5iLRoj*2h%OJJF`kwi|oCeqqJjO@lof zpQii99F@uQTA(#f0ycyJ)H_&?G|_JbcpBhumpRsj?rUZ{@h#)?tW!N#mcb65(nt`C zZauyKy8VTH$S>r5wil;`eMwPt<|8aN;34o)&@cBr(^}Xv&-M0hvv6zFrb(U4dn$@W zMFUCkie3&8APkCqZ-vVjjwr%2!9a#T=3T@t^lBg_<@!IxnpPo^UiZHf^ZKuMeirL@ zko2XXHA>qq!R)Byd8ST1K#2gV!sj+uiU^u?0+Ozsh=h)C-5(nDm$GZ2HyMpINK^aL z0lOzWz|!wsC04_Bsy(6H;JT>YoaOHi#LZ4!^i~+MK;^Cd+2@-N{KFqFdaGk{Zt74> zK5o zcOpbPz5lcCskjxXS$aM0Z_E=hY>$?wJrC@bg7;^fRGU9m35h#ES}?YU_2x*5Gs0Kx z!hx?)1rnW%j&}28oZm6eVB|WlbLkZ*#KIg=DtNQO#J%+>AqE>_4$b-M{43Qk0V_ z2C&|TFhF*}7Ju-g97t$fXcm76!ZlZ=R_6FXT%fQXhlV7r^YGwH|DknL(O!B`^rE3C z0P9tyrRq<}XoZOSsdwOfXQtDq($8uIucPi1jjkI8e|u-2Zi266!Bd*{pr@dVr(@%m zjXNr5xcNbsY( zPZs#X(8YPFD{cw8PW)lCDftB?2fM!nKLl-X1CsEd3J`j|;-ynPCe0x%P6jbIVU6ww z)Zc3I&`|^1?4(&Tm-ujdy*_AyuJqsQ80nu^?s~2$#0amx*Vh=htrdN%g~>6LdFuYF zD>kP4kn2YTB?*wUAH3IG4sq&~kj3Q3UUz0clXMbNGMhq%roE?U0~?DB$jfvFTC$x_ z(%ZyxV9Si)V@;Xw7v&-Qy|5j1s@EgpqZooAsf;{6>=B5=C|3DPZHCGV9d3|q(85ZH zgvu-v>eWlNf%ggF#eeTTLfXN?d7_6W+;;Rlz{UYtbv^t0tpc?{Ai~No9HdOE&+kGi!u$`f4+huS^J?8npZ8qUa>}pN75lTl<=%R(OCb&wDQ0om1$UHHq(_Y4Srv;6*JEG+ zWmi+oxhEn|5ZCl-SFt;;r2*U%?6TE-cjms4aX9XP#Ux7RZcdwdKmO3CaleVMKl-uv z)k~;3-I-SFh!aNh&ARH}u#B|QNtTmqZwD;!di_9vQ33*bextgw#CARLeWg6 zRlEfd^JZ<;vp5{$l=SH|n$7%g?u$~@ta15?53xZvT|I0OBZF4uZ+!z8VOY?0lp=u* zBc>5mkG<=@4wWAAA zpfv6MI;+cl(>xu#gC;qgN*Cu!md)f-Bc#VOCoI@PuvuZXF&MfUvy0vVM|D%+q@+F* zGl0`ao=gi=CuN$`&Hm-RTb*2B!^hK*P1p+Lj1g-|H{;%6UAifyKsFr?GdE_Ot8XGO zr*)1e8P!X1my?08Y+5?In1-B{6`yI)#a1c*CcBXHI_y-qTiDIT%l0y(*lVjGXpxEMr&8T-w*-DuTn!wv?7$wfk0gyS036M+yYuQt4(q9jmK zlItmw=s+JFUUs}NH{xju$<~ce`g*9|E~M(TC}HjrgZOrxhz%HLclt}ngaVfuQ_O6! zQU2(;H<9$BOpn16y>@<$iag-P; z^XevJsbNCW%_(=!J54a(n^;PRoL=d)N1l)8QC} ztNGCJb9VR|m;zj1HDHui`B^usBchA& zkBurLgV>l@T}RxdcJlS-9$RV!weg`Qv2%>LWo=f!b*Q8t3w`SvU%NP5 zo)Hvs!@Vp~SP^Wp21MG8A@>LCjo3VI8%)Qgsln{oc&ij=&*9kTmb3ksm@E2;?@9Oj z*Co}7g;(kx;-59gjScEnlP5nEUNW+{I2bCzWFB5xnavBbqjV~S`Yr@g!SKb(9cY92 z^1oxI6GDSX^VWOrNPg=O4K_Sz()4KygrNB)QKzHPg4s)@rl0m71B7t}(Gv32kss9q zP2#I&VRRzc+h=GiTZPc)NycOTQd$z6B^YHOGjZWek;0tb}NMa&J0!F??{kpO6C_mVW zKxt8*g>IFgsdXrc!x8vWwcY0TMcU9h%}llYTl8V+kE5$&*BZw4UrbDpH+c;w;x@sd z_f;;eFZ?{~^_~32D|iOWG7=JSN`Ei>i526XkKq`^BqbK}@ouW1hG)69R9RZ7f656Dwx11_jDQhDmbAm**~zo{U{HE{_K*cImD9)G*> zv@OyKjEG?T)*~rlnp3`SOXmJ-iN|V9#V>S8Msow!j!EH%wcTuEy=lsDgYyuGw?zNY zOQ7B>%?tmQBFsW=<%036Uf*q(j)cUbjNYJxM0229afNw707Q?`r)&Y%^_>fz`ZCjB zOqYrG)gmQOvap#~3@l%?@R(1015Ge66Ml-t%FjY$CiLQ(NN&U$hqGaPDVjOy&t%C` zHcO#5qxalQWFDPTC0~bo-5$^k;A$Fk0)syv+6DVdNtm{O4rvP?8~lbpdZeAtkkLKD z7CXa8z8-YteVLi9e*}@=MSIv|3ZDf^vAddS`}krjFL?3`&-V)$T<-)pFjGa{W$Vi4 zAZEm@eklAE?Z>+572G>5rIN+<@3_s9^Q-Ekc)U?(^?2c(42~#Z@LU!Y2vaL*CCcv8 z@g2=7Hd6g39iKV7+2t@b-9Q)Gi9caCXc5xA8kOW-zLCLcqYI0*vTc8yHOYTdOm`U0 z*P4&|$64c6#AT3-`VU936Et6_9@hZQA+{|la-^Kl=xnrsu7adn7>XOpo)jUcSQimb zo0uno$?dSdCchq*wNU=nlOGShczlW=5Pc`3JV2+uc~ZhsK;+xqMx1)@J_s`*h29Y} zLG2XXCWUjpNpIQg8tvCcz4!&FIJlG-9vhUZfL;MnX2x3J*@Wl(Q)4x_daVG{m9KnN3)fH?CV4YGAkGN+8;?Bg;@JCGrU%$81MJ|0L{Mm4Xtg{ zNHZ+`LYQeR2mm}DSY~kjyXirGIVM*aa-W^tkj>&UknU^5>k8G zEw`V;S4wK+xh-HHF#m9ZJ2Bqb#9=2h7+5Bbq! zrhnUfX~b##tA=Xh=D4dXbZtWsj0wr#w@~N#)g(^Qgdjfsh0#ze`jRijoEBY<_@?1( zY{v7ekg*m>Y_DqNT080C8BovnABQ9*9+`AR~_3roYW}hzKcG9$(d%^!C-? z3}o@Vs=_j~Svb+yZwW96w50ryJG>PK%t4j_kcVB#;ALihney>=Dun$MpSxKsrht)N ziqIDd{@2}i$Z~C%#~$jZA$-}?gv*U}O zGK?kDA@d@OY+LI^-=G4t6Vhn=O$X<~K#aTK5_AK_F?+7I)UXkxV)rmJ7`&Fn{`MKK zQ_u99UsIaxVGYU?c+{UZMOOV{wULvl%X`V8#)>8kRSm{*7kmCgu_EqxKbWJMS4SAtM-AaaUBUR@Kq0QCBsm16qeoWUXOewJ_9AcdL>rKwo(s zVj;KRFD}PFnQ66~0}9xc>;!1Gq0p*+#T+*{>)j%X&6GU8y31EcFEV>_Ega$) zPs4Q7*!M<9MBqpT0!k3zxGd?%k2H9Pd(79YW^5RB&4ROnrqd#2Dk`VoL57>f;+w0Cs z42_8Cajl5v6}9o!alK_%ypf&v`$|_As5{GJ{^7`o!MFv<7ZLgjk{ zfDzhcFCh^Y@iq?Xt-!D@Q3EQ5^O}-!|G@ac%ujoA5@AWewJ_6mJufuJ7G9 za~08+)c^nXV2GOu+lVfWpPDlJuoypyFx5|g03`j-=&6-Y1IT77MPqPhl)h!zT}{^&p=tIXIR?usRaG~H*=B}ivufk&^tqvoTOfJp@B|N7<%uAw+ zNth!4lK}-8m&O5|X}iqF62Q{_X}ug3jl&~Hdw+CrDqTCy^M?oITmvh5RdaByVvI0fn0e>a;Iz4pr4czwB@n3!PY;OKAZx~?)~ zY4pCe*Y`ese{}s2MH^iZVUg#Xs^ievw7>IsbGq~Qa2|O-BO_z$3;!QYm)CKY?uj~+ zVUN45Z~`JC=*@NSv){4Y>pkAn?p;?osJ<9Lp0@jmoTS?76Da_c?_6*Ik-Wo?0aHDwsW)Qu;0@Cd>U1Ay%~&t34As9>tpbIq~ZBHMT5ud??KdX z$K@EqPnUVc=s#;M4jc84-M5`*P8+_r7ZV)Q=PT2GsY*WE*b>SEvxU<4*ERl=^Gd?L zvvt7W;SupVco;ook%*)Jer)f%slp!oA}(PXAjw!c+R=7g-Tq}s-`j3*SokVqdNX?` zT=;1#YFO8K@_oinOIHX8m?v2YQB|MkV}pHQhkj)xlpLL`;TebcfmZj~+Fbf;l^Zu0tV5?Q==lAl ze*A7GTxj5vlHlOP1d8zM{WP!RW>4RahQ25Dn`G|i(z+xvs|6q*^TSDvZ~y#iT(es} zLQ|9-LOPO(d7l=mI?s zepf`f9@~*mqskJQB|qIae2c8w;t}tA;DvgYm+@s2Sp@|u!+6{=pTP4xWEm&xr1y%@Y5c7>G1i;rQ&}QDKfr0X6h>5E~y5 z`?0l+DX``GT*{Jq9Z)1vZS9UG`5b-9+omMDM_}o?0|VN9T3|v;L*qEb1jFS1%M}zS z^gt*4auN6a_2tp?<$j;n^#}(Zopd*h$X*k{gUiI$Hb$zjcVFn1cW7v+^=gXWb1%b! z>$wfkDR!N@==+Ngyv%zotG1;*F?@qxpf~lacE!Xh`0})#sbi2?u!=FDzQ!;9t5Fy0PLfW%{ZDU*h;1#Z>Utk^kOuf)EX6Q(qDQ8EL?hf`QhZ<<*h z%<(5{v8DfOIU#?RK_*h&gHuPNp5Icdm4*LZlr7{~a`K-}S&AszJhwbfJ+26W5Uszq z|BfdBccy6{k__!?rT$r)y$ql^k&f((U4TkFnPyDxMMFr1W83N?71y=%#sBYkyxHwL m@*^~bRMPqPzKmmM_x_~_>`CIH1@I8SOIGrOM75Y<(EkDGHa!yn literal 0 HcmV?d00001 diff --git a/tool/CMakeLists.txt b/tool/CMakeLists.txt index 031a0d36..001895b1 100644 --- a/tool/CMakeLists.txt +++ b/tool/CMakeLists.txt @@ -9,7 +9,9 @@ message(=============================================================) include_directories(${DRIVER_INCLUDE_DIRS}) -set(CMAKE_BUILD_TYPE Release) +if (CMAKE_BUILD_TYPE STREQUAL "") + set(CMAKE_BUILD_TYPE Release) +endif() if(WIN32) cmake_policy(SET CMP0074 NEW) diff --git a/tool/rs_driver_viewer.cpp b/tool/rs_driver_viewer.cpp index b65fd132..a1691710 100644 --- a/tool/rs_driver_viewer.cpp +++ b/tool/rs_driver_viewer.cpp @@ -40,10 +40,9 @@ using namespace robosense::lidar; using namespace pcl::visualization; typedef PointCloudT PointCloudMsg; -std::shared_ptr g_pointcloud; std::shared_ptr pcl_viewer; -std::mutex mex_viewer; +std::mutex mtx_viewer; bool checkKeywordExist(int argc, const char* const* argv, const char* str) { @@ -80,11 +79,11 @@ bool parseArgument(int argc, const char* const* argv, const char* str, std::stri void parseParam(int argc, char* argv[], RSDriverParam& param) { - param.decoder_param.wait_for_difop = false; - std::string result_str; + // // input param + // parseArgument(argc, argv, "-pcap", param.input_param.pcap_path); if (param.input_param.pcap_path.empty()) { @@ -95,43 +94,54 @@ void parseParam(int argc, char* argv[], RSDriverParam& param) param.input_type = InputType::PCAP_FILE; } - parseArgument(argc, argv, "-host", param.input_param.host_address); - parseArgument(argc, argv, "-group", param.input_param.group_address); - if (parseArgument(argc, argv, "-msop", result_str)) { param.input_param.msop_port = std::stoi(result_str); } + if (parseArgument(argc, argv, "-difop", result_str)) { param.input_param.difop_port = std::stoi(result_str); } + parseArgument(argc, argv, "-group", param.input_param.group_address); + parseArgument(argc, argv, "-host", param.input_param.host_address); + + // // decoder param + // if (parseArgument(argc, argv, "-type", result_str)) { param.lidar_type = strToLidarType(result_str); } + + param.decoder_param.wait_for_difop = false; + if (parseArgument(argc, argv, "-x", result_str)) { param.decoder_param.transform_param.x = std::stof(result_str); } + if (parseArgument(argc, argv, "-y", result_str)) { param.decoder_param.transform_param.y = std::stof(result_str); } + if (parseArgument(argc, argv, "-z", result_str)) { param.decoder_param.transform_param.z = std::stof(result_str); } + if (parseArgument(argc, argv, "-roll", result_str)) { param.decoder_param.transform_param.roll = std::stof(result_str); } + if (parseArgument(argc, argv, "-pitch", result_str)) { param.decoder_param.transform_param.pitch = std::stof(result_str); } + if (parseArgument(argc, argv, "-yaw", result_str)) { param.decoder_param.transform_param.yaw = std::stof(result_str); @@ -140,81 +150,35 @@ void parseParam(int argc, char* argv[], RSDriverParam& param) void printHelpMenu() { - RS_MSG << "Argument list: " << RS_REND; - RS_MSG << " -msop = LiDAR msop port number,the default value is 6699" << RS_REND; - RS_MSG << " -difop = LiDAR difop port number,the default value is 7788" << RS_REND; - RS_MSG << " -host = LiDAR destination address." << RS_REND; - RS_MSG << " -group = LiDAR destination group address." << RS_REND; - RS_MSG << " -pcap = The path of the pcap file, if this argument is set, the driver " - "will work in off-line mode and read the pcap file. Otherwise the driver work in online mode." << RS_REND; - - RS_MSG << " -type = LiDAR type(RS16, RS32, RSBP, RSHELIOS, RS128, RS80, RSM1), the default value is RS16" - << RS_REND; - RS_MSG << " -x = Transformation parameter, unit: m " << RS_REND; - RS_MSG << " -y = Transformation parameter, unit: m " << RS_REND; - RS_MSG << " -z = Transformation parameter, unit: m " << RS_REND; - RS_MSG << " -roll = Transformation parameter, unit: radian " << RS_REND; - RS_MSG << " -pitch = Transformation parameter, unit: radian " << RS_REND; - RS_MSG << " -yaw = Transformation parameter, unit: radian " << RS_REND; + RS_MSG << "Arguments: " << RS_REND; + RS_MSG << " -type = LiDAR type(RS16, RS32, RSBP, RSHELIOS, RS128, RS80, RSM1)" << RS_REND; + RS_MSG << " -pcap = The path of the pcap file, off-line mode if it is true, else online mode." << RS_REND; + RS_MSG << " -msop = LiDAR msop port number,the default value is 6699" << RS_REND; + RS_MSG << " -difop = LiDAR difop port number,the default value is 7788" << RS_REND; + RS_MSG << " -group = LiDAR destination group address if multi-cast mode." << RS_REND; + RS_MSG << " -host = Host address." << RS_REND; + RS_MSG << " -x = Transformation parameter, unit: m " << RS_REND; + RS_MSG << " -y = Transformation parameter, unit: m " << RS_REND; + RS_MSG << " -z = Transformation parameter, unit: m " << RS_REND; + RS_MSG << " -roll = Transformation parameter, unit: radian " << RS_REND; + RS_MSG << " -pitch = Transformation parameter, unit: radian " << RS_REND; + RS_MSG << " -yaw = Transformation parameter, unit: radian " << RS_REND; } -void printParam(const RSDriverParam& param) +void exceptionCallback(const Error& code) { - if (param.input_type == InputType::PCAP_FILE) - { - RS_INFOL << "Working mode: "; - RS_INFO << "Offline Pcap " << RS_REND; - RS_INFOL << "Pcap Path: "; - RS_INFO << param.input_param.pcap_path << RS_REND; - } - else - { - RS_INFOL << "Working mode: "; - RS_INFO << "Online LiDAR " << RS_REND; - } - - RS_INFOL << "MSOP Port: "; - RS_INFO << param.input_param.msop_port << RS_REND; - RS_INFOL << "DIFOP Port: "; - RS_INFO << param.input_param.difop_port << RS_REND; - RS_INFOL << "Host Adress: "; - RS_INFO << param.input_param.host_address << RS_REND; - RS_INFOL << "Group Adress: "; - RS_INFO << param.input_param.group_address << RS_REND; - - RS_INFOL << "LiDAR Type: "; - RS_INFO << lidarTypeToStr(param.lidar_type) << RS_REND; - RS_INFOL << "Transformation Parameters (x, y, z, roll, pitch, yaw): " << RS_REND; - RS_INFOL << "x: "; - RS_INFO << std::fixed << param.decoder_param.transform_param.x << RS_REND; - RS_INFOL << "y: "; - RS_INFO << std::fixed << param.decoder_param.transform_param.y << RS_REND; - RS_INFOL << "z: "; - RS_INFO << std::fixed << param.decoder_param.transform_param.z << RS_REND; - RS_INFOL << "roll: "; - RS_INFO << std::fixed << param.decoder_param.transform_param.roll << RS_REND; - RS_INFOL << "pitch: "; - RS_INFO << std::fixed << param.decoder_param.transform_param.pitch << RS_REND; - RS_INFOL << "yaw: "; - RS_INFO << std::fixed << param.decoder_param.transform_param.yaw << RS_REND; + RS_WARNING << code.toString() << RS_REND; } std::shared_ptr pointCloudGetCallback(void) { - return g_pointcloud; + return std::make_shared(); } -/** - * @brief The point cloud callback function. This function will be registered to lidar driver. - * When the point cloud message is ready, driver can send out messages through this function. - * @param msg The lidar point cloud message. - */ void pointCloudPutCallback(std::shared_ptr msg) { - /* Note: Please do not put time-consuming operations in the callback function! */ - /* Make a copy of the message and process it in another thread is recommended*/ pcl::PointCloud::Ptr pcl_pointcloud(new pcl::PointCloud); - pcl_pointcloud->points.assign(msg->points.begin(), msg->points.end()); + pcl_pointcloud->points.swap(msg->points); pcl_pointcloud->height = msg->height; pcl_pointcloud->width = msg->width; pcl_pointcloud->is_dense = msg->is_dense; @@ -222,22 +186,11 @@ void pointCloudPutCallback(std::shared_ptr msg) PointCloudColorHandlerGenericField point_color_handle(pcl_pointcloud, "intensity"); { - const std::lock_guard lock(mex_viewer); + const std::lock_guard lock(mtx_viewer); pcl_viewer->updatePointCloud(pcl_pointcloud, point_color_handle, "rslidar"); } } -/** - * @brief The exception callback function. This function will be registered to lidar driver. - * @param code The error code struct. - */ -void exceptionCallback(const Error& code) -{ - /* Note: Please do not put time-consuming operations in the callback function! */ - /* Make a copy of the error message and process it in another thread is recommended*/ - RS_WARNING << code.toString() << RS_REND; -} - int main(int argc, char* argv[]) { RS_TITLE << "------------------------------------------------------" << RS_REND; @@ -246,7 +199,8 @@ int main(int argc, char* argv[]) if (argc < 2) { - RS_INFOL << "Use 'rs_driver_viewer -h/--help' to check the argument menu..." << RS_REND; + printHelpMenu(); + return 0; } if (checkKeywordExist(argc, argv, "-h") || checkKeywordExist(argc, argv, "--help")) @@ -255,37 +209,35 @@ int main(int argc, char* argv[]) return 0; } - RSDriverParam param; ///< Create a parameter object + RSDriverParam param; parseParam(argc, argv, param); - printParam(param); - - g_pointcloud = std::make_shared(); + param.print(); pcl_viewer = std::make_shared("RSPointCloudViewer"); - pcl_viewer->setBackgroundColor(0.0, 0.0, 0.0); pcl_viewer->addCoordinateSystem(1.0); + pcl::PointCloud::Ptr pcl_pointcloud(new pcl::PointCloud); pcl_viewer->addPointCloud(pcl_pointcloud, "rslidar"); pcl_viewer->setPointCloudRenderingProperties(PCL_VISUALIZER_POINT_SIZE, 2, "rslidar"); - LidarDriver driver; ///< Declare the driver object - driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback - driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback - if (!driver.init(param)) ///< Call the init function + LidarDriver driver; + driver.regExceptionCallback(exceptionCallback); + driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); + if (!driver.init(param)) { RS_ERROR << "Driver Initialize Error..." << RS_REND; return -1; } - driver.start(); ///< The driver thread will start - RS_INFO << "RoboSense Lidar-Driver Viewer start......" << RS_REND; + driver.start(); + while (!pcl_viewer->wasStopped()) { { - const std::lock_guard lock(mex_viewer); + const std::lock_guard lock(mtx_viewer); pcl_viewer->spinOnce(); } std::this_thread::sleep_for(std::chrono::milliseconds(100)); From bbb9f2b689585a8ef9292c4423d307b7e47715fd Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 1 Jun 2022 14:19:22 +0800 Subject: [PATCH 277/379] feat: tag v1.5.3 --- CHANGELOG.md | 8 +++++++- CMakeLists.txt | 2 +- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index f58bfea8..69c1cc80 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -2,9 +2,15 @@ ## Unreleased +## v1.5.3 2022-06-01 + ### Added +- Add option to receive packet with epoll() +- Support Jumbo Mode + +### Fixed - Check overflow of point cloud -- Add option to receive packet with epoll() instead of select() +- Fix compiling error of multiple definition ## v1.5.2 2022-05-20 diff --git a/CMakeLists.txt b/CMakeLists.txt index b5449f32..edb7a176 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.5.2) +project(rs_driver VERSION 1.5.3) #======================== # Project setup From 4bec874bc78f2210382dfef6b5c928e050c1bd80 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 2 Jun 2022 19:12:04 +0800 Subject: [PATCH 278/379] fix: fix m2 coordinate --- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index 94d538a7..805e214b 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -203,9 +203,10 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size if (this->distance_section_.in(distance)) { - float x = RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; - float y = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; + float x = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; + float y = - RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; + this->transformPoint(x, y, z); typename T_PointCloud::PointT point; From bf1d895374ff8b401a78220e10b25b00f517bdcf Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 6 Jun 2022 09:12:26 +0800 Subject: [PATCH 279/379] fix: fix eos coordinate --- src/rs_driver/driver/decoder/decoder_RSEOS.hpp | 7 ++++--- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 4 ++-- src/rs_driver/macro/version.hpp | 2 +- 3 files changed, 7 insertions(+), 6 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSEOS.hpp b/src/rs_driver/driver/decoder/decoder_RSEOS.hpp index 529cc379..ec1f39c3 100644 --- a/src/rs_driver/driver/decoder/decoder_RSEOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSEOS.hpp @@ -200,9 +200,10 @@ inline bool DecoderRSEOS::decodeMsopPkt(const uint8_t* packet, siz if (this->distance_section_.in(distance)) { - float x = RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; - float y = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; - float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; + float x = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; + float y = - RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; + float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; + this->transformPoint(x, y, z); typename T_PointCloud::PointT point; diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index 805e214b..44643efd 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -203,9 +203,9 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size if (this->distance_section_.in(distance)) { - float x = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; + float x = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; float y = - RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; - float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; + float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; this->transformPoint(x, y, z); diff --git a/src/rs_driver/macro/version.hpp b/src/rs_driver/macro/version.hpp index 9e3e92f2..be467c02 100644 --- a/src/rs_driver/macro/version.hpp +++ b/src/rs_driver/macro/version.hpp @@ -1,3 +1,3 @@ #define RSLIDAR_VERSION_MAJOR 1 #define RSLIDAR_VERSION_MINOR 5 -#define RSLIDAR_VERSION_PATCH 2 +#define RSLIDAR_VERSION_PATCH 3 From 814c2e95a552996ae5f04b8ac5476908a3fedbbb Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 9 Jun 2022 15:25:38 +0800 Subject: [PATCH 280/379] fix: fix calculating temp for mems --- src/rs_driver/driver/decoder/decoder_RSEOS.hpp | 4 ++-- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 4 ++-- src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 4 ++-- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSEOS.hpp b/src/rs_driver/driver/decoder/decoder_RSEOS.hpp index ec1f39c3..311f94a5 100644 --- a/src/rs_driver/driver/decoder/decoder_RSEOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSEOS.hpp @@ -50,7 +50,7 @@ typedef struct RSTimestampUTC timestamp; uint8_t reserved[10]; uint8_t lidar_type; - int8_t temperature; + uint8_t temperature; } RSEOSMsopHeader; typedef struct @@ -159,7 +159,7 @@ inline bool DecoderRSEOS::decodeMsopPkt(const uint8_t* packet, siz const RSEOSMsopPkt& pkt = *(RSEOSMsopPkt*)packet; bool ret = false; - this->temperature_ = static_cast(pkt.header.temperature - this->const_param_.TEMPERATURE_RES); + this->temperature_ = static_cast((int)pkt.header.temperature - this->const_param_.TEMPERATURE_RES); double pkt_ts = 0; if (this->param_.use_lidar_clock) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index af81d18b..bee1f27e 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -49,7 +49,7 @@ typedef struct RSTimestampUTC timestamp; uint8_t reserved[10]; uint8_t lidar_type; - int8_t temperature; + uint8_t temperature; } RSM1MsopHeader; typedef struct @@ -216,7 +216,7 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size const RSM1MsopPkt& pkt = *(RSM1MsopPkt*)packet; bool ret = false; - this->temperature_ = static_cast(pkt.header.temperature - this->const_param_.TEMPERATURE_RES); + this->temperature_ = static_cast((int)pkt.header.temperature - this->const_param_.TEMPERATURE_RES); double pkt_ts = 0; if (this->param_.use_lidar_clock) diff --git a/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp b/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp index 971f4508..db92881d 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp @@ -177,7 +177,7 @@ inline bool DecoderRSM1_Jumbo::internDecodeMsopPkt(const uint8_t* if (memcmp(packet, this->const_param_.MSOP_ID, this->const_param_.MSOP_ID_LEN) != 0) return false; - this->temperature_ = static_cast(pkt.header.temperature - this->const_param_.TEMPERATURE_RES); + this->temperature_ = static_cast((int)pkt.header.temperature - this->const_param_.TEMPERATURE_RES); double pkt_ts = 0; if (this->param_.use_lidar_clock) diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index 44643efd..74576dbb 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -50,7 +50,7 @@ typedef struct RSTimestampUTC timestamp; uint8_t reserved[10]; uint8_t lidar_type; - int8_t temperature; + uint8_t temperature; } RSM2MsopHeader; typedef struct @@ -162,7 +162,7 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size const RSM2MsopPkt& pkt = *(RSM2MsopPkt*)packet; bool ret = false; - this->temperature_ = static_cast(pkt.header.temperature - this->const_param_.TEMPERATURE_RES); + this->temperature_ = static_cast((int)pkt.header.temperature - this->const_param_.TEMPERATURE_RES); double pkt_ts = 0; if (this->param_.use_lidar_clock) From 265bc871ed0948572dc0e4f9dda2312a009d2080 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 13 Jun 2022 12:03:45 +0800 Subject: [PATCH 281/379] feat: differentiate 80 and v80 with model --- src/rs_driver/driver/decoder/decoder.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RSP80.hpp | 14 +++++++------- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 71e539d8..c87ad31c 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -80,7 +80,8 @@ typedef struct RSTimestampUTC timestamp; uint8_t reserved_2[10]; uint8_t lidar_type; - uint8_t reserved_3[49]; + uint8_t lidar_model; + uint8_t reserved_3[48]; } RSMsopHeaderV2; typedef struct diff --git a/src/rs_driver/driver/decoder/decoder_RSP80.hpp b/src/rs_driver/driver/decoder/decoder_RSP80.hpp index 1e668469..2cb68efb 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP80.hpp @@ -101,7 +101,7 @@ class DecoderRSP80 : public DecoderMech template bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); - uint8_t lidar_type_; + uint8_t lidar_model_; }; template @@ -173,8 +173,8 @@ inline void DecoderRSP80::calcParam() 29.579f, 29.579f, 29.579f, 29.579f, 31.963f, 31.963f, 31.963f, 31.963f, }; - float* firing_tss = firing_tss_80; // 80 - lidar_type = 0x07 - if (lidar_type_ == 0x08) // 80v - lidar_type = 0x08 + float* firing_tss = firing_tss_80; // 80 - lidar_model = 0x02 + if (lidar_model_ == 0x03) // 80v - lidar_model = 0x03 { firing_tss = firing_tss_80v; } @@ -218,7 +218,7 @@ inline void DecoderRSP80::decodeDifopPkt(const uint8_t* packet, si template inline DecoderRSP80::DecoderRSP80(const RSDecoderParam& param) : DecoderMech(getConstParam(), param), - lidar_type_(0) + lidar_model_(0) { } @@ -242,10 +242,10 @@ inline bool DecoderRSP80::internDecodeMsopPkt(const uint8_t* packe const RSP80MsopPkt& pkt = *(const RSP80MsopPkt*)(packet); bool ret = false; - uint8_t lidar_type = pkt.header.lidar_type; - if (lidar_type_ != lidar_type) + uint8_t lidar_model = pkt.header.lidar_model; + if (lidar_model_ != lidar_model) { - lidar_type_ = lidar_type; + lidar_model_ = lidar_model; calcParam(); } From 29d000d8955e55a239624b04bce1362f7750124c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 13 Jun 2022 16:26:54 +0800 Subject: [PATCH 282/379] feat: add fuction degree2radian() --- src/rs_driver/common/rs_common.hpp | 3 +++ src/rs_driver/driver/decoder/decoder_mech.hpp | 4 ++++ src/rs_driver/driver/decoder/trigon.hpp | 7 +++---- 3 files changed, 10 insertions(+), 4 deletions(-) diff --git a/src/rs_driver/common/rs_common.hpp b/src/rs_driver/common/rs_common.hpp index e58df913..4e52ec0d 100644 --- a/src/rs_driver/common/rs_common.hpp +++ b/src/rs_driver/common/rs_common.hpp @@ -63,3 +63,6 @@ inline int16_t RS_SWAP_INT16(int16_t value) #include +#define DEGREE_TO_RADIAN(deg) ((deg) * M_PI / 180) +#define RADIAN_TO_DEGREE(deg) ((deg) * 180 / M_PI) + diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index e618ff9c..2de950c7 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -96,8 +96,10 @@ class DecoderMech : public Decoder uint16_t block_az_diff_; // azimuth difference between adjacent blocks. double fov_blind_ts_diff_; // timestamp difference across blind section(defined by fov) +#if 0 int lidar_alph0_; // lens center related float lidar_Rxy_; // lens center related +#endif }; template @@ -133,10 +135,12 @@ inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& con break; } +#if 0 // lens center: (alph0, Rxy) lidar_alph0_ = (int)(std::atan2(mech_const_param_.RY, mech_const_param_.RX) * 180 / M_PI * 100); lidar_Rxy_ = std::sqrt(mech_const_param_.RX * mech_const_param_.RX + mech_const_param_.RY * mech_const_param_.RY); +#endif if (this->param_.config_from_file) { diff --git a/src/rs_driver/driver/decoder/trigon.hpp b/src/rs_driver/driver/decoder/trigon.hpp index 996d1767..8cecca32 100644 --- a/src/rs_driver/driver/decoder/trigon.hpp +++ b/src/rs_driver/driver/decoder/trigon.hpp @@ -61,14 +61,13 @@ class Trigon for (int32_t i = MIN, j = 0; i < MAX; i++, j++) { - double rads = static_cast(i) * 0.01; - rads = rads * M_PI / 180; + double rad = DEGREE_TO_RADIAN(static_cast(i) * 0.01); #ifdef DBG o_angles_[j] = i; #endif - o_sins_[j] = (float)std::sin(rads); - o_coss_[j] = (float)std::cos(rads); + o_sins_[j] = (float)std::sin(rad); + o_coss_[j] = (float)std::cos(rad); } #ifdef DBG From f3fa9b0b395978652850da2c1920867576ff8591 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 15 Jun 2022 11:05:04 +0800 Subject: [PATCH 283/379] feat: support big endian temp for bp --- src/rs_driver/driver/decoder/basic_attr.hpp | 14 +++++++++++ src/rs_driver/driver/decoder/decoder_RSBP.hpp | 25 +++++++++++++++++-- 2 files changed, 37 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index dbc6bc63..da2431a8 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -284,5 +284,19 @@ inline int16_t parseTempInBe(const RSTemperature* tmp) // format of big endian return t; } +inline int16_t parseTempInBe2(const RSTemperature* tmp) // format of big endian +{ + // | neg | msb | lsb | padding | + // | 1 | 7 | 5 | 3 | (in bits) + uint8_t neg = tmp->tt[0] & 0x80; + uint8_t msb = tmp->tt[0] & 0x7F; + uint8_t lsb = tmp->tt[1] >> 3; + + int16_t t = ((uint16_t)msb << 5) + lsb; + if (neg) t = -t; + + return t; +} + } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index ecd7f59e..e62fcec0 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -101,6 +101,8 @@ class DecoderRSBP : public DecoderMech template bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); + + int temp_version_; }; template @@ -166,7 +168,8 @@ inline RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) template inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param) - : DecoderMech(getConstParam(), param) + : DecoderMech(getConstParam(), param), + temp_version_(0) { } @@ -179,6 +182,15 @@ inline void DecoderRSBP::decodeDifopPkt(const uint8_t* packet, siz this->echo_mode_ = getEchoMode (pkt.return_mode); this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? (this->blks_per_frame_ << 1) : this->blks_per_frame_; + + bool modern = (pkt.version.bottom_ver[1] == 0x03) && (pkt.version.bottom_ver[2] == 0x01); + if (modern) + { + if (pkt.version.bottom_ver[3] >= 0x19) + this->temp_version_ = 2; + if (pkt.version.bottom_ver[3] >= 0x14) + this->temp_version_ = 1; + } } template @@ -201,7 +213,16 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet const RSBPMsopPkt& pkt = *(const RSBPMsopPkt*)(packet); bool ret = false; - this->temperature_ = parseTempInLe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + int16_t temp = 0; + + if (this->temp_version_ == 2) + temp = parseTempInBe (&(pkt.header.temp)); + else if (temp_version_ == 1) + temp = parseTempInBe2 (&(pkt.header.temp)); + else + temp = parseTempInLe (&(pkt.header.temp)); + + this->temperature_ = temp * this->const_param_.TEMPERATURE_RES; double pkt_ts = 0; if (this->param_.use_lidar_clock) From 6447c4b44931a4b4e9dd3365c7101910b89772bb Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Jun 2022 10:56:06 +0800 Subject: [PATCH 284/379] Revert "feat: support big endian temp for bp" This reverts commit f3fa9b0b395978652850da2c1920867576ff8591. --- src/rs_driver/driver/decoder/basic_attr.hpp | 14 ----------- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 25 ++----------------- 2 files changed, 2 insertions(+), 37 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index da2431a8..dbc6bc63 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -284,19 +284,5 @@ inline int16_t parseTempInBe(const RSTemperature* tmp) // format of big endian return t; } -inline int16_t parseTempInBe2(const RSTemperature* tmp) // format of big endian -{ - // | neg | msb | lsb | padding | - // | 1 | 7 | 5 | 3 | (in bits) - uint8_t neg = tmp->tt[0] & 0x80; - uint8_t msb = tmp->tt[0] & 0x7F; - uint8_t lsb = tmp->tt[1] >> 3; - - int16_t t = ((uint16_t)msb << 5) + lsb; - if (neg) t = -t; - - return t; -} - } // namespace lidar } // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index e62fcec0..ecd7f59e 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -101,8 +101,6 @@ class DecoderRSBP : public DecoderMech template bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); - - int temp_version_; }; template @@ -168,8 +166,7 @@ inline RSEchoMode DecoderRSBP::getEchoMode(uint8_t mode) template inline DecoderRSBP::DecoderRSBP(const RSDecoderParam& param) - : DecoderMech(getConstParam(), param), - temp_version_(0) + : DecoderMech(getConstParam(), param) { } @@ -182,15 +179,6 @@ inline void DecoderRSBP::decodeDifopPkt(const uint8_t* packet, siz this->echo_mode_ = getEchoMode (pkt.return_mode); this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? (this->blks_per_frame_ << 1) : this->blks_per_frame_; - - bool modern = (pkt.version.bottom_ver[1] == 0x03) && (pkt.version.bottom_ver[2] == 0x01); - if (modern) - { - if (pkt.version.bottom_ver[3] >= 0x19) - this->temp_version_ = 2; - if (pkt.version.bottom_ver[3] >= 0x14) - this->temp_version_ = 1; - } } template @@ -213,16 +201,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet const RSBPMsopPkt& pkt = *(const RSBPMsopPkt*)(packet); bool ret = false; - int16_t temp = 0; - - if (this->temp_version_ == 2) - temp = parseTempInBe (&(pkt.header.temp)); - else if (temp_version_ == 1) - temp = parseTempInBe2 (&(pkt.header.temp)); - else - temp = parseTempInLe (&(pkt.header.temp)); - - this->temperature_ = temp * this->const_param_.TEMPERATURE_RES; + this->temperature_ = parseTempInLe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; double pkt_ts = 0; if (this->param_.use_lidar_clock) From 83c1e14d8d8f7f71d8669612d8c5820f4dc40941 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 16 Jun 2022 11:46:09 +0800 Subject: [PATCH 285/379] feat: support rs48 --- src/rs_driver/driver/decoder/decoder_RS48.hpp | 259 ++++++++++++++++++ .../driver/decoder/decoder_factory.hpp | 4 + src/rs_driver/driver/driver_param.hpp | 10 +- 3 files changed, 272 insertions(+), 1 deletion(-) create mode 100644 src/rs_driver/driver/decoder/decoder_RS48.hpp diff --git a/src/rs_driver/driver/decoder/decoder_RS48.hpp b/src/rs_driver/driver/decoder/decoder_RS48.hpp new file mode 100644 index 00000000..20e7f16f --- /dev/null +++ b/src/rs_driver/driver/decoder/decoder_RS48.hpp @@ -0,0 +1,259 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once + +#include + +namespace robosense +{ +namespace lidar +{ +template +class DecoderRS48 : public DecoderMech +{ +public: + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRS48() = default; + + explicit DecoderRS48(const RSDecoderParam& param); + +#ifndef UNIT_TEST +protected: +#endif + + static RSDecoderMechConstParam& getConstParam(); + static RSEchoMode getEchoMode(uint8_t mode); + + template + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); +}; + +template +inline RSDecoderMechConstParam& DecoderRS48::getConstParam() +{ + static RSDecoderMechConstParam param = + { + 1268 // msop len + , 1248 // difop len + , 4 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x5A} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFE} // block id + , 48 // laser number + , 8 // blocks per packet + , 48 // channels per block + , 1.0f // distance min + , 230.0f // distance max + , 0.005f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.03615f // RX + , -0.017f // RY + , 0.0f // RZ + }; + + INIT_ONLY_ONCE(); + + float blk_ts = 55.552f; + float firing_tss[48] = + { + 0.0f, 3.236f, 6.472f, 9.708f, 12.944f, 12.944f, 16.18f, 16.18f, + 19.416f, 19.416f, 22.652f, 22.652f, 25.888f, 29.124f, 32.36f, 35.596f, + 38.832f, 38.832f, 42.068f, 42.068f, 45.304f, 45.304f, 48.54f, 48.54f, + + 0.0f, 3.236f, 6.472f, 9.708f, 12.944f, 12.944f, 16.18f, 16.18f, + 19.416f, 19.416f, 22.652f, 22.652f, 25.888f, 29.124f, 32.36f, 35.596f, + 38.832f, 38.832f, 42.068f, 42.068f, 45.304f, 45.304f, 48.54f, 48.54f, + }; + + param.BLOCK_DURATION = blk_ts / 1000000; + for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) + { + param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; + param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; + } + + return param; +} + +template +inline RSEchoMode DecoderRS48::getEchoMode(uint8_t mode) +{ + switch (mode) + { + case 0x03: // dual return + return RSEchoMode::ECHO_DUAL; + case 0x01: // strongest return + case 0x02: // last return + default: + return RSEchoMode::ECHO_SINGLE; + } +} + +template +inline void DecoderRS48::decodeDifopPkt(const uint8_t* packet, size_t size) +{ + const RSP48DifopPkt& pkt = *(const RSP48DifopPkt*)(packet); + this->template decodeDifopCommon(pkt); + + this->echo_mode_ = getEchoMode (pkt.return_mode); + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; +} + +template +inline DecoderRS48::DecoderRS48(const RSDecoderParam& param) + : DecoderMech(getConstParam(), param) +{ +} + +template +inline bool DecoderRS48::decodeMsopPkt(const uint8_t* pkt, size_t size) +{ + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) + { + return internDecodeMsopPkt>(pkt, size); + } + else + { + return internDecodeMsopPkt>(pkt, size); + } +} + +template +template +inline bool DecoderRS48::internDecodeMsopPkt(const uint8_t* packet, size_t size) +{ + const RSP48MsopPkt& pkt = *(const RSP48MsopPkt*)(packet); + bool ret = false; + + this->temperature_ = parseTempInBe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) + { + pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 1e-6; + } + else + { + uint64_t ts = getTimeHost(); + + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = ts * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeUTCWithNs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + } + } + + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + this->block_az_diff_, this->fov_blind_ts_diff_); + + double block_ts = pkt_ts; + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + { + const RSP48MsopBlock& block = pkt.blocks[blk]; + + if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) + { + this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + break; + } + + int32_t block_az = ntohs(block.azimuth); + if (this->split_strategy_->newBlock(block_az)) + { + this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + ret = true; + } + + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) + { + const RSChannel& channel = block.channels[chan]; + + double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + int32_t angle_horiz = block_az + + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); + + int32_t angle_vert = this->chan_angles_.vertAdjust(chan); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + + if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) + { + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); + } + else if (!this->param_.dense_points) + { + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); + } + + this->prev_point_ts_ = chan_ts; + } + } + + this->prev_pkt_ts_ = pkt_ts; + return ret; +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index fcdab106..d69d8e9a 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -36,6 +36,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include #include #include @@ -89,6 +90,9 @@ inline std::shared_ptr> DecoderFactory::crea case LidarType::RS80: ret_ptr = std::make_shared>(param); break; + case LidarType::RS48: + ret_ptr = std::make_shared>(param); + break; case LidarType::RSP128: ret_ptr = std::make_shared>(param); break; diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 9e6d61a0..3b53e2c1 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -48,6 +48,7 @@ enum LidarType ///< LiDAR type RSBP, RS128, RS80, + RS48, RSP128, RSP80, RSP48, @@ -91,6 +92,9 @@ inline std::string lidarTypeToStr(const LidarType& type) case LidarType::RS80: str = "RS80"; break; + case LidarType::RS48: + str = "RS48"; + break; case LidarType::RSP128: str = "RSP128"; break; @@ -149,6 +153,10 @@ inline LidarType strToLidarType(const std::string& type) { return lidar::LidarType::RS80; } + else if (type == "RS48") + { + return lidar::LidarType::RS48; + } else if (type == "RSP128") { return lidar::LidarType::RSP128; @@ -180,7 +188,7 @@ inline LidarType strToLidarType(const std::string& type) else { RS_ERROR << "Wrong lidar type: " << type << RS_REND; - RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS80, RS128, RSP128, RSP80, RSP48, " + RS_ERROR << "Please give correct type: RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS48, RS80, RS128, RSP128, RSP80, RSP48, " << "RSM1, RSM2, RSEOS, RSM1_JUMBO." << RS_REND; exit(-1); From b9a6e0869badc4f079e8817106977eeb01ea8e87 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 17 Jun 2022 17:37:00 +0800 Subject: [PATCH 286/379] feat: recover to ros coordinate for EOS --- src/rs_driver/driver/decoder/decoder_RSEOS.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSEOS.hpp b/src/rs_driver/driver/decoder/decoder_RSEOS.hpp index 311f94a5..3a5b359a 100644 --- a/src/rs_driver/driver/decoder/decoder_RSEOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSEOS.hpp @@ -200,9 +200,9 @@ inline bool DecoderRSEOS::decodeMsopPkt(const uint8_t* packet, siz if (this->distance_section_.in(distance)) { - float x = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; - float y = - RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; - float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; + float x = RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; + float y = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; + float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; this->transformPoint(x, y, z); From 5bebec5369aaa62c56e319da4dfbf5fd9ec2833b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 22 Jun 2022 16:43:33 +0800 Subject: [PATCH 287/379] fix: add tips in case of input type of PCAP_FILE --- src/rs_driver/driver/input/input_factory.hpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index e5765157..0600f8f2 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -99,7 +99,14 @@ inline std::shared_ptr InputFactory::createInput(InputType type, const RS break; default: - RS_ERROR << "Wrong Input Type." << RS_REND; + + RS_ERROR << "Wrong Input Type " << type << "." << RS_REND; + + if (type == InputType::PCAP_FILE) + { + RS_ERROR << "InputType::PCAP_FILE is specified. Please enable the cmake option -DENABLE_PCAP_PARSE." << RS_REND; + } + exit(-1); } From 61467b052db5bf28bbcb63c75b1fd2b118a051ae Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 22 Jun 2022 17:27:06 +0800 Subject: [PATCH 288/379] fix: add tips in case of input type of PCAP_FILE --- src/rs_driver/driver/input/input_factory.hpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 0600f8f2..98c50a29 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -104,7 +104,9 @@ inline std::shared_ptr InputFactory::createInput(InputType type, const RS if (type == InputType::PCAP_FILE) { - RS_ERROR << "InputType::PCAP_FILE is specified. Please enable the cmake option -DENABLE_PCAP_PARSE." << RS_REND; + RS_ERROR << "InputType::PCAP_FILE is specified. " + << "Please add add_definitions(""-DENABLE_PCAP_PARSE"") to enable it. " + << "For how to add it, refer to CMakeLists.txt in the top directory of rs_driver." << RS_REND; } exit(-1); From 609051ec4a4a860f31ec51a7c377c920c4fbdab8 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 23 Jun 2022 18:46:20 +0800 Subject: [PATCH 289/379] feat: enable pcap parsing in default mode --- CMakeLists.txt | 12 +++++++----- demo/CMakeLists.txt | 10 +++++----- src/rs_driver/driver/input/input_factory.hpp | 8 +++----- 3 files changed, 15 insertions(+), 15 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index edb7a176..c50fe84e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -18,7 +18,7 @@ endif() #============================= # Compile Features #============================= -option(ENABLE_PCAP_PARSE "Enable PCAP file parse" ON) +option(DISABLE_PCAP_PARSE "Disable PCAP file parse" OFF) option(ENABLE_TRANSFORM "Enable transform functions" OFF) option(ENABLE_EPOLL_RECEIVE "Receive packets with epoll() instead of select()" OFF) option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) @@ -113,13 +113,15 @@ if(${ENABLE_HIGH_PRIORITY_THREAD}) add_definitions("-DENABLE_HIGH_PRIORITY_THREAD") endif(${ENABLE_HIGH_PRIORITY_THREAD}) -if(${ENABLE_PCAP_PARSE}) +if(${DISABLE_PCAP_PARSE}) message(=============================================================) - message("-- Enable PCAP parse") + message("-- Disable PCAP parse") message(=============================================================) - add_definitions("-DENABLE_PCAP_PARSE") + add_definitions("-DDISABLE_PCAP_PARSE") + +else() if(WIN32) set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}/cmake) @@ -130,7 +132,7 @@ if(${ENABLE_PCAP_PARSE}) list(APPEND EXTERNAL_LIBS pcap) endif(WIN32) -endif(${ENABLE_PCAP_PARSE}) +endif(${DISABLE_PCAP_PARSE}) if(${ENABLE_TRANSFORM}) diff --git a/demo/CMakeLists.txt b/demo/CMakeLists.txt index fccf85fb..6ce99e8e 100644 --- a/demo/CMakeLists.txt +++ b/demo/CMakeLists.txt @@ -24,15 +24,15 @@ target_link_libraries(demo_online pthread ${EXTERNAL_LIBS}) -if(${ENABLE_PCAP_PARSE}) +if(NOT ${DISABLE_PCAP_PARSE}) add_executable(demo_pcap - demo_pcap.cpp) + demo_pcap.cpp) target_link_libraries(demo_pcap - pthread - ${EXTERNAL_LIBS}) + pthread + ${EXTERNAL_LIBS}) -endif(${ENABLE_PCAP_PARSE}) +endif(NOT ${DISABLE_PCAP_PARSE}) diff --git a/src/rs_driver/driver/input/input_factory.hpp b/src/rs_driver/driver/input/input_factory.hpp index 98c50a29..10b6e0ee 100644 --- a/src/rs_driver/driver/input/input_factory.hpp +++ b/src/rs_driver/driver/input/input_factory.hpp @@ -38,7 +38,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include -#ifdef ENABLE_PCAP_PARSE +#ifndef DISABLE_PCAP_PARSE #include #include #endif @@ -71,7 +71,7 @@ inline std::shared_ptr InputFactory::createInput(InputType type, const RS } break; -#ifdef ENABLE_PCAP_PARSE +#ifndef DISABLE_PCAP_PARSE case InputType::PCAP_FILE: { if (isJumbo) @@ -104,9 +104,7 @@ inline std::shared_ptr InputFactory::createInput(InputType type, const RS if (type == InputType::PCAP_FILE) { - RS_ERROR << "InputType::PCAP_FILE is specified. " - << "Please add add_definitions(""-DENABLE_PCAP_PARSE"") to enable it. " - << "For how to add it, refer to CMakeLists.txt in the top directory of rs_driver." << RS_REND; + RS_ERROR << "To use InputType::PCAP_FILE, please do not specify the make option DISABLE_PCAP_PARSE." << RS_REND; } exit(-1); From 2886e718360b2f9a6c9f1204b768394922639ec5 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 24 Jun 2022 11:21:37 +0800 Subject: [PATCH 290/379] feat: parse difop in case of pcap file --- .../driver/input/input_pcap_jumbo.hpp | 32 ++--- src/rs_driver/driver/input/jumbo.hpp | 112 ++++++++++-------- 2 files changed, 70 insertions(+), 74 deletions(-) diff --git a/src/rs_driver/driver/input/input_pcap_jumbo.hpp b/src/rs_driver/driver/input/input_pcap_jumbo.hpp index ebe478e8..d4cc8f01 100644 --- a/src/rs_driver/driver/input/input_pcap_jumbo.hpp +++ b/src/rs_driver/driver/input/input_pcap_jumbo.hpp @@ -62,18 +62,15 @@ class InputPcapJumbo : public Input pcap_offset_ += input_param.user_layer_bytes; pcap_tail_ += input_param.tail_layer_bytes; - std::stringstream msop_stream, difop_stream; + std::stringstream msop_stream; if (input_param_.use_vlan) { msop_stream << "vlan && "; - difop_stream << "vlan && "; } msop_stream << "udp"; - difop_stream << "udp dst port " << input_param_.difop_port; msop_filter_str_ = msop_stream.str(); - difop_filter_str_ = difop_stream.str(); } virtual bool init(); @@ -88,7 +85,6 @@ class InputPcapJumbo : public Input size_t pcap_offset_; size_t pcap_tail_; std::string msop_filter_str_; - std::string difop_filter_str_; bpf_program msop_filter_; bpf_program difop_filter_; bool difop_filter_valid_; @@ -112,12 +108,6 @@ inline bool InputPcapJumbo::init() pcap_compile(pcap_, &msop_filter_, msop_filter_str_.c_str(), 1, 0xFFFFFFFF); - if ((input_param_.difop_port != 0) && (input_param_.difop_port != input_param_.msop_port)) - { - pcap_compile(pcap_, &difop_filter_, difop_filter_str_.c_str(), 1, 0xFFFFFFFF); - difop_filter_valid_ = true; - } - init_flag_ = true; return true; } @@ -155,7 +145,7 @@ inline void InputPcapJumbo::recvPacket() while (!to_exit_recv_) { struct pcap_pkthdr* header; - const u_char* pkt_data; + const uint8_t* pkt_data; int ret = pcap_next_ex(pcap_, &header, &pkt_data); if (ret < 0) // reach file end. { @@ -178,25 +168,21 @@ inline void InputPcapJumbo::recvPacket() if (pcap_offline_filter(&msop_filter_, header, pkt_data) != 0) { - bool new_pkt = jumbo_.new_fragment(pkt_data, header->len); + uint16_t udp_port = 0; + const uint8_t* udp_data = NULL; + size_t udp_data_len = 0; + bool new_pkt = jumbo_.new_fragment(pkt_data, header->len, &udp_port, &udp_data, &udp_data_len); if (new_pkt) { - if (jumbo_.dst_port() == input_param_.msop_port) + if ((udp_port == input_param_.msop_port) || (udp_port == input_param_.difop_port)) { std::shared_ptr pkt = cb_get_pkt_(IP_LEN); - memcpy(pkt->data(), jumbo_.buf() + UDP_HDR_LEN, jumbo_.buf_len() - UDP_HDR_LEN); - pkt->setData(0, jumbo_.buf_len() - UDP_HDR_LEN); + memcpy(pkt->data(), udp_data, udp_data_len); + pkt->setData(0, udp_data_len); pushPacket(pkt); } } } - else if (difop_filter_valid_ && (pcap_offline_filter(&difop_filter_, header, pkt_data) != 0)) - { - std::shared_ptr pkt = cb_get_pkt_(IP_LEN); - memcpy(pkt->data(), pkt_data + pcap_offset_, header->len - pcap_offset_ - pcap_tail_); - pkt->setData(0, header->len - pcap_offset_ - pcap_tail_); - pushPacket(pkt); - } else { continue; diff --git a/src/rs_driver/driver/input/jumbo.hpp b/src/rs_driver/driver/input/jumbo.hpp index eb2da112..a25f76ae 100644 --- a/src/rs_driver/driver/input/jumbo.hpp +++ b/src/rs_driver/driver/input/jumbo.hpp @@ -43,27 +43,27 @@ namespace lidar struct iphdr { - u_char version; - u_char tos; - u_short tot_len; + uint8_t version; + uint8_t tos; + uint16_t tot_len; - u_short id; - u_short frag_off; + uint16_t id; + uint16_t frag_off; - u_char ttl; - u_char protocol; - u_short check; + uint8_t ttl; + uint8_t protocol; + uint16_t check; - u_int saddr; - u_int daddr; + uint32_t saddr; + uint32_t daddr; }; struct udphdr { - u_short source; - u_short dest; - u_short len; - u_short check; + uint16_t source; + uint16_t dest; + uint16_t len; + uint16_t check; }; #pragma pack(pop) @@ -77,31 +77,23 @@ class Jumbo { } - u_char* buf() - { - return buf_; - } - - u_short buf_len() - { - return buf_off_; - } - - bool new_fragment(const u_char* pkt_data, size_t pkt_data_size); - - u_short dst_port(); + bool new_fragment(const uint8_t* pkt_data, size_t pkt_data_size, + uint16_t* udp_port, const uint8_t**ip_data, size_t* ip_data_len); private: - u_short ip_id_; - u_char buf_[IP_LEN]; - u_short buf_off_; + uint16_t dst_port(const uint8_t* buf); + + uint16_t ip_id_; + uint8_t buf_[IP_LEN]; + uint16_t buf_off_; }; -inline bool Jumbo::new_fragment(const u_char* pkt_data, size_t pkt_data_size) +inline bool Jumbo::new_fragment(const uint8_t* pkt_data, size_t pkt_data_size, + uint16_t* udp_port, const uint8_t** udp_data, size_t* udp_data_len) { // Is it an ip packet ? - const u_short* eth_type = (const u_short*)(pkt_data + 12); + const uint16_t* eth_type = (const uint16_t*)(pkt_data + 12); if (ntohs(*eth_type) != 0x0800) return false; @@ -111,18 +103,19 @@ inline bool Jumbo::new_fragment(const u_char* pkt_data, size_t pkt_data_size) return false; // ip data - //u_short ip_hdr_size = ip_hdr->ihl * 4; - u_short ip_hdr_size = (ip_hdr->version & 0xf) * 4; - u_short ip_len = ntohs(ip_hdr->tot_len); + uint16_t ip_hdr_size = (ip_hdr->version & 0xf) * 4; + uint16_t ip_len = ntohs(ip_hdr->tot_len); - const u_char* ip_data = pkt_data + 14 + ip_hdr_size; - u_short ip_data_len = ip_len - ip_hdr_size; + const uint8_t* ip_data = pkt_data + 14 + ip_hdr_size; + uint16_t ip_data_len = ip_len - ip_hdr_size; // ip fragment - u_short ip_id = ntohs (ip_hdr->id); - u_short f_off = ntohs(ip_hdr->frag_off); - u_short frag_flags = (f_off >> 13); - u_short frag_off = (f_off & 0x1fff) * 8; // 8 octet boudary + uint16_t ip_id = ntohs (ip_hdr->id); + uint16_t f_off = ntohs(ip_hdr->frag_off); + uint16_t frag_flags = (f_off >> 13); + uint16_t frag_off = (f_off & 0x1fff) * 8; // 8 octet boudary + +#define MORE_FRAGS(flags) ((flags & 0x01) != 0) if (ip_id == ip_id_) { @@ -131,7 +124,7 @@ inline bool Jumbo::new_fragment(const u_char* pkt_data, size_t pkt_data_size) memcpy (buf_ + buf_off_, ip_data, ip_data_len); buf_off_ += ip_data_len; - if ((frag_flags & 0x1) == 0) + if (!MORE_FRAGS(frag_flags)) { #if 0 printf ("--- end new packet. ip_id:0x%x, len:%d\n", ip_id_, buf_off_); @@ -146,33 +139,50 @@ inline bool Jumbo::new_fragment(const u_char* pkt_data, size_t pkt_data_size) #endif ip_id_ = 0; + + *udp_port = dst_port (buf_); + *udp_data = buf_ + UDP_HDR_LEN; + *udp_data_len = buf_off_ - UDP_HDR_LEN; return true; } } } else { - if ((frag_off == 0) && ((frag_flags & 0x1) != 0)) - //if (frag_off == 0) + if (frag_off == 0) { - ip_id_ = ip_id; - buf_off_ = 0; + if (MORE_FRAGS(frag_flags)) + { + ip_id_ = ip_id; + buf_off_ = 0; - memcpy (buf_ + buf_off_, ip_data, ip_data_len); - buf_off_ += ip_data_len; + memcpy (buf_ + buf_off_, ip_data, ip_data_len); + buf_off_ += ip_data_len; #if 0 - printf ("+++ start packet 0x%x\n", ip_id_); + printf ("+++ start packet 0x%x\n", ip_id_); +#endif + } + else + { +#if 0 + printf ("+++ non-fragment packet 0x%x\n", ip_id); #endif + + *udp_port = dst_port (ip_data); + *udp_data = ip_data + UDP_HDR_LEN; + *udp_data_len = ip_data_len - UDP_HDR_LEN; + return true; + } } } return false; } -inline u_short Jumbo::dst_port() +inline uint16_t Jumbo::dst_port(const uint8_t* buf) { - const struct udphdr * udp_hdr = (const struct udphdr*)buf_; + const struct udphdr* udp_hdr = (const struct udphdr*)buf; return ntohs(udp_hdr->dest); } From a6f2e41897cb8191f83c89f1142a85cfe80125fe Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 24 Jun 2022 15:39:46 +0800 Subject: [PATCH 291/379] feat: add help doc to port app to 1.5.x --- ..._your_app_from_rs_driver_1.3.x_to_1.5.x.md | 195 ++++++++++++++++++ 1 file changed, 195 insertions(+) create mode 100644 doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md diff --git a/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md b/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md new file mode 100644 index 00000000..3fd63bf3 --- /dev/null +++ b/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md @@ -0,0 +1,195 @@ +# How to port your app from rs_driver 1.3.x to 1.5.x + +## 1 Introduction + +This document illustrates how to port your app from rs_driver 1.3.x to 1.5.x. + +The interface of rs_driver contains two parts: RSDriverParam and LidarDriver. + +Here are the changes to them. + +## 2 RSDriverParam + +### 2.1 RSDriverParam + +RSDriverParam contains the options to change the rs_driver's behavior. + +RSDriverParam is as below in rs_driver 1.3.x. + +```c++ +typedef struct RSDriverParam ///< The LiDAR driver parameter +{ + RSInputParam input_param; ///< Input parameter + RSDecoderParam decoder_param; ///< Decoder parameter + std::string angle_path = "null"; ///< Path of angle calibration files(angle.csv).Only used for internal debugging. + std::string frame_id = "rslidar"; ///< The frame id of LiDAR message + LidarType lidar_type = LidarType::RS16; ///< Lidar type + bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + bool saved_by_rows = false; ///< true: the output point cloud will be saved by rows (default is saved by columns) +}; +``` + +And it is as below in rs_driver 1.5.x. + +```c++ +typedef struct RSDriverParam ///< The LiDAR driver parameter +{ + LidarType lidar_type = LidarType::RS16; ///< Lidar type + InputType input_type = InputType::ONLINE_LIDAR; ///< Input type + RSInputParam input_param; ///< Input parameter + RSDecoderParam decoder_param; ///< Decoder parameter +}; +``` + +Below are the changes. ++ A new member `input_type` is added. It means the type of data sources: `ONLINE_LIDAR`, `PCAP_FILE`, or `RAW_PACKET`. ++ The member `waitf_for_difop` specifies whether to handle MSOP packets before handling DIFOP packet. For mechenical LiDARs, the point cloud will be flat without the angle data in DIFOP packet。This option is about decoding, so it is shifted to RSDecoderParam. ++ The member `saved_by_rows` specifies to give point cloud row by row. There are two reasons to remove it: + + Even point cloud is given column by column, it is easier to access row by row (by skipping column). + + The option consumes two much CPU resources, so not suggested. ++ The member `angle_path` specifies a file which contains the angle data. It is about data source, so it is shifted to RSInputParam. ++ The member `frame_id` is a concept from ROS. It is removed, and the driver `rslidar_sdk` (for ROS) will handle it. + +### 2.2 RSInputParam + +RSInputParam is as below in rs_driver 1.3.x. + +```c++ +typedef struct RSInputParam ///< The LiDAR input parameter +{ + std::string device_ip = "192.168.1.200"; ///< Ip of LiDAR + std::string multi_cast_address = "0.0.0.0"; ///< Address of multicast + std::string host_address = "0.0.0.0"; ///< Address of host + uint16_t msop_port = 6699; ///< Msop packet port number + uint16_t difop_port = 7788; ///< Difop packet port number + bool read_pcap = false; ///< true: The driver will process the pcap through pcap_path. false: The driver will + ///< Get data from online LiDAR + double pcap_rate = 1; ///< Rate to read the pcap file + bool pcap_repeat = true; ///< true: The pcap bag will repeat play + std::string pcap_path = "null"; ///< Absolute path of pcap file + bool use_vlan = false; ///< Vlan on-off + bool use_someip = false; ///< Someip on-off + bool use_custom_proto = false; ///< Customer Protocol on-off +}; +``` + +And it is as below in rs_driver 1.5.x. + +```c++ +typedef struct RSInputParam ///< The LiDAR input parameter +{ + uint16_t msop_port = 6699; ///< Msop packet port number + uint16_t difop_port = 7788; ///< Difop packet port number + std::string host_address = "0.0.0.0"; ///< Address of host + std::string group_address = "0.0.0.0"; ///< Address of multicast group + std::string pcap_path = ""; ///< Absolute path of pcap file + bool pcap_repeat = true; ///< true: The pcap bag will repeat play + float pcap_rate = 1.0f; ///< Rate to read the pcap file + bool use_vlan = false; ///< Vlan on-off + uint16_t user_layer_bytes = 0; ///< Bytes of user layer. thers is no user layer if it is 0 + uint16_t tail_layer_bytes = 0; ///< Bytes of tail layer. thers is no tail layer if it is 0 +}; +``` + +Below are the changes. ++ The member `device_ip` is not needed for receiving packets, so it is removed. ++ The member `multi_cast_address` is renamed to `group_address`。This is to say, in the multicast mode, the host will join the group to receive packets. ++ The member `read_pcap` is not needed now. `RSDriverParam.input_type` replaces it. ++ The members `use_someip` and `use_custom_proto` is not needed now. `user_layer_bytes` replaces them. + +### 2.2 RSDecoderParam + +RSDecoderParam is as below in rs_driver 1.3.x. + +```c++ +typedef struct RSDecoderParam ///< LiDAR decoder parameter +{ + float max_distance = 200.0f; ///< Max distance of point cloud range + float min_distance = 0.2f; ///< Minimum distance of point cloud range + float start_angle = 0.0f; ///< Start angle of point cloud + float end_angle = 360.0f; ///< End angle of point cloud + SplitFrameMode split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; ///< 1: Split frames by cut_angle; + ///< 2: Split frames by fixed number of packets; + ///< 3: Split frames by custom number of packets (num_pkts_split) + uint32_t num_pkts_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 + float cut_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 + bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp + RSTransformParam transform_param; ///< Used to transform points + RSCameraTriggerParam trigger_param; ///< Used to trigger camera +}; +``` + +And it is as below in rs_driver 1.5.x. + +```c++ +typedef struct RSDecoderParam ///< LiDAR decoder parameter +{ + bool config_from_file = false; ///< Internal use only for debugging + std::string angle_path = ""; ///< Internal use only for debugging + bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + float min_distance = 0.2f; ///< Minimum distance of point cloud range + float max_distance = 200.0f; ///< Max distance of point cloud range + float start_angle = 0.0f; ///< Start angle of point cloud + float end_angle = 360.0f; ///< End angle of point cloud + SplitFrameMode split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; + ///< 1: Split frames by split_angle; + ///< 2: Split frames by fixed number of blocks; + ///< 3: Split frames by custom number of blocks (num_blks_split) + float split_angle = 0.0f; ///< Split angle(degree) used to split frame, only be used when split_frame_mode=1 + uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 + bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp + bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points + RSTransformParam transform_param; ///< Used to transform points +}; +``` + +Below are the changes. ++ The member `cut_angle` is renamed to `split_angle`, to align to `split_frame_mode`. ++ The member `config_from_file` is added. Only if it is true, the member `angle_path` is valid. ++ The member `num_pkts_split` is renamed to `number_blks_split`. That means to split frames `by blocks (in MSOP packets)` instead of `by MSOP packets`. + +## 3 LidarDriver + +LidarDriver contains the functions to run rs_driver. + +LidarDriver is as below in rs_driver 1.3.x. + +```c++ +template +class LidarDriver +{ +public: + + inline void regPointCloudCallback(const std::function(void)>& cb_get_cloud, + const std::function)>& cb_put_cloud) + { + driver_ptr_->regPointCloudCallback(cb_get_cloud, cb_put_cloud); + } + ... +}; +``` + +And it is as below in rs_driver 1.5.x. + +```c++ +template +class LidarDriver +{ +public: + + inline void regRecvCallback(const std::function&)>& callback) + { + driver_ptr_->regRecvCallback(callback); + } + ... +}; +``` + +Below are the changes. ++ The template parameter is changed from typename `PointT` to typename `T_PointCloud`. ++ The function to get point cloud is now requested to have two callbacks instead of one. + +For details of these two changes, please refer to [Decode online Lidar](./how_to_decode_online_lidar.md). + + + From 8ba7fc176d560a8ca3a18820eeee1fd5de83958f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Jun 2022 15:28:06 +0800 Subject: [PATCH 292/379] fix: fox doc --- doc/src_intro/rs_driver_intro.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/src_intro/rs_driver_intro.md b/doc/src_intro/rs_driver_intro.md index 09d96e7d..f1b7098e 100644 --- a/doc/src_intro/rs_driver_intro.md +++ b/doc/src_intro/rs_driver_intro.md @@ -362,7 +362,7 @@ int8_t temperature; 雷达内部有多种回波模式。 + 最强回波, -+ 最强回波, ++ 最后回波, + 双回波, MSOP格式中用一个字节表示: From 70cbd883cf435509e746c5b159b7d26fd7878a88 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Jun 2022 16:14:34 +0800 Subject: [PATCH 293/379] fix: fix doc --- doc/src_intro/rs_driver_intro.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/doc/src_intro/rs_driver_intro.md b/doc/src_intro/rs_driver_intro.md index f1b7098e..a061a93c 100644 --- a/doc/src_intro/rs_driver_intro.md +++ b/doc/src_intro/rs_driver_intro.md @@ -768,11 +768,11 @@ Block水平角差 = 第三个Block的水平角 - 第一个Block的水平角 为了充分利用MSOP Packet的空间,RS16的Packet格式与其他机械式雷达不同。 -在单回波模式下,RS16将相邻两个通道的数据放在同一Block中,如下图所示。 +在单回波模式下,一组`16通道数据`包含一个回波,将相邻两组的回波数据放在同一Block中。如下图所示。 ![](./img/rs16_msop_single_return.png) -在双回波模式下,RS16将一个通道两个回波数据放在同一Block中,如下图所示。 +在双回波模式下,一组`16通道数据`就有两个回波,将两个回波的数据放在同一Block中。如下图所示。 ![](./img/rs16_msop_dual_return.png) @@ -995,7 +995,7 @@ DecoderFactory根据指定的雷达类型,生成Decoder实例。 如下图是Decoder的详细定义。 + 成员`const_param_`是雷达的参数配置。 + 成员`param_`是用户的参数配置。 -+ 成员`trigon_`是Trigon类的实例,提供快速的sin/con计算。定义如下的宏,可以清晰、方便调用它。 ++ 成员`trigon_`是Trigon类的实例,提供快速的sin()/cos()计算。定义如下的宏,可以清晰、方便调用它。 ``` #define SIN(angle) this->trigon_.sin(angle) From 2103c20d6a77d33733ccddd35ce698093adab474 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Jun 2022 16:54:51 +0800 Subject: [PATCH 294/379] feat: support to stamp point cloud with first point --- src/rs_driver/driver/decoder/decoder.hpp | 14 ++++++++++++-- src/rs_driver/driver/decoder/decoder_RS128.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RS16.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RS32.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RS48.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RS80.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RSEOS.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp | 3 ++- .../driver/decoder/decoder_RSHELIOS_16P.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RSM1.hpp | 3 ++- .../driver/decoder/decoder_RSM1_Jumbo.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RSP128.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RSP48.hpp | 3 ++- src/rs_driver/driver/decoder/decoder_RSP80.hpp | 3 ++- src/rs_driver/driver/driver_param.hpp | 1 + 17 files changed, 43 insertions(+), 17 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index c87ad31c..eec5b675 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -275,6 +275,8 @@ class Decoder protected: #endif + double cloudTs(); + RSDecoderConstParam const_param_; // const param RSDecoderParam param_; // user param std::function cb_split_frame_; @@ -296,8 +298,9 @@ class Decoder float temperature_; // lidar temperature bool angles_ready_; // is vert_angles/horiz_angles ready from csv file/difop packet? - double prev_pkt_ts_; // last packet's timestamp - double prev_point_ts_; // last point's timestamp + double prev_pkt_ts_; // timestamp of prevous packet + double prev_point_ts_; // timestamp of previous point + double first_point_ts_; // timestamp of first point }; template @@ -321,6 +324,7 @@ inline Decoder::Decoder(const RSDecoderConstParam& const_param, co , angles_ready_(false) , prev_pkt_ts_(0.0) , prev_point_ts_(0.0) + , first_point_ts_(0.0) { #ifdef ENABLE_TRANSFORM Eigen::AngleAxisd current_rotation_x(param_.transform_param.roll, Eigen::Vector3d::UnitX()); @@ -356,6 +360,12 @@ inline double Decoder::prevPktTs() return prev_pkt_ts_; } +template +inline double Decoder::cloudTs() +{ + return (param_.ts_first_point ? first_point_ts_ : prev_point_ts_); +} + template inline void Decoder::transformPoint(float& x, float& y, float& z) { diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index d60341b6..125a05fd 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -248,7 +248,8 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 2ee2d7a1..41deb0f9 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -284,7 +284,8 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index b5e8febc..c64e831d 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -267,7 +267,8 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RS48.hpp b/src/rs_driver/driver/decoder/decoder_RS48.hpp index 20e7f16f..ba5805cc 100644 --- a/src/rs_driver/driver/decoder/decoder_RS48.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS48.hpp @@ -197,7 +197,8 @@ inline bool DecoderRS48::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 05026602..08667c57 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -243,7 +243,8 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index ecd7f59e..fb32bf4e 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -238,7 +238,8 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSEOS.hpp b/src/rs_driver/driver/decoder/decoder_RSEOS.hpp index 3a5b359a..4d7995ef 100644 --- a/src/rs_driver/driver/decoder/decoder_RSEOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSEOS.hpp @@ -182,7 +182,8 @@ inline bool DecoderRSEOS::decodeMsopPkt(const uint8_t* packet, siz uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); if (split_strategy_.newPacket(pkt_seq)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 5b9e5731..d59356cc 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -250,7 +250,8 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp index 363d77b8..0a14d03a 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp @@ -216,7 +216,8 @@ inline bool DecoderRSHELIOS_16P::internDecodeMsopPkt(const uint8_t int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSM1.hpp b/src/rs_driver/driver/decoder/decoder_RSM1.hpp index bee1f27e..47054083 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1.hpp @@ -239,7 +239,8 @@ inline bool DecoderRSM1::decodeMsopPkt(const uint8_t* packet, size uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); if (split_strategy_.newPacket(pkt_seq)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp b/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp index db92881d..ec06433c 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM1_Jumbo.hpp @@ -200,7 +200,8 @@ inline bool DecoderRSM1_Jumbo::internDecodeMsopPkt(const uint8_t* uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); if (split_strategy_.newPacket(pkt_seq)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index 74576dbb..a40bb0e9 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -185,7 +185,8 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size uint16_t pkt_seq = ntohs(pkt.header.pkt_seq); if (split_strategy_.newPacket(pkt_seq)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSP128.hpp b/src/rs_driver/driver/decoder/decoder_RSP128.hpp index a286446b..96a484b2 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP128.hpp @@ -253,7 +253,8 @@ inline bool DecoderRSP128::internDecodeMsopPkt(const uint8_t* pack int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSP48.hpp b/src/rs_driver/driver/decoder/decoder_RSP48.hpp index 75968a6b..82eb05ea 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP48.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP48.hpp @@ -242,7 +242,8 @@ inline bool DecoderRSP48::internDecodeMsopPkt(const uint8_t* packe int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/decoder/decoder_RSP80.hpp b/src/rs_driver/driver/decoder/decoder_RSP80.hpp index 2cb68efb..3343a63c 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP80.hpp @@ -286,7 +286,8 @@ inline bool DecoderRSP80::internDecodeMsopPkt(const uint8_t* packe int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { - this->cb_split_frame_(this->const_param_.LASER_NUM, this->prev_point_ts_); + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = pkt_ts; ret = true; } diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 3b53e2c1..ac5052b1 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -270,6 +270,7 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points + bool ts_first_point = false; ///< true: time-stamp point cloud with the first point; false: with the last point; RSTransformParam transform_param; ///< Used to transform points void print() const From 25907b6daa5ac65ba2fd6f8c22446da079372bb0 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Jun 2022 17:22:03 +0800 Subject: [PATCH 295/379] fix: fix doc --- doc/src_intro/rs_driver_intro.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/doc/src_intro/rs_driver_intro.md b/doc/src_intro/rs_driver_intro.md index a061a93c..c908c0ab 100644 --- a/doc/src_intro/rs_driver_intro.md +++ b/doc/src_intro/rs_driver_intro.md @@ -1220,7 +1220,7 @@ decodeMsopPkt()使用不同的模板参数调用internDecodeMsopPkt()。 + 得到Block的角度值。 + 计算得到Block的时间戳,保存到本地变量`block_ts`。 + 调用SplitStrategy::newBlock(),检查是否分帧。如果是,调用回调函数`cb_split_frame_`,通知使用者。 - `cb_split_frame_`应该转移点云`pont_cloud_`,并重置它。 + `cb_split_frame_`应该转移点云`point_cloud_`,并重置它。 + 遍历Block内所有的Channel。 + 计算Channel的时间戳 @@ -1271,8 +1271,8 @@ RSM1是MEMS雷达。这里说明RSM1的Decoder。 | DIFOP_ID_LEN | 8 | DIFOP_LEN[]中的字节长度 | | BLOCK_ID[] | {0xFF, 0xEE} | block标志字节,长度为2 | | LASER_NUM | 5 | 5通道 | -| BLOCKS_PER_PKT | 25 | 每Packet中12个Block | -| CHANNEL_PER_BLOCK | 5 | RSBP为32线雷达 | +| BLOCKS_PER_PKT | 25 | 每Packet中25个Block | +| CHANNEL_PER_BLOCK | 5 | RSM1有5个通道 | | DISTANCE_MIN | 0.2 | 测距最小值,单位米 | | DISTANCE_MAX | 200.0 | 测距最大值,单位米 | | DISTANCE_RES | 0.005 | Packet中distance的解析度,单位米 | From aa40f943163c4867dd24db683c865a6cdaa488fb Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Jun 2022 17:41:18 +0800 Subject: [PATCH 296/379] feat: update doc for ts_first_point --- doc/intro/parameter_intro_cn.md | 3 +++ doc/intro/parameter_intro_en.md | 3 +++ 2 files changed, 6 insertions(+) diff --git a/doc/intro/parameter_intro_cn.md b/doc/intro/parameter_intro_cn.md index 42dab4e0..c9842f22 100644 --- a/doc/intro/parameter_intro_cn.md +++ b/doc/intro/parameter_intro_cn.md @@ -59,6 +59,7 @@ typedef struct RSDecoderParam { bool use_lidar_clock = false; bool dense_points = false; + bool ts_first_point = false; bool wait_for_difop = true; RSTransformParam transform_param; bool config_from_file = false; @@ -80,6 +81,8 @@ typedef struct RSDecoderParam + 如果`use_lidar_clock`=`true`,则使用雷达写入Packet中的时间戳;如果`use_lidar_clock`=`false`,则使用rs_driver在主机端产生的时间戳。 + dense_points - 指定点云是否是dense的。 + 如果`dense_points`=`false`, 则点云中包含NAN点;如果`dense_points`=`true`,则去除点云中的NAN点。 ++ ts_first_point - 指定点云的时间戳来自点云的第一个点,还是最后第一个点。 + + 如果`ts_first_point`=`false`, 则第一个点的时间作为点云的时间戳;如果`ts_first_point`=`true`,则最后一个点的时间作为点云的时间戳。 + wait_for_difop - 解析MSOP Packet之前,是否等待DIFOP Packet。 + DIFOP Packet中包含角度校准等参数数据。如果没有这个数据,rs_driver输出的点云将是扁平的。 + 在rs_driver不输出点云时,设置`wait_for_difop`=`false`,有助于定位问题的位置。 diff --git a/doc/intro/parameter_intro_en.md b/doc/intro/parameter_intro_en.md index 38882de2..6924d65c 100644 --- a/doc/intro/parameter_intro_en.md +++ b/doc/intro/parameter_intro_en.md @@ -60,6 +60,7 @@ typedef struct RSDecoderParam { bool use_lidar_clock = false; bool dense_points = false; + bool ts_first_point = false; bool wait_for_difop = true; RSTransformParam transform_param; bool config_from_file = false; @@ -82,6 +83,8 @@ The following parameters are for all Lidars。 + If `use_lidar_clock`=`true`,use the Lidar timestamp, else use the host one. + dense_points - Whether the point cloud is dense. + If `dense_points`=`false`, then point cloud contains NAN points, else discard them. ++ ts_first_point - Whether to stamp the point cloud with the first point, or the last point. + + If `ts_first_point`=`false`, then stamp it with the last point, else with the first point。 + wait_for_difop - Whether wait for DIFOP Packet, before parse MSOP packets. + DIFOP Packet contains angle calibration parameters. If it is unavailable, the point cloud is flat. + If you get no point cloud, try `wait_for_difop`=`false`. It might help to locate the problem. From c21b4cfaf5b48bff201f18501a621ec21ea8f5b1 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 27 Jun 2022 20:32:56 +0800 Subject: [PATCH 297/379] feat: update CHANGELOG --- CHANGELOG.md | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 69c1cc80..93aaa576 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -2,6 +2,16 @@ ## Unreleased +### Added +- Support Ruby_3.0_48 +- Add option to stamp point cloud with first point + +### Updated +- Different 80/80v with lidar model +- Use ROS coordinate for EOS +- Enable PCAP file parsing in default mode +- Parse DIFOP packet in case of jumbo pcap file + ## v1.5.3 2022-06-01 ### Added From fb8501e35cd152aee3739c66dd0a30c17e0c35cd Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 28 Jun 2022 15:04:24 +0800 Subject: [PATCH 298/379] feat: update doc --- README.md | 13 ++++++++++--- README_CN.md | 10 ++++++++-- 2 files changed, 18 insertions(+), 5 deletions(-) diff --git a/README.md b/README.md index 0ffb13a7..4e835915 100644 --- a/README.md +++ b/README.md @@ -8,13 +8,20 @@ ## 2 Supported LiDARs +Below are the supported LiDARS. + - RS-LiDAR-16 - RS-LiDAR-32 - RS-Bpearl -- RS-Ruby -- RS-Ruby Lite -- RS-LiDAR-M1 - RS-Helios +- RS-Helios-16P +- RS-Ruby-128 +- RS-Ruby-80 +- RS-Ruby-48 +- RS-Ruby-Plus-128 +- RS-Ruby-Plus-80 +- RS-Ruby-Plus-48 +- RS-LiDAR-M1 ## 3 Supported Platforms diff --git a/README_CN.md b/README_CN.md index 2b2f98dd..1e38d198 100644 --- a/README_CN.md +++ b/README_CN.md @@ -9,12 +9,18 @@ ## 2 支持的雷达型号 支持的雷达型号如下。 + - RS-LiDAR-16 - RS-LiDAR-32 - RS-Bpearl - RS-Helios -- RS-Ruby -- RS-Ruby Lite +- RS-Helios-16P +- RS-Ruby-128 +- RS-Ruby-80 +- RS-Ruby-48 +- RS-Ruby-Plus-128 +- RS-Ruby-Plus-80 +- RS-Ruby-Plus-48 - RS-LiDAR-M1 ## 3 支持的操作系统 From c4876ef7b7d038ae1ee67ac09b3377e1256bf95a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 28 Jun 2022 17:30:31 +0800 Subject: [PATCH 299/379] feat: update demo_online to adapt to the reality --- demo/demo_online.cpp | 63 +++++++++++++++++++++------- demo/demo_pcap.cpp | 33 +++++++++------ src/rs_driver/utility/sync_queue.hpp | 2 +- 3 files changed, 70 insertions(+), 28 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index c6478f79..699d8fba 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -43,40 +43,75 @@ typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; +SyncQueue> free_cloud_queue; +SyncQueue> cloud_queue; + +// +// @brief point cloud callback function. The caller should register it to the lidar driver. +// Via this fucntion, the driver fetches an EMPTY point cloud message from the caller. +// @param msg The empty point cloud message. +// std::shared_ptr pointCloudGetCallback(void) { + // Note: This callback function runs in the packet-parsing thread of the driver, + // so please DO NOT do time-consuming task here. + std::shared_ptr msg = free_cloud_queue.pop(); + if (msg.get() != NULL) + { + return msg; + } + return std::make_shared(); } -/** - * @brief The point cloud callback function. This function will be registered to lidar driver. - * When the point cloud message is ready, driver can send out messages through this function. - * @param msg The lidar point cloud message. - */ +// +// @brief point cloud callback function. The caller should register it to the lidar driver. +// Via this function, the driver returns a STUFFED point cloud message to the caller. +// @param msg The stuffed point cloud message. +// void pointCloudPutCallback(std::shared_ptr msg) { - /* Note: Please do not put time-consuming operations in the callback function! */ - /* Make a copy of the message and process it in another thread is recommended*/ - RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; + // Note: This callback function runs in the packet-parsing thread of the driver, + // so please DO NOT do time-consuming task here. Instead, process it in another thread. + cloud_queue.push(msg); } -/** - * @brief The exception callback function. This function will be registered to lidar driver. - * @param code The error code struct. - */ +// +// @brief exception callback function. The caller should register it to the lidar driver. +// @param code The error code to represent the error/warning/information +// void exceptionCallback(const Error& code) { - /* Note: Please do not put time-consuming operations in the callback function! */ - /* Make a copy of the error message and process it in another thread is recommended*/ + // Note: This callback function runs in the packet-receving/packet-parsing thread of the driver, + // so please DO NOT do time-consuming task here. RS_WARNING << code.toString() << RS_REND; } +void processCloud(void) +{ + while (1) + { + std::shared_ptr msg = cloud_queue.popWait(); + if (msg.get() == NULL) + { + continue; + } + + // process the point cloud msg, even it is time-consuming + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; + + free_cloud_queue.push(msg); + } +} + int main(int argc, char* argv[]) { RS_TITLE << "------------------------------------------------------" << RS_REND; RS_TITLE << " RS_Driver Core Version: v" << getDriverVersion() << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; + std::thread cloud_handle_thread = std::thread(processCloud); + RSDriverParam param; ///< Create a parameter object param.input_type = InputType::ONLINE_LIDAR; param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index b9c81523..80964903 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -43,31 +43,38 @@ typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; +// +// @brief point cloud callback function. The caller should register it to the lidar driver. +// Via this fucntion, the driver fetches an EMPTY point cloud message from the caller. +// @param msg The empty point cloud message. +// std::shared_ptr pointCloudGetCallback(void) { + // Note: This callback function runs in the packet-parsing thread of the driver, + // so please DO NOT do time-consuming task here. return std::make_shared(); } -/** - * @brief The point cloud callback function. This function will be registered to lidar driver. - * When the point cloud message is ready, driver can send out messages through this function. - * @param msg The lidar point cloud message. - */ +// +// @brief point cloud callback function. The caller should register it to the lidar driver. +// Via this function, the driver returns a STUFFED point cloud message to the caller. +// @param msg The stuffed point cloud message. +// void pointCloudPutCallback(std::shared_ptr msg) { - /* Note: Please do not put time-consuming operations in the callback function! */ - /* Make a copy of the message and process it in another thread is recommended*/ + // Note: This callback function runs in the packet-parsing thread of the driver, + // so please DO NOT do time-consuming task here. Instead, process it in another thread. RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; } -/** - * @brief The exception callback function. This function will be registered to lidar driver. - * @param code The error code struct. - */ +// +// @brief exception callback function. The caller should register it to the lidar driver. +// @param code The error code to represent the error/warning/information +// void exceptionCallback(const Error& code) { - /* Note: Please do not put time-consuming operations in the callback function! */ - /* Make a copy of the error message and process it in another thread is recommended*/ + // Note: This callback function runs in the packet-receving/packet-parsing thread of the driver, + // so please DO NOT do time-consuming task here. RS_WARNING << code.toString() << RS_REND; } diff --git a/src/rs_driver/utility/sync_queue.hpp b/src/rs_driver/utility/sync_queue.hpp index 1df0e992..81798980 100644 --- a/src/rs_driver/utility/sync_queue.hpp +++ b/src/rs_driver/utility/sync_queue.hpp @@ -73,7 +73,7 @@ class SyncQueue return value; } - inline T popWait(unsigned int usec) + inline T popWait(unsigned int usec = 1000000) { // // Low latency, or low CPU usage, that is the question. From 25f749c8aee8cf7f1a01b1f9335e01b5a3689cfa Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 29 Jun 2022 21:04:52 +0800 Subject: [PATCH 300/379] fix: fix temperature --- src/rs_driver/driver/lidar_driver_impl.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index aa498fb2..9d046b7a 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -260,7 +260,7 @@ inline void LidarDriverImpl::decodePacket(const Packet& pkt) template inline bool LidarDriverImpl::getTemperature(float& temp) { - if (decoder_ptr_ != nullptr) + if (decoder_ptr_ == nullptr) { return false; } From fb897f678b1a03577080978091c07cc5e5ef3e44 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 1 Jul 2022 11:58:15 +0800 Subject: [PATCH 301/379] feat: update docs --- CHANGELOG.md | 7 +- doc/src_intro/rs_driver_intro.md | 149 ++++++++++++++++--------------- 2 files changed, 82 insertions(+), 74 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 93aaa576..507bc253 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -7,10 +7,15 @@ - Add option to stamp point cloud with first point ### Updated -- Different 80/80v with lidar model +- Distinguish 80/80v with lidar model - Use ROS coordinate for EOS - Enable PCAP file parsing in default mode - Parse DIFOP packet in case of jumbo pcap file +- Update demo_online example to use ponit cloud queue +- Update help documents + +### Fixed +- Fix lidar temperature ## v1.5.3 2022-06-01 diff --git a/doc/src_intro/rs_driver_intro.md b/doc/src_intro/rs_driver_intro.md index c908c0ab..8cf3305b 100644 --- a/doc/src_intro/rs_driver_intro.md +++ b/doc/src_intro/rs_driver_intro.md @@ -1,4 +1,4 @@ -# rs_driver v1.5.2 源代码解析 +# rs_driver v1.5.4 源代码解析 ## 1 基本概念 @@ -10,10 +10,9 @@ rs_driver支持RoboSense的两种雷达: ### 1.2 通道 Channel -对于机械式雷达,通道指的是垂直方向上扫描的点数,每个通道上的点连成一条线。 -+ 比如,RS16是16线雷达,也就是16个通道; RSBP是32线雷达,RS128是128线雷达。 +对于机械式雷达,通道指的是垂直方向上扫描的点数,每个通道上的点连成一条线。比如,RS16是16线雷达,也就是16个通道; RSBP是32线雷达,RS128是128线雷达。 -MEMS雷达的通道与机械式不同,它的每个通道可能对应一块区域,比如一个矩形。 +MEMS雷达的通道与机械式雷达不同,它的每个通道可能对应一块区域,比如一个矩形区域。 ### 1.3 MSOP/DIFOP @@ -22,16 +21,16 @@ RoboSense雷达与电脑主机的通信协议有三种。 + DIFOP (Device Information Output Protocol)。激光雷达将自身的配置信息,以及当前的状态封装成DIFOP Packet,输出给电脑主机。 + UCWP (User Configuration Write Protocol)。用户可以修改激光雷达的某些配置参数。 -rs_driver处理前两类,也就是处理MSOP Packet和DIFOP Packet。 +rs_driver处理前两类协议的包,也就是MSOP Packet和DIFOP Packet。 一般来说,激光雷达与电脑主机通过以太网连接,使用UDP协议。MSOP/DIFOP的格式,不同的雷达可能有较大差异。 ### 1.4 点云帧 + 机械式雷达持续旋转,输出点。扫描一圈360°得到的所有点,构成一帧点云。 - + 使用者可以指定一个角度。rs_driver,按照这个角度来分割MSOP Pacekt序列,得到点云。 + + 使用者可以指定一个角度,rs_driver按照这个角度,分割MSOP Pacekt序列得到点云。 -+ 对于MEMS雷达,雷达自己确定点云帧的开始点和结束点。 ++ 对于MEMS雷达,点云在MSOP Packet序列中的开始和结束位置,由雷达自己确定。 + 一帧点云包含固定数目(比如N)的MSOP Packet。雷达对MSOP Packet从 1 到 N 编号,并一直循环。 ## 2 rs_driver的组件 @@ -40,11 +39,11 @@ rs_driver主要由三部分组成: Input、Decoder、LidarDriverImpl。 ![components](./img/components.png) -+ Input部分负责从Socket、或PCAP文件等源,获取MSOP/DIFOP Packet。Input类一般有自己的接收线程。 -+ Decoder部分负责解析MSOP/DIFOP Packet,得到点云。Decoder没有自己的线程,它运行在LiarDriverImpl的Packet处理线程中。 -+ LidarDrvierImpl将Input和Decoder组合到一起。它从Input得到Packet,根据Packet的类型将它派发到Decoder。得到点云后,通过用户的回调函数传递给用户。 - + LidarDriverImpl提供Packet队列。Input收到MSOP/DIFOP Packet后,调用LidarDriverImpl的回调函数。回调函数将它保存到Packet Queue。 - + LidarDriverImpl提供Packet处理线程。在Packet处理线程中,将MSOP Packet和DIFOP Packet分别派发给Decoder相应的处理函数。 ++ Input部分负责从Socket/PCAP文件等数据源,获取MSOP/DIFOP Packet。Input的类一般有自己的接收线程`recv_thread_`。 ++ Decoder部分负责解析MSOP/DIFOP Packet,得到点云。Decoder部分没有自己的线程,它运行在LiarDriverImpl的Packet处理线程`handle_thread_`中。 ++ LidarDrvierImpl部分将Input和Decoder组合到一起。它从Input得到Packet,根据Packet的类型将它派发到Decoder。得到点云后,通过用户的回调函数传递给用户。 + + LidarDriverImpl提供Packet队列。Input收到MSOP/DIFOP Packet后,调用LidarDriverImpl的回调函数。回调函数将它保存到Packet队列。 + + LidarDriverImpl提供Packet处理线程`handle_thread_`。在这个线程中,将MSOP Packet和DIFOP Packet分别派发给Decoder相应的处理函数。 + Decoder解析完一帧点云时,通知LidarDriverImpl。后者再将点云传递给用户。 ## 3 Packet接收 @@ -71,7 +70,7 @@ Input定义接收MSOP/DIFOP Packet的接口。 ### 3.2 InputSock -InputSock类从UDP Socket接收MSOP/DIFOP Packet。雷达将MSOP/DIFOP Packet发送到这个Socket上。 +InputSock类从UDP Socket接收MSOP/DIFOP Packet。雷达将MSOP/DIFOP Packet发送到这个Socket。 ![InputSock](./img/class_input_sock.png) @@ -114,11 +113,12 @@ start() 开始接收MSOP/DIFOP Packet。 #### 3.2.4 InputSock::recvPacket() recvPacket() 接收MSOP/DIFOP Packet。 -在while循环中, +在while()循环中, + + 调用FD_ZERO()初始化本地变量`rfds`,调用FD_SET()将`fds_[2]`中的两个fd加入`rfds`。当然,如果MSOP/DIFOP Packet共用一个socket, 无效的`fds_[1]`就不必加入了。 -+ 调用select()在`rfds`上等待Packet, 超时值设置为`0.5`秒。 ++ 调用select()在`rfds`上等待Packet, 超时值设置为`1`秒。 如果select()的返回值提示`rfds`上有信号,调用FD_ISSET()检查是`fds_[]`中的哪一个fd可读。对这个fd, -+ 调用回调函数`cb_get_pkt_`, 得到大小为`MAX_PKT_LEN`的缓存。`MAX_PKT_LEN` = `1500`,对当前Robosense雷达来说,够大了。 ++ 调用回调函数`cb_get_pkt_`, 得到大小为`MAX_PKT_LEN`的缓存。`MAX_PKT_LEN` = `1500`,对当前RoboSense雷达来说,够大了。 + 调用recvfrom()接收Packet,保存到这个缓存中 + 调用回调函数`cb_put_pkt_`,将Packet派发给InputSock的使用者。 + 注意在派发之前,调用Buffer::setData()设置了MSOP Packet在Buffer的中偏移量及长度,以便剥除`USER_LAYER`和`TAIL_LAYER`(如果有的话)。 @@ -150,7 +150,7 @@ InputPcap解析PCAP文件得到MSOP/DIFOP Packet。使用第三方工具,如Wi ![layers of packet](./img/packet_layers_full.png) -+ PCAP库可能包括非UDP库的Packet。为了校验是否MSOP/DIFOP Packet,需要使用libpcap库的过滤器,也就是`bpf_program`,它由pcap_compile()生成。成员`msop_filter_`和`difop_filter_`分别是MSOP Packet和DIFOP Packet的过滤器。 ++ PCAP文件中可能不止包括MSOP/DIFOP Packet,所以需要使用libpcap库的过滤功能。libpcap过滤器`bpf_program`,由库函数pcap_compile()生成。成员`msop_filter_`和`difop_filter_`分别是MSOP Packet和DIFOP Packet的过滤器。 + MSOP/DIFOP Packet都是UDP Packet,所以给pcap_compile()指定选项`udp`。 + 如果是基于VLAN的,则需要指定选项`vlan` + 如果在一个PCAP文件中包含多个雷达的Packet,则还需要指定选项 `udp dst port`,以便只提取其中一个雷达的Packet。 @@ -194,17 +194,17 @@ recvPacket()解析PCAP文件。 如果是DIFOP Packet,处理与MSOP Packet一样。 -+ 调用this_thread::sleep_for()让解析线程睡眠一小会。这是为了模拟雷达发送MSOP Packet的间隔。这个间隔时间来自`Decoder`,每个雷达有自己的值。在`Decoder`部分,会说明如何计算这个值。 ++ 调用this_thread::sleep_for()让解析线程睡眠一小会。这是为了模拟雷达发送MSOP Packet的间隔。这个间隔时间来自每个雷达的`Decoder`类,每个雷达有自己的值。在Decoder部分,会说明如何计算这个值。 如果pcap_next_ex()不能读出Packet,一般意味着到了文件结尾,则: + 调用pcap_close()关闭pcap文件指针 `pcap_` 。 用户配置RSInputParam的设置决定是否重新进行下一轮的解析。这个选项是`RSInputParam::pcap_repeat`。 -+ 如果这个选项为真,调用pcap_open_offline()重新打开PCAP文件。这时成员变量`pcap_`回到文件的开始位置。下一次调用pcap_next_ex()又可以重新得到PCAP文件的第一个Packet了。 ++ 如果这个选项为真,调用pcap_open_offline()重新打开PCAP文件。这时成员变量`pcap_`回到文件的开始位置。下一次调用pcap_next_ex(),又可以重新得到PCAP文件的第一个Packet了。 ### 3.4 InputRaw -InputRaw是为了重播MSOP/DIFOP Packet而设计的Input类型。将在Packet Record/Replay章节中说明。 +InputRaw是为了重播MSOP/DIFOP Packet而设计的Input类型。将在后面的Packet Record/Replay章节中说明。 ### 3.5 InputFactory @@ -227,7 +227,7 @@ enum InputType createInput() 根据指定的类型,创建Input实例。 + 创建InputPcap时,需指定`sec_to_delay`。这是InputPcap回放MSOP Packet的间隔。 -+ 创建InputRaw时,需指定`cb_feed_pkt`。这个将在Packet Record/Replay章节中说明。 ++ 创建InputRaw时,需指定`cb_feed_pkt`。这个将在后面的Packet Record/Replay章节中说明。 ## 4 Packet解析 @@ -244,7 +244,7 @@ createInput() 根据指定的类型,创建Input实例。 其中前五个与点云直接相关。 -MSOP格式中的点是极坐标系的坐标,包括极径和极角。距离就是这里的极径。从距离和角度可计算直角垂直坐标系的坐标,也就是点云使用的坐标。 +MSOP格式中的点是极坐标系的坐标,包括极径和极角。距离就是这里的极径。从距离和角度可计算直角坐标系的坐标,也就是点云使用的坐标。 #### 4.1.1 Distance @@ -385,17 +385,17 @@ enum RSEchoMode 不同雷达有不同的回波模式`return_mode`。每个Decoder实现自己的解析函数getEchoMode(),得到rs_driver的回波模式。 -回波模式会影响MSOP Packet的结构,还会影响点云的分帧。 +回波模式会影响MSOP Packet中数据的布局,还可能影响点云的分帧。 ### 4.2 ChanAngles #### 4.2.1 垂直角/水平角的修正 -如前面MSOP格式的章节所说,理论上从distance、垂直角、水平角就可以计算点的直角坐标系的坐标。 +如前面MSOP格式的章节所说,理论上,从distance、垂直角、水平角就可以计算点的直角坐标系的坐标。 -但在实践中,装配雷达总是无可避免地有细微的误差,导致雷达的角度不精确,需要进行修正。雷达装配后的参数标定过程,会找出相关的修正值,写入雷达的寄存器。标定后,使用修正值调整点,就可以使其精度达到要求。 +但在生产实践中,装配雷达总是无可避免地有细微的误差,导致雷达的角度不精确,需要进行修正。雷达装配后的参数标定过程,会找出相关的修正值,写入雷达的寄存器。标定后,使用修正值调整点,就可以使其精度达到要求。 -MEMS雷达的角度修正,在雷达内部完成,所以驱动不需要做什么;机械式雷达的角度修正,由驱动在电脑主机端完成。 +MEMS雷达的角度修正,在雷达内部完成,所以rs_driver不需要做什么;机械式雷达的角度修正,由rs_driver在电脑主机端完成。 这里说明机械式雷达的垂直角/水平角修正。 @@ -414,12 +414,12 @@ MEMS雷达的角度修正,在雷达内部完成,所以驱动不需要做什 ``` 89.4375, 81.0625, 78.25, 72.625, 67, 61.375, 55.75, 50.125, - 86.8125, 83.875, 75.4375, 69.8125, 64.1875, 58.5, 52.9375, 47.3125, + 86.8125, 83.875, 75.4375, 69.8125, 64.1875, 58.5, 52.9375, 47.3125, 44.5625, 38.875, 33.25, 27.625, 22, 16.375, 10.75, 5.125, 41.6875, 36.1875, 30.4375, 24.8125, 19.0625, 13.5625, 7.9375, 2.3125 ``` -同时,水平角修正值的例子如下。(这里有32个值,对应RSBP的32个通道) +类似的,水平角修正值的例子如下。(这里也有32个值,对应RSBP的32个通道) ``` 0.0625, 0.0625, -0.25, 0.625, 0, -0.375, 0.75, -0.125, @@ -525,7 +525,7 @@ typedef struct 有些场景下,雷达可能还没有写入有效的修正值,或者是因为还没有标定,或者是由于雷达故障。这时可以从外部文件读入角度修正值。 文件格式如下。 -+ 每行是对应一个通道的修正值。行中第`1`个值是垂直角,第`2`个值是水平角修正值。 ++ 每行是对应一个通道的修正值。其中第`1`个值是垂直角,第`2`个值是水平角修正值。 + 每行对应一个通道。所以对于RSBP来说,应该有`32`行。这个例子略去了部分行。 ``` @@ -558,7 +558,7 @@ vertAdjust()根据内部通道编号,得到修正后的垂直角。 点云中的`ring`值是从用户角度看的通道编号,它来自于ChanAngles的成员变量`user_chans_`。 -回到RSBP的例子,如下是它的垂直角,它们按照雷达内部通道编号排列,而不是降序或升序排列。换句话说,雷达内部通道不是按照垂直角的升序或降序编号的。 +回到RSBP的例子。如下是它的垂直角,它们按照雷达内部通道编号排列,而不是降序或升序排列。换句话说,雷达内部通道不是按照垂直角的升序/降序编号的。 ``` 89.5, 81.0625, 78.25, 72.625, 67, 61.375, 55.75, 50.125, @@ -566,7 +566,7 @@ vertAdjust()根据内部通道编号,得到修正后的垂直角。 44.5, 38.875, 33.25, 27.625, 22, 16.375, 10.75, 5.125, 41.6875, 36.0625, 30.4375, 24.8125, 19.1875, 13.5625, 7.9375, 2.3125 ``` -但用户希望看到通道编号按照垂直角按升序或降序排列。 +但用户希望看到通道编号按照垂直角按升序/降序排列。 ChanAngles的成员变量`user_chans`保存的是按升序排列的编号,也就是角度小的通道在前。 @@ -634,10 +634,12 @@ cos()查表返回角度的cos值。 ![msop single return](./img/msop_single_return.png) -雷达的每轮激光发射时序包括充能、发射等步骤。每轮发射内,相邻发射的时间戳不均匀,但每轮发射的持续时间(也是相邻两轮发射的时间差)相等。 +雷达的每轮激光发射时序包括充能、发射等步骤。虽然每轮发射的持续时间(也是相邻两轮发射的时间差)相同,但在每轮发射内,每次发射的时间不是均匀分布。 + 以RSBP为例, + + 一轮发射的时长为`55.52`纳秒,这是Block之间的时间差。 -+ 一轮发射中,`32`次发射的时间戳如下(相对于Block的相对时间,单位纳秒)。这是Block内的每个Channel相对于Block的相对时间。 ++ 一轮发射内,`32`次发射的时间戳如下(相对于Block的相对时间,单位纳秒)。这是每个Channel对所属Block的相对时间。 ``` 0.00, 2.56, 5.12, 7.68, 10.24, 12.80, 15.36, 17.92, @@ -650,7 +652,7 @@ cos()查表返回角度的cos值。 MSOP格式中,Packet头部包含一个时间戳。 -如对于RSBP雷达,Packet的时间戳如下。 +如RSBP雷达,Packet的时间戳如下。 ``` RSTimestampYMD timestamp; @@ -660,19 +662,19 @@ RSTimestampYMD timestamp; ``` Block的时间戳 = Packet的时间戳 + Block的持续时间 * Block数 -Channel的时间戳 = 所在Block的时间戳 + Channel对Block的相对时间戳 +Channel的时间戳 = 所在Block的时间戳 + Channel对Block的相对时间 ``` #### 4.4.3 Channel的角度 在MSOP格式中,Block的成员中包括水平角`azimuth`。 -雷达的旋转当然不是匀速的,但放到一个Block这么短时间内来看,认为旋转是匀速的,还是合理的。 +雷达的旋转当然不是匀速的,但放到一个Block这么短的时间内看,认为旋转是匀速的,还是合理的。 所以,通过Channel占Block的时间比例,可以估计Channel对Block的相对水平角。 ``` -Channel的水平角 = Block的水平角 + 当前Block与下一个Block的水平角差 * Channel对Block的相对时间戳 / Block的持续时间 +Channel的水平角 = Block的水平角 + 当前Block与下一个Block的水平角差 * Channel对Block的相对时间 / Block的持续时间 ``` #### 4.4.4 双回波模式的影响 @@ -687,7 +689,7 @@ Channel的水平角 = Block的水平角 + 当前Block与下一个Block的水平 #### 4.4.5 BlockIterator定义 -引入BlockIterator的目的是定义一个接口,来计算: +引入BlockIterator的目的,是定义一个接口来计算: + Block的时间戳。这个时间戳是相对于Packet的时间戳。 + Block与下一次Block的水平角差。也就是当前Block内雷达旋转的水平角。 @@ -719,7 +721,7 @@ SingleReturnBlockIterator实现单回波模式下的BlockIterator接口。 ``` Block水平角差 = 下一个Block的水平角 - 当前Block的水平角 ``` - + 最后一个Block的水平角差,认为等于`BLOCK_AZ_DURATION`,这时雷达理论上每个Block的水平角差。 + + 最后一个Block的水平角差,认为等于`BLOCK_AZ_DURATION`,这是雷达理论上每个Block的水平角差。 + 相邻Block可能跨`角度0`,所以它们的水平角差可能小于`0`,这时需要将它修正到[`0`, `36000`)内。 @@ -747,7 +749,7 @@ DualReturnBlockIterator实现双回波模式下的BlockIterator接口。 双回波模式下,Ruby128是个特殊情况。 -Ruby128的每个block有`128`个Channel,每个block占的空间太大,以至于每个packet只能放下`3`个Block。这样一次扫描的两个Block可能在不同的Packet中。相邻的两个packet格式如下图。 +Ruby128的每个Block有`128`个Channel,每个Block占的空间太大,以至于每个packet只能放下`3`个Block。这样一次扫描的两个Block可能在不同的Packet中。相邻的两个packet格式如下图。 ![msop ruby128](./img/msop_ruby128.png) @@ -766,7 +768,7 @@ Block水平角差 = 第三个Block的水平角 - 第一个Block的水平角 #### 4.4.9 RS16的Packet格式 -为了充分利用MSOP Packet的空间,RS16的Packet格式与其他机械式雷达不同。 +为了充分利用MSOP Packet的空间,16线雷达(如RS16)的Packet格式与其他机械式雷达不同。 在单回波模式下,一组`16通道数据`包含一个回波,将相邻两组的回波数据放在同一Block中。如下图所示。 @@ -777,7 +779,7 @@ Block水平角差 = 第三个Block的水平角 - 第一个Block的水平角 ![](./img/rs16_msop_dual_return.png) 这样的结果是, -+ Packet中的相邻BLOCK之间的角度差不再一定是`BLOCK_AZ_DURATION`,时间差也不再一定是`BLOCK_DURATION`。 ++ MSOP Packet中的相邻Block之间的角度差不再一定是`BLOCK_AZ_DURATION`,时间差也不再一定是`BLOCK_DURATION`。 + 对于RS16,RSDecoderConstParam.CHANNELS_PER_BLOCK = 32。遍历所有通道时,这个值需要做一次映射,才能得到实际的通道值。 ``` @@ -793,7 +795,7 @@ RS16SingleReturnBlockIterator和RS16DualReturnBlockIterator,分别处理RS16 ##### 4.4.9.1 Rs16SingleReturnBlockIterator() -在构造函数中,遍历Packet中的block,并计算az_diffs[]和tss[]。 +在构造函数中,遍历Packet中的Block,并计算az_diffs[]和tss[]。 与SingleReturnBlockIterator()中不同的地方是:单回波模式下,一个Block中包括相邻的两个通道数据。 + 缺省的角度差是`BLOCK_AZ_DURATION` * 2 @@ -807,9 +809,10 @@ calcChannel()计算单回波模式下,32个Channel的角度占比,和时间 ##### 4.4.10.1 Rs16DualReturnBlockIterator() -双回波模式下,Block两两成对。 +在构造函数中,遍历Packet中的Block,并计算az_diffs[]和tss[]。 + +与Rs16DualReturnBlockIterator不同的地方是:双回波模式下,一个Block中包括两个回波的数据。 -在构造函数中,遍历Packet中的Block,并计算az_diffs[]和tss[]。与Rs16DualReturnBlockIterator不同的地方是:双回波模式下,一个Block中包括两个回波的数据。 + 缺省的角度差是`BLOCK_AZ_DURATION` + 缺省的时间差是`BLOCK_DURATION` @@ -821,7 +824,7 @@ calcChannel()计算双回波模式下,32个Channel的角度占比,和时间戳 机械式雷达的扫描角度是[0,360),这也是雷达输出点的角度范围。 -也可以限制雷达的输出角度,如下图。 +也可以对雷达进行设置,限制它的输出角度,如下图。 + FOV的范围是[start_angle,end_angle)。 + 与FOV互补的角度范围FOV_blind是FOV的盲区,雷达不会输出这个范围的点。 @@ -855,7 +858,8 @@ void DecoderMech::decodeDifopCommon(const T_Difop& pkt); #### 4.5.2 FOV对BlockIterator的影响 在BlockIterator的各种实现中,需要考虑Packet的相邻两个Block跨过FOV盲区的情况。 -如果跨过盲区,则 +如果跨过盲区,则: + + 第一个Block的水平角度差调整为`BLOCK_AZ_DURATION`。这时理论上每个Block的水平角差。 + 两个Block的时间差调整为`FOV_BLIND_DURATION`。这个值是盲区时间差,也就是前面说的`fov_blind_ts_diff_`。 @@ -873,7 +877,7 @@ void DecoderMech::decodeDifopCommon(const T_Difop& pkt); ![split angle](./img/split_angle.png) + 按理论上每圈的Block数分帧。这样每帧包含的Block数和点数都是固定的。 - + Robosense雷达支持两种转速:`600`圈/分钟和`1200`圈/分钟。以`600`圈/分钟距离,相当于每圈`0.1`秒,而Block的持续时间是固定的,由此计算理论上每圈的block数(实际上是假设雷达转速均匀) + + Robosense雷达支持两种转速:`600`圈/分钟和`1200`圈/分钟。以`600`圈/分钟距离,相当于每圈`0.1`秒,而Block的持续时间是固定的,由此计算理论上每圈的Block数(实际上是假设雷达转速均匀) ``` 每圈Block数 = 每圈秒数 / Block持续时间 @@ -885,7 +889,7 @@ void DecoderMech::decodeDifopCommon(const T_Difop& pkt); #### 4.6.2 SplitStrategy SplitStrategy定义机械式雷达的分帧模式接口。 -+ 使用者遍历Packet中的Block,用block的水平角调用SplitStrategy::newBlock()。应该分帧时,newBlock()返回`true`,否则返回`false`。 ++ 使用者遍历Packet中的Block,以Block的水平角为参数,调用SplitStrategy::newBlock()。应该分帧时,newBlock()返回`true`,否则返回`false`。 ![split strategy](./img/classes_split_strategy.png) @@ -903,7 +907,7 @@ SplitStrategyByAngle按Block角度分帧。 #### 4.6.4 SplitStrategyByNum -SplitStrategyByNum实现按block数分帧。 +SplitStrategyByNum实现按Block数分帧。 + 成员`max_blks_`是每帧的Block数。 + 成员`blks_`是当前已累积的Block数。 @@ -914,7 +918,7 @@ newBlock()简单地累加Block数到成员`blks_`,当`blk_`达到`max_blks_` #### 4.6.5 MEMS雷达的分帧模式 MEMS雷达的分帧是在雷达内部确定的。 -+ 一帧的Packet数是固定的。假设这个数为`N`, 则雷达给Packet编号,从`1`开始,依次编号到`N`。 ++ 一帧的MSOP Packet数是固定的。假设这个数为`N`, 则雷达给Packet编号,从`1`开始,依次编号到`N`。 + 对于RSM1,单回波模式下,Packet数是`630`;在双回波模式下,输出的点数要翻倍,相应的,Packet数也要翻倍,Packet数是`1260`。 #### 4.6.6 SplitStrategyByPktSeq @@ -922,13 +926,13 @@ MEMS雷达的分帧是在雷达内部确定的。 SplitStrategyBySeq按Packet编号分帧。 + 注意SplitStrategyBySeq的接口与SplitStrategy不同,不是后者的派生类。 + 成员变量`prev_seq_`是前一个Packet的编号。 -+ 成员变量`safe_seq_min_`和`safe_seq_max`,是基于`prev_seq_`的一个安全区间。稍后说明它的用处。 ++ 成员变量`safe_seq_min_`和`safe_seq_max`,是基于`prev_seq_`的一个安全区间。 ![split strategy by seq](./img/classes_split_strategy_by_seq.png) ##### 4.6.6.1 SplitStrategyByPktSeq::newPacket() -使用者用Packet的编号值,调用newPacket()。如果分帧,返回`true`。 +使用者用MSOP Packet的编号值,调用newPacket()。如果分帧,返回`true`。 MSOP使用UDP协议,理论上Packet可能丢包、乱序。 @@ -947,7 +951,7 @@ safe_seq_max_ = prev_seq_ + RANGE ![safe range](./img/safe_range.png) -+ 如果Packet在范围(`safe_seq_min_`, `safe_seq_max_`)内,都不算异常,丢包、乱序都不触发分帧。这样大多数情况,之前的问题可以避免。 ++ 如果Packet在范围(`safe_seq_min_`, `safe_seq_max_`)内,都不算异常,丢包、乱序都不触发分帧。这样在大多数情况下,之前的问题可以避免。 ### 4.7 点云的有效性校验 @@ -982,9 +986,10 @@ Decoder解析雷达MSOP/DIFOP Packet,得到点云。 + 它是针对所有雷达的接口类,包括机械式雷达和MEMS雷达。 DecoderMech派生于Decoder,给机械式雷达完成一些通用的功能,如解析DIFOP Packet。 + 每个机械式雷达分别派生自DecoderMech的类,如DecoderRS16、DecoderRS32、DecoderBP、DecoderRSHELIOS、DecoderRS80、DecoderRS128等。 -MEMS雷达的类直接派生自Decoder。 +MEMS雷达的类,如DecoderRSM1,直接派生自Decoder。 DecoderFactory根据指定的雷达类型,生成Decoder实例。 @@ -995,7 +1000,7 @@ DecoderFactory根据指定的雷达类型,生成Decoder实例。 如下图是Decoder的详细定义。 + 成员`const_param_`是雷达的参数配置。 + 成员`param_`是用户的参数配置。 -+ 成员`trigon_`是Trigon类的实例,提供快速的sin()/cos()计算。定义如下的宏,可以清晰、方便调用它。 ++ 成员`trigon_`是Trigon类的实例,提供快速的sin/cos计算。定义如下的宏,可以清晰、方便调用它。 ``` #define SIN(angle) this->trigon_.sin(angle) @@ -1064,7 +1069,7 @@ processDifopPkt()处理DIFOP Packet。 processMsopPkt()处理MSOP Packet。 + 检查当前配置信息是否已经就绪(`angles_ready_`)。 - + 当`angles_readys` = `false`时,驱动还没有获得垂直角信息,这时得到的点云是扁平的。所以用户一般希望等待`angles_ready` = `true` 才输出点云。 + + 对于机械式雷达,当`angles_readys` = `false`时,驱动还没有获得垂直角信息,这时得到的点云是扁平的。所以用户一般希望等待`angles_ready` = `true` 才输出点云。 + 通过用户配置参数`RSDecoderParam::wait_for_difop`,可以设置是否等待配置信息就绪。 + 校验DIFOP Packet的长度是否匹配。 + 校验DIFOP Packet的标志字节是否匹配。 @@ -1091,14 +1096,14 @@ DecoderMech处理机械式雷达的共同特性,如转速,分帧角度、光 + 成员`split_blks_per_frame_`是按Block数分帧时,每帧的Block数。包括按理论上每圈Block数分帧,和按用户指定的Block数分帧。 + 成员`block_azi_diff_`是理论上相邻block之间的角度差。 + 成员`fov_blind_ts_diff_`是FOV盲区的时间差 -+ 成员`lidar_alpha0_`和`lidar_Rxy_`是雷达光心相对于物理中心的位置参数。MSOP格式中的点的坐标是相对于光心的,需要借助这两个值,将它转换到相对于物理中心。 ++ 成员`lidar_alpha0_`和`lidar_Rxy_`是雷达光学中心相对于物理中心的位置参数。MSOP格式中的点的坐标是相对于光学中心的,需要借助这两个值,将它转换到相对于物理中心。 ![decoder mech](./img/class_decoder_mech.png) ##### 4.8.2.1 RSDecoderMechConstParam RSDecoderMechConstParam基于RSDecoderConstParam,增加机械式雷达特有的参数。 -+ `RX`、`RY`、`RZ`是雷达光心相对于物理中心的坐标。`lidar_alpha0_`和`lidar_Rxy_`由它们计算而来。 ++ `RX`、`RY`、`RZ`是雷达光学中心相对于物理中心的坐标。`lidar_alpha0_`和`lidar_Rxy_`由它们计算而来。 + `BLOCK_DURATION`是Block的持续时间。 + `CHAN_TSS[]`是Block中Channel对Block的相对时间。 + `CHAN_AZIS[]`是Block中Channel占Block的时间比例,也是水平角比例。 @@ -1119,8 +1124,8 @@ struct RSDecoderMechConstParam float CHAN_AZIS[128]; }; ``` -+ Decoder初始化时,从每轮激光发射中的发射时间列表,计算`CHAN_TSS[]`、`CHAN_AZIS[]`。这可以简化每个Channel的时间戳和角度的计算。 -前面的"Channel的时间戳"章节,已经列出过这个发射时间列表。如下。 ++ Decoder初始化时,从每轮激光发射中的每次发射时间表,计算`CHAN_TSS[]`、`CHAN_AZIS[]`。这可以简化每个Channel的时间戳和角度的计算。 +前面的"Channel的时间戳"章节,已经列出过RSBP的发射时间表,如下。 ``` 0.00, 2.56, 5.12, 7.68, 10.24, 12.80, 15.36, 17.92, @@ -1144,7 +1149,7 @@ decodeDifopCommon()解析DIFOP Packet。 每帧Block数 = (1/rps) / Block的持续时间 ``` -+ 计算相邻block之间的角度差,也就是`block_azi_diff_`。 ++ 计算相邻Block之间的角度差,也就是`block_azi_diff_`。 ``` Block间的角度差 = 360 / 每帧Block数 @@ -1244,7 +1249,7 @@ decodeMsopPkt()使用不同的模板参数调用internDecodeMsopPkt()。 #### 4.8.4 DecoderRS16 -RS16的处理与别的机械式雷达不同。请参考前面的“RS16的Packet格式”等章节。 +RS16的处理与其他机械式雷达有差异,请先参考前面的“RS16的Packet格式”等章节。 ##### 4.8.4.1 DecoderRS16::internDecodeMsopPkt() @@ -1365,7 +1370,7 @@ typedef struct RSDriverParam 组合Input, + 成员`free_pkt_queue_`、`pkt_queue_`分别保存空闲的Packet, 待处理的MSOP/DIFOP Packet。 + 这2个队列是SyncQueue类的实例。SyncQueue提供多线程访问的互斥保护。 -+ 函数packetGet()和packetPut()用来向input_ptr_注册。`input_ptr_`调用前者得到空闲的Buffer,和调用后者派发填充好Packet的Buffer。 ++ 函数packetGet()和packetPut()用来向input_ptr_注册。`input_ptr_`调用前者得到空闲的Buffer,调用后者派发填充好Packet的Buffer。 组合Decoder, + 成员`cb_get_cloud_`和`cb_put_cloud_`是回调函数,由驱动的使用者提供。它们的作用类似于Input类的`cb_get_pkt_`和`cb_put_pkt_`。驱动调用`cb_get_cloud_`得到空闲的点云,调用`cb_put_cloud_`派发填充好的点云。 @@ -1440,7 +1445,7 @@ getTemperature()调用Decoder::getTemperature(), 得到雷达温度。 ## 5 Packet的录制与回放 -使用者调试自己的程序时,点云的录制与回放是有用的。同时,点云占的空间较大,而MSOP/DIFOP Packet占的较小,所以Packet的录制与回放是更好的选择。 +使用者调试自己的程序时,点云的录制与回放是有用的,只是点云占的空间比较大。MSOP/DIFOP Packet占的空间较小,所以Packet的录制与回放是更好的选择。 与MSOP/DIFP Packet的录制与回放相关的逻辑,散布在rs_driver的各个模块中,所以这里单独分一个章节说明。 @@ -1474,11 +1479,9 @@ getTemperature()调用Decoder::getTemperature(), 得到雷达温度。 ![InputRaw](./img/class_input_raw.png) InputRaw回放MOSP/DIFOP Packet。 -+ 使用者从某种源(比如文件)中解析MSOP/DIFOP Packet,调用InputRaw的成员函数feedPacket(),将Packet喂给它。 ++ 使用者从某种数据源(比如rosbag文件)中解析MSOP/DIFOP Packet,调用InputRaw的成员函数feedPacket(),将Packet喂给它。 + 在feedPacket()中,InputRaw简单地调用成员`cb_put_pkt_`,将Packet推送给调用者。这样,它的后端处理就与InputSock/InputPcap一样了。 -所以除了输出点云之外,驱动还可以直接输出Packet,以后再重新导入进行播放。 - #### 5.2.2 LidarDriverImpl + InputRaw::feedBack()在InputFactory::createInput()中被打包,最后保存在LidarDriverImpl类的成员`cb_feed_pkt_`中。 @@ -1489,14 +1492,14 @@ InputRaw回放MOSP/DIFOP Packet。 点云的时间戳来自于MSOP Packet的时间戳。MSOP Packet的时间戳可以有两种产生方式。 + 用户配置参数`RSDecoderParam::use_lidar_clock`决定使用哪种方式。 + `use_lidar_clock` = `true`时, 使用雷达产生的时间戳,这个时间戳在Packet中保存。这种情况下,一般已经使用时间同步协议对雷达做时间同步。 -+ `use_lidar_clock` = `false`时, 忽略Packet中的时间戳,在电脑主机侧由驱动重新产生一个。 ++ `use_lidar_clock` = `false`时, 忽略Packet中的时间戳,在电脑主机侧由rs_driver重新产生一个。 #### 5.3.1 使用雷达时间戳 录制时,设置`use_lidar_clock` = `true` + 解析MSOP Packet的时间戳。这个时间戳是雷达产生的。 + 输出的点云使用这个时间戳 -+ 如果输出Packet,也是用这个时间戳 ++ 如果输出Packet,也是这个时间戳 回放时,设置`use_lidar_clock` = `true` + MSOP Packet内保存的仍然是雷达产生的时间戳。 @@ -1505,13 +1508,13 @@ InputRaw回放MOSP/DIFOP Packet。 #### 5.3.2 使用主机时间戳 录制时,设置`use_lidar_clock` = `false` -+ rs_driver在电脑主机侧重新产生时间戳。这个时间戳记录到用户的Packet文件中;如果这时有点云输出,使用rs_driver产生的时间戳 - + 在DecoderRSBP::internDecodeMsopPacket()中,rs_driver调用getTimeHost()产生时间戳,然后调用createTimeYMD(),用这个新时间戳替换Packet中老的。 ++ rs_driver在电脑主机侧重新产生时间戳。这个时间戳覆盖Packet文件中原有的时间戳;如果这时有点云输出,使用rs_driver产生的时间戳 + + 在DecoderRSBP::internDecodeMsopPacket()中,rs_driver调用getTimeHost()产生时间戳,然后调用createTimeYMD(),用这个新时间戳替换Packet中原有的时间戳。 + 这时输出的Packet的时间戳是rs_driver产生的时间戳 回放时,设置`use_lidar_clock` = `true` + 解析MSOP Packet的时间戳。这个时间戳是录制时rs_driver在电脑主机侧产生的。 -+ 输出的点云使用这个时间戳 ++ 输出的点云使用这个时间戳。 From 1667a1baa53231bc05712bf965c1f87cd3d1ac1b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 1 Jul 2022 11:58:46 +0800 Subject: [PATCH 302/379] feat: tag v1.5.4 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c50fe84e..390ca303 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.5.3) +project(rs_driver VERSION 1.5.4) #======================== # Project setup From 5ab604015a8be7dc0595335304822cad88183c6e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 1 Jul 2022 12:00:52 +0800 Subject: [PATCH 303/379] feat: update doc --- CHANGELOG.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 507bc253..cfcfdc06 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -2,6 +2,10 @@ ## Unreleased +### Added + +## v1.5.3 2022-07-01 + ### Added - Support Ruby_3.0_48 - Add option to stamp point cloud with first point From 087a3bd8405e59937dcfa6bf0fcdc7ef967f5b65 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 1 Jul 2022 15:09:02 +0800 Subject: [PATCH 304/379] feat: update doc --- CHANGELOG.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index cfcfdc06..3e135ffb 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -4,7 +4,7 @@ ### Added -## v1.5.3 2022-07-01 +## v1.5.4 2022-07-01 ### Added - Support Ruby_3.0_48 From 4b3c38836e41165400d52c8ab0fcdd31dd981e1e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 1 Jul 2022 17:53:44 +0800 Subject: [PATCH 305/379] fix: fix pcap_rate --- src/rs_driver/driver/input/input_pcap.hpp | 2 +- src/rs_driver/driver/input/input_pcap_jumbo.hpp | 2 +- src/rs_driver/macro/version.hpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/rs_driver/driver/input/input_pcap.hpp b/src/rs_driver/driver/input/input_pcap.hpp index 34016b33..daff7498 100644 --- a/src/rs_driver/driver/input/input_pcap.hpp +++ b/src/rs_driver/driver/input/input_pcap.hpp @@ -51,7 +51,7 @@ class InputPcap : public Input public: InputPcap(const RSInputParam& input_param, double sec_to_delay) : Input(input_param), pcap_(NULL), pcap_offset_(ETH_HDR_LEN), pcap_tail_(0), difop_filter_valid_(false), - msec_to_delay_((uint64_t)(sec_to_delay*1000000)) + msec_to_delay_((uint64_t)(sec_to_delay / input_param.pcap_rate * 1000000)) { if (input_param.use_vlan) { diff --git a/src/rs_driver/driver/input/input_pcap_jumbo.hpp b/src/rs_driver/driver/input/input_pcap_jumbo.hpp index d4cc8f01..ab62cb59 100644 --- a/src/rs_driver/driver/input/input_pcap_jumbo.hpp +++ b/src/rs_driver/driver/input/input_pcap_jumbo.hpp @@ -52,7 +52,7 @@ class InputPcapJumbo : public Input public: InputPcapJumbo(const RSInputParam& input_param, double sec_to_delay) : Input(input_param), pcap_(NULL), pcap_offset_(ETH_HDR_LEN), pcap_tail_(0), difop_filter_valid_(false), - msec_to_delay_((uint64_t)(sec_to_delay*1000000)) + msec_to_delay_((uint64_t)(sec_to_delay / input_param.pcap_rate * 1000000)) { if (input_param.use_vlan) { diff --git a/src/rs_driver/macro/version.hpp b/src/rs_driver/macro/version.hpp index be467c02..d33caacb 100644 --- a/src/rs_driver/macro/version.hpp +++ b/src/rs_driver/macro/version.hpp @@ -1,3 +1,3 @@ #define RSLIDAR_VERSION_MAJOR 1 #define RSLIDAR_VERSION_MINOR 5 -#define RSLIDAR_VERSION_PATCH 3 +#define RSLIDAR_VERSION_PATCH 4 From a94ea0dfedeaaf748dec3325649cb53150094ed8 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 4 Jul 2022 10:33:27 +0800 Subject: [PATCH 306/379] feat: update project --- win/demo_online/demo_online.vcxproj | 5 +++-- win/demo_pcap/demo_pcap.vcxproj | 4 ++-- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/win/demo_online/demo_online.vcxproj b/win/demo_online/demo_online.vcxproj index b6e9fe62..ee0780b0 100644 --- a/win/demo_online/demo_online.vcxproj +++ b/win/demo_online/demo_online.vcxproj @@ -93,12 +93,13 @@ Disabled true true - ../../src + ../../src;../../../3th-party/libpcap/Include _MBCS;%(PreprocessorDefinitions);_CRT_SECURE_NO_WARNINGS Console - kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);Ws2_32.lib + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);Ws2_32.lib;wpcap.lib + ../../../3th-party/libpcap/Lib/x64 diff --git a/win/demo_pcap/demo_pcap.vcxproj b/win/demo_pcap/demo_pcap.vcxproj index e3c4a2da..a0febf5f 100644 --- a/win/demo_pcap/demo_pcap.vcxproj +++ b/win/demo_pcap/demo_pcap.vcxproj @@ -76,13 +76,13 @@ Disabled true true - ../../src;../../Include + ../../src;;../../../3th-party/libpcap/Include _MBCS;%(PreprocessorDefinitions);_CRT_SECURE_NO_WARNINGS;ENABLE_PCAP_PARSE Console kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);Ws2_32.lib;wpcap.lib - ../../Lib/x64 + ../../../3th-party/libpcap/Lib/x64 From 255831e3cee81640358b0dc7dfe4e14998d0483e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 5 Jul 2022 11:59:19 +0800 Subject: [PATCH 307/379] feat: adapt to vs2019 --- win/demo_online/demo_online.vcxproj | 18 ++++++++++++------ win/demo_pcap/demo_pcap.vcxproj | 18 ++++++++++++------ 2 files changed, 24 insertions(+), 12 deletions(-) diff --git a/win/demo_online/demo_online.vcxproj b/win/demo_online/demo_online.vcxproj index ee0780b0..1e17ae81 100644 --- a/win/demo_online/demo_online.vcxproj +++ b/win/demo_online/demo_online.vcxproj @@ -25,32 +25,32 @@ 15.0 {A30B3B76-84F3-4A17-B42B-6284FCC3138F} demoonline - 10.0.17763.0 + 10.0 Application true - v141 + v142 MultiByte Application false - v141 + v142 true MultiByte Application true - v141 + v142 MultiByte Application false - v141 + v142 true MultiByte @@ -72,7 +72,10 @@ - + + C:\Program Files\WpdPack_4_1_2\WpdPack\Include;$(IncludePath) + C:\Program Files\WpdPack_4_1_2\WpdPack\Lib\x64;$(LibraryPath) + Level3 @@ -125,11 +128,14 @@ true true true + ../../src + _CRT_SECURE_NO_WARNINGS;%(PreprocessorDefinitions) Console true true + wpcap.lib;ws2_32.lib;%(AdditionalDependencies) diff --git a/win/demo_pcap/demo_pcap.vcxproj b/win/demo_pcap/demo_pcap.vcxproj index a0febf5f..2a7052ec 100644 --- a/win/demo_pcap/demo_pcap.vcxproj +++ b/win/demo_pcap/demo_pcap.vcxproj @@ -22,32 +22,32 @@ 15.0 {E7971DE6-C89C-4572-A3A4-07BE68897D30} demopcap - 10.0.17763.0 + 10.0 Application true - v141 + v142 MultiByte Application false - v141 + v142 true MultiByte Application true - v141 + v142 MultiByte Application false - v141 + v142 true MultiByte @@ -69,7 +69,10 @@ - + + C:\Program Files\WpdPack_4_1_2\WpdPack\Lib\x64;$(LibraryPath) + C:\Program Files\WpdPack_4_1_2\WpdPack\Include;$(IncludePath) + Level3 @@ -119,11 +122,14 @@ true true true + ../../src + _CRT_SECURE_NO_WARNINGS;%(PreprocessorDefinitions) Console true true + wpcap.lib;ws2_32.lib;%(AdditionalDependencies) From eb2160814435a8cecaf56ddb30a2d84a7cb6536f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 5 Jul 2022 18:02:21 +0800 Subject: [PATCH 308/379] feat: compile on windows --- win/rs_driver.sln | 14 +- win/rs_driver_viewer/rs_driver_viewer.vcxproj | 151 ++++++++++++++++++ 2 files changed, 163 insertions(+), 2 deletions(-) create mode 100644 win/rs_driver_viewer/rs_driver_viewer.vcxproj diff --git a/win/rs_driver.sln b/win/rs_driver.sln index 33dd0633..c9d9963e 100644 --- a/win/rs_driver.sln +++ b/win/rs_driver.sln @@ -1,12 +1,14 @@  Microsoft Visual Studio Solution File, Format Version 12.00 -# Visual Studio 15 -VisualStudioVersion = 15.0.28307.1927 +# Visual Studio Version 16 +VisualStudioVersion = 16.0.32602.291 MinimumVisualStudioVersion = 10.0.40219.1 Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "demo_online", "demo_online\demo_online.vcxproj", "{A30B3B76-84F3-4A17-B42B-6284FCC3138F}" EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "demo_pcap", "demo_pcap\demo_pcap.vcxproj", "{E7971DE6-C89C-4572-A3A4-07BE68897D30}" EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "rs_driver_viewer", "rs_driver_viewer\rs_driver_viewer.vcxproj", "{F15B6ACB-D381-48D2-B6F1-E4817FADF216}" +EndProject Global GlobalSection(SolutionConfigurationPlatforms) = preSolution Debug|x64 = Debug|x64 @@ -31,6 +33,14 @@ Global {E7971DE6-C89C-4572-A3A4-07BE68897D30}.Release|x64.Build.0 = Release|x64 {E7971DE6-C89C-4572-A3A4-07BE68897D30}.Release|x86.ActiveCfg = Release|Win32 {E7971DE6-C89C-4572-A3A4-07BE68897D30}.Release|x86.Build.0 = Release|Win32 + {F15B6ACB-D381-48D2-B6F1-E4817FADF216}.Debug|x64.ActiveCfg = Debug|x64 + {F15B6ACB-D381-48D2-B6F1-E4817FADF216}.Debug|x64.Build.0 = Debug|x64 + {F15B6ACB-D381-48D2-B6F1-E4817FADF216}.Debug|x86.ActiveCfg = Debug|Win32 + {F15B6ACB-D381-48D2-B6F1-E4817FADF216}.Debug|x86.Build.0 = Debug|Win32 + {F15B6ACB-D381-48D2-B6F1-E4817FADF216}.Release|x64.ActiveCfg = Release|x64 + {F15B6ACB-D381-48D2-B6F1-E4817FADF216}.Release|x64.Build.0 = Release|x64 + {F15B6ACB-D381-48D2-B6F1-E4817FADF216}.Release|x86.ActiveCfg = Release|Win32 + {F15B6ACB-D381-48D2-B6F1-E4817FADF216}.Release|x86.Build.0 = Release|Win32 EndGlobalSection GlobalSection(SolutionProperties) = preSolution HideSolutionNode = FALSE diff --git a/win/rs_driver_viewer/rs_driver_viewer.vcxproj b/win/rs_driver_viewer/rs_driver_viewer.vcxproj new file mode 100644 index 00000000..f9d463b7 --- /dev/null +++ b/win/rs_driver_viewer/rs_driver_viewer.vcxproj @@ -0,0 +1,151 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + 16.0 + Win32Proj + {f15b6acb-d381-48d2-b6f1-e4817fadf216} + rsdriverviewer + 10.0 + + + + Application + true + v142 + Unicode + + + Application + false + v142 + true + Unicode + + + Application + true + v142 + Unicode + + + Application + false + v142 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + + + false + + + true + + + false + C:\Program Files\WpdPack_4_1_2\WpdPack\Include;C:\Program Files\PCL 1.11.1\include\pcl-1.11;C:\Program Files\PCL 1.11.1\3rdParty\Boost\include\boost-1_74;C:\Program Files\PCL 1.11.1\3rdParty\Eigen\eigen3;C:\Program Files\PCL 1.11.1\3rdParty\FLANN\include;C:\Program Files\PCL 1.11.1\3rdParty\Qhull\include;C:\Program Files\PCL 1.11.1\3rdParty\VTK\include\vtk-8.2;C:\Program Files\PCL 1.11.1\3rdParty\OpenNI2\Include;$(IncludePath) + C:\Program Files\WpdPack_4_1_2\WpdPack\Lib\x64;C:\Program Files\PCL 1.11.1\lib;C:\Program Files\PCL 1.11.1\3rdParty\Boost\lib;C:\Program Files\PCL 1.11.1\3rdParty\FLANN\lib;C:\Program Files\PCL 1.11.1\3rdParty\Qhull\lib;C:\Program Files\PCL 1.11.1\3rdParty\VTK\lib;C:\Program Files\PCL 1.11.1\3rdParty\OpenNI2\Lib;$(LibraryPath) + + + + Level3 + true + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + + + Console + true + + + + + Level3 + true + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + + + Console + true + true + true + + + + + Level3 + true + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + + + Console + true + + + + + Level3 + true + true + false + BOOST_USE_WINDOWS_H;NOMINMAX;_CRT_SECURE_NO_DEPRECATE;_CRT_SECURE_NO_WARNINGS;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + ../../src + + + Console + true + true + true + wpcap.lib;ws2_32.lib;vtkChartsCore-8.2.lib;vtkCommonColor-8.2.lib;vtkCommonComputationalGeometry-8.2.lib;vtkCommonCore-8.2.lib;vtkCommonDataModel-8.2.lib;vtkCommonExecutionModel-8.2.lib;vtkCommonMath-8.2.lib;vtkCommonMisc-8.2.lib;vtkCommonSystem-8.2.lib;vtkCommonTransforms-8.2.lib;vtkDICOMParser-8.2.lib;vtkDomainsChemistry-8.2.lib;vtkDomainsChemistryOpenGL2-8.2.lib;vtkdoubleconversion-8.2.lib;vtkexodusII-8.2.lib;vtkexpat-8.2.lib;vtkFiltersAMR-8.2.lib;vtkFiltersCore-8.2.lib;vtkFiltersExtraction-8.2.lib;vtkFiltersFlowPaths-8.2.lib;vtkFiltersGeneral-8.2.lib;vtkFiltersGeneric-8.2.lib;vtkFiltersGeometry-8.2.lib;vtkFiltersHybrid-8.2.lib;vtkFiltersHyperTree-8.2.lib;vtkFiltersImaging-8.2.lib;vtkFiltersModeling-8.2.lib;vtkFiltersParallel-8.2.lib;vtkFiltersParallelImaging-8.2.lib;vtkFiltersPoints-8.2.lib;vtkFiltersProgrammable-8.2.lib;vtkFiltersSelection-8.2.lib;vtkFiltersSMP-8.2.lib;vtkFiltersSources-8.2.lib;vtkFiltersStatistics-8.2.lib;vtkFiltersTexture-8.2.lib;vtkFiltersTopology-8.2.lib;vtkFiltersVerdict-8.2.lib;vtkfreetype-8.2.lib;vtkGeovisCore-8.2.lib;vtkgl2ps-8.2.lib;vtkglew-8.2.lib;vtkGUISupportMFC-8.2.lib;vtkhdf5-8.2.lib;vtkhdf5_hl-8.2.lib;vtkImagingColor-8.2.lib;vtkImagingCore-8.2.lib;vtkImagingFourier-8.2.lib;vtkImagingGeneral-8.2.lib;vtkImagingHybrid-8.2.lib;vtkImagingMath-8.2.lib;vtkImagingMorphological-8.2.lib;vtkImagingSources-8.2.lib;vtkImagingStatistics-8.2.lib;vtkImagingStencil-8.2.lib;vtkInfovisCore-8.2.lib;vtkInfovisLayout-8.2.lib;vtkInteractionImage-8.2.lib;vtkInteractionStyle-8.2.lib;vtkInteractionWidgets-8.2.lib;vtkIOAMR-8.2.lib;vtkIOAsynchronous-8.2.lib;vtkIOCityGML-8.2.lib;vtkIOCore-8.2.lib;vtkIOEnSight-8.2.lib;vtkIOExodus-8.2.lib;vtkIOExport-8.2.lib;vtkIOExportOpenGL2-8.2.lib;vtkIOExportPDF-8.2.lib;vtkIOGeometry-8.2.lib;vtkIOImage-8.2.lib;vtkIOImport-8.2.lib;vtkIOInfovis-8.2.lib;vtkIOLegacy-8.2.lib;vtkIOLSDyna-8.2.lib;vtkIOMINC-8.2.lib;vtkIOMovie-8.2.lib;vtkIONetCDF-8.2.lib;vtkIOParallel-8.2.lib;vtkIOParallelXML-8.2.lib;vtkIOPLY-8.2.lib;vtkIOSegY-8.2.lib;vtkIOSQL-8.2.lib;vtkIOTecplotTable-8.2.lib;vtkIOVeraOut-8.2.lib;vtkIOVideo-8.2.lib;vtkIOXML-8.2.lib;vtkIOXMLParser-8.2.lib;vtkjpeg-8.2.lib;vtkjsoncpp-8.2.lib;vtklibharu-8.2.lib;vtklibxml2-8.2.lib;vtklz4-8.2.lib;vtklzma-8.2.lib;vtkmetaio-8.2.lib;vtkNetCDF-8.2.lib;vtkogg-8.2.lib;vtkParallelCore-8.2.lib;vtkpng-8.2.lib;vtkproj-8.2.lib;vtkpugixml-8.2.lib;vtkRenderingAnnotation-8.2.lib;vtkRenderingContext2D-8.2.lib;vtkRenderingContextOpenGL2-8.2.lib;vtkRenderingCore-8.2.lib;vtkRenderingExternal-8.2.lib;vtkRenderingFreeType-8.2.lib;vtkRenderingGL2PSOpenGL2-8.2.lib;vtkRenderingImage-8.2.lib;vtkRenderingLabel-8.2.lib;vtkRenderingLOD-8.2.lib;vtkRenderingOpenGL2-8.2.lib;vtkRenderingVolume-8.2.lib;vtkRenderingVolumeOpenGL2-8.2.lib;vtksqlite-8.2.lib;vtksys-8.2.lib;vtktheora-8.2.lib;vtktiff-8.2.lib;vtkverdict-8.2.lib;vtkViewsContext2D-8.2.lib;vtkViewsCore-8.2.lib;vtkViewsInfovis-8.2.lib;vtkzlib-8.2.lib;pcl_common.lib;pcl_commond.lib;pcl_features.lib;pcl_featuresd.lib;pcl_filters.lib;pcl_filtersd.lib;pcl_io.lib;pcl_iod.lib;pcl_io_ply.lib;pcl_io_plyd.lib;pcl_kdtree.lib;pcl_kdtreed.lib;pcl_keypoints.lib;pcl_keypointsd.lib;pcl_ml.lib;pcl_mld.lib;pcl_octree.lib;pcl_octreed.lib;pcl_outofcore.lib;pcl_outofcored.lib;pcl_people.lib;pcl_peopled.lib;pcl_recognition.lib;pcl_recognitiond.lib;pcl_registration.lib;pcl_registrationd.lib;pcl_sample_consensus.lib;pcl_sample_consensusd.lib;pcl_search.lib;pcl_searchd.lib;pcl_segmentation.lib;pcl_segmentationd.lib;pcl_stereo.lib;pcl_stereod.lib;pcl_surface.lib;pcl_surfaced.lib;pcl_tracking.lib;pcl_trackingd.lib;pcl_visualization.lib;pcl_visualizationd.lib;%(AdditionalDependencies) + + + + + + + + + \ No newline at end of file From 8a0c4ab52e032cc35dbfa6799caae020c6dace85 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 6 Jul 2022 11:09:17 +0800 Subject: [PATCH 309/379] feat: compile on windows --- win/rs_driver_viewer/rs_driver_viewer.vcxproj | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/win/rs_driver_viewer/rs_driver_viewer.vcxproj b/win/rs_driver_viewer/rs_driver_viewer.vcxproj index f9d463b7..a1b05a6e 100644 --- a/win/rs_driver_viewer/rs_driver_viewer.vcxproj +++ b/win/rs_driver_viewer/rs_driver_viewer.vcxproj @@ -81,8 +81,8 @@ false - C:\Program Files\WpdPack_4_1_2\WpdPack\Include;C:\Program Files\PCL 1.11.1\include\pcl-1.11;C:\Program Files\PCL 1.11.1\3rdParty\Boost\include\boost-1_74;C:\Program Files\PCL 1.11.1\3rdParty\Eigen\eigen3;C:\Program Files\PCL 1.11.1\3rdParty\FLANN\include;C:\Program Files\PCL 1.11.1\3rdParty\Qhull\include;C:\Program Files\PCL 1.11.1\3rdParty\VTK\include\vtk-8.2;C:\Program Files\PCL 1.11.1\3rdParty\OpenNI2\Include;$(IncludePath) - C:\Program Files\WpdPack_4_1_2\WpdPack\Lib\x64;C:\Program Files\PCL 1.11.1\lib;C:\Program Files\PCL 1.11.1\3rdParty\Boost\lib;C:\Program Files\PCL 1.11.1\3rdParty\FLANN\lib;C:\Program Files\PCL 1.11.1\3rdParty\Qhull\lib;C:\Program Files\PCL 1.11.1\3rdParty\VTK\lib;C:\Program Files\PCL 1.11.1\3rdParty\OpenNI2\Lib;$(LibraryPath) + C:\Program Files\WpdPack_4_1_2\WpdPack\Include;C:\Program Files\PCL 1.11.1\include\pcl-1.11;C:\Program Files\PCL 1.11.1\3rdParty\Boost\include\boost-1_74;C:\Program Files\PCL 1.11.1\3rdParty\Eigen\eigen3;C:\Program Files\PCL 1.11.1\3rdParty\FLANN\include;C:\Program Files\PCL 1.11.1\3rdParty\Qhull\include;C:\Program Files\PCL 1.11.1\3rdParty\VTK\include\vtk-8.2;C:\Program Files\OpenNI2\Include;$(IncludePath) + C:\Program Files\WpdPack_4_1_2\WpdPack\Lib\x64;C:\Program Files\PCL 1.11.1\lib;C:\Program Files\PCL 1.11.1\3rdParty\Boost\lib;C:\Program Files\PCL 1.11.1\3rdParty\FLANN\lib;C:\Program Files\PCL 1.11.1\3rdParty\Qhull\lib;C:\Program Files\PCL 1.11.1\3rdParty\VTK\lib;C:\Program Files\OpenNI2\Lib;$(LibraryPath) From 122cf2fec8e083da6a1f4d2ade169f3af3f58735 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 8 Jul 2022 09:38:19 +0800 Subject: [PATCH 310/379] feat: update help docs --- README.md | 68 +++++++++++++++++++++++----------------------------- README_CN.md | 67 +++++++++++++++++++++++---------------------------- 2 files changed, 60 insertions(+), 75 deletions(-) diff --git a/README.md b/README.md index 4e835915..bf381a53 100644 --- a/README.md +++ b/README.md @@ -31,28 +31,26 @@ Below are the supported LiDARS. - gcc (4.8+) - Windows - - MSVC ( tested with VC2017 and VC2019) - - Mingw-w64 (tested with x86_64-8.1.0-posix-seh-rt_v6-rev0 ) + - MSVC ( tested with VS2019) ## 4 Dependency Libraries **rs_driver** depends on the following third-party libraries. Please install them before compiling **rs_driver**. -- libpcap (optional, needed if parsing PCAP file) -- PCL (optional, needed if building the visualization tool) -- Eigen3 (optional, needed if use the internal transformation function) +- libpcap (optional, needed to parse PCAP file) +- Eigen3 (optional, needed to use the internal transformation function) +- PCL (optional, needed to build the visualization tool) +- Boost (optional, needed to build the visualization tool) -## 5 Compilation and Installation +## 5 Compile On Ubuntu -### 5.1 On Ubuntu - -#### 5.1.1 Dependency Libraries +### 5.1 Dependency Libraries ```sh -sudo apt-get install libpcap-dev libpcl-dev libeigen3-dev +sudo apt-get install libpcap-dev libeigen3-dev libboost-dev libpcl-dev ``` -#### 5.1.2 Compilation +### 5.2 Compilation ```bash cd rs_driver @@ -60,13 +58,13 @@ mkdir build && cd build cmake .. && make -j4 ``` -#### 5.1.3 Installation +### 5.3 Installation ```bash sudo make install ``` -#### 5.1.4 Use rs_driver as a third party library +### 5.4 Use rs_driver as a third party library In your ```CMakeLists.txt```, find the **rs_driver** package and link to it . @@ -76,7 +74,7 @@ include_directories(${rs_driver_INCLUDE_DIRS}) target_link_libraries(your_project ${rs_driver_LIBRARIES}) ``` -#### 5.1.5 Use rs_driver as a submodule +### 5.5 Use rs_driver as a submodule Add **rs_driver** into your project as a submodule. @@ -89,35 +87,29 @@ include_directories(${rs_driver_INCLUDE_DIRS}) target_link_libraries(your_project ${rs_driver_LIBRARIES}) ``` -### 5.2 On Windows +## 6 Compile On Windows -#### 5.2.1 Dependency Libraries +### 6.1 Dependency Libraries -##### libpcap +#### libpcap Install [libpcap runtime library](https://www.winpcap.org/install/bin/WinPcap_4_1_3.exe). -Download [libpcap's developer's pack](https://www.winpcap.org/install/bin/WpdPack_4_1_2.zip) to your favorite location, and add the path to ```WpdPack_4_1_2/WpdPack``` folder to the environment variable ```PATH``` . - -##### PCL +Unzip [libpcap's developer's pack](https://www.winpcap.org/install/bin/WpdPack_4_1_2.zip) to your favorite location, and add the path to the folder ```WpdPack_4_1_2/WpdPack``` to the environment variable ```PATH``` . -+ MSVC +#### PCL -Please use the official installation package [All-in-one installer](https://github.com/PointCloudLibrary/pcl/releases). +To compile with VS2019, please use the official installation package [PCL All-in-one installer](https://github.com/PointCloudLibrary/pcl/releases). Select the "Add PCL to the system PATH for xxx" option during the installation. ![](./doc/img/01_install_pcl.PNG) -+ Mingw-w64 - -Since there'are no installers for mingw-w64 compiler available, Please compile PCL out from source as instructed in this [tutorial](https://pointclouds.org/documentation/tutorials/compiling_pcl_windows.html). - -#### 5.2.2 Installation +### 6.2 Installation Installation is not supported on Windows. -## 6 Quick Start +## 7 Quick Start **rs_driver** offers two demo programs in ```rs_driver/demo```. @@ -134,11 +126,11 @@ To build `demo_online` and `demo_pcap`, enable the option COMPILE_DEMOS when con cmake -DCOMPILE_DEMOS=ON .. ``` -For more info about how to decode an online Lidar, Please refer to [Online connect LiDAR](doc/howto/how_to_online_use_driver.md) +For more info about how to decode an online Lidar, Please refer to [Decode online LiDAR](doc/howto/how_to_decode_online_lidar.md) -For more info about how to decode a PCAP file, Please refer to [Decode pcap bag](doc/howto/how_to_decode_pcap.md) +For more info about how to decode a PCAP file, Please refer to [Decode pcap bag](doc/howto/how_to_decode_pcap_file.md) -## 7 Visualization of Point Cloud +## 8 Visualization of Point Cloud **rs_driver** offers a visualization tool `rs_driver_viwer` in ```rs_driver/tool``` , which is based on PCL. @@ -150,16 +142,16 @@ cmake -DCOMPILE_TOOLS=ON .. For more info about how to use the `rs_driver_viewer`, please refer to [Visualization tool guide](doc/howto/how_to_use_rs_driver_viewer.md) -## 8 More Topics +## 9 More Topics For more topics, Please refer to: -Multi-Cast function: [Multi-Cast](doc/howto/how_to_use_multi_cast_function.md) -Trasformation function: [Transformation guide](doc/howto/ow_to_transform_pointcloud.md) +Trasformation function: [Transformation guide](doc/howto/how_to_transform_pointcloud.md) +Network configuration advanced topics: [Advanced Topics](doc/howto/online_lidar_advanced_topics.md) For more info about the `rs_driver` API, Please refer to: -- **Parameters definition**: ```rs_driver/src/rs_driver/driver/driver_param.h``` -- **Point Cloud message definition**: ```rs_driver/src/rs_driver/msg/point_cloud_msg.h``` -- **API definition**: ```rs_driver/src/rs_driver/api/lidar_driver.h``` -- **Error code definition**: ```rs_driver/src/rs_driver/common/error_code.h``` +- **Point Cloud message definition**: ```rs_driver/src/rs_driver/msg/point_cloud_msg.hpp```, ```rs_driver/src/rs_driver/msg/pcl_point_cloud_msg.hpp``` +- **API definition**: ```rs_driver/src/rs_driver/api/lidar_driver.hpp``` +- **Parameters definition**: ```rs_driver/src/rs_driver/driver/driver_param.hpp```, +- **Error code definition**: ```rs_driver/src/rs_driver/common/error_code.hpp``` diff --git a/README_CN.md b/README_CN.md index 1e38d198..28c45267 100644 --- a/README_CN.md +++ b/README_CN.md @@ -30,24 +30,23 @@ - gcc (4.8+) - Windows - - MSVC (VS2017 & VS2019 已测试) - - Mingw-w64 (x86_64-8.1.0-posix-seh-rt_v6-rev0 已测试) + - MSVC (VS2019 已测试) ## 4 依赖的第三方库 依赖的第三方库如下。 - libpcap (可选。如不需要解析PCAP文件,可忽略) -- PCL (可选。如不需要可视化工具,可忽略) - Eigen3 (可选。如不需要内置坐标变换,可忽略) +- PCL (可选。如不需要可视化工具,可忽略) +- Boost (可选。如不需要可视化工具,可忽略) -## 5 编译与安装 -### 5.1 Ubuntu下的编译与安装 -#### 5.1.1 安装第三方库 +## 5 Ubuntu下的编译及安装 +### 5.1 安装第三方库 ```bash -sudo apt-get install libpcap-dev libpcl-dev libeigen3-dev +sudo apt-get install libpcap-dev libeigen3-dev libboost-dev libpcl-dev ``` -#### 5.1.2 编译 +### 5.2 编译 ```bash cd rs_driver @@ -55,13 +54,13 @@ mkdir build && cd build cmake .. && make -j4 ``` -#### 5.1.3 安装 +### 5.3 安装 ```bash sudo make install ``` -#### 5.1.4 作为第三方库使用 +### 5.4 作为第三方库使用 配置您的```CMakeLists```文件,使用find_package()指令找到**rs_driver**库,并链接。 @@ -71,7 +70,7 @@ include_directories(${rs_driver_INCLUDE_DIRS}) target_link_libraries(your_project ${rs_driver_LIBRARIES}) ``` -#### 5.1.5 作为子模块使用 +### 5.5 作为子模块使用 将**rs_driver**作为子模块添加到您的工程,相应配置您的```CMakeLists```文件。 @@ -84,35 +83,29 @@ include_directories(${rs_driver_INCLUDE_DIRS}) target_link_libraries(project ${rs_driver_LIBRARIES}) ``` -### 5.2 Windows下的编译与安装 +## 6 Windows下的编译及安装 -#### 5.2.1 安装第三方库 +### 6.1 安装第三方库 -##### libpcap +#### libpcap 安装[libpcap运行库](https://www.winpcap.org/install/bin/WinPcap_4_1_3.exe)。 - 下载[libpcap开发者包](https://www.winpcap.org/install/bin/WpdPack_4_1_2.zip)到任意位置,并将```WpdPack_4_1_2/WpdPack``` 的路径添加到环境变量```PATH```。 - -##### PCL - -+ MSVC - -​ 如果使用MSVC编译器,可使用PCL官方提供的[PCL安装包](https://github.com/PointCloudLibrary/pcl/releases)安装。 + 解压[libpcap开发者包](https://www.winpcap.org/install/bin/WpdPack_4_1_2.zip)到任意位置,并将```WpdPack_4_1_2/WpdPack``` 的路径添加到环境变量```PATH```。 -​ 安装过程中选择 “Add PCL to the system PATH for xxx”: +#### PCL -![](./doc/img/01_install_pcl.PNG) + 如果使用MSVC编译器,可使用PCL官方提供的[PCL安装包](https://github.com/PointCloudLibrary/pcl/releases)安装。 -+ Mingw-w64 + 安装过程中选择 “Add PCL to the system PATH for xxx”: -​ PCL官方没有提供mingw编译的库,所以需要按照[PCL官方教程](https://pointclouds.org/documentation/tutorials/compiling_pcl_windows.html), 从源码编译PCL并安装。 + ![](./doc/img/01_install_pcl.PNG) -#### 5.2.2 安装 +### 6.2 安装 Windows下,**rs_driver** 暂不支持安装。 -## 6 快速上手 +## 7 快速上手 **rs_driver**在目录```rs_driver/demo``` 下,提供了两个使用示例程序。 @@ -129,11 +122,11 @@ Windows下,**rs_driver** 暂不支持安装。 cmake -DCOMPILE_DEMOS=ON .. ``` -关于`demo_online`的更多说明,可以参考[在线连接雷达](doc/howto/how_to_online_use_driver.md) +关于`demo_online`的更多说明,可以参考[在线连接雷达](doc/howto/how_to_decode_online_lidar.md) -关于`demo_pcap`的更多说明,可以参考[解析pcap包](doc/howto/how_to_decode_pcap.md) +关于`demo_pcap`的更多说明,可以参考[解析pcap包](doc/howto/how_to_decode_pcap_file.md) -## 7 可视化工具 +## 8 可视化工具 **rs_driver**在目录```rs_driver/tool``` 下,提供了一个点云可视化工具`rs_driver_viewer`。它基于PCL库。 @@ -145,17 +138,17 @@ cmake -DCOMPILE_TOOLS=ON .. 关于`rs_driver_viewer`的使用方法,请参考[可视化工具操作指南](doc/howto/how_to_use_rs_driver_viewer.md) -## 8 更多主题 +## 9 更多主题 关于**rs_driver**的其他主题,请参考如下链接。 -组播模式: [组播模式](doc/howto/how_to_use_multi_cast_function.md) -坐标变换:[坐标变换](doc/howto/how_to_transform_pointcloud.md) +坐标变换: [坐标变换](doc/howto/how_to_transform_pointcloud.md) +网络配置的高级主题: [高级主题](doc/howto/online_lidar_advanced_topics.md) **rs_driver**的主要接口文件如下。 -- 点云消息定义: ```rs_driver/src/rs_driver/msg/point_cloud_msg.h``` -- 接口定义: ```rs_driver/src/rs_driver/api/lidar_driver.h``` -- 参数定义: ```rs_driver/src/rs_driver/driver/driver_param.h``` -- 错误码定义: ```rs_driver/src/rs_driver/common/error_code.h``` +- 点云消息定义: ```rs_driver/src/rs_driver/msg/point_cloud_msg.hpp```, ```rs_driver/src/rs_driver/msg/pcl_point_cloud_msg.hpp``` +- 接口定义: ```rs_driver/src/rs_driver/api/lidar_driver.hpp``` +- 参数定义: ```rs_driver/src/rs_driver/driver/driver_param.hpp``` +- 错误码定义: ```rs_driver/src/rs_driver/common/error_code.hpp``` From 3bb41dbc782c4c712eca23a8572443e09d94a87e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 13 Jul 2022 11:26:01 +0800 Subject: [PATCH 311/379] feat: fix compiler error on qnx --- src/rs_driver/common/rs_common.hpp | 6 +++--- src/rs_driver/driver/input/input_pcap.hpp | 4 ++-- src/rs_driver/driver/input/input_pcap_jumbo.hpp | 4 ++-- src/rs_driver/driver/input/input_sock.hpp | 10 +++++----- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/rs_driver/common/rs_common.hpp b/src/rs_driver/common/rs_common.hpp index 4e52ec0d..a68b8ced 100644 --- a/src/rs_driver/common/rs_common.hpp +++ b/src/rs_driver/common/rs_common.hpp @@ -35,10 +35,10 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. // // define ntohs() // -#ifdef __linux__ -#include -#elif _WIN32 +#ifdef _WIN32 #include +#else //__linux__ +#include #endif inline int16_t RS_SWAP_INT16(int16_t value) diff --git a/src/rs_driver/driver/input/input_pcap.hpp b/src/rs_driver/driver/input/input_pcap.hpp index daff7498..633bce5a 100644 --- a/src/rs_driver/driver/input/input_pcap.hpp +++ b/src/rs_driver/driver/input/input_pcap.hpp @@ -35,9 +35,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include -#ifdef __linux__ -#elif _WIN32 +#ifdef _WIN32 #define WIN32 +#else //__linux__ #endif #include diff --git a/src/rs_driver/driver/input/input_pcap_jumbo.hpp b/src/rs_driver/driver/input/input_pcap_jumbo.hpp index ab62cb59..72372000 100644 --- a/src/rs_driver/driver/input/input_pcap_jumbo.hpp +++ b/src/rs_driver/driver/input/input_pcap_jumbo.hpp @@ -36,9 +36,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include -#ifdef __linux__ -#elif _WIN32 +#ifdef _WIN32 #define WIN32 +#else //__linux__ #endif #include diff --git a/src/rs_driver/driver/input/input_sock.hpp b/src/rs_driver/driver/input/input_sock.hpp index daca9851..a01dd60d 100644 --- a/src/rs_driver/driver/input/input_sock.hpp +++ b/src/rs_driver/driver/input/input_sock.hpp @@ -1,7 +1,11 @@ #pragma once -#ifdef __linux__ +#ifdef _WIN32 + +#include + +#else //__linux__ #ifdef ENABLE_EPOLL_RECEIVE #include @@ -9,9 +13,5 @@ #include #endif -#elif _WIN32 - -#include - #endif From 6646e0fe740c093b64eccd83b2f41e17e655272a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 15 Jul 2022 11:44:12 +0800 Subject: [PATCH 312/379] feat: add func to determin lidar type --- src/rs_driver/driver/driver_param.hpp | 21 +++++++++++++++++++-- src/rs_driver/driver/lidar_driver_impl.hpp | 4 ++-- 2 files changed, 21 insertions(+), 4 deletions(-) diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index ac5052b1..04ae13ac 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -43,7 +43,8 @@ namespace lidar enum LidarType ///< LiDAR type { // mechanical - RS16 = 0x01, + RS_MECH = 0x01, + RS16 = RS_MECH, RS32, RSBP, RS128, @@ -57,7 +58,8 @@ enum LidarType ///< LiDAR type RSROCK, // mems - RSM1 = 0x20, + RS_MEMS = 0x20, + RSM1 = RS_MEMS, RSM2, RSEOS, @@ -66,6 +68,21 @@ enum LidarType ///< LiDAR type RSM1_JUMBO = RS_JUMBO + RSM1, }; +inline bool isMech(LidarType type) +{ + return ((LidarType::RS_MECH <= type) && (type < LidarType::RS_MEMS)); +} + +inline bool isMems (LidarType type) +{ + return ((LidarType::RS_MEMS <= type) && (type < LidarType::RS_JUMBO)); +} + +inline bool isJumbo (LidarType type) +{ + return (LidarType::RS_JUMBO <= type); +} + inline std::string lidarTypeToStr(const LidarType& type) { std::string str = ""; diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index 9d046b7a..e5e647ab 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -186,12 +186,12 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) std::bind(&LidarDriverImpl::splitFrame, this, std::placeholders::_1, std::placeholders::_2)); double packet_duration = decoder_ptr_->getPacketDuration(); - bool isJumbo = (param.lidar_type >= LidarType::RS_JUMBO); + bool is_jumbo = isJumbo(param.lidar_type); // // input // - input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, isJumbo, packet_duration, cb_feed_pkt_); + input_ptr_ = InputFactory::createInput(param.input_type, param.input_param, is_jumbo, packet_duration, cb_feed_pkt_); input_ptr_->regCallback( std::bind(&LidarDriverImpl::runExceptionCallback, this, std::placeholders::_1), From 1da0e61d68c61c7f9e2105901395754808bf7ce9 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sat, 16 Jul 2022 17:07:40 +0800 Subject: [PATCH 313/379] fix: fix crash in case of demo_pcap exit --- src/rs_driver/driver/input/input_pcap.hpp | 2 ++ src/rs_driver/driver/input/input_pcap_jumbo.hpp | 2 ++ 2 files changed, 4 insertions(+) diff --git a/src/rs_driver/driver/input/input_pcap.hpp b/src/rs_driver/driver/input/input_pcap.hpp index 633bce5a..09e96f9a 100644 --- a/src/rs_driver/driver/input/input_pcap.hpp +++ b/src/rs_driver/driver/input/input_pcap.hpp @@ -144,6 +144,7 @@ inline InputPcap::~InputPcap() if (pcap_ != NULL) { pcap_close(pcap_); + pcap_ = NULL; } } @@ -157,6 +158,7 @@ inline void InputPcap::recvPacket() if (ret < 0) // reach file end. { pcap_close(pcap_); + pcap_ = NULL; if (input_param_.pcap_repeat) { diff --git a/src/rs_driver/driver/input/input_pcap_jumbo.hpp b/src/rs_driver/driver/input/input_pcap_jumbo.hpp index 72372000..b1d0b673 100644 --- a/src/rs_driver/driver/input/input_pcap_jumbo.hpp +++ b/src/rs_driver/driver/input/input_pcap_jumbo.hpp @@ -137,6 +137,7 @@ inline InputPcapJumbo::~InputPcapJumbo() if (pcap_ != NULL) { pcap_close(pcap_); + pcap_ = NULL; } } @@ -150,6 +151,7 @@ inline void InputPcapJumbo::recvPacket() if (ret < 0) // reach file end. { pcap_close(pcap_); + pcap_ = NULL; if (input_param_.pcap_repeat) { From d18427e5c688cf97655e312b984fee65499dc248 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sat, 16 Jul 2022 17:08:40 +0800 Subject: [PATCH 314/379] feat: add default ctor of ErrCode --- src/rs_driver/common/error_code.hpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/rs_driver/common/error_code.hpp b/src/rs_driver/common/error_code.hpp index 96ed746f..b7d0c628 100644 --- a/src/rs_driver/common/error_code.hpp +++ b/src/rs_driver/common/error_code.hpp @@ -82,6 +82,12 @@ struct Error { ErrCode error_code; ErrCodeType error_code_type; + + Error () + : error_code(ErrCode::ERRCODE_SUCCESS) + { + } + explicit Error(const ErrCode& code) : error_code(code) { if (error_code < 0x40) From 83f2e4b2621afddfca247ba227bb039d4f9ea36f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 19 Jul 2022 15:33:43 +0800 Subject: [PATCH 315/379] fix: fix compiler error on qnx --- CMakeLists.txt | 8 +++++--- demo/CMakeLists.txt | 2 -- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 390ca303..e71b9253 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -83,13 +83,15 @@ set(INSTALL_CMAKE_DIR ${CMAKE_INSTALL_PREFIX}/lib/cmake) set(DRIVER_INCLUDE_DIRS ${CMAKE_CURRENT_LIST_DIR}/src) set(DRIVER_CMAKE_ROOT ${CMAKE_CURRENT_LIST_DIR}/cmake) -# fix pthread missing on ubuntu18.04 or ubuntu20.04 if(WIN32) else() - list(APPEND EXTERNAL_LIBS pthread) + if (CMAKE_SYSTEM_NAME STREQUAL "QNX") + list(APPEND EXTERNAL_LIBS socket) + else() + list(APPEND EXTERNAL_LIBS pthread) + endif() endif(WIN32) - #======================== # Build Features #======================== diff --git a/demo/CMakeLists.txt b/demo/CMakeLists.txt index 6ce99e8e..0d258784 100644 --- a/demo/CMakeLists.txt +++ b/demo/CMakeLists.txt @@ -21,7 +21,6 @@ add_executable(demo_online demo_online.cpp) target_link_libraries(demo_online - pthread ${EXTERNAL_LIBS}) if(NOT ${DISABLE_PCAP_PARSE}) @@ -30,7 +29,6 @@ add_executable(demo_pcap demo_pcap.cpp) target_link_libraries(demo_pcap - pthread ${EXTERNAL_LIBS}) endif(NOT ${DISABLE_PCAP_PARSE}) From e975529c3d6caba66672aa29ad18e4e2626d4331 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 19 Jul 2022 15:41:51 +0800 Subject: [PATCH 316/379] feat: remove high priority thread --- CMakeLists.txt | 11 ----------- .../driver/input/unix/input_sock_epoll.hpp | 18 ------------------ .../driver/input/unix/input_sock_select.hpp | 18 ------------------ 3 files changed, 47 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e71b9253..8e6fbc06 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -21,7 +21,6 @@ endif() option(DISABLE_PCAP_PARSE "Disable PCAP file parse" OFF) option(ENABLE_TRANSFORM "Enable transform functions" OFF) option(ENABLE_EPOLL_RECEIVE "Receive packets with epoll() instead of select()" OFF) -option(ENABLE_HIGH_PRIORITY_THREAD "Use High priority thread to receive packets" OFF) option(ENABLE_RECVMMSG "Enable recvmmsg() to receive MSOP message" OFF) option(ENABLE_PCL_POINTCLOUD "Enable PCL Point Cloud" OFF) @@ -105,16 +104,6 @@ if(${ENABLE_EPOLL_RECEIVE}) add_definitions("-DENABLE_EPOLL_RECEIVE") endif(${ENABLE_EPOLL_RECEIVE}) - -if(${ENABLE_HIGH_PRIORITY_THREAD}) - - message(=============================================================) - message("-- Enable High Priority Thread") - message(=============================================================) - - add_definitions("-DENABLE_HIGH_PRIORITY_THREAD") -endif(${ENABLE_HIGH_PRIORITY_THREAD}) - if(${DISABLE_PCAP_PARSE}) message(=============================================================) diff --git a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp index 6b527292..ce226e35 100644 --- a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp @@ -62,7 +62,6 @@ class InputSock : public Input private: inline void recvPacket(); - inline void higherThreadPrioty(std::thread::native_handle_type handle); inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); protected: @@ -73,21 +72,6 @@ class InputSock : public Input size_t sock_tail_; }; -inline void InputSock::higherThreadPrioty(std::thread::native_handle_type handle) -{ -#ifdef ENABLE_HIGH_PRIORITY_THREAD - int policy; - sched_param sch; - pthread_getschedparam(handle, &policy, &sch); - - sch.sched_priority = 63; - if (pthread_setschedparam(handle, SCHED_RR, &sch)) - { - std::cout << "setschedparam failed: " << std::strerror(errno) << std::endl; - } -#endif -} - inline bool InputSock::init() { if (init_flag_) @@ -159,8 +143,6 @@ inline bool InputSock::start() recv_thread_ = std::thread(std::bind(&InputSock::recvPacket, this)); - higherThreadPrioty(recv_thread_.native_handle()); - start_flag_ = true; return true; } diff --git a/src/rs_driver/driver/input/unix/input_sock_select.hpp b/src/rs_driver/driver/input/unix/input_sock_select.hpp index 592a7cce..21631c2b 100644 --- a/src/rs_driver/driver/input/unix/input_sock_select.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_select.hpp @@ -62,7 +62,6 @@ class InputSock : public Input private: inline void recvPacket(); - inline void higherThreadPrioty(std::thread::native_handle_type handle); inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); protected: @@ -72,21 +71,6 @@ class InputSock : public Input size_t sock_tail_; }; -inline void InputSock::higherThreadPrioty(std::thread::native_handle_type handle) -{ -#ifdef ENABLE_HIGH_PRIORITY_THREAD - int policy; - sched_param sch; - pthread_getschedparam(handle, &policy, &sch); - - sch.sched_priority = 63; - if (pthread_setschedparam(handle, SCHED_RR, &sch)) - { - std::cout << "setschedparam failed: " << std::strerror(errno) << std::endl; - } -#endif -} - inline bool InputSock::init() { if (init_flag_) @@ -134,8 +118,6 @@ inline bool InputSock::start() recv_thread_ = std::thread(std::bind(&InputSock::recvPacket, this)); - higherThreadPrioty(recv_thread_.native_handle()); - start_flag_ = true; return true; } From cb36710cf66b067d0e93a342db2c9e3586316557 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 19 Jul 2022 15:59:27 +0800 Subject: [PATCH 317/379] fix: fix runtime error in case of ENABLE_TRANSFORM --- src/rs_driver/driver/decoder/decoder.hpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index eec5b675..9a711c46 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -248,6 +248,10 @@ class Decoder { public: +#ifdef ENABLE_TRANSFORM + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +#endif + constexpr static uint16_t PROTOCOL_VER_0 = 0x00; virtual void decodeDifopPkt(const uint8_t* pkt, size_t size) = 0; From d294e3cb0c8982c0968bd5abf9c9107e56678353 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 19 Jul 2022 16:28:49 +0800 Subject: [PATCH 318/379] feat: add option to double RCVBUF --- CMakeLists.txt | 13 +++++++++---- .../driver/input/unix/input_sock_select.hpp | 10 ++++++++++ 2 files changed, 19 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8e6fbc06..233c2794 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -18,10 +18,11 @@ endif() #============================= # Compile Features #============================= -option(DISABLE_PCAP_PARSE "Disable PCAP file parse" OFF) -option(ENABLE_TRANSFORM "Enable transform functions" OFF) -option(ENABLE_EPOLL_RECEIVE "Receive packets with epoll() instead of select()" OFF) -option(ENABLE_RECVMMSG "Enable recvmmsg() to receive MSOP message" OFF) +option(DISABLE_PCAP_PARSE "Disable PCAP file parse" OFF) +option(ENABLE_TRANSFORM "Enable transform functions" OFF) +option(ENABLE_EPOLL_RECEIVE "Receive packets with epoll() instead of select()" OFF) +option(ENABLE_RECVMMSG "Enable recvmmsg() to receive MSOP message" OFF) +option(ENABLE_DOUBLE_RCVBUF "Enable double size of RCVBUF" OFF) option(ENABLE_PCL_POINTCLOUD "Enable PCL Point Cloud" OFF) #============================= @@ -147,6 +148,10 @@ if(${ENABLE_RECVMMSG}) add_definitions("-DENABLE_RECVMMSG") endif(${ENABLE_RECVMMSG}) +if(${ENABLE_DOUBLE_RCVBUF}) + add_definitions("-DENABLE_DOUBLE_RCVBUF") +endif(${ENABLE_DOUBLE_RCVBUF}) + if(${COMPILE_DEMOS}) add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/demo) endif(${COMPILE_DEMOS}) diff --git a/src/rs_driver/driver/input/unix/input_sock_select.hpp b/src/rs_driver/driver/input/unix/input_sock_select.hpp index 21631c2b..58c6ffd8 100644 --- a/src/rs_driver/driver/input/unix/input_sock_select.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_select.hpp @@ -188,6 +188,16 @@ inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, con } } +#ifdef ENABLE_DOUBLE_RCVBUF + { + uint32_t opt_val; + socklen_t opt_len = sizeof(uint32_t); + getsockopt(fd, SOL_SOCKET, SO_RCVBUF, (char*)&opt_val, &opt_len); + opt_val *= 4; + setsockopt(fd, SOL_SOCKET, SO_RCVBUF, (char*)&opt_val, opt_len); + } +#endif + { int flags = fcntl(fd, F_GETFL, 0); ret = fcntl(fd, F_SETFL, flags | O_NONBLOCK); From 1e8bd186ee23f9c062e99c0f1f2ceab83b42056b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 20 Jul 2022 10:32:22 +0800 Subject: [PATCH 319/379] format: format section test --- src/rs_driver/driver/decoder/section.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/rs_driver/driver/decoder/section.hpp b/src/rs_driver/driver/decoder/section.hpp index cf1fb624..687e931c 100644 --- a/src/rs_driver/driver/decoder/section.hpp +++ b/src/rs_driver/driver/decoder/section.hpp @@ -42,11 +42,11 @@ class AzimuthSection public: AzimuthSection(int32_t start, int32_t end) { + full_round_ = ((start == 0) && (end == 36000)); + start_ = start % 36000; - end_ = (end <= 36000) ? end : (end % 36000); + end_ = end % 36000; cross_zero_ = (start_ > end_); - - full_round_ = ((start_ == 0) && (end_ == 36000)); } bool in(int32_t angle) @@ -67,10 +67,10 @@ class AzimuthSection #ifndef UNIT_TEST private: #endif + bool full_round_; int32_t start_; int32_t end_; bool cross_zero_; - bool full_round_; }; class DistanceSection From 2db9eb4b64b98a92d7f785a3e3cac4de5a09e4be Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 20 Jul 2022 12:03:11 +0800 Subject: [PATCH 320/379] fix: fix help doc --- doc/intro/parameter_intro_cn.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/intro/parameter_intro_cn.md b/doc/intro/parameter_intro_cn.md index c9842f22..1c17fd69 100644 --- a/doc/intro/parameter_intro_cn.md +++ b/doc/intro/parameter_intro_cn.md @@ -82,7 +82,7 @@ typedef struct RSDecoderParam + dense_points - 指定点云是否是dense的。 + 如果`dense_points`=`false`, 则点云中包含NAN点;如果`dense_points`=`true`,则去除点云中的NAN点。 + ts_first_point - 指定点云的时间戳来自点云的第一个点,还是最后第一个点。 - + 如果`ts_first_point`=`false`, 则第一个点的时间作为点云的时间戳;如果`ts_first_point`=`true`,则最后一个点的时间作为点云的时间戳。 + + 如果`ts_first_point`=`true`, 则第一个点的时间作为点云的时间戳;如果`ts_first_point`=`false`,则最后一个点的时间作为点云的时间戳。 + wait_for_difop - 解析MSOP Packet之前,是否等待DIFOP Packet。 + DIFOP Packet中包含角度校准等参数数据。如果没有这个数据,rs_driver输出的点云将是扁平的。 + 在rs_driver不输出点云时,设置`wait_for_difop`=`false`,有助于定位问题的位置。 From 8897990e2fd452a2dfeee49f9db2538acd8c98b9 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 20 Jul 2022 14:42:39 +0800 Subject: [PATCH 321/379] feat: add tests for section --- src/rs_driver/driver/decoder/section.hpp | 2 +- test/section_test.cpp | 8 ++++++++ 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/src/rs_driver/driver/decoder/section.hpp b/src/rs_driver/driver/decoder/section.hpp index 687e931c..9865a157 100644 --- a/src/rs_driver/driver/decoder/section.hpp +++ b/src/rs_driver/driver/decoder/section.hpp @@ -42,7 +42,7 @@ class AzimuthSection public: AzimuthSection(int32_t start, int32_t end) { - full_round_ = ((start == 0) && (end == 36000)); + full_round_ = (start == 0) && (end == 36000); start_ = start % 36000; end_ = end % 36000; diff --git a/test/section_test.cpp b/test/section_test.cpp index d446fb16..8b3d26b3 100644 --- a/test/section_test.cpp +++ b/test/section_test.cpp @@ -5,6 +5,14 @@ using namespace robosense::lidar; +TEST(TestAzimuthSection, ctorFull) +{ + AzimuthSection sec(0, 36000); + ASSERT_TRUE(sec.in(0)); + ASSERT_TRUE(sec.in(10)); + ASSERT_TRUE(sec.in(36000)); +} + TEST(TestAzimuthSection, ctor) { AzimuthSection sec(10, 20); From f151ec9dff7a32d5ba47f7f5a63ab80f9461be19 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 22 Jul 2022 10:59:26 +0800 Subject: [PATCH 322/379] feat: update docs to request the compiler to support c++14 --- README.md | 2 +- README_CN.md | 12 ++++++------ 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/README.md b/README.md index bf381a53..aede5f39 100644 --- a/README.md +++ b/README.md @@ -25,7 +25,7 @@ Below are the supported LiDARS. ## 3 Supported Platforms -**rs_driver** is compatible with the following platforms and compilers: +**rs_driver** is compatible with the following platforms and compilers. Note the compiler should support C++ 14. - Ubuntu (16.04, 18.04) - gcc (4.8+) diff --git a/README_CN.md b/README_CN.md index 28c45267..147d2c45 100644 --- a/README_CN.md +++ b/README_CN.md @@ -25,7 +25,7 @@ ## 3 支持的操作系统 -支持的操作系统及编译器如下。 +支持的操作系统及编译器如下。注意编译器需支持C++14标准。 - Ubuntu (16.04, 18.04, 20.04) - gcc (4.8+) @@ -89,17 +89,17 @@ target_link_libraries(project ${rs_driver_LIBRARIES}) #### libpcap - 安装[libpcap运行库](https://www.winpcap.org/install/bin/WinPcap_4_1_3.exe)。 +安装[libpcap运行库](https://www.winpcap.org/install/bin/WinPcap_4_1_3.exe)。 - 解压[libpcap开发者包](https://www.winpcap.org/install/bin/WpdPack_4_1_2.zip)到任意位置,并将```WpdPack_4_1_2/WpdPack``` 的路径添加到环境变量```PATH```。 +解压[libpcap开发者包](https://www.winpcap.org/install/bin/WpdPack_4_1_2.zip)到任意位置,并将```WpdPack_4_1_2/WpdPack``` 的路径添加到环境变量```PATH```。 #### PCL - 如果使用MSVC编译器,可使用PCL官方提供的[PCL安装包](https://github.com/PointCloudLibrary/pcl/releases)安装。 +如果使用MSVC编译器,可使用PCL官方提供的[PCL安装包](https://github.com/PointCloudLibrary/pcl/releases)安装。 - 安装过程中选择 “Add PCL to the system PATH for xxx”: +安装过程中选择 “Add PCL to the system PATH for xxx”: - ![](./doc/img/01_install_pcl.PNG) +![](./doc/img/01_install_pcl.PNG) ### 6.2 安装 From b130c2d9597231580da140f1f9b0f3dd79ba5911 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 22 Jul 2022 14:50:10 +0800 Subject: [PATCH 323/379] fix: restart in case of repeated start() and stop() --- src/rs_driver/driver/input/unix/input_sock_epoll.hpp | 1 + src/rs_driver/driver/input/unix/input_sock_select.hpp | 1 + src/rs_driver/driver/input/win/input_sock_select.hpp | 1 + 3 files changed, 3 insertions(+) diff --git a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp index ce226e35..5541b8d6 100644 --- a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp @@ -141,6 +141,7 @@ inline bool InputSock::start() return false; } + to_exit_recv_ = false; recv_thread_ = std::thread(std::bind(&InputSock::recvPacket, this)); start_flag_ = true; diff --git a/src/rs_driver/driver/input/unix/input_sock_select.hpp b/src/rs_driver/driver/input/unix/input_sock_select.hpp index 58c6ffd8..488d4ef7 100644 --- a/src/rs_driver/driver/input/unix/input_sock_select.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_select.hpp @@ -116,6 +116,7 @@ inline bool InputSock::start() return false; } + to_exit_recv_ = false; recv_thread_ = std::thread(std::bind(&InputSock::recvPacket, this)); start_flag_ = true; diff --git a/src/rs_driver/driver/input/win/input_sock_select.hpp b/src/rs_driver/driver/input/win/input_sock_select.hpp index 44497545..fbb4e177 100644 --- a/src/rs_driver/driver/input/win/input_sock_select.hpp +++ b/src/rs_driver/driver/input/win/input_sock_select.hpp @@ -123,6 +123,7 @@ inline bool InputSock::start() return false; } + to_exit_recv_ = false; recv_thread_ = std::thread(std::bind(&InputSock::recvPacket, this)); start_flag_ = true; From e4f7552b52d3a94ea00d3875bb8ee7da122a4890 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 29 Jul 2022 16:27:51 +0800 Subject: [PATCH 324/379] feat: update demo_online to show orderly exit --- demo/demo_online.cpp | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 699d8fba..b70d24bf 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -38,6 +38,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #endif +//#define ORDERLY_EXIT + typedef PointXYZI PointT; typedef PointCloudT PointCloudMsg; @@ -87,9 +89,10 @@ void exceptionCallback(const Error& code) RS_WARNING << code.toString() << RS_REND; } +bool to_exit_process = false; void processCloud(void) { - while (1) + while (!to_exit_process) { std::shared_ptr msg = cloud_queue.popWait(); if (msg.get() == NULL) @@ -127,13 +130,23 @@ int main(int argc, char* argv[]) RS_ERROR << "Driver Initialize Error..." << RS_REND; return -1; } + driver.start(); ///< The driver thread will start RS_DEBUG << "RoboSense Lidar-Driver Linux online demo start......" << RS_REND; +#ifdef ORDERLY_EXIT + std::this_thread::sleep_for(std::chrono::seconds(10)); + + driver.stop(); + + to_exit_process = true; + cloud_handle_thread.join(); +#else while (true) { std::this_thread::sleep_for(std::chrono::seconds(1)); } +#endif return 0; } From 46b9ac978a78255cd8d3dad6d170c3816e970f15 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 1 Aug 2022 11:11:51 +0800 Subject: [PATCH 325/379] feat: update help docs --- README.md | 2 +- README_CN.md | 2 +- doc/howto/how_to_decode_online_lidar.md | 6 ++++-- doc/howto/how_to_transform_pointcloud.md | 2 +- doc/howto/how_to_use_rs_driver_viewer.md | 2 +- doc/src_intro/rs_driver_intro.md | 14 +------------- 6 files changed, 9 insertions(+), 19 deletions(-) diff --git a/README.md b/README.md index aede5f39..781edb7b 100644 --- a/README.md +++ b/README.md @@ -31,7 +31,7 @@ Below are the supported LiDARS. - gcc (4.8+) - Windows - - MSVC ( tested with VS2019) + - MSVC ( tested with Win10 / VS2019) ## 4 Dependency Libraries diff --git a/README_CN.md b/README_CN.md index 147d2c45..a0365a88 100644 --- a/README_CN.md +++ b/README_CN.md @@ -30,7 +30,7 @@ - gcc (4.8+) - Windows - - MSVC (VS2019 已测试) + - MSVC (Win10 / VS2019 已测试) ## 4 依赖的第三方库 diff --git a/doc/howto/how_to_decode_online_lidar.md b/doc/howto/how_to_decode_online_lidar.md index 6b690eca..8205a7b2 100644 --- a/doc/howto/how_to_decode_online_lidar.md +++ b/doc/howto/how_to_decode_online_lidar.md @@ -103,12 +103,14 @@ Here user may add new member variables, remove member variables, or change the o ### 3.3 Point in Point Cloud -Here is an example of 5_lasers Lidar. +For mechanical Lidar, it may be useful to explain how the layout of point cloud is like. + +Here is an example of mechanical 5_lasers Lidar. The Lidar scans block by block. It starts from b0c0(block 0 channel/laser 0), b0c1, b0c2, b0c3, b0c4, and then go to b1c0, b1c1, b1c2, b1c3, b1c4, and so on. ![](../img/11_rs_driver_point_cloud.png) -At the same time, it saves the points in a point vector, point by point, as below. +At the same time, it saves the points in a vector, point by point, as below. ![](../img/11_rs_driver_point_cloud_vector.png) ### 3.4 Define the driver object diff --git a/doc/howto/how_to_transform_pointcloud.md b/doc/howto/how_to_transform_pointcloud.md index 2327101f..0f70d90a 100644 --- a/doc/howto/how_to_transform_pointcloud.md +++ b/doc/howto/how_to_transform_pointcloud.md @@ -1,4 +1,4 @@ -# How to use transform point cloud +# How to transform point cloud ## 1 Introduction diff --git a/doc/howto/how_to_use_rs_driver_viewer.md b/doc/howto/how_to_use_rs_driver_viewer.md index 2da41b95..fbe2bdf6 100644 --- a/doc/howto/how_to_use_rs_driver_viewer.md +++ b/doc/howto/how_to_use_rs_driver_viewer.md @@ -1,4 +1,4 @@ -# How to visualize the point cloud with rs_driver_viewer +# How to visualize point cloud with rs_driver_viewer ## 1 Introduction diff --git a/doc/src_intro/rs_driver_intro.md b/doc/src_intro/rs_driver_intro.md index 8cf3305b..d2fe133e 100644 --- a/doc/src_intro/rs_driver_intro.md +++ b/doc/src_intro/rs_driver_intro.md @@ -1,4 +1,4 @@ -# rs_driver v1.5.4 源代码解析 +# rs_driver v1.5.5 源代码解析 ## 1 基本概念 @@ -108,7 +108,6 @@ init() 调用createSocket(),创建两个Socket,分别接收MSOP Packet和DIFOP start() 开始接收MSOP/DIFOP Packet。 + 启动接收线程,线程函数为InputSock::recvPacket() -+ 调用higherThreadPriority(),提升接收线程的优先级。 #### 3.2.4 InputSock::recvPacket() @@ -123,17 +122,6 @@ recvPacket() 接收MSOP/DIFOP Packet。 + 调用回调函数`cb_put_pkt_`,将Packet派发给InputSock的使用者。 + 注意在派发之前,调用Buffer::setData()设置了MSOP Packet在Buffer的中偏移量及长度,以便剥除`USER_LAYER`和`TAIL_LAYER`(如果有的话)。 -#### 3.2.5 InputSock::higherThreadPrioty() - -higherThreadPrioty()用于设置接收线程的优先级。 -+ 调用pthread_getschedparam(),pthread_setschedparam(),给线程重新设置更高的优先级。 - -缺省情况,higherThreadPriorty()的功能是不启用的。要启用这个特性,要在编译时使用`-DENABLE_HIGH_PRIORITY_THREAD`选项。 - -``` -cmake -DENABLE_HIGH_PRIORITY_THREAD=TRUE . -``` - ### 3.3 InputPcap InputPcap解析PCAP文件得到MSOP/DIFOP Packet。使用第三方工具,如WireShark,可以将雷达数据保存到PCAP文件中。 From 2e19fe7ce8eb78d9ffddfc0915d8e194c591f1ad Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 1 Aug 2022 11:28:08 +0800 Subject: [PATCH 326/379] format: remove rock --- src/rs_driver/driver/decoder/decoder_factory.hpp | 4 ++-- src/rs_driver/driver/driver_param.hpp | 5 ++--- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index d69d8e9a..4609abb4 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -36,9 +36,9 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include -#include #include +#include +#include #include #include #include diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 04ae13ac..4b26bac1 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -47,15 +47,14 @@ enum LidarType ///< LiDAR type RS16 = RS_MECH, RS32, RSBP, + RSHELIOS, + RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48, - RSHELIOS, - RSHELIOS_16P, - RSROCK, // mems RS_MEMS = 0x20, From 82e1e4854fcba266848a0b5a48859e337a20235d Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 1 Aug 2022 11:36:30 +0800 Subject: [PATCH 327/379] feat: update CHANGELOG --- CHANGELOG.md | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 3e135ffb..e8182b4e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,8 +1,24 @@ -# Changelog +# ChangeLog ## Unreleased +## v1.5.5 2022-08-01 + ### Added +- Compiled rs_driver_viewer on Windows, and add help doc +- Add option to double RECVBUF of UDP sockets + +### Changed +- Update demo_online to exit orderly. + +### Fixed +- Fix runtime error of Eigen in case of ENABLE_TRANSFORM +- Fix Compiling error on QNX +- Fix pcap_rate +- Fix the problem with repeated stop and start of driver + +### Removed +- Remove option of high priority thread ## v1.5.4 2022-07-01 From 2eb41dcb774caa1bf23072ef933b7f4747e0c4de Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 1 Aug 2022 14:55:23 +0800 Subject: [PATCH 328/379] feat: tag v1.5.5 --- CMakeLists.txt | 2 +- src/rs_driver/macro/version.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 233c2794..e609fe56 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.5.4) +project(rs_driver VERSION 1.5.5) #======================== # Project setup diff --git a/src/rs_driver/macro/version.hpp b/src/rs_driver/macro/version.hpp index d33caacb..f80de532 100644 --- a/src/rs_driver/macro/version.hpp +++ b/src/rs_driver/macro/version.hpp @@ -1,3 +1,3 @@ #define RSLIDAR_VERSION_MAJOR 1 #define RSLIDAR_VERSION_MINOR 5 -#define RSLIDAR_VERSION_PATCH 4 +#define RSLIDAR_VERSION_PATCH 5 From d21b9f223060db8fb603bd3cce862c0711c3331a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 3 Aug 2022 20:02:48 +0800 Subject: [PATCH 329/379] format: format --- src/rs_driver/driver/driver_param.hpp | 40 +++++++++++++-------------- 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 4b26bac1..360a5338 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -143,43 +143,43 @@ inline LidarType strToLidarType(const std::string& type) { if (type == "RS16") { - return lidar::LidarType::RS16; + return LidarType::RS16; } else if (type == "RS32") { - return lidar::LidarType::RS32; + return LidarType::RS32; } else if (type == "RSBP") { - return lidar::LidarType::RSBP; + return LidarType::RSBP; } else if (type == "RSHELIOS") { - return lidar::LidarType::RSHELIOS; + return LidarType::RSHELIOS; } else if (type == "RSHELIOS_16P") { - return lidar::LidarType::RSHELIOS_16P; + return LidarType::RSHELIOS_16P; } else if (type == "RS128") { - return lidar::LidarType::RS128; + return LidarType::RS128; } else if (type == "RS80") { - return lidar::LidarType::RS80; + return LidarType::RS80; } else if (type == "RS48") { - return lidar::LidarType::RS48; + return LidarType::RS48; } else if (type == "RSP128") { - return lidar::LidarType::RSP128; + return LidarType::RSP128; } else if (type == "RSP80") { - return lidar::LidarType::RSP80; + return LidarType::RSP80; } else if (type == "RSP48") { @@ -195,11 +195,11 @@ inline LidarType strToLidarType(const std::string& type) } else if (type == "RSEOS") { - return lidar::LidarType::RSEOS; + return LidarType::RSEOS; } else if (type == "RSM1_JUMBO") { - return lidar::LidarType::RSM1_JUMBO; + return LidarType::RSM1_JUMBO; } else { @@ -246,7 +246,7 @@ enum SplitFrameMode SPLIT_BY_CUSTOM_BLKS }; -typedef struct RSTransformParam ///< The Point transform parameter +struct RSTransformParam ///< The Point transform parameter { float x = 0.0f; ///< unit, m float y = 0.0f; ///< unit, m @@ -267,9 +267,9 @@ typedef struct RSTransformParam ///< The Point transform parameter RS_INFOL << "yaw: " << yaw << RS_REND; RS_INFO << "------------------------------------------------------" << RS_REND; } -} RSTransformParam; +}; -typedef struct RSDecoderParam ///< LiDAR decoder parameter +struct RSDecoderParam ///< LiDAR decoder parameter { bool config_from_file = false; ///< Internal use only for debugging std::string angle_path = ""; ///< Internal use only for debugging @@ -309,9 +309,9 @@ typedef struct RSDecoderParam ///< LiDAR decoder parameter transform_param.print(); } -} RSDecoderParam; +}; -typedef struct RSInputParam ///< The LiDAR input parameter +struct RSInputParam ///< The LiDAR input parameter { uint16_t msop_port = 6699; ///< Msop packet port number uint16_t difop_port = 7788; ///< Difop packet port number @@ -341,9 +341,9 @@ typedef struct RSInputParam ///< The LiDAR input parameter RS_INFO << "------------------------------------------------------" << RS_REND; } -} RSInputParam; +}; -typedef struct RSDriverParam ///< The LiDAR driver parameter +struct RSDriverParam ///< The LiDAR driver parameter { LidarType lidar_type = LidarType::RS16; ///< Lidar type InputType input_type = InputType::ONLINE_LIDAR; ///< Input type @@ -362,7 +362,7 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter decoder_param.print(); } -} RSDriverParam; +}; } // namespace lidar } // namespace robosense From ef7e5e6cdba20dd379da4d4c474909590cc54470 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 8 Aug 2022 15:17:42 +0800 Subject: [PATCH 330/379] format: fix comments --- src/rs_driver/driver/decoder/decoder_RS128.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 125a05fd..37235bc5 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -167,8 +167,8 @@ inline RSEchoMode DecoderRS128::getEchoMode(uint8_t mode) { case 0x03: // dual return return RSEchoMode::ECHO_DUAL; - case 0x01: // strongest return - case 0x02: // last return + case 0x01: // last return + case 0x02: // strongest return default: return RSEchoMode::ECHO_SINGLE; } From 0ad176ed7b6d9575c357f98102b513b268d80f08 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 9 Aug 2022 09:24:09 +0800 Subject: [PATCH 331/379] feat: diff error_code of msop and difop --- src/rs_driver/common/error_code.hpp | 53 +++++++++++-------- src/rs_driver/driver/decoder/decoder.hpp | 10 ++-- .../driver/decoder/decoder_RS128.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS16.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS32.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS48.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS80.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 2 +- .../driver/decoder/decoder_RSHELIOS.hpp | 2 +- .../driver/decoder/decoder_RSHELIOS_16P.hpp | 2 +- .../driver/decoder/decoder_RSP128.hpp | 2 +- .../driver/decoder/decoder_RSP48.hpp | 2 +- .../driver/decoder/decoder_RSP80.hpp | 2 +- 13 files changed, 47 insertions(+), 38 deletions(-) diff --git a/src/rs_driver/common/error_code.hpp b/src/rs_driver/common/error_code.hpp index b7d0c628..d124a49c 100644 --- a/src/rs_driver/common/error_code.hpp +++ b/src/rs_driver/common/error_code.hpp @@ -56,26 +56,29 @@ enum class ErrCodeType enum ErrCode { // info - ERRCODE_SUCCESS = 0x00, ///< Normal - ERRCODE_PCAPREPEAT = 0x01, ///< Pcap file will play repeatedly - ERRCODE_PCAPEXIT = 0x02, ///< Pcap thread will exit + ERRCODE_SUCCESS = 0x00, ///< Normal + ERRCODE_PCAPREPEAT = 0x01, ///< Pcap file will play repeatedly + ERRCODE_PCAPEXIT = 0x02, ///< Pcap thread will exit // warning - ERRCODE_MSOPTIMEOUT = 0x40, ///< Msop packets receive overtime (1 sec) - ERRCODE_DIFOPTIMEOUT = 0x41, ///< Difop packets receive overtime (2 sec) - ERRCODE_NODIFOPRECV = 0x42, ///< Point cloud decoding process will not start until the difop packet receive - ERRCODE_WRONGPKTHEADER = 0x43, ///< Packet header is wrong - ERRCODE_WRONGPKTLENGTH = 0x44, ///< Packet length is wrong - ERRCODE_ZEROPOINTS = 0x45, ///< Size of the point cloud is zero - ERRCODE_PKTBUFOVERFLOW = 0x46, ///< Packet buffer is overflow - ERRCODE_CLOUDBUFOVERFLOW = 0x47, ///< Point cloud buffer is overflow + ERRCODE_MSOPTIMEOUT = 0x40, ///< Msop packets receive overtime (1 sec) + ERRCODE_DIFOPTIMEOUT = 0x41, ///< Difop packets receive overtime (2 sec) + ERRCODE_NODIFOPRECV = 0x42, ///< Point cloud decoding process will not start until the difop packet receive + ERRCODE_WRONGMSOPID = 0x43, ///< Packet header is wrong + ERRCODE_WRONGMSOPLEN = 0x44, ///< Packet length is wrong + ERRCODE_WRONGMSOPBLKID = 0x45, ///< Packet header is wrong + ERRCODE_WRONGDIFOPID = 0x46, ///< Packet header is wrong + ERRCODE_WRONGDIFOPLEN = 0x47, ///< Packet length is wrong + ERRCODE_ZEROPOINTS = 0x48, ///< Size of the point cloud is zero + ERRCODE_PKTBUFOVERFLOW = 0x49, ///< Packet buffer is overflow + ERRCODE_CLOUDSIZEOVERFLOW = 0x4a, ///< Point cloud buffer is overflow // error - ERRCODE_STARTBEFOREINIT = 0x80, ///< start() function is called before initializing successfully - ERRCODE_MSOPPORTBUZY = 0x81, ///< Input msop port is already used - ERRCODE_DIFOPPORTBUZY = 0x82, ///< Input difop port is already used - ERRCODE_PCAPWRONGPATH = 0x83, ///< Input directory of pcap file is wrong - ERRCODE_POINTCLOUDNULL = 0x84, ///< PointCloud buffer is invalid + ERRCODE_STARTBEFOREINIT = 0x80, ///< start() function is called before initializing successfully + ERRCODE_MSOPPORTBUZY = 0x81, ///< Input msop port is already used + ERRCODE_DIFOPPORTBUZY = 0x82, ///< Input difop port is already used + ERRCODE_PCAPWRONGPATH = 0x83, ///< Input directory of pcap file is wrong + ERRCODE_POINTCLOUDNULL = 0x84, ///< PointCloud buffer is invalid }; struct Error @@ -120,10 +123,16 @@ struct Error return "ERRCODE_DIFOPTIMEOUT"; case ERRCODE_NODIFOPRECV: return "ERRCODE_NODIFOPRECV"; - case ERRCODE_WRONGPKTHEADER: - return "ERRCODE_WRONGPKTHEADER"; - case ERRCODE_WRONGPKTLENGTH: - return "ERRCODE_WRONGPKTLENGTH"; + case ERRCODE_WRONGMSOPID: + return "ERRCODE_WRONGMSOPID"; + case ERRCODE_WRONGMSOPLEN: + return "ERRCODE_WRONGMSOPLEN"; + case ERRCODE_WRONGMSOPBLKID: + return "ERRCODE_WRONGMSOPBLKID"; + case ERRCODE_WRONGDIFOPID: + return "ERRCODE_WRONGDIFOPID"; + case ERRCODE_WRONGDIFOPLEN: + return "ERRCODE_WRONGDIFOPLEN"; case ERRCODE_ZEROPOINTS: return "ERRCODE_ZEROPOINTS"; @@ -140,8 +149,8 @@ struct Error return "ERRCODE_POINTCLOUDNULL"; case ERRCODE_PKTBUFOVERFLOW: return "ERRCODE_PKTBUFOVERFLOW"; - case ERRCODE_CLOUDBUFOVERFLOW: - return "ERRCODE_CLOUDBUFOVERFLOW"; + case ERRCODE_CLOUDSIZEOVERFLOW: + return "ERRCODE_CLOUDSIZEOVERFLOW"; //default default: diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 9a711c46..65dbcc5a 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -387,13 +387,13 @@ inline void Decoder::processDifopPkt(const uint8_t* pkt, size_t si { if (size != this->const_param_.DIFOP_LEN) { - LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGPKTLENGTH)), 1); + LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGDIFOPLEN)), 1); return; } if (memcmp(pkt, this->const_param_.DIFOP_ID, const_param_.DIFOP_ID_LEN) != 0) { - LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)), 1); + LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGDIFOPID)), 1); return; } @@ -407,7 +407,7 @@ inline bool Decoder::processMsopPkt(const uint8_t* pkt, size_t siz if (this->point_cloud_ && (this->point_cloud_->points.size() > CLOUD_POINT_MAX)) { - LIMIT_CALL(this->cb_excep_(Error(ERRCODE_CLOUDBUFOVERFLOW)), 1); + LIMIT_CALL(this->cb_excep_(Error(ERRCODE_CLOUDSIZEOVERFLOW)), 1); } if (param_.wait_for_difop && !angles_ready_) @@ -418,13 +418,13 @@ inline bool Decoder::processMsopPkt(const uint8_t* pkt, size_t siz if (size != this->const_param_.MSOP_LEN) { - LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGPKTLENGTH)), 1); + LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGMSOPLEN)), 1); return false; } if (memcmp(pkt, this->const_param_.MSOP_ID, this->const_param_.MSOP_ID_LEN) != 0) { - LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)), 1); + LIMIT_CALL(this->cb_excep_(Error(ERRCODE_WRONGMSOPID)), 1); return false; } diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 37235bc5..064a5ad5 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -241,7 +241,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 41deb0f9..e49b3557 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -277,7 +277,7 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index c64e831d..f67d8d25 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -260,7 +260,7 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGMSOPID)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RS48.hpp b/src/rs_driver/driver/decoder/decoder_RS48.hpp index ba5805cc..be4ccc9a 100644 --- a/src/rs_driver/driver/decoder/decoder_RS48.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS48.hpp @@ -190,7 +190,7 @@ inline bool DecoderRS48::internDecodeMsopPkt(const uint8_t* packet if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 08667c57..9aead54c 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -236,7 +236,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index fb32bf4e..430b7369 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -231,7 +231,7 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index d59356cc..115caafa 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -243,7 +243,7 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp index 0a14d03a..932881ec 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp @@ -209,7 +209,7 @@ inline bool DecoderRSHELIOS_16P::internDecodeMsopPkt(const uint8_t if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RSP128.hpp b/src/rs_driver/driver/decoder/decoder_RSP128.hpp index 96a484b2..65817c79 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP128.hpp @@ -246,7 +246,7 @@ inline bool DecoderRSP128::internDecodeMsopPkt(const uint8_t* pack if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RSP48.hpp b/src/rs_driver/driver/decoder/decoder_RSP48.hpp index 82eb05ea..fdfc9097 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP48.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP48.hpp @@ -235,7 +235,7 @@ inline bool DecoderRSP48::internDecodeMsopPkt(const uint8_t* packe if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); break; } diff --git a/src/rs_driver/driver/decoder/decoder_RSP80.hpp b/src/rs_driver/driver/decoder/decoder_RSP80.hpp index 3343a63c..41398971 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP80.hpp @@ -279,7 +279,7 @@ inline bool DecoderRSP80::internDecodeMsopPkt(const uint8_t* packe if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGPKTHEADER)); + this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); break; } From 12403d787fd7679c00d12b0fb9e53e2ebccab95f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 10 Aug 2022 15:08:42 +0800 Subject: [PATCH 332/379] feat: rename error code CLOUDOVERFLOW --- src/rs_driver/common/error_code.hpp | 42 ++++++++++++------------ src/rs_driver/driver/decoder/decoder.hpp | 2 +- 2 files changed, 22 insertions(+), 22 deletions(-) diff --git a/src/rs_driver/common/error_code.hpp b/src/rs_driver/common/error_code.hpp index d124a49c..0e66b3d3 100644 --- a/src/rs_driver/common/error_code.hpp +++ b/src/rs_driver/common/error_code.hpp @@ -56,29 +56,29 @@ enum class ErrCodeType enum ErrCode { // info - ERRCODE_SUCCESS = 0x00, ///< Normal - ERRCODE_PCAPREPEAT = 0x01, ///< Pcap file will play repeatedly - ERRCODE_PCAPEXIT = 0x02, ///< Pcap thread will exit + ERRCODE_SUCCESS = 0x00, ///< Normal + ERRCODE_PCAPREPEAT = 0x01, ///< Pcap file will play repeatedly + ERRCODE_PCAPEXIT = 0x02, ///< Pcap thread will exit // warning - ERRCODE_MSOPTIMEOUT = 0x40, ///< Msop packets receive overtime (1 sec) - ERRCODE_DIFOPTIMEOUT = 0x41, ///< Difop packets receive overtime (2 sec) - ERRCODE_NODIFOPRECV = 0x42, ///< Point cloud decoding process will not start until the difop packet receive - ERRCODE_WRONGMSOPID = 0x43, ///< Packet header is wrong - ERRCODE_WRONGMSOPLEN = 0x44, ///< Packet length is wrong - ERRCODE_WRONGMSOPBLKID = 0x45, ///< Packet header is wrong - ERRCODE_WRONGDIFOPID = 0x46, ///< Packet header is wrong - ERRCODE_WRONGDIFOPLEN = 0x47, ///< Packet length is wrong - ERRCODE_ZEROPOINTS = 0x48, ///< Size of the point cloud is zero - ERRCODE_PKTBUFOVERFLOW = 0x49, ///< Packet buffer is overflow - ERRCODE_CLOUDSIZEOVERFLOW = 0x4a, ///< Point cloud buffer is overflow + ERRCODE_MSOPTIMEOUT = 0x40, ///< Msop packets receive overtime (1 sec) + ERRCODE_DIFOPTIMEOUT = 0x41, ///< Difop packets receive overtime (2 sec) + ERRCODE_NODIFOPRECV = 0x42, ///< Point cloud decoding process will not start until the difop packet receive + ERRCODE_WRONGMSOPID = 0x43, ///< Packet header is wrong + ERRCODE_WRONGMSOPLEN = 0x44, ///< Packet length is wrong + ERRCODE_WRONGMSOPBLKID = 0x45, ///< Packet header is wrong + ERRCODE_WRONGDIFOPID = 0x46, ///< Packet header is wrong + ERRCODE_WRONGDIFOPLEN = 0x47, ///< Packet length is wrong + ERRCODE_ZEROPOINTS = 0x48, ///< Size of the point cloud is zero + ERRCODE_PKTBUFOVERFLOW = 0x49, ///< Packet buffer is overflow + ERRCODE_CLOUDOVERFLOW = 0x4a, ///< Point cloud buffer is overflow // error - ERRCODE_STARTBEFOREINIT = 0x80, ///< start() function is called before initializing successfully - ERRCODE_MSOPPORTBUZY = 0x81, ///< Input msop port is already used - ERRCODE_DIFOPPORTBUZY = 0x82, ///< Input difop port is already used - ERRCODE_PCAPWRONGPATH = 0x83, ///< Input directory of pcap file is wrong - ERRCODE_POINTCLOUDNULL = 0x84, ///< PointCloud buffer is invalid + ERRCODE_STARTBEFOREINIT = 0x80, ///< start() function is called before initializing successfully + ERRCODE_MSOPPORTBUZY = 0x81, ///< Input msop port is already used + ERRCODE_DIFOPPORTBUZY = 0x82, ///< Input difop port is already used + ERRCODE_PCAPWRONGPATH = 0x83, ///< Input directory of pcap file is wrong + ERRCODE_POINTCLOUDNULL = 0x84, ///< PointCloud buffer is invalid }; struct Error @@ -149,8 +149,8 @@ struct Error return "ERRCODE_POINTCLOUDNULL"; case ERRCODE_PKTBUFOVERFLOW: return "ERRCODE_PKTBUFOVERFLOW"; - case ERRCODE_CLOUDSIZEOVERFLOW: - return "ERRCODE_CLOUDSIZEOVERFLOW"; + case ERRCODE_CLOUDOVERFLOW: + return "ERRCODE_CLOUDOVERFLOW"; //default default: diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index 65dbcc5a..d3d0f2f2 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -407,7 +407,7 @@ inline bool Decoder::processMsopPkt(const uint8_t* pkt, size_t siz if (this->point_cloud_ && (this->point_cloud_->points.size() > CLOUD_POINT_MAX)) { - LIMIT_CALL(this->cb_excep_(Error(ERRCODE_CLOUDSIZEOVERFLOW)), 1); + LIMIT_CALL(this->cb_excep_(Error(ERRCODE_CLOUDOVERFLOW)), 1); } if (param_.wait_for_difop && !angles_ready_) From 6a4fc3d612468392057e82a89d1829d10b3b42ef Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 12 Aug 2022 09:56:19 +0800 Subject: [PATCH 333/379] feat: recover RSM2 to ros coordinate --- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index a40bb0e9..62376f68 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -75,6 +75,8 @@ typedef struct RSM2MsopHeader header; RSM2Block blocks[25]; uint8_t reserved[4]; + uint8_t crc32[4]; + uint8_t rolling_counter[4]; } RSM2MsopPkt; #pragma pack(pop) @@ -107,7 +109,7 @@ inline RSDecoderConstParam& DecoderRSM2::getConstParam() { static RSDecoderConstParam param = { - 1336 // msop len + 1342 // msop len , 256 // difop len , 4 // msop id len , 8 // difop id len @@ -204,9 +206,9 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size if (this->distance_section_.in(distance)) { - float x = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; - float y = - RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; - float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; + float x = RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; + float y = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; + float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; this->transformPoint(x, y, z); From a131c391ca030841ecb0ec57b0046a7bf74ecbfb Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 12 Aug 2022 11:30:59 +0800 Subject: [PATCH 334/379] feat: use cloud queue for demo_pcan and rs_driver_viewer --- demo/demo_online.cpp | 2 +- demo/demo_pcap.cpp | 44 ++++++++++++++++++++++++++++-- tool/rs_driver_viewer.cpp | 57 ++++++++++++++++++++++++++++++++------- 3 files changed, 91 insertions(+), 12 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index b70d24bf..b0a14f4c 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -122,7 +122,7 @@ int main(int argc, char* argv[]) param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct param.print(); - LidarDriver driver; + LidarDriver driver; ///< Declare the driver object driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback function driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function if (!driver.init(param)) ///< Call the init function diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 80964903..1b7632e7 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -38,11 +38,16 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #endif +//#define ORDERLY_EXIT + typedef PointXYZI PointT; typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; +SyncQueue> free_cloud_queue; +SyncQueue> cloud_queue; + // // @brief point cloud callback function. The caller should register it to the lidar driver. // Via this fucntion, the driver fetches an EMPTY point cloud message from the caller. @@ -52,6 +57,12 @@ std::shared_ptr pointCloudGetCallback(void) { // Note: This callback function runs in the packet-parsing thread of the driver, // so please DO NOT do time-consuming task here. + std::shared_ptr msg = free_cloud_queue.pop(); + if (msg.get() != NULL) + { + return msg; + } + return std::make_shared(); } @@ -64,7 +75,7 @@ void pointCloudPutCallback(std::shared_ptr msg) { // Note: This callback function runs in the packet-parsing thread of the driver, // so please DO NOT do time-consuming task here. Instead, process it in another thread. - RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; + cloud_queue.push(msg); } // @@ -78,19 +89,38 @@ void exceptionCallback(const Error& code) RS_WARNING << code.toString() << RS_REND; } +bool to_exit_process = false; +void processCloud(void) +{ + while (!to_exit_process) + { + std::shared_ptr msg = cloud_queue.popWait(); + if (msg.get() == NULL) + { + continue; + } + + // process the point cloud msg, even it is time-consuming + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; + + free_cloud_queue.push(msg); + } +} + int main(int argc, char* argv[]) { RS_TITLE << "------------------------------------------------------" << RS_REND; RS_TITLE << " RS_Driver Core Version: v" << getDriverVersion() << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; + std::thread cloud_handle_thread = std::thread(processCloud); + RSDriverParam param; ///< Create a parameter object param.input_type = InputType::PCAP_FILE; param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file directory param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct - param.print(); LidarDriver driver; ///< Declare the driver object @@ -101,13 +131,23 @@ int main(int argc, char* argv[]) RS_ERROR << "Driver Initialize Error..." << RS_REND; return -1; } + driver.start(); ///< The driver thread will start RS_DEBUG << "RoboSense Lidar-Driver Linux pcap demo start......" << RS_REND; +#ifdef ORDERLY_EXIT + std::this_thread::sleep_for(std::chrono::seconds(10)); + + driver.stop(); + + to_exit_process = true; + cloud_handle_thread.join(); +#else while (true) { std::this_thread::sleep_for(std::chrono::seconds(1)); } +#endif return 0; } diff --git a/tool/rs_driver_viewer.cpp b/tool/rs_driver_viewer.cpp index a1691710..7b5ab00a 100644 --- a/tool/rs_driver_viewer.cpp +++ b/tool/rs_driver_viewer.cpp @@ -44,6 +44,9 @@ typedef PointCloudT PointCloudMsg; std::shared_ptr pcl_viewer; std::mutex mtx_viewer; +SyncQueue> free_cloud_queue; +SyncQueue> cloud_queue; + bool checkKeywordExist(int argc, const char* const* argv, const char* str) { for (int i = 1; i < argc; i++) @@ -172,25 +175,53 @@ void exceptionCallback(const Error& code) std::shared_ptr pointCloudGetCallback(void) { + std::shared_ptr msg = free_cloud_queue.pop(); + if (msg.get() != NULL) + { + return msg; + } + return std::make_shared(); } void pointCloudPutCallback(std::shared_ptr msg) { - pcl::PointCloud::Ptr pcl_pointcloud(new pcl::PointCloud); - pcl_pointcloud->points.swap(msg->points); - pcl_pointcloud->height = msg->height; - pcl_pointcloud->width = msg->width; - pcl_pointcloud->is_dense = msg->is_dense; - - PointCloudColorHandlerGenericField point_color_handle(pcl_pointcloud, "intensity"); + cloud_queue.push(msg); +} +bool to_exit_process = false; +void processCloud(void) +{ + while (!to_exit_process) { - const std::lock_guard lock(mtx_viewer); - pcl_viewer->updatePointCloud(pcl_pointcloud, point_color_handle, "rslidar"); + std::shared_ptr msg = cloud_queue.popWait(); + if (msg.get() == NULL) + { + continue; + } + + // + // show the point cloud + // + pcl::PointCloud::Ptr pcl_pointcloud(new pcl::PointCloud); + pcl_pointcloud->points.swap(msg->points); + pcl_pointcloud->height = msg->height; + pcl_pointcloud->width = msg->width; + pcl_pointcloud->is_dense = msg->is_dense; + + PointCloudColorHandlerGenericField point_color_handle(pcl_pointcloud, "intensity"); + + { + const std::lock_guard lock(mtx_viewer); + pcl_viewer->updatePointCloud(pcl_pointcloud, point_color_handle, "rslidar"); + } + + free_cloud_queue.push(msg); } } + + int main(int argc, char* argv[]) { RS_TITLE << "------------------------------------------------------" << RS_REND; @@ -209,6 +240,8 @@ int main(int argc, char* argv[]) return 0; } + std::thread cloud_handle_thread = std::thread(processCloud); + RSDriverParam param; parseParam(argc, argv, param); param.print(); @@ -240,9 +273,15 @@ int main(int argc, char* argv[]) const std::lock_guard lock(mtx_viewer); pcl_viewer->spinOnce(); } + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } + driver.stop(); + + to_exit_process = true; + cloud_handle_thread.join(); + return 0; } From 3d73801d3525314cc9de9210106c1999423b8eef Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 12 Aug 2022 11:55:21 +0800 Subject: [PATCH 335/379] feat: add option ENABLE_DOUBLE_RCVBUF to InputSock of windows version --- src/rs_driver/driver/input/win/input_sock_select.hpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/rs_driver/driver/input/win/input_sock_select.hpp b/src/rs_driver/driver/input/win/input_sock_select.hpp index fbb4e177..7f2ff562 100644 --- a/src/rs_driver/driver/input/win/input_sock_select.hpp +++ b/src/rs_driver/driver/input/win/input_sock_select.hpp @@ -196,6 +196,16 @@ inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, con } } +#ifdef ENABLE_DOUBLE_RCVBUF + { + uint32_t opt_val; + socklen_t opt_len = sizeof(uint32_t); + getsockopt(fd, SOL_SOCKET, SO_RCVBUF, (char*)&opt_val, &opt_len); + opt_val *= 4; + setsockopt(fd, SOL_SOCKET, SO_RCVBUF, (char*)&opt_val, opt_len); + } +#endif + { u_long mode = 1; ret = ioctlsocket(fd, FIONBIO, &mode); From 7174fa487c32aba27526ded5a1b41da9e9b5d489 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 12 Aug 2022 12:59:56 +0800 Subject: [PATCH 336/379] feat: support x64 debug/release mode on windows --- win/rs_driver_viewer/rs_driver_viewer.vcxproj | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/win/rs_driver_viewer/rs_driver_viewer.vcxproj b/win/rs_driver_viewer/rs_driver_viewer.vcxproj index a1b05a6e..5de8a52d 100644 --- a/win/rs_driver_viewer/rs_driver_viewer.vcxproj +++ b/win/rs_driver_viewer/rs_driver_viewer.vcxproj @@ -78,6 +78,8 @@ true + C:\Program Files\WpdPack_4_1_2\WpdPack\Include;C:\Program Files\PCL 1.11.1\include\pcl-1.11;C:\Program Files\PCL 1.11.1\3rdParty\Boost\include\boost-1_74;C:\Program Files\PCL 1.11.1\3rdParty\Eigen\eigen3;C:\Program Files\PCL 1.11.1\3rdParty\FLANN\include;C:\Program Files\PCL 1.11.1\3rdParty\Qhull\include;C:\Program Files\PCL 1.11.1\3rdParty\VTK\include\vtk-8.2;C:\Program Files\OpenNI2\Include;$(IncludePath) + C:\Program Files\WpdPack_4_1_2\WpdPack\Lib\x64;C:\Program Files\PCL 1.11.1\lib;C:\Program Files\PCL 1.11.1\3rdParty\Boost\lib;C:\Program Files\PCL 1.11.1\3rdParty\FLANN\lib;C:\Program Files\PCL 1.11.1\3rdParty\Qhull\lib;C:\Program Files\PCL 1.11.1\3rdParty\VTK\lib;C:\Program Files\OpenNI2\Lib;$(LibraryPath) false @@ -115,13 +117,15 @@ Level3 - true - _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + false + BOOST_USE_WINDOWS_H;NOMINMAX;_CRT_SECURE_NO_DEPRECATE;_CRT_SECURE_NO_WARNINGS;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) true + ../../src Console true + wpcap.lib;ws2_32.lib;vtkChartsCore-8.2.lib;vtkCommonColor-8.2.lib;vtkCommonComputationalGeometry-8.2.lib;vtkCommonCore-8.2.lib;vtkCommonDataModel-8.2.lib;vtkCommonExecutionModel-8.2.lib;vtkCommonMath-8.2.lib;vtkCommonMisc-8.2.lib;vtkCommonSystem-8.2.lib;vtkCommonTransforms-8.2.lib;vtkDICOMParser-8.2.lib;vtkDomainsChemistry-8.2.lib;vtkDomainsChemistryOpenGL2-8.2.lib;vtkdoubleconversion-8.2.lib;vtkexodusII-8.2.lib;vtkexpat-8.2.lib;vtkFiltersAMR-8.2.lib;vtkFiltersCore-8.2.lib;vtkFiltersExtraction-8.2.lib;vtkFiltersFlowPaths-8.2.lib;vtkFiltersGeneral-8.2.lib;vtkFiltersGeneric-8.2.lib;vtkFiltersGeometry-8.2.lib;vtkFiltersHybrid-8.2.lib;vtkFiltersHyperTree-8.2.lib;vtkFiltersImaging-8.2.lib;vtkFiltersModeling-8.2.lib;vtkFiltersParallel-8.2.lib;vtkFiltersParallelImaging-8.2.lib;vtkFiltersPoints-8.2.lib;vtkFiltersProgrammable-8.2.lib;vtkFiltersSelection-8.2.lib;vtkFiltersSMP-8.2.lib;vtkFiltersSources-8.2.lib;vtkFiltersStatistics-8.2.lib;vtkFiltersTexture-8.2.lib;vtkFiltersTopology-8.2.lib;vtkFiltersVerdict-8.2.lib;vtkfreetype-8.2.lib;vtkGeovisCore-8.2.lib;vtkgl2ps-8.2.lib;vtkglew-8.2.lib;vtkGUISupportMFC-8.2.lib;vtkhdf5-8.2.lib;vtkhdf5_hl-8.2.lib;vtkImagingColor-8.2.lib;vtkImagingCore-8.2.lib;vtkImagingFourier-8.2.lib;vtkImagingGeneral-8.2.lib;vtkImagingHybrid-8.2.lib;vtkImagingMath-8.2.lib;vtkImagingMorphological-8.2.lib;vtkImagingSources-8.2.lib;vtkImagingStatistics-8.2.lib;vtkImagingStencil-8.2.lib;vtkInfovisCore-8.2.lib;vtkInfovisLayout-8.2.lib;vtkInteractionImage-8.2.lib;vtkInteractionStyle-8.2.lib;vtkInteractionWidgets-8.2.lib;vtkIOAMR-8.2.lib;vtkIOAsynchronous-8.2.lib;vtkIOCityGML-8.2.lib;vtkIOCore-8.2.lib;vtkIOEnSight-8.2.lib;vtkIOExodus-8.2.lib;vtkIOExport-8.2.lib;vtkIOExportOpenGL2-8.2.lib;vtkIOExportPDF-8.2.lib;vtkIOGeometry-8.2.lib;vtkIOImage-8.2.lib;vtkIOImport-8.2.lib;vtkIOInfovis-8.2.lib;vtkIOLegacy-8.2.lib;vtkIOLSDyna-8.2.lib;vtkIOMINC-8.2.lib;vtkIOMovie-8.2.lib;vtkIONetCDF-8.2.lib;vtkIOParallel-8.2.lib;vtkIOParallelXML-8.2.lib;vtkIOPLY-8.2.lib;vtkIOSegY-8.2.lib;vtkIOSQL-8.2.lib;vtkIOTecplotTable-8.2.lib;vtkIOVeraOut-8.2.lib;vtkIOVideo-8.2.lib;vtkIOXML-8.2.lib;vtkIOXMLParser-8.2.lib;vtkjpeg-8.2.lib;vtkjsoncpp-8.2.lib;vtklibharu-8.2.lib;vtklibxml2-8.2.lib;vtklz4-8.2.lib;vtklzma-8.2.lib;vtkmetaio-8.2.lib;vtkNetCDF-8.2.lib;vtkogg-8.2.lib;vtkParallelCore-8.2.lib;vtkpng-8.2.lib;vtkproj-8.2.lib;vtkpugixml-8.2.lib;vtkRenderingAnnotation-8.2.lib;vtkRenderingContext2D-8.2.lib;vtkRenderingContextOpenGL2-8.2.lib;vtkRenderingCore-8.2.lib;vtkRenderingExternal-8.2.lib;vtkRenderingFreeType-8.2.lib;vtkRenderingGL2PSOpenGL2-8.2.lib;vtkRenderingImage-8.2.lib;vtkRenderingLabel-8.2.lib;vtkRenderingLOD-8.2.lib;vtkRenderingOpenGL2-8.2.lib;vtkRenderingVolume-8.2.lib;vtkRenderingVolumeOpenGL2-8.2.lib;vtksqlite-8.2.lib;vtksys-8.2.lib;vtktheora-8.2.lib;vtktiff-8.2.lib;vtkverdict-8.2.lib;vtkViewsContext2D-8.2.lib;vtkViewsCore-8.2.lib;vtkViewsInfovis-8.2.lib;vtkzlib-8.2.lib;pcl_common.lib;pcl_commond.lib;pcl_features.lib;pcl_featuresd.lib;pcl_filters.lib;pcl_filtersd.lib;pcl_io.lib;pcl_iod.lib;pcl_io_ply.lib;pcl_io_plyd.lib;pcl_kdtree.lib;pcl_kdtreed.lib;pcl_keypoints.lib;pcl_keypointsd.lib;pcl_ml.lib;pcl_mld.lib;pcl_octree.lib;pcl_octreed.lib;pcl_outofcore.lib;pcl_outofcored.lib;pcl_people.lib;pcl_peopled.lib;pcl_recognition.lib;pcl_recognitiond.lib;pcl_registration.lib;pcl_registrationd.lib;pcl_sample_consensus.lib;pcl_sample_consensusd.lib;pcl_search.lib;pcl_searchd.lib;pcl_segmentation.lib;pcl_segmentationd.lib;pcl_stereo.lib;pcl_stereod.lib;pcl_surface.lib;pcl_surfaced.lib;pcl_tracking.lib;pcl_trackingd.lib;pcl_visualization.lib;pcl_visualizationd.lib;%(AdditionalDependencies) From 046e883940705e622f7a2a012fb252c3ef148701 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 12 Aug 2022 18:59:06 +0800 Subject: [PATCH 337/379] format: rename variables,etc --- src/rs_driver/common/error_code.hpp | 3 ++- src/rs_driver/driver/decoder/decoder.hpp | 2 -- src/rs_driver/driver/decoder/decoder_RSEOS.hpp | 12 ++++++++---- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 10 +++++++--- .../driver/decoder/decoder_factory.hpp | 2 ++ src/rs_driver/driver/decoder/trigon.hpp | 18 +++++++++--------- src/rs_driver/driver/lidar_driver_impl.hpp | 2 +- src/rs_driver/utility/buffer.hpp | 2 ++ src/rs_driver/utility/sync_queue.hpp | 16 ++++++++++------ tool/rs_driver_viewer.cpp | 2 -- 10 files changed, 41 insertions(+), 28 deletions(-) diff --git a/src/rs_driver/common/error_code.hpp b/src/rs_driver/common/error_code.hpp index 0e66b3d3..4a56470c 100644 --- a/src/rs_driver/common/error_code.hpp +++ b/src/rs_driver/common/error_code.hpp @@ -91,7 +91,8 @@ struct Error { } - explicit Error(const ErrCode& code) : error_code(code) + explicit Error(const ErrCode& code) + : error_code(code) { if (error_code < 0x40) { diff --git a/src/rs_driver/driver/decoder/decoder.hpp b/src/rs_driver/driver/decoder/decoder.hpp index d3d0f2f2..41682c87 100644 --- a/src/rs_driver/driver/decoder/decoder.hpp +++ b/src/rs_driver/driver/decoder/decoder.hpp @@ -252,8 +252,6 @@ class Decoder EIGEN_MAKE_ALIGNED_OPERATOR_NEW #endif - constexpr static uint16_t PROTOCOL_VER_0 = 0x00; - virtual void decodeDifopPkt(const uint8_t* pkt, size_t size) = 0; virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size) = 0; virtual ~Decoder() = default; diff --git a/src/rs_driver/driver/decoder/decoder_RSEOS.hpp b/src/rs_driver/driver/decoder/decoder_RSEOS.hpp index 4d7995ef..abb5bf38 100644 --- a/src/rs_driver/driver/decoder/decoder_RSEOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSEOS.hpp @@ -84,7 +84,7 @@ class DecoderRSEOS : public Decoder public: constexpr static double FRAME_DURATION = 0.1; - constexpr static uint32_t SINGLE_PKT_NUM = 112; //126 + constexpr static uint32_t SINGLE_PKT_NUM = 112; constexpr static int VECTOR_BASE = 32768; virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); @@ -201,9 +201,13 @@ inline bool DecoderRSEOS::decodeMsopPkt(const uint8_t* packet, siz if (this->distance_section_.in(distance)) { - float x = RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; - float y = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; - float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; + int16_t vector_x = RS_SWAP_INT16(channel.x); + int16_t vector_y = RS_SWAP_INT16(channel.y); + int16_t vector_z = RS_SWAP_INT16(channel.z); + + float x = vector_x * distance / VECTOR_BASE; + float y = vector_y * distance / VECTOR_BASE; + float z = vector_z * distance / VECTOR_BASE; this->transformPoint(x, y, z); diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index 62376f68..17a5b97d 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -206,9 +206,13 @@ inline bool DecoderRSM2::decodeMsopPkt(const uint8_t* packet, size if (this->distance_section_.in(distance)) { - float x = RS_SWAP_INT16(channel.x) * distance / VECTOR_BASE; - float y = RS_SWAP_INT16(channel.y) * distance / VECTOR_BASE; - float z = RS_SWAP_INT16(channel.z) * distance / VECTOR_BASE; + int16_t vector_x = RS_SWAP_INT16(channel.x); + int16_t vector_y = RS_SWAP_INT16(channel.y); + int16_t vector_z = RS_SWAP_INT16(channel.z); + + float x = vector_x * distance / VECTOR_BASE; + float y = vector_y * distance / VECTOR_BASE; + float z = vector_z * distance / VECTOR_BASE; this->transformPoint(x, y, z); diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 4609abb4..46327c76 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -31,6 +31,8 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once + +#include #include #include #include diff --git a/src/rs_driver/driver/decoder/trigon.hpp b/src/rs_driver/driver/decoder/trigon.hpp index 8cecca32..b2d73a90 100644 --- a/src/rs_driver/driver/decoder/trigon.hpp +++ b/src/rs_driver/driver/decoder/trigon.hpp @@ -47,19 +47,19 @@ class Trigon { public: - constexpr static int32_t MIN = -9000; - constexpr static int32_t MAX = 45000; + constexpr static int32_t ANGLE_MIN = -9000; + constexpr static int32_t ANGLE_MAX = 45000; Trigon() { - int32_t range = MAX - MIN; + int32_t range = ANGLE_MAX - ANGLE_MIN; #ifdef DBG o_angles_ = (int32_t*)malloc(range * sizeof(int32_t)); #endif o_sins_ = (float*)malloc(range * sizeof(float)); o_coss_ = (float*)malloc(range * sizeof(float)); - for (int32_t i = MIN, j = 0; i < MAX; i++, j++) + for (int32_t i = ANGLE_MIN, j = 0; i < ANGLE_MAX; i++, j++) { double rad = DEGREE_TO_RADIAN(static_cast(i) * 0.01); @@ -71,10 +71,10 @@ class Trigon } #ifdef DBG - angles_ = o_angles_ - MIN; + angles_ = o_angles_ - ANGLE_MIN; #endif - sins_ = o_sins_ - MIN; - coss_ = o_coss_ - MIN; + sins_ = o_sins_ - ANGLE_MIN; + coss_ = o_coss_ - ANGLE_MIN; } ~Trigon() @@ -88,7 +88,7 @@ class Trigon float sin(int32_t angle) { - if (angle < MIN || angle >= MAX) + if (angle < ANGLE_MIN || angle >= ANGLE_MAX) { angle = 0; } @@ -98,7 +98,7 @@ class Trigon float cos(int32_t angle) { - if (angle < MIN || angle >= MAX) + if (angle < ANGLE_MIN || angle >= ANGLE_MAX) { angle = 0; } diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index e5e647ab..c4392373 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -31,12 +31,12 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *********************************************************************************************************************/ #pragma once + #include #include #include #include #include - #include #include #include diff --git a/src/rs_driver/utility/buffer.hpp b/src/rs_driver/utility/buffer.hpp index 12a5ebd8..32eb0a0f 100644 --- a/src/rs_driver/utility/buffer.hpp +++ b/src/rs_driver/utility/buffer.hpp @@ -51,6 +51,8 @@ class Buffer buf_size_ = buf_size; } + ~Buffer() = default; + uint8_t* buf() { return buf_.data(); diff --git a/src/rs_driver/utility/sync_queue.hpp b/src/rs_driver/utility/sync_queue.hpp index 81798980..dd0e38de 100644 --- a/src/rs_driver/utility/sync_queue.hpp +++ b/src/rs_driver/utility/sync_queue.hpp @@ -32,10 +32,10 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #pragma once -#include #include #include #include +#include namespace robosense { @@ -47,16 +47,20 @@ class SyncQueue public: inline size_t push(const T& value) { - std::lock_guard lg(mtx_); - - bool empty = queue_.empty(); + bool empty = false; + size_t size = 0; - queue_.push(value); + { + std::lock_guard lg(mtx_); + empty = queue_.empty(); + queue_.push(value); + size = queue_.size(); + } if (empty) cv_.notify_one(); - return queue_.size(); + return size; } inline T pop() diff --git a/tool/rs_driver_viewer.cpp b/tool/rs_driver_viewer.cpp index 7b5ab00a..a09a519d 100644 --- a/tool/rs_driver_viewer.cpp +++ b/tool/rs_driver_viewer.cpp @@ -220,8 +220,6 @@ void processCloud(void) } } - - int main(int argc, char* argv[]) { RS_TITLE << "------------------------------------------------------" << RS_REND; From 93be348321865cf996b005cae12113d8926b762b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 15 Aug 2022 11:36:04 +0800 Subject: [PATCH 338/379] feat: accept angle.csv with vert angle only --- src/rs_driver/driver/decoder/chan_angles.hpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/src/rs_driver/driver/decoder/chan_angles.hpp b/src/rs_driver/driver/decoder/chan_angles.hpp index 80cc49b6..5673cef2 100644 --- a/src/rs_driver/driver/decoder/chan_angles.hpp +++ b/src/rs_driver/driver/decoder/chan_angles.hpp @@ -172,9 +172,14 @@ class ChanAngles if (!std::getline(fd, line)) return -1; - size_t pos_comma = 0; - float vert = std::stof(line, &pos_comma); - float horiz = std::stof(line.substr(pos_comma+1)); + float vert = std::stof(line); + + float horiz = 0; + size_t pos_comma = line.find_first_of(','); + if (pos_comma != std::string::npos) + { + horiz = std::stof(line.substr(pos_comma+1)); + } vert_angles.emplace_back(static_cast(vert * 100)); horiz_angles.emplace_back(static_cast(horiz * 100)); From 527e10544161bdbf785dcf71d6b70f639309c777 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 15 Aug 2022 17:04:00 +0800 Subject: [PATCH 339/379] fix: fix inaccurate cloud timestamp when ts_first_point is true --- src/rs_driver/driver/decoder/decoder_RS128.hpp | 15 +++++++-------- src/rs_driver/driver/decoder/decoder_RS16.hpp | 14 +++++++------- src/rs_driver/driver/decoder/decoder_RS32.hpp | 14 +++++++------- src/rs_driver/driver/decoder/decoder_RS48.hpp | 14 +++++++------- src/rs_driver/driver/decoder/decoder_RS80.hpp | 14 +++++++------- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 14 +++++++------- src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp | 14 +++++++------- .../driver/decoder/decoder_RSHELIOS_16P.hpp | 14 +++++++------- src/rs_driver/driver/decoder/decoder_RSP128.hpp | 14 +++++++------- src/rs_driver/driver/decoder/decoder_RSP48.hpp | 14 +++++++------- src/rs_driver/driver/decoder/decoder_RSP80.hpp | 14 +++++++------- 11 files changed, 77 insertions(+), 78 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 064a5ad5..3dc1a0e5 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -234,7 +234,6 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); - double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RS128MsopBlock& block = pkt.blocks[blk]; @@ -245,23 +244,23 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe break; } + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + double block_ts = pkt_ts + block_ts_off; int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); - this->first_point_ts_ = pkt_ts; + this->first_point_ts_ = block_ts; ret = true; } - int32_t block_az_diff; - double block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; - - double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index e49b3557..5b33b415 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -270,7 +270,6 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); - double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RS16MsopBlock& block = pkt.blocks[blk]; @@ -281,23 +280,24 @@ inline bool DecoderRS16::internDecodeMsopPkt(const uint8_t* packet break; } + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + double block_ts = pkt_ts + block_ts_off; int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); - this->first_point_ts_ = pkt_ts; + this->first_point_ts_ = block_ts; ret = true; } - int32_t block_az_diff; - double block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index f67d8d25..9ff0435f 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -253,7 +253,6 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); - double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RS32MsopBlock& block = pkt.blocks[blk]; @@ -264,23 +263,24 @@ inline bool DecoderRS32::internDecodeMsopPkt(const uint8_t* packet break; } + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + double block_ts = pkt_ts + block_ts_off; int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); - this->first_point_ts_ = pkt_ts; + this->first_point_ts_ = block_ts; ret = true; } - int32_t block_az_diff; - double block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); diff --git a/src/rs_driver/driver/decoder/decoder_RS48.hpp b/src/rs_driver/driver/decoder/decoder_RS48.hpp index be4ccc9a..dd8db05e 100644 --- a/src/rs_driver/driver/decoder/decoder_RS48.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS48.hpp @@ -183,7 +183,6 @@ inline bool DecoderRS48::internDecodeMsopPkt(const uint8_t* packet T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); - double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSP48MsopBlock& block = pkt.blocks[blk]; @@ -194,23 +193,24 @@ inline bool DecoderRS48::internDecodeMsopPkt(const uint8_t* packet break; } + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + double block_ts = pkt_ts + block_ts_off; int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); - this->first_point_ts_ = pkt_ts; + this->first_point_ts_ = block_ts; ret = true; } - int32_t block_az_diff; - double block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 9aead54c..e01d1c95 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -229,7 +229,6 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); - double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RS80MsopBlock& block = pkt.blocks[blk]; @@ -240,23 +239,24 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet break; } + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + double block_ts = pkt_ts + block_ts_off; int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); - this->first_point_ts_ = pkt_ts; + this->first_point_ts_ = block_ts; ret = true; } - int32_t block_az_diff; - double block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 430b7369..0adbe344 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -224,7 +224,6 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); - double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSBPMsopBlock& block = pkt.blocks[blk]; @@ -235,23 +234,24 @@ inline bool DecoderRSBP::internDecodeMsopPkt(const uint8_t* packet break; } + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + double block_ts = pkt_ts + block_ts_off; int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); - this->first_point_ts_ = pkt_ts; + this->first_point_ts_ = block_ts; ret = true; } - int32_t block_az_diff; - double block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 115caafa..770b0102 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -236,7 +236,6 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); - double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSHELIOSMsopBlock& block = pkt.blocks[blk]; @@ -247,23 +246,24 @@ inline bool DecoderRSHELIOS::internDecodeMsopPkt(const uint8_t* pa break; } + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + double block_ts = pkt_ts + block_ts_off; int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); - this->first_point_ts_ = pkt_ts; + this->first_point_ts_ = block_ts; ret = true; } - int32_t block_az_diff; - double block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp index 932881ec..97602fbe 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp @@ -202,7 +202,6 @@ inline bool DecoderRSHELIOS_16P::internDecodeMsopPkt(const uint8_t T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); - double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSHELIOSMsopBlock& block = pkt.blocks[blk]; @@ -213,23 +212,24 @@ inline bool DecoderRSHELIOS_16P::internDecodeMsopPkt(const uint8_t break; } + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + double block_ts = pkt_ts + block_ts_off; int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); - this->first_point_ts_ = pkt_ts; + this->first_point_ts_ = block_ts; ret = true; } - int32_t block_az_diff; - double block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); diff --git a/src/rs_driver/driver/decoder/decoder_RSP128.hpp b/src/rs_driver/driver/decoder/decoder_RSP128.hpp index 65817c79..efcdd63e 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP128.hpp @@ -239,7 +239,6 @@ inline bool DecoderRSP128::internDecodeMsopPkt(const uint8_t* pack T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); - double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSP128MsopBlock& block = pkt.blocks[blk]; @@ -250,23 +249,24 @@ inline bool DecoderRSP128::internDecodeMsopPkt(const uint8_t* pack break; } + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + double block_ts = pkt_ts + block_ts_off; int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); - this->first_point_ts_ = pkt_ts; + this->first_point_ts_ = block_ts; ret = true; } - int32_t block_az_diff; - double block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); diff --git a/src/rs_driver/driver/decoder/decoder_RSP48.hpp b/src/rs_driver/driver/decoder/decoder_RSP48.hpp index fdfc9097..617a67c5 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP48.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP48.hpp @@ -228,7 +228,6 @@ inline bool DecoderRSP48::internDecodeMsopPkt(const uint8_t* packe T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); - double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSP48MsopBlock& block = pkt.blocks[blk]; @@ -239,23 +238,24 @@ inline bool DecoderRSP48::internDecodeMsopPkt(const uint8_t* packe break; } + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + double block_ts = pkt_ts + block_ts_off; int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); - this->first_point_ts_ = pkt_ts; + this->first_point_ts_ = block_ts; ret = true; } - int32_t block_az_diff; - double block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); diff --git a/src/rs_driver/driver/decoder/decoder_RSP80.hpp b/src/rs_driver/driver/decoder/decoder_RSP80.hpp index 41398971..99d5fa01 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP80.hpp @@ -272,7 +272,6 @@ inline bool DecoderRSP80::internDecodeMsopPkt(const uint8_t* packe T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, this->block_az_diff_, this->fov_blind_ts_diff_); - double block_ts = pkt_ts; for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) { const RSP80MsopBlock& block = pkt.blocks[blk]; @@ -283,23 +282,24 @@ inline bool DecoderRSP80::internDecodeMsopPkt(const uint8_t* packe break; } + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + double block_ts = pkt_ts + block_ts_off; int32_t block_az = ntohs(block.azimuth); if (this->split_strategy_->newBlock(block_az)) { this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); - this->first_point_ts_ = pkt_ts; + this->first_point_ts_ = block_ts; ret = true; } - int32_t block_az_diff; - double block_ts_off; - iter.get(blk, block_az_diff, block_ts_off); - for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) { const RSChannel& channel = block.channels[chan]; - double chan_ts = block_ts + block_ts_off + this->mech_const_param_.CHAN_TSS[chan]; + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; int32_t angle_horiz = block_az + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); From 95f3e2e0bf9bbe03705ced0efd7e2adf207e9845 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Mon, 15 Aug 2022 18:54:41 +0800 Subject: [PATCH 340/379] fix: fix cloud timestamp for Ruby series --- doc/src_intro/rs_driver_intro.md | 3 ++- src/rs_driver/driver/decoder/decoder_RS128.hpp | 4 ++-- src/rs_driver/driver/decoder/decoder_RS48.hpp | 4 ++-- src/rs_driver/driver/decoder/decoder_RS80.hpp | 4 ++-- src/rs_driver/driver/decoder/decoder_RSP128.hpp | 4 ++-- src/rs_driver/driver/decoder/decoder_RSP48.hpp | 4 ++-- src/rs_driver/driver/decoder/decoder_RSP80.hpp | 4 ++-- 7 files changed, 14 insertions(+), 13 deletions(-) diff --git a/doc/src_intro/rs_driver_intro.md b/doc/src_intro/rs_driver_intro.md index d2fe133e..52f03ebf 100644 --- a/doc/src_intro/rs_driver_intro.md +++ b/doc/src_intro/rs_driver_intro.md @@ -316,7 +316,8 @@ typedef struct } RSTimestampUTC; ``` + 如果`ss[4]`保存微秒值,使用parseTimeUTCWithUs()解析。遵循这种格式的有RSHELIOS/RSM1。 -+ 如果`ss[4]`保存纳秒值,使用parseTimeUTCWithNs()解析。遵循这种格式的有RS128/RS80。 ++ 如果`ss[4]`保存纳秒值,使用parseTimeUTCWithNs()解析。 ++ 目前出货的RS128/RS80都遵循微秒格式,只有早期出货的一些RS128/RS80是纳秒格式。当前版本的rs_driver只支持微秒格式的解析。 #### 4.1.6 temperature diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 3dc1a0e5..41aaf06e 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -216,7 +216,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 1e-6; + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 1e-6; } else { @@ -227,7 +227,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe if (this->write_pkt_ts_) { - createTimeUTCWithNs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); } } diff --git a/src/rs_driver/driver/decoder/decoder_RS48.hpp b/src/rs_driver/driver/decoder/decoder_RS48.hpp index dd8db05e..48e39fca 100644 --- a/src/rs_driver/driver/decoder/decoder_RS48.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS48.hpp @@ -165,7 +165,7 @@ inline bool DecoderRS48::internDecodeMsopPkt(const uint8_t* packet double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 1e-6; + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 1e-6; } else { @@ -176,7 +176,7 @@ inline bool DecoderRS48::internDecodeMsopPkt(const uint8_t* packet if (this->write_pkt_ts_) { - createTimeUTCWithNs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); } } diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index e01d1c95..2a1f8ed2 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -211,7 +211,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 1e-6; + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 1e-6; } else { @@ -222,7 +222,7 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet if (this->write_pkt_ts_) { - createTimeUTCWithNs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); } } diff --git a/src/rs_driver/driver/decoder/decoder_RSP128.hpp b/src/rs_driver/driver/decoder/decoder_RSP128.hpp index efcdd63e..edc0b3c1 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP128.hpp @@ -221,7 +221,7 @@ inline bool DecoderRSP128::internDecodeMsopPkt(const uint8_t* pack double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 1e-6; + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 1e-6; } else { @@ -232,7 +232,7 @@ inline bool DecoderRSP128::internDecodeMsopPkt(const uint8_t* pack if (this->write_pkt_ts_) { - createTimeUTCWithNs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); } } diff --git a/src/rs_driver/driver/decoder/decoder_RSP48.hpp b/src/rs_driver/driver/decoder/decoder_RSP48.hpp index 617a67c5..aed4e8b2 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP48.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP48.hpp @@ -210,7 +210,7 @@ inline bool DecoderRSP48::internDecodeMsopPkt(const uint8_t* packe double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 1e-6; + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 1e-6; } else { @@ -221,7 +221,7 @@ inline bool DecoderRSP48::internDecodeMsopPkt(const uint8_t* packe if (this->write_pkt_ts_) { - createTimeUTCWithNs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); } } diff --git a/src/rs_driver/driver/decoder/decoder_RSP80.hpp b/src/rs_driver/driver/decoder/decoder_RSP80.hpp index 99d5fa01..b138a0c9 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP80.hpp @@ -254,7 +254,7 @@ inline bool DecoderRSP80::internDecodeMsopPkt(const uint8_t* packe double pkt_ts = 0; if (this->param_.use_lidar_clock) { - pkt_ts = parseTimeUTCWithNs(&pkt.header.timestamp) * 1e-6; + pkt_ts = parseTimeUTCWithUs(&pkt.header.timestamp) * 1e-6; } else { @@ -265,7 +265,7 @@ inline bool DecoderRSP80::internDecodeMsopPkt(const uint8_t* packe if (this->write_pkt_ts_) { - createTimeUTCWithNs (ts, (RSTimestampUTC*)&pkt.header.timestamp); + createTimeUTCWithUs (ts, (RSTimestampUTC*)&pkt.header.timestamp); } } From b61880356908f416c14ec2728fa5efeab2251ff2 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 16 Aug 2022 08:55:16 +0800 Subject: [PATCH 341/379] format: update demo_online and demo_pcap --- demo/demo_online.cpp | 31 ++++++++++++++++--------------- demo/demo_pcap.cpp | 31 ++++++++++++++++--------------- tool/rs_driver_viewer.cpp | 6 +++--- 3 files changed, 35 insertions(+), 33 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index b0a14f4c..fecfe245 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -46,16 +46,16 @@ typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; SyncQueue> free_cloud_queue; -SyncQueue> cloud_queue; +SyncQueue> stuffed_cloud_queue; // // @brief point cloud callback function. The caller should register it to the lidar driver. -// Via this fucntion, the driver fetches an EMPTY point cloud message from the caller. -// @param msg The empty point cloud message. +// Via this fucntion, the driver gets an free/unused point cloud message from the caller. +// @param msg The free/unused point cloud message. // -std::shared_ptr pointCloudGetCallback(void) +std::shared_ptr driverGetPointCloudFromCallerCallback(void) { - // Note: This callback function runs in the packet-parsing thread of the driver, + // Note: This callback function runs in the packet-parsing/point-cloud-constructing thread of the driver, // so please DO NOT do time-consuming task here. std::shared_ptr msg = free_cloud_queue.pop(); if (msg.get() != NULL) @@ -68,23 +68,24 @@ std::shared_ptr pointCloudGetCallback(void) // // @brief point cloud callback function. The caller should register it to the lidar driver. -// Via this function, the driver returns a STUFFED point cloud message to the caller. +// Via this function, the driver gets/returns a stuffed point cloud message to the caller. // @param msg The stuffed point cloud message. // -void pointCloudPutCallback(std::shared_ptr msg) +void driverReturnPointCloudToCallerCallback(std::shared_ptr msg) { - // Note: This callback function runs in the packet-parsing thread of the driver, - // so please DO NOT do time-consuming task here. Instead, process it in another thread. - cloud_queue.push(msg); + // Note: This callback function runs in the packet-parsing/point-cloud-constructing thread of the driver, + // so please DO NOT do time-consuming task here. Instead, process it in caller's own thread. (see processCloud() below) + stuffed_cloud_queue.push(msg); } // // @brief exception callback function. The caller should register it to the lidar driver. +// Via this function, the driver inform the caller that something happens. // @param code The error code to represent the error/warning/information // void exceptionCallback(const Error& code) { - // Note: This callback function runs in the packet-receving/packet-parsing thread of the driver, + // Note: This callback function runs in the packet-receving and packet-parsing/point-cloud_constructing thread of the driver, // so please DO NOT do time-consuming task here. RS_WARNING << code.toString() << RS_REND; } @@ -94,13 +95,13 @@ void processCloud(void) { while (!to_exit_process) { - std::shared_ptr msg = cloud_queue.popWait(); + std::shared_ptr msg = stuffed_cloud_queue.popWait(); if (msg.get() == NULL) { continue; } - // process the point cloud msg, even it is time-consuming + // Well, it is time to process the point cloud msg, even it is time-consuming. RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; free_cloud_queue.push(msg); @@ -122,8 +123,8 @@ int main(int argc, char* argv[]) param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct param.print(); - LidarDriver driver; ///< Declare the driver object - driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback function + LidarDriver driver; ///< Declare the driver object + driver.regPointCloudCallback(driverGetPointCloudFromCallerCallback, driverReturnPointCloudToCallerCallback); ///< Register the point cloud callback functions driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function if (!driver.init(param)) ///< Call the init function { diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index 1b7632e7..daee7958 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -46,16 +46,16 @@ typedef PointCloudT PointCloudMsg; using namespace robosense::lidar; SyncQueue> free_cloud_queue; -SyncQueue> cloud_queue; +SyncQueue> stuffed_cloud_queue; // // @brief point cloud callback function. The caller should register it to the lidar driver. -// Via this fucntion, the driver fetches an EMPTY point cloud message from the caller. -// @param msg The empty point cloud message. +// Via this fucntion, the driver gets an free/unused point cloud message from the caller. +// @param msg The free/unused point cloud message. // -std::shared_ptr pointCloudGetCallback(void) +std::shared_ptr driverGetPointCloudFromCallerCallback(void) { - // Note: This callback function runs in the packet-parsing thread of the driver, + // Note: This callback function runs in the packet-parsing/point-cloud-constructing thread of the driver, // so please DO NOT do time-consuming task here. std::shared_ptr msg = free_cloud_queue.pop(); if (msg.get() != NULL) @@ -68,23 +68,24 @@ std::shared_ptr pointCloudGetCallback(void) // // @brief point cloud callback function. The caller should register it to the lidar driver. -// Via this function, the driver returns a STUFFED point cloud message to the caller. +// Via this function, the driver gets/returns a stuffed point cloud message to the caller. // @param msg The stuffed point cloud message. // -void pointCloudPutCallback(std::shared_ptr msg) +void driverReturnPointCloudToCallerCallback(std::shared_ptr msg) { - // Note: This callback function runs in the packet-parsing thread of the driver, - // so please DO NOT do time-consuming task here. Instead, process it in another thread. - cloud_queue.push(msg); + // Note: This callback function runs in the packet-parsing/point-cloud-constructing thread of the driver, + // so please DO NOT do time-consuming task here. Instead, process it in caller's own thread. (see processCloud() below) + stuffed_cloud_queue.push(msg); } // // @brief exception callback function. The caller should register it to the lidar driver. +// Via this function, the driver inform the caller that something happens. // @param code The error code to represent the error/warning/information // void exceptionCallback(const Error& code) { - // Note: This callback function runs in the packet-receving/packet-parsing thread of the driver, + // Note: This callback function runs in the packet-receving and packet-parsing/point-cloud_constructing thread of the driver, // so please DO NOT do time-consuming task here. RS_WARNING << code.toString() << RS_REND; } @@ -94,13 +95,13 @@ void processCloud(void) { while (!to_exit_process) { - std::shared_ptr msg = cloud_queue.popWait(); + std::shared_ptr msg = stuffed_cloud_queue.popWait(); if (msg.get() == NULL) { continue; } - // process the point cloud msg, even it is time-consuming + // Well, it is time to process the point cloud msg, even it is time-consuming. RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; free_cloud_queue.push(msg); @@ -123,8 +124,8 @@ int main(int argc, char* argv[]) param.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct param.print(); - LidarDriver driver; ///< Declare the driver object - driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback function + LidarDriver driver; ///< Declare the driver object + driver.regPointCloudCallback(driverGetPointCloudFromCallerCallback, driverReturnPointCloudToCallerCallback); ///< Register the point cloud callback functions driver.regExceptionCallback(exceptionCallback); ///< Register the exception callback function if (!driver.init(param)) ///< Call the init function { diff --git a/tool/rs_driver_viewer.cpp b/tool/rs_driver_viewer.cpp index a09a519d..e70c0174 100644 --- a/tool/rs_driver_viewer.cpp +++ b/tool/rs_driver_viewer.cpp @@ -45,7 +45,7 @@ std::shared_ptr pcl_viewer; std::mutex mtx_viewer; SyncQueue> free_cloud_queue; -SyncQueue> cloud_queue; +SyncQueue> stuffed_cloud_queue; bool checkKeywordExist(int argc, const char* const* argv, const char* str) { @@ -186,7 +186,7 @@ std::shared_ptr pointCloudGetCallback(void) void pointCloudPutCallback(std::shared_ptr msg) { - cloud_queue.push(msg); + stuffed_cloud_queue.push(msg); } bool to_exit_process = false; @@ -194,7 +194,7 @@ void processCloud(void) { while (!to_exit_process) { - std::shared_ptr msg = cloud_queue.popWait(); + std::shared_ptr msg = stuffed_cloud_queue.popWait(); if (msg.get() == NULL) { continue; From a4fb3497111c629c7cb688b9a71df39411f0c63e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 16 Aug 2022 11:35:18 +0800 Subject: [PATCH 342/379] fix: fix input_sock_epoll MSOPTIMEOUT error --- .../driver/input/unix/input_sock_epoll.hpp | 48 ++++++++++++++----- 1 file changed, 37 insertions(+), 11 deletions(-) diff --git a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp index 5541b8d6..b04cbd06 100644 --- a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp @@ -61,6 +61,7 @@ class InputSock : public Input virtual ~InputSock(); private: + ssize_t readSocket(int fd); inline void recvPacket(); inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); @@ -237,6 +238,39 @@ inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, con return -1; } +inline ssize_t InputSock::readSocket(int fd) +{ + while (1) + { + std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); + ssize_t ret = recvfrom(fd, pkt->buf(), pkt->bufSize(), 0, NULL, NULL); + if (ret < 0) + { + if (errno == EAGAIN) + { + return 0; + } + else + { + perror("recvfrom: "); + return -1; + } + } + else if (ret > 0) + { + pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); + pushPacket(pkt); + } + else + { + // never reach here. + } + } + + // never reach here. + return 0; +} + inline void InputSock::recvPacket() { while (!to_exit_recv_) @@ -261,21 +295,13 @@ inline void InputSock::recvPacket() { if (events[i].events & EPOLLIN) { - std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); - ssize_t ret = recvfrom(events[i].data.fd, pkt->buf(), pkt->bufSize(), 0, NULL, NULL); + int ret = readSocket(events[i].data.fd); if (ret < 0) - { - perror("recvfrom: "); - break; - } - else if (ret > 0) - { - pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); - pushPacket(pkt); - } + return; } } } + } } // namespace lidar From 30a1008a2ce85a438bab53566f01a782673bd719 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 16 Aug 2022 12:52:18 +0800 Subject: [PATCH 343/379] feat: recycle packet in case of epoll and recvmmsg --- src/rs_driver/driver/input/input.hpp | 12 ++++++------ src/rs_driver/driver/input/unix/input_sock_epoll.hpp | 1 + .../driver/input/unix/input_sock_select.hpp | 7 +++++-- src/rs_driver/driver/lidar_driver_impl.hpp | 12 +++++++++--- 4 files changed, 21 insertions(+), 11 deletions(-) diff --git a/src/rs_driver/driver/input/input.hpp b/src/rs_driver/driver/input/input.hpp index a2cfc1c3..610c6047 100644 --- a/src/rs_driver/driver/input/input.hpp +++ b/src/rs_driver/driver/input/input.hpp @@ -57,7 +57,7 @@ class Input inline void regCallback( const std::function& cb_excep, const std::function(size_t)>& cb_get_pkt, - const std::function)>& cb_put_pkt); + const std::function, bool)>& cb_put_pkt); virtual bool init() = 0; virtual bool start() = 0; @@ -67,11 +67,11 @@ class Input } protected: - inline void pushPacket(std::shared_ptr pkt); + inline void pushPacket(std::shared_ptr pkt, bool stuffed = true); RSInputParam input_param_; std::function(size_t size)> cb_get_pkt_; - std::function)> cb_put_pkt_; + std::function, bool)> cb_put_pkt_; std::function cb_excep_; std::thread recv_thread_; bool to_exit_recv_; @@ -88,7 +88,7 @@ inline Input::Input(const RSInputParam& input_param) inline void Input::regCallback( const std::function& cb_excep, const std::function(size_t)>& cb_get_pkt, - const std::function)>& cb_put_pkt) + const std::function, bool)>& cb_put_pkt) { cb_excep_ = cb_excep; cb_get_pkt_ = cb_get_pkt; @@ -106,9 +106,9 @@ inline void Input::stop() } } -inline void Input::pushPacket(std::shared_ptr pkt) +inline void Input::pushPacket(std::shared_ptr pkt, bool stuffed) { - cb_put_pkt_(pkt); + cb_put_pkt_(pkt, stuffed); } } // namespace lidar diff --git a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp index b04cbd06..8b186ccd 100644 --- a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp @@ -248,6 +248,7 @@ inline ssize_t InputSock::readSocket(int fd) { if (errno == EAGAIN) { + pushPacket(pkt, false); return 0; } else diff --git a/src/rs_driver/driver/input/unix/input_sock_select.hpp b/src/rs_driver/driver/input/unix/input_sock_select.hpp index 488d4ef7..56845520 100644 --- a/src/rs_driver/driver/input/unix/input_sock_select.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_select.hpp @@ -254,7 +254,7 @@ inline void InputSock::recvPacket() { #ifdef ENABLE_RECVMMSG -#define VLEN 1 +#define VLEN 2 struct mmsghdr msgs[VLEN]; struct iovec iovecs[VLEN]; std::shared_ptr pkts[VLEN]; @@ -279,7 +279,10 @@ inline void InputSock::recvPacket() pkts[i]->setData(sock_offset_, msgs[i].msg_len - sock_offset_ - sock_tail_); pushPacket(pkts[i]); } - + for (i = ret; i < VLEN; i++) + { + pushPacket(pkts[i], false); + } #else std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); diff --git a/src/rs_driver/driver/lidar_driver_impl.hpp b/src/rs_driver/driver/lidar_driver_impl.hpp index c4392373..e533712e 100644 --- a/src/rs_driver/driver/lidar_driver_impl.hpp +++ b/src/rs_driver/driver/lidar_driver_impl.hpp @@ -85,7 +85,7 @@ class LidarDriverImpl void runExceptionCallback(const Error& error); std::shared_ptr packetGet(size_t size); - void packetPut(std::shared_ptr pkt); + void packetPut(std::shared_ptr pkt, bool stuffed); void processPacket(); @@ -196,7 +196,7 @@ inline bool LidarDriverImpl::init(const RSDriverParam& param) input_ptr_->regCallback( std::bind(&LidarDriverImpl::runExceptionCallback, this, std::placeholders::_1), std::bind(&LidarDriverImpl::packetGet, this, std::placeholders::_1), - std::bind(&LidarDriverImpl::packetPut, this, std::placeholders::_1)); + std::bind(&LidarDriverImpl::packetPut, this, std::placeholders::_1, std::placeholders::_2)); if (!input_ptr_->init()) { @@ -309,10 +309,16 @@ inline std::shared_ptr LidarDriverImpl::packetGet(size_t s } template -inline void LidarDriverImpl::packetPut(std::shared_ptr pkt) +inline void LidarDriverImpl::packetPut(std::shared_ptr pkt, bool stuffed) { constexpr static int PACKET_POOL_MAX = 1024; + if (!stuffed) + { + free_pkt_queue_.push(pkt); + return; + } + size_t sz = pkt_queue_.push(pkt); if (sz > PACKET_POOL_MAX) { From bdf333b96aa8950672f21d99aa7e643c5df8cfc2 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 18 Aug 2022 16:06:15 +0800 Subject: [PATCH 344/379] feat: update CHANGELOG --- CHANGELOG.md | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index e8182b4e..b9d6a44e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -2,6 +2,16 @@ ## Unreleased +### Changed +- Make error code different for MSOP/DIFOP Packets +- Rename error code CLOUDOVERFOW +- Recover M2 decoder's coordinate +- Update demo_pcap and rs_driver_viewer with cloud queue +- Add option ENABLE_DOUBLE_RCVBUF + +### Fixed +- Fix timestamp of Ruby series' cloud to follow new format instead of old one. + ## v1.5.5 2022-08-01 ### Added From 21a5c6fe83d97eee76bc6158f36fc79bcd460d5b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 18 Aug 2022 16:22:05 +0800 Subject: [PATCH 345/379] feat: update CHANGELOG.md --- CHANGELOG.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index b9d6a44e..fb4e0df1 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -11,6 +11,7 @@ ### Fixed - Fix timestamp of Ruby series' cloud to follow new format instead of old one. +- Fix ERRCODE_MSOPTIMEOUT problem of input_sock_epoll ## v1.5.5 2022-08-01 From 3800ee9d08254c0105d5f0b51b255cce3dfa64ee Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 19 Aug 2022 15:17:34 +0800 Subject: [PATCH 346/379] feat: add option ENABLE_WAIT_IF_QUEUE_EMPTY --- CMakeLists.txt | 19 ++++++++++++------ src/rs_driver/utility/sync_queue.hpp | 29 ++++++++++++++-------------- 2 files changed, 28 insertions(+), 20 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e609fe56..3b00ba47 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -18,12 +18,15 @@ endif() #============================= # Compile Features #============================= -option(DISABLE_PCAP_PARSE "Disable PCAP file parse" OFF) -option(ENABLE_TRANSFORM "Enable transform functions" OFF) -option(ENABLE_EPOLL_RECEIVE "Receive packets with epoll() instead of select()" OFF) -option(ENABLE_RECVMMSG "Enable recvmmsg() to receive MSOP message" OFF) -option(ENABLE_DOUBLE_RCVBUF "Enable double size of RCVBUF" OFF) -option(ENABLE_PCL_POINTCLOUD "Enable PCL Point Cloud" OFF) +option(DISABLE_PCAP_PARSE "Disable PCAP file parse" OFF) +option(ENABLE_TRANSFORM "Enable transform functions" OFF) + +option(ENABLE_DOUBLE_RCVBUF "Enable double size of RCVBUF" OFF) +option(ENABLE_WAIT_IF_QUEUE_EMPTY "Enable waiting for a while in handle thread if the queue is empty" OFF) +option(ENABLE_EPOLL_RECEIVE "Receive packets with epoll() instead of select()" OFF) +option(ENABLE_RECVMMSG "Enable recvmmsg() to receive MSOP message" OFF) + +option(ENABLE_PCL_POINTCLOUD "Enable PCL Point Cloud" OFF) #============================= # Compile Demos, Tools, Tests @@ -152,6 +155,10 @@ if(${ENABLE_DOUBLE_RCVBUF}) add_definitions("-DENABLE_DOUBLE_RCVBUF") endif(${ENABLE_DOUBLE_RCVBUF}) +if(${ENABLE_WAIT_IF_QUEUE_EMPTY}) + add_definitions("-DENABLE_WAIT_IF_QUEUE_EMPTY") +endif(${ENABLE_WAIT_IF_QUEUE_EMPTY}) + if(${COMPILE_DEMOS}) add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/demo) endif(${COMPILE_DEMOS}) diff --git a/src/rs_driver/utility/sync_queue.hpp b/src/rs_driver/utility/sync_queue.hpp index dd0e38de..039ca667 100644 --- a/src/rs_driver/utility/sync_queue.hpp +++ b/src/rs_driver/utility/sync_queue.hpp @@ -83,20 +83,7 @@ class SyncQueue // Low latency, or low CPU usage, that is the question. // - Hamlet -#if 1 - T value; - - std::unique_lock ul(mtx_); - cv_.wait_for(ul, std::chrono::microseconds(usec), [this] { return (!queue_.empty()); }); - - if (!queue_.empty()) - { - value = queue_.front(); - queue_.pop(); - } - - return value; -#else +#ifdef ENABLE_WAIT_IF_QUEUE_EMPTY T value; { @@ -110,6 +97,20 @@ class SyncQueue } std::this_thread::sleep_for(std::chrono::microseconds(1000)); + return value; +#else + + T value; + + std::unique_lock ul(mtx_); + cv_.wait_for(ul, std::chrono::microseconds(usec), [this] { return (!queue_.empty()); }); + + if (!queue_.empty()) + { + value = queue_.front(); + queue_.pop(); + } + return value; #endif } From 966b318faa66df260fdc517aeca3624fe5de424e Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 19 Aug 2022 17:31:59 +0800 Subject: [PATCH 347/379] feat: add option ENABLE_STAMP_WITH_LOCAL --- CMakeLists.txt | 5 ++ src/rs_driver/driver/decoder/basic_attr.hpp | 54 +++++++++++++++++++++ 2 files changed, 59 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3b00ba47..27e59d11 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -26,6 +26,7 @@ option(ENABLE_WAIT_IF_QUEUE_EMPTY "Enable waiting for a while in handle thread i option(ENABLE_EPOLL_RECEIVE "Receive packets with epoll() instead of select()" OFF) option(ENABLE_RECVMMSG "Enable recvmmsg() to receive MSOP message" OFF) +option(ENABLE_STAMP_WITH_LOCAL "Enable stamp point cloud with local time" OFF) option(ENABLE_PCL_POINTCLOUD "Enable PCL Point Cloud" OFF) #============================= @@ -159,6 +160,10 @@ if(${ENABLE_WAIT_IF_QUEUE_EMPTY}) add_definitions("-DENABLE_WAIT_IF_QUEUE_EMPTY") endif(${ENABLE_WAIT_IF_QUEUE_EMPTY}) +if(${ENABLE_STAMP_WITH_LOCAL}) + add_definitions("-DENABLE_STAMP_WITH_LOCAL") +endif(${ENABLE_STAMP_WITH_LOCAL}) + if(${COMPILE_DEMOS}) add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/demo) endif(${COMPILE_DEMOS}) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index dbc6bc63..159d6920 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -73,6 +73,29 @@ typedef struct #pragma pack(pop) +#ifdef ENABLE_STAMP_WITH_LOCAL +inline long getTimezone(void) +{ + static long tzone = 0; + static bool tzoneReady = false; + + if (!tzoneReady) + { +#ifdef _MSC_VER + _get_timezone(&tzone); +#else + tzset(); + tzone = timezone; +#endif + + tzoneReady = true; + } + + return tzone; +} +#endif + +#if 0 inline uint64_t parseTimeUTCWithNs(const RSTimestampUTC* tsUtc) { // sec @@ -91,6 +114,10 @@ inline uint64_t parseTimeUTCWithNs(const RSTimestampUTC* tsUtc) ns += tsUtc->ss[i]; } +#ifdef ENABLE_STAMP_WITH_LOCAL + sec -= getTimezone(); +#endif + return (sec * 1000000 + ns/1000); } @@ -99,6 +126,10 @@ inline void createTimeUTCWithNs(uint64_t us, RSTimestampUTC* tsUtc) uint64_t sec = us / 1000000; uint64_t nsec = (us % 1000000) * 1000; +#ifdef ENABLE_STAMP_WITH_LOCAL + sec += getTimezone(); +#endif + for (int i = 5; i >= 0; i--) { tsUtc->sec[i] = sec & 0xFF; @@ -111,6 +142,7 @@ inline void createTimeUTCWithNs(uint64_t us, RSTimestampUTC* tsUtc) nsec >>= 8; } } +#endif inline uint64_t parseTimeUTCWithUs(const RSTimestampUTC* tsUtc) { @@ -130,6 +162,10 @@ inline uint64_t parseTimeUTCWithUs(const RSTimestampUTC* tsUtc) us += tsUtc->ss[i]; } +#ifdef ENABLE_STAMP_WITH_LOCAL + sec -= getTimezone(); +#endif + return (sec * 1000000 + us); } @@ -138,6 +174,10 @@ inline void createTimeUTCWithUs(uint64_t us, RSTimestampUTC* tsUtc) uint64_t sec = us / 1000000; uint64_t usec = us % 1000000; +#ifdef ENABLE_STAMP_WITH_LOCAL + sec += getTimezone(); +#endif + for (int i = 5; i >= 0; i--) { tsUtc->sec[i] = sec & 0xFF; @@ -151,6 +191,7 @@ inline void createTimeUTCWithUs(uint64_t us, RSTimestampUTC* tsUtc) } } +#if 0 inline uint64_t parseTimeUTCWithMs(const RSTimestampUTC* tsUtc) { // sec @@ -171,8 +212,13 @@ inline uint64_t parseTimeUTCWithMs(const RSTimestampUTC* tsUtc) us <<= 8; us += tsUtc->ss[3]; +#ifdef ENABLE_STAMP_WITH_LOCAL + sec -= getTimezone(); +#endif + return (sec * 1000000 + ms * 1000 + us); } +#endif inline uint64_t parseTimeYMD(const RSTimestampYMD* tsYmd) { @@ -205,6 +251,10 @@ inline uint64_t parseTimeYMD(const RSTimestampYMD* tsYmd) << std::endl; #endif +#ifdef ENABLE_STAMP_WITH_LOCAL + sec -= getTimezone(); +#endif + return (sec * 1000000 + ms * 1000 + us); } @@ -216,6 +266,10 @@ inline void createTimeYMD(uint64_t usec, RSTimestampYMD* tsYmd) uint64_t ms = tot_ms % 1000; uint64_t sec = tot_ms / 1000; +#ifdef ENABLE_STAMP_WITH_LOCAL + sec += getTimezone(); +#endif + time_t t_sec = sec; std::tm* stm = localtime(&t_sec); From a7485266a3a6dc574ed59414bf3fc2d6aa576db4 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 19 Aug 2022 17:37:52 +0800 Subject: [PATCH 348/379] fix: fix option ENABLE_PCL_POINTCLOUD --- CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 27e59d11..696da938 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -164,6 +164,10 @@ if(${ENABLE_STAMP_WITH_LOCAL}) add_definitions("-DENABLE_STAMP_WITH_LOCAL") endif(${ENABLE_STAMP_WITH_LOCAL}) +if(${ENABLE_PCL_POINTCLOUD}) + add_definitions("-DENABLE_PCL_POINTCLOUD") +endif(${ENABLE_PCL_POINTCLOUD}) + if(${COMPILE_DEMOS}) add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/demo) endif(${COMPILE_DEMOS}) From a3fdd97ee919694d9f0dfd4438cf073fd50d3497 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 23 Aug 2022 09:06:05 +0800 Subject: [PATCH 349/379] feat: update tests --- test/basic_attr_test.cpp | 2 ++ test/decoder_test.cpp | 8 ++++---- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/test/basic_attr_test.cpp b/test/basic_attr_test.cpp index fb65e971..7b157b25 100644 --- a/test/basic_attr_test.cpp +++ b/test/basic_attr_test.cpp @@ -17,6 +17,7 @@ TEST(TestParseTime, parseTimeYMD) ASSERT_EQ(memcmp(ts2, ts1, 10), 0); } +#if 0 TEST(TestParseTime, parseTimeUTCWithNs) { RSTimestampUTC ts1 = @@ -28,6 +29,7 @@ TEST(TestParseTime, parseTimeUTCWithNs) createTimeUTCWithNs(0x010203040506 * 1000000 + 0x06A11CF0/1000, &ts2); ASSERT_EQ(memcmp(&ts2, &ts1, sizeof(ts1)), 0); } +#endif TEST(TestParseTime, parseTimeUTCWithUs) { diff --git a/test/decoder_test.cpp b/test/decoder_test.cpp index 377a8818..cd49e6b7 100644 --- a/test/decoder_test.cpp +++ b/test/decoder_test.cpp @@ -106,12 +106,12 @@ TEST(TestDecoder, processDifopPkt_fail) MyDifopPkt pkt = {0}; errCode = ERRCODE_SUCCESS; decoder.processDifopPkt((const uint8_t*)&pkt, 10); - ASSERT_EQ(errCode, ERRCODE_WRONGPKTLENGTH); + ASSERT_EQ(errCode, ERRCODE_WRONGDIFOPLEN); // wrong difop id errCode = ERRCODE_SUCCESS; decoder.processDifopPkt((const uint8_t*)&pkt, sizeof(pkt)); - ASSERT_EQ(errCode, ERRCODE_WRONGPKTHEADER); + ASSERT_EQ(errCode, ERRCODE_WRONGDIFOPID); } TEST(TestDecoder, processDifopPkt) @@ -268,14 +268,14 @@ TEST(TestDecoder, processMsopPkt) // wrong msop len errCode = ERRCODE_SUCCESS; decoder.processMsopPkt((const uint8_t*)&pkt, 2); - ASSERT_EQ(errCode, ERRCODE_WRONGPKTLENGTH); + ASSERT_EQ(errCode, ERRCODE_WRONGMSOPLEN); decoder.param_.wait_for_difop = false; // wrong msop header errCode = ERRCODE_SUCCESS; decoder.processMsopPkt((const uint8_t*)&pkt, sizeof(pkt)); - ASSERT_EQ(errCode, ERRCODE_WRONGPKTHEADER); + ASSERT_EQ(errCode, ERRCODE_WRONGMSOPID); // valid msop uint8_t id[] = {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0}; From 2378615e6c7ef476a450226bb7fb6202c916524f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 24 Aug 2022 09:40:22 +0800 Subject: [PATCH 350/379] fix: fix src_intro docs --- doc/src_intro/img/class_decoder_mech.png | Bin 24579 -> 21951 bytes doc/src_intro/rs_driver_intro.md | 21 +++++++++++---------- 2 files changed, 11 insertions(+), 10 deletions(-) diff --git a/doc/src_intro/img/class_decoder_mech.png b/doc/src_intro/img/class_decoder_mech.png index e6801ff23eb4ab85a601557644c91af51006ba19..fe543cde80cd3020ea353ddabfae2c84fe8c11ff 100644 GIT binary patch literal 21951 zcma*P2|QNs+CTajQ&Hxz$Wv)B&yrB)P@<5KsgTT>%9L418c@j;l37WpWD1cC88TFa zl$jJE{@?Z6d!O^Z=Y7xloc-B*m&#+Ud)@bSeWzK)Ty*u=ewL?SV0X{zdzNEF)m zeH$Gu{{OnAN)CS6=%RVrokZGFNBocCj^Gv^5@`oXOZD(c@1)5GUdAUIR-P+e(#zPV z#!gLbzyGK*MKvwiA|cDFS|oDQu59sZG}2+;Wh2`osek<#^vJ0h>? zQ?pXvu4rA^@cPh<$csr4%HkG3v$2Yg4W`34z9Lnq}Uu!PaDj?p=o}alZR)s zhsQ4?MZI(9cK`F;LhC%Y&YGERPw`)VJaBIB?c28-x5=~e@I<|Pr$f&vmiqRNjTmRN zY}~@aC3+qidOrW9G}9HqX35{0_$De^`l|WS=KH4)(FRw0OYRjG4y~xDFdY`{mD9$b z++blB;-aTj*be(DrkQ*-m1N+Ufz<^EDf zwMuKF_!*{e-@fVT=>-M_QQp3D$I{9wNb8os(9G*~f8k%JD}4{Jva-5Nek?X>619uX z&CP9GoaoLU?)%g4{8~Eq`jy4$P<&%|{+XUUH%@0IA>+z$-=8hA#^r9iP0h@T9ePCM z4jdS&kKrkNVdAzk&*IdH6V;>533E$x*3&OaN~E&0vtM4%5&vvyT;#hoGCI1>HpMUO z@5-X}&u=YzMMWE4`ur?gsH;=GG||n#&CTuN;!^eJ=U92kmw@%{=H}*Y-QBdY4Jwx| zNiF#*k_Pcti3hzz-o1O5nwd#sWMq^i=Ni+o=S$@>QfYrDJIn-fGe?#npNesAANQeK??l$Mtl-Pw7PRQ2J} z@wth@*Xg#c$>eiNKJ(Q4{QP2KVu9DMZ#mzZ9MjilLQ-~g6gJE=rqI^bw!3g4{p@T1 zGS8`dnrj@Q<`$jVC+t3CF(f4=x!_ZcrUUBxH*SufIq)G%Hy9rwAt9k>U=VyZ;4d3K zx9I89+BZ=gmUeb@0RaIg4Gq)t^5{Q*{#GhT)&BN)3I_94JTzkB+_Z z`r;RU`ssPg*5pH2)2g;K71x#Dj-;xPjVvysO>Dlux{MO#J@zxRu#{iM=BsLG*zo7i zA367L^hb^yVPt2orx8AN>Xd^2D(Bt1cb9(mJEuK-NJS#9=*5eJTeiuONOIn@JC=Ma zKXwk>xWTwh&V|(f+__<^(rO^~3hzWu;RcfL-(Nk(r5Cw;{rrl(X3SS{fwOaShtL33eZSH2W%-S5LT4+J;)Tx$v=&6ma!N`{-n`T_H8r)7 zbjWY{_WAcoTBPqCncAwVmsXctDV5*8eT$1%CG8au2#biw$;sI(Eq%xT?=PeMLPEPp zosW+56%5?I%}S}fnO!KgA(oGYG~WMQG(pk2o}N-!BbGPw(3Rheq~-Z$(a4DJSl^87 zY|W>(tpa2+4-XHea(Q_PXI04L zoX3yTWE}f$WM-cGd7N(e88a7`R&jALo~%IWorHv_$us);Mp=cF+L|gU0vO{Rm#=Bf0@|WLQ#x1?m3pE ztfLd%=&pOX_x0-hW+`cDiq123ot>Q|(t!g9+CF?3Ry-&tS5;koc!ble;t~aEub`lc zkrBt8J9lC{_6=_jrDhGjD zdtc`8*|U698@5pE@p)4#c+ZlQ{YX=7X;h>gqN2xzwv)UDaD;bCN!?yCS5XOGIn9{I zW98(uMMFa)&-@iP8ynl~;-bdUqt}dk@gb_Frb)*Bys_aci!%>%ayDJKaG?y(N5rfm zWT-aWeP!?7y_yO#!+)O#gLx&D!WMmBDqU1a$IkEPx z-`;VR_l?ZV#7<6LT$t=-VP|J2+pDXqbBbAz-lr(VI`k9_O@Dg9dC*gcLvD{wVqi|r zepNNKp{2RuL@9e_c2Vj*ePpW)Jf6^7bk!CTqXA{A>TOiJn+I=C@Tb zInl>h`f&)~d`+c{oAjuqX$?$lMb~>N=({@CASNMEGuiv}O$Yb;K}*H|A1(6V{c|L_ z+8vLkuCA`+ycs7w?Xc2t(;Y$b(-NEZj33wC=-(1O+Kah7cr=iL>SO99+TgkOdL|}) z8Gm~v|J7^%*G8OrDtNTQVn-2TLNm5EmRa27=S6}`YC!LX*nUXhlgP)&YVq)SB zA))9qRHImRoTI^}wvLV?DT;ox!?8-G=YQ=c8#5I@rt3qw7Ks0iR&?a>VT$(l_LiLc zSoAI1{9SsW({2WV_;+ye&-Hb#8iRijSWV z0+7hldHgZuzr-V$oYA|Y_ z%F$8=rk9q=*f@@lk4tP_o_hYpEq6()wy}|pWzVrX?Bw#9wWZ;$1ZF~ir_g(SOxwhS zTXB8WJ@VY8?`;&;_0flq9^Lfy>(|)^z5o(Q#QY_ltgP(Ej~`Rf56HP26fZB()rK(y z7Z;0TIn)Y{$~q0uUAb}v|Dvk5m+R572VXmwnVHMZ8Sf;M>$*MX78k=~Vi+c;ri$&_ z$xc39ZEbq*?#pid^ulW_sPf)DZc|g!qJVY(f@s`0Sy(vcOgsh2cB-_v_$nS!P;l^x zlPBvko%>2QqL^Ndi(?Ag$|v$9<094>4ySOWtCJUe$k;m4w}+Yg5E z9=cpLFtE+g&`?uTlcX1rke-%yb!o}l`|{N+Ca20uHV0Z69u>~l0~h9 zdstUKpyuMI3O2wSy3LzazEt{I+S-OY_LsW;h~nE${5E>e-_l!>v4 zNzJ==^v8}JE4%bV|7mNk6skrlV4N$<^{XTkCyxeP$1--7YURqe`_6K=o&^pJm~tz4 zi-m@SxP0+j8Vau)p8Jjil*J?Kq=)LLnG68KLc08CKJ%livA}qt(?@(2Q`T009=`xo_jhe&=5})OF>xRSo?hn3Q6eAKmfOLa|PeLdBeoi z{_d{iV?erv!D^}k1_j>O-_xJ8!2kxwUjt5aOJ87ZNj`KREkH+ARa{&g2tobaxpS(j zQeM-ho3?BbAg4>(zSnEGzJ1@GJ>fVtc6}xG0P%IdLLWWagCncw;UVqg?X3sU%)}&o zrZoEHt5-jO$ro1txVyQyq@tDUySj?oJ2-qOwr+@s*o%)@`1PyY-QL<-r8a!)BkXZ9 zdH&b0%-!1Yj3@qXiahh&X*W3?+g;zzZm-#E{|D&AbR=Aq)}a6t3MtDPYBHHv{+9c) zu@Mm{BSgnQZP-yPDkvzZg@r=#QdL#u;^NB4%hNfYtdREdr2?h$eOYJRPVk1UH?LjW zgbfiB5pna@t+znhlZz1%cHMcWZE#JkDN1`3Q;xrX|Gx8~#@3wd>>cL3u_uT1|9pJ3#XMhrYef@Mi=X-~)$h6#(j?yN|bx#7? zdx>?!7Llo^t%?sp6PcI@{JT$FJWgA1-@Y`koVH58m2B+<5wc^F#JNpss;VyMra!+r zV|BN>x?1YecRd0%;PE-}ovyywI`-j?piwqpmZ`EYKL2?LHB($l3g2@fr`k%^&Xm?M z_Y`RBYpf3=BRgQJ_4nYmlv(86NJ@0l;L;KoUZuCS}Asm=cUdFym|Qqnd^13U5U z*kWR`vSX#_V!#CvSK|BdI7H5dZ`qy-zKQSqJ~0t>yEjc`1I})0SsCZ$%a^U}No5kB zK7A@57B;J3-MxGFKqcyp)vr?q2DN3b!#8f+2t-dC!s2jB*hDlc0@6lYyY{u|*TO*E>5V>riki{Q3FYUS*$G7Y^n6QDWu+qU zA?l-W_jwASQ`GFM1qC8UR8)#DbnTDkJ;bg2>WT#r@%K+JWYN4_=f0}N^?wNSD|hUd zK^Lp->S8M>D9A1-VDCL!^fA#wO>?NVBRO`XsD2hu%J0)!k1!!dc^M-lyOR=?vLcp5oB>(drn&`h&Bs|;wznjUa#iJ<8 z53ZrPlsNXY57);8KY8-qUQ9-&9$S=&k#R?S55Pc1<>=^WV@pfuvuDrhtfk`%Q&UO! zt$x2~l;>2RWmnEA<7XGxcon<@nRcpIb#&;Dj6M*OVGtXVdJNH3~AWKRbjGSJZ_@=~XTYj-uV&K&kj)R_)B+~33UxK(ebmt9) zon&QWvqa}}ad*G9)Brgk6s4CeCdSwtFHGPg^sBgpgz%jj*GZ)P`}d21Rhz!{-wwv% z;^oyK`^A?^F@<0>zO&UEyk`d~z>{X70k}_?@hSRpqD*VN_WwILG;|dYfCue@mNfbK z)%`0Gg}J$#MMXvP%wEJhXk5IQXX@;QA`S5^2EE8?e&nsykE>U&MnpvohaKB~z>PY^ zcYY(uV&Qu`7?uh!49>3N%A}-_X_?+Pah!k{AQjN>)bw=9o$ArbfPXJvzSJ`{jRtF` z$UfV=0(E47?X2}lBcobCJk&i(z1P1zarTr|^-i7)L4!^{bVcB)x$@s_pHKxC#=AC? zT)wyQJ9UQaLie(?upj|yVd=n1mzDT#?wr`BH9qleRv_gyPPmiqABcJ*BO_I{wGZEp zJuWI@EG;c<>+DoLeVVJg@N6s!;K@^`-uCO}AC01ECe*IB)WZ^sAG*8ib57-o1+4i( zdk6&J*}0PnVpC{nD9t4gkD-wfYA|3ZFUq?LAs9h$AkZSn%3zdeW!25y+GTEAx66m1 zrq(nyZ9=IGPfq6Dwrv}U^ulwh1}&j#cuvf&Z3otw{m|uws;aA0#lC;smX?;P>g#C* zjSA{omDcI8@`?BFTVos0(bI>NmmdJ1rUo6Hb_)QeSX!BRZE0^GiS9Q1{EI)!3-X0% zfR!4Q75qRB?K4Fd6x+6MANu~C4jNdVY5C1Ftyge&#ub#py)S}q=K}o=v zi%LtwKyR{+r))tji{5^aJ(!lE21LuITX$BV)Tq!L{hWu81Arf`fbq#Yxv8mXXs$L4 zS7U+rd}k>pCnv>Rzp93Wg?)vJ74P#hUb*kUg}lQ1wfBA30OW7P$J3rUb0#DtWH6l1 zKM=w}=g$SmiP!G1Kt2JeAOu5yfB&V0569b|IT$TWe_FY-lE2$hdq{#a+UPu(?niWA ztkz;hZimfB{W5}7s$HMR_X=8HpxFxTRtNm9jADj?OWcYY(%~FmPj>S5gPwyxr%qC4 z9g>SZk$KC!2i!ug9Oys!(NPWpu&CwpAt=r5oBpjow~bfNzrD2w;5ir?5U{WXR9uLG zuET8Wn;q}mzt5wiqhm733BfKrJX|B{_U@>nA~BGb8Knb;4%SXi*B2HRddwJThws=G zTkO+nH#9NX$!>s-E zX*(W&V`C%Z9+pb31}9J2W}@u7#U&{Ff>ExR{hw z2mz{i&h5)Db^dbwa4>E4=g+(>0y;Mw5;Y*!3mi{=_v;S|MEO3)gI?1iv9VjB`h>6j zU8%*M0ZZWcu^Bu2V}JkfhvQ122?+_RT2G}OdYcnKXWA=^(6)QN@dd2L$$L&}N=r*iIdlt2$jD^9@S0&}YJZgCf0UP( zS9MoP$9@@^_=t#PrGR57>zC$7v>uNIN7(%u?;^xiJWm1@{==lg!&#V4SXq%DXJ@xT zJ^*-zf zK1FI$MrJ0_R!QTI`@snto0`7P|5;jc>1Km&2$3;RyZ@=}R$pIVIiE3Xy}AMs?26_{ zp^%>`3O>xY1ayP2v$2*;%*^EC&p5Iw%F3jk^U&R)mJHT}ZYDbXtv$z!+{caqj9E0^ z;9ml*tZULdemorD9nFPA!Vaney*V%!R9Gl_@!~}iDLFaW^h;Sq#aHNlNmA84Jw_SM zB#W5$m1YPp>@rk_c;N0#vUEhloeG8z};W+eQC z5PYviMa_Y`zJGKYWeak1x%tBP@82WJ_RV~GE$XU-mZOs-$Fw-}Wvmnrn&=bCua?NT z4K&t7Iajim^llxMzwAr|aL#`GIL<`FGP5gFI{^zM`qXS*%zxGU(s<`aXz4YOF~o6l z%IBpgB}vSMHZd_V?U~vfaf;2YtqrhXHV|&bW*O(t(cxS92wiJwX*kvuzkZXAuC}Ai z=N7_YWB`*SG!cMCZ_pk>LLjhoPvO~wa!n(HF0&fn^}mbQ`t0sUX*X<$`gBdZ26YmI zWe53oe7qG}A@kzqO`DE@KXT~cpPofiO9R*ekvVK^%n9WOo)tYbtVmH~0{IvlM-WQC z@~i5%A3i)i!Iu@-t#87{&R+BO?Z!=;HsQe3fVPc{yF(a*ddfF&PZKD^ z%hF+6wr@fiqu(yi3dunOm&3GeTlAAB5|^e2xBzA9SO5Ghwr%AtmO$%5mkxt~Q40`4 zK!pnzauQj~`13PMmcK@c7P$-^LAAD?`}*c%i9O5O@`UJJL3@+ar}<@M*efe5q0ek^ zb9Zllb;YaL|5nxqcUX*p6jXzglk}T6Z${U#{?U>79X{LBzB&sj4jEa~O%QPhwBzAQ z=AC(do#$TdjcAt?ieH|q9uwVfpQ+LX&z-IL7WSMG_Rj45{1LdWIk~yTek+~}6FoB? zMiVjLu#I3G4(5G&bUdYgxFHtMZsDFoy@eECmYqY$0rzi%XeUJ_B?J;(UYuz?-TTGU zM0-OwDDTDoQU=s<@$)VBLP00^#l=s2t#Q=Nlg*i7adY^wG2>uQKHnLauRL|oWe*aj!6Ci)|{Rb2761W(y zO8tF(Ur~o+reC1t0&!D?g@v{C^n^pKl9ees0F%dcm~PMU)sdlvKV`iCVt^B}Y&Fp4fPNPh2?~}K8jRc26|@^)h!Gzv z{SIPZ;l2iHIzSo{76*vlOGruuyA&6ZQ7ku*c^dx-V^7)J(OPuuO&@uQ=_v1L9)oNE)y#yO%{KKQIOiXO7 ztT({@(0C%Ji~umuVUx(Z#=-H4iJH*)uqMJ}GIY*#RD%w59%w#rRI~0%+5%W4id(CW zV?!PVtbs&$*8fkaw*qg%dFU@_kI=@Bbai!&3=JIy&j*aTb4Sg@#6-$-(wLB>vdhYh z^WNj%vGVdBgVqYq=Pj%uNcqtIAc&1jP3aO~W2`mh7Lb$UKv~>>ghvQdkRpZ6UnWLG zq(6LUKUj4&>G~v8E0!O@^__MMuI}y+L5^{SfGGRmHx`_IEpm!xF~>y4Uh_k~mO;N( z?ilcl{p!-3s_Fu`0W*nkaKC=FB9uJvNc@Cj$F}^Km~el6tK*Vy^y00?M$K!Hk%Vwr zEUct-R%pw96k?U`?nGYg_;iMB*>xcO?aHr08{fR40UokC2UN%isR@qx-8$=yS#Kx; zA3WF&yUxRAe-v=+fjk?b0{0YbhfWf;&mc=PzxgWF20~9McwJjl zL$vT?$J!IQ^Z9XtzespI%p0e3DvC9?bl#`Q_ z$Pg(1-QHYeS*x0?C7U&D{qi;X=V3sPuL9est{NJa;8XaerP;unk_4upV_JD8K|L6R zRZs_p&HXnRta!xVP+y;UMJV>N4s*Mv8c;@hL(aIzNO4<9Cjh!n8X}(a!UY2W;1#sSQhMOkwSw!_ zjBPp2wJglcjOZ|sW0-XNP++Ugo{fx-T0(pPpx>;ct9##12Z|e$N()%u*~dxH?FLc6 zMiier^lV8>OPgI-s6!7b?_U-r z1T&Ic$6>WZS%i_nS2gxi90EJYlr^@Du$w8CfBM{U1X0j+n=>B+vI836m`OAra2uf` z{B7v^oINJQamYrhPoVaNJ$))^y58hnuaI1$je3P}V`M!D?l_3PIM=e)(l#Sfd9 z-0O5(TYSB4iT*+d#00+-!VpSyDB;o14px)K#{^sNN^XFYmYtg$j0?{?_FxmqxWtYL zuo5Lc3a$Zwwl%OZZoTefv9&lP6o@Vn+uVn0LcNz4_CaD%Rwc?h@ZjEnO;+^sL7E&Sm`Va%VveBSKoReN%uqsPY%=|7mu2jYNZc?6canOC^ z*(_#W-s`B}M|C7+WSruD<9e*kI`dE$P47S$2SB1lfDg@s#LSXe?rLtQ8CY<75MPGgyW#zFjC6RT;t zTc%nwYxls$#k1}!D$4H5YQ_c)7B3mVSMqmD+t%!V3V$ksx*36^66Y_xr%#{WDuC*^rgvCIO96CH`@b z)@ts_(+)ePo?>&Hw|kExU3|WU8@oOYm>lx_aHmBL-O2M%LaPzID7JaajKqa&1DDK2 z&PQGo=$joK9kYMNQlji%k*Z)nBBMcr>=_*VhnFR^Ol0j%N&$ojb|@w(Nu;LGs4Ofk ziM)=Ton6FB`f_Bq2+>sM;*g|{uQ*l~=RczL%#S|Ai^_zI2h-cgeX z;({v32@nUeHTeDe-nmVu+5&Dat8m|Bb-1~_TS|%*98v{=vho0ZTu~@=5a4Mvg*xG# z19}GN*rD0kdkHfeN)=3)z5Dl5B76fc+v387O(4jVpI&e@H8l}>Es@xB`XnFc|8>rL zK!}(2p<0~Axf0($^G5n5Zyz22eSgTW5=KZ8OiajebU+f*R83!&7)pUD@dIBCHZ9H8 zZjEdhZtpo8pbH~?u!(s`-Y+uwNolD7;v>hz1$2*h>rDvgHbcizhd7&x<8>Kl$PbdS zjlI2=sw$+xhd_O9qe8GIgMxy}mh+(tBo}>djk;(E%->9jpyZx;h zo-3>TRAfoj+uzR;m;LQn**f=c4Qow;xA8Cur}nR{4vXg7PJ^XdS{ z18=p#T;U3q!!aU6^!tksZr`rUH~bDX5UaFiJhESl6BR}QDMg%cRn$GmXhF`Ef5NmE zfBp=HFdVp?TZ+HZd@1j|zk}6*;RJpZ_@jM&Zvu6)c0F$)# z!y`cx$j;Ayg9NWYP$`jJU43 zzl&dLzkEqCxG6oUMA98sv8Q8oAk9KUuIcIFn4X?yUSym80DLkGVkze_&WiX~+}*p8 zz=22K*wm(bnXU8J9N7oEr!UFclI?A_tY~oay~h+TlrqHj`4(mcJsIC z>Fc;tMkb`qik-hG#trKvD{w)LtA#>-{}N3Jz#IBRT4^aeN)lQshpQ*Al7Euqo0)-f zmMvSh=m%%!tugM@s-;_wJ=5%r?~X>fyN?adB7CKWjiF5z&SO9R%zot5DzCx)lP_ z5!9hwTO63azeRqid>MJ!vkKluLeVO^F3;cliOwqjurP2g0tw zqT@fB!p98*=ok(2P8%Cn0Z;!^9m9xRAqr0s)Ezu>#lH&%m!|sIa4^{0JHe5*fKdcK ze7F;?4)IB7zE%Tet_Ytle*!}WA%$o(osyS&7DN$r<{E^rqYoYdZY1;+*h$LDHekn{ zGuN#YM(cAG<%AbN^cbf`dcAcCs5Rz;WsZj z0&dC$tSNwWE++CLgN(*%n)l7Be~z$?N82PCBvQ(ukQ~sbcuz7+_j?S+?f#-m5g3Tr_$n*k2^ET9%Hjpr8Db>LygB_%~e7aV>uQyC0=1&$kv z>X>xUYYXK2S|E`KNYwm?4sFLTZy*=mxN|2IIn)Tf5PghTRkw4bR`Vg zn+OnObvB2XIYhoz5e`qpUYP#!I+kWLJ7F{Hiag?H_+_p9*INmjo%HML7AS*|*A8bL zBi8tVRI}~A*mPals;=QZ-hhRemSG zORxED$769!e1xNw+!?*An_f_`cGO^;h_}xl3Rrvj_M8+A9x)n(>BvDcs>so&08LgT z##nJFtXlYh@1 zjRO9o^B0<_;Y<&Li<1K3Qcuf0xpV=Z{F-QArS4S*FO5zE5L8iFG> zG~Si#M&p5O1AH2O1%++s9t3fv=$u{_@T5 z@B6H7qst?_e}7HfPK{Z3-vr0jZECi7DJrJMVdBG!*_k+M-gcMJsle?AsT4@H03ealk+J_0^z75q3iFR@@53+iJ`X5eYK= z#f@}ysSx4RMqUtd{D`)$ZYIVtn3+xh-ju(10kiJ^&C!GHN2v?~Mn0Ev(Ca!Ocg~w3 zK?rrD9eat$D|Y4@i5AOChk^P01q)#QfSeGK^CJ{@a?Z?F_z}gPaN0Yt7DV1~WP17- za&9}w>1b+5y0M)yG=v}rl)q0xLjU{≷uYoQM-KEmKxiMMi^+ebe;zEy32}fL}8+ zG8maoApJpP=MYfF6h>d)Jya>;vn670B_wE&vf->oL=aOX59B@4v0E9L+7a|aY$OVj ze`EwPMuMlNI*-8f-H3=Syb78qSqS&YkjY1n9TR}o3X*|x_+xy$104}z$lbd`fr_%> zbDrPM6&)`iA#oE5?PH`CFA9o^a`ZmW$OuVH*FA;{fsV&ON|bTrM&NI!zz5R!=xYEs zK!UIF)sELo^TpW)uv^m}J=y@P(djjA+}$XSa^j|iyq$qvc80r$#~akRcEphiL_v8} z=joijOifM_GdZcLJEosnw9F7$v>iJFSN;N`hC^z=VzrIPOK`4Bqr}bJN^fawj959H zYRlsPW7iv!}o!DzRHkwTP2A_N3a-fw+>Unvx8um{34^M{e8{!^y2Nt$Np<^KpTvB0Uk=ytch zzMgRGWG;T3ZTe*;X2N{6^$9<$0uU0mKgUj-Im7d$)TsOp)n{R~euP(N0h~xxu!@0V zcZeICoH_Fl+E+wO%o~8U6NZM}Lc}V_!83%`=lWrn;6I_JXhR=M{r?4A=9@mG4}oDu z_-^P9TS-euEHI(SfsL^jN(S?9rA*1pAR_BJ?e+Y+?S_coqrmChmtnxcAp}@#>5O;| zbW2S60q0s`^s6w>(Lsl110jLc5D9Ad5Ljp!dMLq%3*7D>IeC(`K9+AQkS-Bt|Khi} z9os1wwttk_TWtc10z}orqB(Ku6b()Y5rV3luCaLeSWK;-hu)xCoHKueLCGuY#w#y? zNK6tIYvdOM_V(@K*Y0QEwrw?K+nC41(C5ydwH9s&hd7`42&9OO(n5j!-urY9a)D)!6R>hn&4Li@2W3Phf7haw zkm2PJEn2xmiHrn1#r<$niG(E-kSaJiuw5wil-zRwFp%TKn8lq&8xpW1F#|{R0|cj# zNeu*ss)0;S*!^P?va%c)kSf9?z^hk>*o93N49z1Y&3DdcM}PKGyN{TT2~7k#~2Gi798@WJlNF2q`uiOK~| zg@OghMWizDvsIf|*A8Gr4%8VjZjB3{&f)Z{tAx>~L3bgOH__8)V1n;P#5kKH=vq>T zBlZ^Swrx79UoXp^M!Yf#+A+))L@zQPKi0w?C6fu|1yJ&6#1?SparGiWnzq6Vd%aFx`G2SwYfs?wgyNs|H5D=b>PU3`^sW_mHgv0sN#d z2vxWYQ4%)S!uJz+?2V_q>=D>7ezY2+j+*>ey`Wjqyk=E=J4^xreMAia!hXs(Td$EUGD;&O=t09I1R_D@Mw)yA=i1G8JtqQQCnW$$2J3#m2`kh?p5a6wu3l##(bh zuDY08@T^$T8RJ5M-02RxJhOjCb)_6&cM+aQ^6BTdxwmA?=DzrEG1~Upjg&Ha&gB=D z$_omv=O&=n8jXRwr)Ol0+?jamy>8d_e5g>Ry<5*-T{zVag5Y+;e3MX^24BIAkXLEI zuv*!rA?r=77lcEL@DqA!r483`H|?(j0$@;?O;>0?EcWE$;UO}5WdZAo&xu&H(Np2f zu!A_J#9$49G?J+H^OwpN5ao&fRI2z0?{VI5+K?qjEpu=Q3V^`)#pNcLD0bX z^y$Oe+MBiGg@~aUCT{Mgzf^GvhzVLiKm<}$g(i#j755nLL?;@aIx_h5V#KZqMuQUR zU`$8C<)cJ;W58|G%qBR8L{aR_wSg8Mwy)2eYW{O~rQ^%oDJwDaP@+3z?XNOVkk?IK zTPnQ%v!ctvxuWv=+_x&C1;9Oc!C;FaIK%%8muK0nC}r&HLu?Ka0J}(gU3(2{x|2@p zG%b%2>lH*qVRu%@3e-B};zN%s{bhy7N=OaRRGwcF3!W3HVs%{CZ~)TYb+2P4rd{tq zLSiEEOnv{1CY0e|%f7kMF#JsQ4p+1+WtLs=MKvBhrIt3-R0Pufonw7SB(~GUdjW{i za3H@ozkUA9@Ba4gE){|(#%IpdwzeKuT`sc!AVBEq#E7M$uN-#Bngh5i1J>$426o8KDw&Cnpg^3g3LLIcIANVUQ0A;3J@-ncd}3ONj6VNSP~A z8bq7~<3b~pv$z#va)IBf>G;w!$k^LxdJFMIH#Y^wOw z|F$E6PzaUQmUcqk{xI?*5ffOLcxL%iu-ow{eSN=r?)yQX?bk{HW}#3CE$mN!L%g2-6zz0DE)dNoWTvEP)rde zQzNEQJM#8c@ww)B0U8Sm2!&Sb^!Mf|W2?P;?7D2@XM)motAJn2IM^Wy2EqU}E~2NS zt0Ic`^BK&ng`kc>Z4kS>U`LQ@B<*|^`BMCTbFqttgJWu(&ag)-0qApO2RabC+}I0^fY=?zO}M-li##vB%(HlkdaTg8hAg%MBDLZUlwF zzHciqI~XV1N{Js4fh|^pe6K1sNF5OqAQ8E8Aq=HpU_c%7{zP0gGAi~>L&HP#L4!^qqT$rV_d6G>x16!PdQVVL-7*nElSA7|?nNzM)nA|gHfD&$j` z*0N@?}_kOc9VJd3#GE!Jrbqgo zr&Sc}W>lOeI67|OEYvA&rrkkihAk<_;4)#4^H(<2;O$YA41>K0? zRdsb4YS$NYh+)nA%CFYo%b@dhS-VSFYaH#oMQBV)H?jznG!>(^#TXitJW%k_&nXZ@ z>i^%N9>mjUiHTQx3>y)67oZZhCE*j2Yw%(Y%ZU();w65%D~W?2?hDlxfLXB zMsh@h=hpiU{!Gj+5WODIaDtufc0Bnjt>)dh+r_jeWDdQ>?vHNCWD}Vk-3-+AS*AGIuB&s2z>S&pJX1k2eZcKO%jXV@U z`}Wb@1*YXepkX%W&RH(a4iONs{`&TQ)orLvM?QK&$DyXBl@Yuv1CL8HQy)*0Zcb@+ zHh9OQ^U)w72xHNr+=UwEO3Q1f0?)|#ugYQk&J`m@SWGKS%#Z@nxCt799*^XeZg;7y zhV_pMjFX}+5-siaT9&E;I)e8ddS#BKmukILGCdOLG?qtnDeI2eGC8+B_F=& zDl~q=M8mM4+OvM+0^N5i@%7A?D$bB%GTV|*(K-Uf7?-*5V^KDM=n`?(qM|lCQ-@!z zVukXp=f?G{_erKse?AR4GtDp;qgH_c8&F`0w>Dt*$oY={xONu9HaSM;mvgj`b|4Um zEHiJj+uzfDlk$V{ru^MU-e97w28o?$l)H3n1N^+9fIg+#mrV)@R!CB8cxDpw&wP*p zJz*9V=RJ(-IMRShPTK~c?@m+UmNg!y%WCu19UJxQIzYfO*UN*N$ zK0EPFoRpN5?;q=lp>*Oa!(25Cv#09YMAvtC;K&8dSHPx+@U+9qwOeu#_sElPD1?Br zXww#oY@QYbw;3@*8LA`jkCc5X*U%EF0+&md>Y#-W;&6I>_St~c8}as+Vj!Ez{^wiK zzUzTC+98`ibh89%cJc5CJ(3oPL<_{N-c(K~Z{W~WNPsd6Gn#@*Z&h3(A!Z1dEnJmc z4G%;0&A9cOYiwZ{$g3GBxm%zB1$^5^u>&40noajgGPwTrZ3jBie{+3P zyBc-w5D`8{s%Pv0Es5CI>EE=tcY;Q+J+V*5_m|qQ(Em)Y%2A=O6(bK?y%nS1NhuOf ze8K3~DzRq|F%a)~cXO@SyMTHk)Q!kt`-)N*6>qX)o!GmHYu~L7AdHiI`@PsZL6y^| zdkv;q7lpXOELE%C+_dCWr#AhsUx?ZiOWDZsz{HP;pgS=ITyFu!oPYP;;ks|0zs64; z?y3XAL&OMi;2P+yA%564yO=j3tw>5em2Zn+#n6u*ks!0x9UaUd2|;h_o0}lo60xC& zD_qM?et4%6De(2$@@B*@)!EkX_Cy&9#@oJ6I*ccsTjGJiOGKqhPW4@m+lQAJfVL2+ zau`y4$jPgt?*z&pe}JjGGqY3er&}?DlBMPcAW9YzqQ`zL!+Sa))e$_EOY*!0daAHu z*4SYfaDeYbGqH7gh<8`y8s<}yFyX|5-+&TnI%GD!q%46)5nPOz$({Bv?lVK&Pwz|H zgicIPi|p++t+=!i!)+SKtBWIzLmR&(rnlI71NaSpLbG_l+A8hOBbbn9WM!qkt3wNa z02U?P!_t4f>Ld*zC}JBTkV@0ar{cril#kxA>kN&SNXbAE zA+o;6ac;SDG!)s4hgn&)=za`&w)dYd(F8&vCPpiXI!`1a{QoWwq2W=H?4-EyV=ahr zH%t*BNDFZx0zGaR({bMD+Z0t6EB5yG-cTo*wr^*EREQTG45D5F{s&^9p4f&EYDmhM zOTZB!h6VPrZldRwqC;t-qoWHvl2+9ix06OK10dJ}P8`zmVK~@mAgS$kA)W-GCI+Ek zGrE-%@UiC48TgKsOJ6sm8V@54IfAO{N#sSK%^{on zIb$6?Q$k!k4MhvNSiH$XD^nkZ0U;x>fNR&U3*;MWLt)v4F~UAPBqpZa0sFFV~->$$g8V~ym2jJw16Ngn*;r;$2MyVPVnDUcO;uwy|*+_5^L0@2RIufKO z)sOy|%OsOcux76oKVLzo@>TG;a)pJd9k4tbvE$n?0#sGed3J*0=|4V+QI35#HFv?s z*%_RYnf7~es$T;~0sKW8fuNX}OdP{@R1j$W(Dn)M0DX_@z=(<3Ji912x zJM5(J6_H4;Twl8ad24Pi4ZIbvdP3w9`UUYun^4coi_^NO?0d-R7^L9_a6+P*gX7l8 z{kxx;2>Wg!?LBY+&I8ni#?POV@w$n~@9SS+dO4jy1qp4P2Xw(p4Pt4>_+jxN$Zj)h zDlRHYyxj^PhgTig&0ofxSFj)Cmd7o5E}8oFPd%U3=ec-*O$}i{Qw1^Tz={>!7N1eD z9s((1xR;7VO-)UAIrhRcZW!e?NTXAqXvN9j0mD@J!R~q@G;sbrElf^=%vxGn(*Bf+ zKLg5z20~-m4p(#s#)&ywWHb;$!2545xTJg&^7n8>@DeDMnuHh*!48mnArx{;1mfM@ zf3iQD0b9d6*+_%|up^-vb9q9m=3h>^)kQEB6%_@llCPSI5F>?ca6B}3F*n*su(Gp% zMQV#Mq#;C-IyXMSl#uk2A^_1*m+?I3-AO4aTkq<0SEVtNkUya$5lS)K=B}!OC43(s zM+3Msy-6BoTuaL9w*Q=O%Q7r$>22YDTGN&GB9G0wtM6mSv$e{KD~~^a{!Fw&D6?Q$ z0;_YVN5d_$Us%5qV}-CagMGN0^D&2y5_BYhm>U@=f7-rMvHwm}c6K3u)L9b4bu}*q zm?O}4@j`$|i?!c*Q$0rU@kcXt{R;!$3Z6e}_9A8_Z{5%C{m~`p_r%L4Zdu!{`gD60 zMI*6^2`Y@hcCBiW;Nm?O_@edgSEg=Cn5?a=L*u6Bija^=JDPHy6=w?0u9F`NDq?^- zO#g9+{$o{3%d{N}{Y$Z5@u{Fz1=R{Mqv!Do6>!`%rA+-uxV9MSH*j7fxl9in7^v`Q z&i;@=Tr%`M|KPt}7o_v@^9j(8-eiSzsczr9_wVZw;S6R@n5Z7HwF5~ zQ>Z@8O%Rg_Kms2S>6%$gxJ{ z8nWY36T?Wk#sG0!;ypH+IyzGFPo&Pz(Mp5`}y6&kGh~8DI578HOG~INlpQpUMjkAe}-q zV0TpGZTh#)9d&npk$2HGV4F?v`7wfJA=eB;!VUWc{;nhYwGK> zB571m^(aWVfN&fv=r(Gnwd&ryNz2Hf-V{oyO3lHMK+FD`VC<;an36bwb;V0oHa>g~ zl^%&v!iB~Hhu~m>GU0U=qO7deQ_pG84vDucf++IGX%6BgX03`V@9dH=jq5Z}#y=3- zh1d6N2t7gsU(wl+LP*t`#9p7nn~J_7L81mV6|eoe3UQw-D7YCm3~{~z{!D(!-A&-w z80Y%w**_t%+%2!DCz1Oi-ZKcco9wlJoeKw#ZsW#k2x+M&_YVyY2Ev!t%OUstB;m9E@bj*FnOwv+Em%*?FXLrX zV-M;B-b1+!O*tcM#HALX~Q zTr)qHsndKlIjZHir<>VSRp*JfC)_38R(5)^v(wWL--tVGmUih)*1QY<^JJ5*BAd6@ z8QvbOaiylA3|L5LU{$3IsEa1I-^W5jsj$7^hLtcg&50a7>hSRJdu(TQbT+xWFMFJh z|L2WmU;cji(%;{|@a@^BfmNU6>Su#@?%WagT|er*G_Czb6K`#9X$@iI9hskx>Pc65 zJALSBJ-byDyYyr8x|{3mYyoxVK3b-=J_h+e-Z3A*Ppv1FOv4OybZ%18vTn4zvk+zu zU(rxg+v@*dnMZ#@Iw(Ise|+!mcf<#)giTLwH&Sab7iM<%7mLQx@23j9Qi8)CcTIot zgsG{iN$c#{`{JGB3*8mYmLZk}RBH*Ac6QY4QB?SQ=gytXEG!lit#>M}|NTSN)^&69 zwwL1zPWXjKm8qNT>C>kfTFw<3HhrApxW1vCEj2e>!zRT}mw&b}Pgg4Z499?+-~IyQ zN`|mqhi=}z%XszcAQ=@E)lh}=xPnc7bMOmcJ$?PA`4@j9v(KcswCL#QJj%;k-(T9i z8g4;5vAe!6S6AfPPlvA`pYLWne!20>+hP&lbvGd?85wrR_fJkX+@`g#u?gC?Tgb`c z*_BVXpFfv;aLkcfCM7C3c*~YRdD6@LbH&2e?M(6U@p8Jlj5u8Jt6!NtzL{PBz1hab z=BQoYmbtmP*4M9NTi=%3zwNHM=5h2=FGX{6b8tk&WPQi$*A|YB5u3N|dZeAM?729x zmGsE*!&5D7?UODpM@S=UKc-f3SG#L{uZ2{kNMF1C=+VCE*;#oFjcs>%PRVKrxv6}$_7OD+v@G@{e5{^3AdYi+qTh}nUHHMbE8u!*Okr9 z_tpOWb4^i2g`CtJ&JutdLeI#1y0OUQxt5;ZEg9eSkNnPluOBS?3EWy(kas!%*qrQjimaKb z@Hk^#W8*C={j$QsLu8Mpx>DZU+RC_vWK!#s5F8xIF0D@D6A`(?z`(GDq@=9OK(Br2 z5&NYT_wL#DW~eDDT3K5wk@!SKb;tZ9JmxfC#U19gwzh76^(y^j z0Ht=EkO`lJ!~;@y?7?$*(Opt>R1}>@VOg1I`Q?uff`c6#98^tAlGN4JgM+6(zkYZx zF;UaY%ZrJF_}cv9T29V1tXG|MSpWc=`rC;v@I-B8>g1Pyw#a1 zdp2mc51X*Hwbj3>O5(|rC(#KBTS?RJ%6L7c*jH9Jx@7-4U0J80p&{x0oTc2pXA8;r zOcyR%*oW5EEu`-gZH!Xaerk>xE;x~ltA2cb-B2I6jf^Cpy5sN04?2&?+qZ8wE_3?$ z`qHzrN1FMqZElI&t6*i7(I}qDH#goArJ$fd?msd6I6RzYdV1RF)3>i*&24OW?ok71lZW#IXDu<@8d%H}W@cswxVhDuK9<>>X>4p%HR+oAvG9FV;oklGX}CWX zE|b(kX0_pdzt^3ozI#d~ToSF_GsujB^7qe*tfG>V#rKiAcnNm_T+r_gbh0GU?d^N1 zNx@-Z3fKYz1qK0i0aRR)l5E4n!?wfKCoWi8mR$eqr>Lxa0gI!;>j%$+<5#xJ%E}s7 zIFVs#wBY3;Sm!zU`Ibx5J;FzhjG3+$n7v^C@a&3;x;k|n@8QFTaRK-7^KXsfkZr!h zr84s6OPHulXWw)(uKu0m$RPE9j24r%YDmx0@MJAHdEHuT(sPT@AqDC;Zi zTcTo*j*g0ZFYzfy?g^=MopPx;MM+L#3)mQr5;AD??{B^@%Zhz?f0Kob)@J@Y1eVt)S2>jz@#Jf|LX`;(DRx83Dc zRMb0rR@rr`lbex|(XRUu*@+V;wC(H!=;@DBR=P~83z^8Iobi!)5m{ch+TC}RMkiG` zE;ybp23_%(=EGyO>+9=SEBCz(%@1B;rlCyVCCq^)xthjz=+I_Twcl^UG4ZID@m&nT z<}&Eo3rhQES4&hJ(7$uY|I@f1Q{uyfCmuO*zfKUf*}=lHW;Pj!-wYo-S7dzW{2~3l z{X$|^hwac$<3j5xOI4!S9n!?{9S%8dXN$)ki~MhB;6ER#HBUQ{r=R~QBZI=--F+@S zJ39#F)yl@kb;{bxY9Alp7VHz;Hvc?!RZw*Fj@-we{C?45i_z25ySG0qFBjXsM_emgd^YUXEefgYfA;vh{m#wL zZ>X=|gvI&yW#z_|w$4ttXE4)#XLib4q!5{K^=L zPQ0+iCXdr7=nur~Z$Ei*bmH^pF|>;c*QxFG_4NnF1o-&m(0u-^O>x``479+K*g{KN zsPXhKBgz4Zgk?4O>{=4%((0UoRGfR02$Hc_!U}OxC{ky?Pa+>MoMq6oUZ>RqDzWnZ>*gRI)^oM7M zX=rKp@7Qv{JLStjVF3C`K|#UD^mMRp_GxDeY?Pt<=@u3iI@gj`*VpUu=BH1e#*5l) zw;^razP)*A=1tF2N28+DD_EWA2H`c=R$QE!cJJom<_`Q&N+Q`jdsB{~arNsK4GoRK!9nxo*?wc6O*crge^$AwtE+LSeDpTh6dp;Hl_#=JCxtF9x~%^C zHIBkVG;VqMn|i z)){TkdA=_#DXOY&sk-`&8c4?BU1{L9xN~RZCeQBa>FF8yv8Jl2NkIa5QP{WRWn&}7 z_U+p%eAZl&zLXC~+YA?mXb*LDMMZMR3OPGWw#Oze7${!6$b+jCcJt=V3QIHJ<(&&_ zK87V1Hh-*e4!}x0P*mynTY~J-*w}?!x59z~TU4E;v8HXkJw2%z83#By)z6&aJ#^?$ z71lL9{ql5AK<%$NNe1e`rMG6+0rn!MQIOrn8n^cL_h$kwFltW<`8{~>;9gvu%9&)T z{bFKb>*GjKiEOu#cr?pQdmQ=KR#G_FU6^Rnanbz8>>T>mJR(-uZC+CAB*3_FRDH-T{ zP?uU?zVttGWX1-#VcI88lEucx-pS8DsHCX4gT7~D?MK_2H+QiE zXHf1@X;iS}(>FGJ?A|}&-+RL4R&X%!F-l>(j7O(9w~{m2w+-Nyf=3fpwjmlhX|_%Xjc#7^%BCf-NN2_V1tH8F_i?Mo%5~ zbEY*mDwaNZa&KK4XDsf_X<%T`1Kh64#}t#E&IMQ=85$ajpL9Mvb-eVp$fSSZPIc+7 zNk@PLJs|OfgoKRDOeNmaiO~rh&N5cN`8kDzBC)@w$C|J3r_)nTV1|V07R~I&9mPZD8JvN(j^c;sZ;DG-aGpA+&<35g@w_l{)LA3 z(>AsR%FkT`fty*Jd^Nb5tD(>pg3i_cgzBJ^Ydrcrf5CD2(k!{CfJhb=7GW{5$$GE>Q2eflh-3Bx;oBI$mB!t@OMdX+!4Pq@-pItnJt!k5 z@l66Wq}|zJVcT|}H8t%FB#*U>)W3wr1Be=0Q6a9GC{FJ&H*|7-xTbP1xsr2GP>>~> z@Q?^CEiE=XP^%H=3tF~g_XgL_7#ThMWuT@O!uA3E|9-`FZIh{qiAUJ^IxBp&lBu31 zAuW}c-tZ9pI361h8$sB6$yU&$ib-9)RK*@$xH4tUM`qVy({L<)vK-?tFHn=Ky_czR zE>Hwyz-M`$2|japcN2SfPNWR$YD`;yVukVBExtb{J)UtDyS1>LXP?)#BGveVyZxcEmZg{ zf~GkA`stYaL($R=uyW{C^z}b$R1y*r-EZHjoIV}dw}zGLxjY-&Cs&?harEd>3KAfQ z{_JkWTh)c~E#WNW0QpBR4>9AO2Zn}P^{}zBUI2<2lI3tlNjR|hYkk??>f*)v-d>%H zhKoh7+S*Qfc~#c`Dvm@&H(wZQI$!N6f=Yku&+lL8Y^v4%j96)Gz~nkDKYsiWF@H%S z#Esv-R;aWpU!{tVSyzH+`2797LU5Rlj*fjy)PH~M-D0n+l2&^E8Q}aX^XwV+H0ds- ziK!_90g2`DE_j=OGhhB#6$m(U5|k}BHJ(t~$0Z<;r+mfw+qZ8$PcG>e7(LsLz8gcmva+J0sY!GE z^$fmz_4C6kBvJq+tvq;C@0&OKnWzaxsN;cH{`;d;w5+!PTbOq4OwGyJf{Uo4qr))t z@#CG8lqeK1QqEBR`pX;S#$Bh`!E>D4+!~=!fGKamhTG106J-)x4mT;x?#E`mp9RCU zzG0DjB{z`(r(eFl8m)w)fapA(IRIOlcjr$u@Z*21Nv5rl4%Y0sc)!I6e?2q08 zIgjkzxwnRIb@7IR!a^W`8|dE!24$3!laoVFw{Sd=5Q|2Uj`gm-ukA91uu5GE>7QBhla`-ZwYvb?-JfasLQa=<99bLUjbF1`jU3CYxm8+$%qJ3c1u zG(rN0ra⁢`m_~*7M`CGUzdbCFCCS!<$pOP!y=r($jkY^p?K9W8Ah&&_6D2H!$yG z+aAsh?4s`8-kZ6({GhtzsB-{=V<^K;?(UOSi)aB2xRgN4=9e!=0)Q&yO>squST@U@ zIYWod7EAr`ge%Y2Z{IAgT%o%m=Z|vY{7e6ur>8kK#&m!FZa{5<(7Jya(0@3bc*3lE90BcpWv{Ik=8C0y7T6poIL8)!?bbI<3^t*rymWG&lbxToKj=hv_H_4Ntcbnc

`L14oV}7)717w7))uV+9W4R*8ARz7 zDJUrXyQT>GgT?6|5kadQ&U^znX6VKB7w?y5$(7s>6c>D{Z!x}(Mx%^%g?mQN#B?jg zZ+$D+B=wh>;un8nLV2a6_Usli_6M#?%Wt%O(TNpO$g$Vo3ZKgNy;Vsix)BwxT`oO==kpl0YIE=OrusyfX_QY9 zZv!PnJz5|zerM-)J3Bku{=A)I1uh<0jCsF#^ zSx!2(V-9joPQuDj>=D39>bLlHP6AEPfJ)sC3E66FYzz)ZjxCU|QfvKc*JXxc)Q)Ty zM(RM&%Rsq(a=7ONVS^T#;GBrs4}u^pEbI@2_{^Is$5?j`7PCxbib=A|$%L4dydbmbXP*9MNEJI3nY@v8u zUf%TVlixNE508WkmP&S2uOA+FWlSq9EG&T~VE3cLyxL>J;P9}%2k_BxT$KCuU-ES2 z_IV3#|i}O zK5QC|mwG@5+z@49X6}aMbP4y`%GOpDk}DTy8r0DH#wI2qITyWia&q`MIlY%>cb41s z+&rBumHSvGIQYJxfxJnTTPk{(_phIa2vQ}lpb!$wCnJ*#d42{B0WccGnt;*ZQ|+y- z`}Fno*FnPZqGQMIvmUj5IWwxMsX4v6Fizd?rlh0fl3mtM)A!fU*h?-KglFX) z-EGR}PV#VbpM=DPeI|}7hEv#aZPdvjYGA?JN=qyVE}uqGz~%#*bEc~G#T z`8d2ZQ)Ko+Dhh;(uBWFrGB+ngUyPc2oYMZvl_*dLqP-4Px;`!~9UIWY=dfc#=`5s3 zc`=}%L*w79RoVC0?1dkg@hynI=tT5vY+*0{{$YbZF^F2$A+|=-d_5$zI^v0jy1MwG zXz~7;PQ0vA_Va9XwtwE~0PZuB6eK8r1XlA~o7_$Mdwl%w^}oM3j<=`{FR!hwG2CbO zihBF*-8*r=4RO%x&b`-ue5NfeD}xb52Z`0<_xduin*|RYD!I@^y;bP}-}Z$k*h&YO z&MvlR@p$toO>%)9xph1|PDjTfa|=Bc?}lq~==kYJItgaw9iCFjxBO0T_)X@{;C)U% zzZ#%aH@tbn*xuewXe`Z99A=KSEaC4tSwH8mZ;ERfcYaPDoKsF$DuI<62o7smcXKnt zU7>>l0^j@3nOXe&`i?=UA+Jv{fIA8b-9A}a4iM28Edg5Aqgxgh7MPD;POSe@{^W_4 zmexz(>#N^WJAR-i5rR^I$@8-pE6^OJq@=V=O(TJmU%q{NPW_C&zO|C#>W?njOsQCX zFEj5Pi-y~&sJN=Cs-&ovhTcq#%;u}s+T|Uj)~_W{ZQAwUkP#)RBKZ&Y7v+^JS0L-W z92oeyckXsw^chE==w+GLHV})u`}%Hygb`{qNY)4%OZ}sh0ZzEAcE|Jb3Mn-baSZ!} zg|*t-n3siHGFjlX&oCO?0!2daQzccD5K2zzwf5<4~&o*+coUG>%w!MFTZSxXGsq4XE9==#}czir_*xd#tyBUOe6cza8 zOF06j0AZg!dzP>d}yHLFa<~2G~LK^?kX9z;-wY85tRH zL^pT8dD8$NAUZKokh{0A9Vd7Qj0G6!CUm{eok?MkUdG`m7G0%M144q_U-#hy8?b=_ zB%}9F9S`bX4()Thdi5&GDb=36do3K5$vEn=f0|FYTI#~j=J>usy!=X!#qkW*=z<^c8RXcHQExYrVj=dO6N$4VV z5Zs6kPxz5o)JKjV&ObD-YuRMpM=>B53W&Miwfej32+G&|p*b>gO7oZgWXtUHt#`OY zTqat*qvGmv_`lLWB!umk|Jv0J*X;M1ReO?=laoU?>R)}ZlF4NB!cTgo>|X_W-^$P- zqoGtGKw3t>qAd3e+Hc{LeKSo4E+=-3V|K_7jnJxnm;wh2C`(IgrgkY@8 z3oxUZ#q93&3GCwH;+jh@ER0Z&U?t1>Y8`Ta_vKHuduzOxGKy+}YZ^IHbhyUyZ z$b{wc%-gaxdOyPtFw^39C9VReBW@e_&6xd%3TWXVG!|MWX-;UAZ%K)vsi)=tsW8?p?dI__Xfdm8uI0GF2 z0745rJ=9LEu4L&GgjM;oC09To~ zb@cQ-I4cbjp?%&2fenkG9>|zekJK;Jhk*m@NxRcqIIc{K4d>yYfq)C z%>iCsjV3Y3gGU_(cl?;@ic7d}tHw%#Z2$88dsYyZp%vaU$$iIukpx;uU?7mQ<_rPBLE+SA-)b(GRkGDjw9<34`OxviywqPqVH%`F1dgu5(E&Y zoD+19aCT`!3sb^rcOGwcwkw7g1PAg4qg?BoaQ&viL1rj}4Pc1~QG}wDr2%_Um)p(f ziR<3tbWh+sW$eCw+#nHq5L#_wM5D>Z8!Av+3*tNkSA$PR0 z`;R(0E6$bz7{3I_xOnm6>P&V@#iAM-XnSX0-@P}D{OvZUUY*wS8@r$3q5VRHnbYoD zKtUw5H3~{fb-oqg3}VZ|`+8#6PmMK=>cVu)@jZp5<+w*@^%h78TYtQQLOsl%47^!~ z>wfImF_J)FSzTQnVSf4j{q5m4KfIUZv^=XHB72cuf9FMPH@?G%gOZbzhmI~UFLM{Q zy?(u!gqE)w-lb36-^b7d1Wl`%;fKpZi2?m)vg;q#cRss!vClg6sB=h2Ncq4E{X>$E zN;edbSWqhLDqlD$fNRE7Dl>n zkWQJ!9|nM}#a%%>2cmUA@W1DmwMA+6h|&Xbr8PaM@dj6kJWf~F)W8i{@1-qN+xO%= z`*g5*Dx`w0bT->g@_cqB10kfW`T^QQ0RxWIogD%sq1h|JL{3Tb5-|!V$Xy{NX&P}t zHLfzXf7b1BTZx|t%>z*EZ9vJhXH?Kg;JCs|WNQBL;_q)djr)Qp<>W{%E-u(SNY-p4 z?0a;MO!I8PXlKWbQ87%If($Si$8u4>7dY1YM6#ZFhEO3r#^bW!pP|84Y)WV zM{Qm|2t;b70bE&;!pO)7$e{e}N^w@!?Gvt_3F{XZaAd&~&R8S#jqXP$$$@Z2;0M+r z=Yl2JdZ}MAv<&)6DvA^Elr+4=AozITVwq>XcI+<_;^NH7%~i{JrTCx%><#~K0Y%4l zs6vGG_+`Q4DQG2x#0N$i0{rEA>5{$uc$}HvNo*lBvPW=|2nYt6I)BfDGF?E^qZv^S z=J>gApoZD4Pxsu=K8QfqL62uDr1KR{`;Wi-Ysr1|C=*cKU6zZsw&xFPXt1PE!A0+* zHZuBP_pE4jFn1<&A7y~_1yN?2+X#iUA$aEEd6?G9@0R#luBDmclZdXH7iLGFr!%l!yQwQvz1Q*<#1lOuVSE=guyem)3)o zuDpa}cq=H#b!O??hdA9#u?}ZMHu$s<-)Qp z5Fv5*w@_>%>QZE6r0S_tn@Qo!BAb8)nT5?su%>CQUAvYbt*yP*CP1gu+8f&@5Qm0I zFi|LXlYc~%{=30CbiYzR_6oZ57CO41*w~$f42EJ+T`fh5jc`1Fo*8BnM7}8GI23?| zQJIJg-`PS#Ztc@PGATx<8qE6+EO}JeDrDpFL$@KXGz#wY__nfWiRt5|EV%gVYS1fZ*US28`5(Qj4sH+pnhilKdy5}9H z@8|DCVdb7{>gWjn_3q=xy#)0HZ4SkHAp)1*fBvM@;(rR#bQ`EqGhG`9EBfBOTM%d( z0KcHXB*l3e!xx)qc|~1TvI?MJ3#4Z(*@mf&d(O#grrX_WO6IBF&FO zLysWYfBotZX#E~e1j;!qOM7-VC8f)2hrRsS zv%8@CMxp)8ori2r&%&}5fDS50YxU`&L+5q-<7_Rxy+TEiGbk#d*tfu`j^qqLLU2@6 zP-Z4Kq6>EAaiRZHj);46P5+QAsa!xosr5~4n|!tAZo%{Zh;5AmB6fFo%OM8>n$G`2 z0`WY8wPGddScJAS<$O(`LmNb$LIUk(Qj&?|l{)rWK`6`-`X zw)PDmHfNqoUcm>8Z^`c`lv(Rn_np0qPyh(;0$>{0GcLcCAypNCMK%Al^Jj?0a8`HF zBaR#b`BpVU)UJ`_6m(fBnF?%PL#QSuTU{N>aSXXsRkk{;WE9|-^ib_AKD zGFK26x58)b2r34@D|M*qvbDYaE3D`jf0b=*b8c~d10NrRwhz~f5H($0T{jk5I1)c! z?@3egTwmfxQy`o&@DH`6Jc>sVy`#L}MZ{$M9WPL@%0y)fs!@!iiiS z5=YgCD6~&V=(L3oaRr@CkPKjfY%XqM(C?C~j+QQDTtS2_S65d@K3sXB1Y?58c5R*f zfc%*-D$U@B4-Lb^>_`<6f(&$jGQFR3Nnpj+)?MZ?<7jNhu)nX*qx%W);5On2&z4_Lmt%?s!e6H$iai#0PC6%&yuw|#$rb5 z_^hkKb0#?)Tjk`w9de+c=v*xxpM0rE1jd3r8Hg_EeC2`c(UhA-9f&dC@3LQ z(9n=o=khOzhlJsA>eMN;=e*{D2YJ+DNEz##nYt_AApTM`NqO6&N5NSN#DcMAkh%|R)FPH&>g{#hNTyL==^ z%8I|QF*k4VJ-jO^X=%bOLQou_1Wu>OL=cn$G@C#@7dzr_ z;IO|U=`T0wQUxiX0SpMKm?PtrNOHqS5q6nSMdJPu913wLSmiTai6&LI2yYh-h1-h#DXd7EW7#Y#Tv72qBwT1n{;lAoR_A)K;r-JXc*mcDL3EjxNZaa+!M& zw50(*EI9kmd7c^$n=8n&wX^$Uru^pxTj|qrUkLCxMy2f2N#axK*k`EnW?we+l#C}g z%e8;z>V2Z0&4W9W!n6D*7~wL(5}G;a)XPb?C=lw=NjuMZGcV6BX?$1QX;QShit(Gz zpae*rL7ctN7)%dsztD9ZHerL#JZ%O*=AVrpXGn4=n#YsR=WFU~Tk_W6;w#g=6@)z?HQ_Z?2bD#GpoT@vI@`xWNUjKd&41zvi3M#5MFtBnfD&ouvP(L>Lbr2>nyiBN7XA23HKJMNEd^2IwJW z;mFPszJ77GFBe%7B}hJc=g;#kc>P{4?_1OK$RfetId5pViG<)~7;2IF)`R})7MBr{ zChqAWvoC3KceC{+y%rC+xw(nc--dUA_0qDuOX(O_k50#XE&ch=6BD-}lQw`291MfB z6k@L!^%=5}Cmh#Jn>JO@RDUq^>_!54qaHg}*bJ)wu%I?I+^WB+(WzlE%^+DaLR^Knh1-ev8N$;hcMv*+; zj|P5z`1%}+d&|2%!d6G1mk9TuUs58mHb+=$gsf!IKuLgSUf%5YZj+b#QI>o1^bZcz z`WnrZ>+f_dKe_Q9!&D>Cmc`v?nUJ@NhQ^J0KOk`$SeBr&&<1>`d_XcI@04h&0F}m`A6nk9rx3{hL>E)?f+?4Hbrjy0X~Ib^Q45 zfq?-6G6Pr$A=@8AX0gP!KO`h7oX1bkfy$`3N8v(jBO%D%eU>=RQ3lKD9~ zau}&1?l^82;lf}kQjdd})*+QhSZ}bIUX*P*m3)?#2n-R#Yd^#hz*9JM$m8T|SC{Wc zgamQJ02nN=gCdEMERcVquVi?C4MmG-f|1poeTD;rEAo)zU}D9TW})SCRYMa<`1k;V z+fmzY|C!D|mhopJ>O8L#6A$m-zefP^rXDjA{oZxCy`U@!^a%Wm*1V;<87mpE@Mp*C zJ4GRMi)H0&J~UOL271|Y+h}Mu&h)Nz=aom5`!Ulv%Y2|Lt#!9qRyxIGTi%~nV=uuG z^Y5R;zYh9urV;s@r2ewkEs$#AhQ9>K;=Zbu?=8EirKddRd^X~*?ieU{cYl9iSlBC~ z)TZvplDu}NN)#XvyY{3~rc3;}4L=zhyHY(j2!+$1UcBh*)yOii^l=dWn6T%g0m#gM za_{jEA6jAuf?uk5drS27_m^D#W=KTRp@e|*-&r5;#2D0#8)R5%nRD4Znn(%|X&3~n zF+F7bZ4Fs#L^qWD{A!1)&jtN|#G9eg7GO*WHpFxQ)&&6f#DM=Roy;~%2xX7+L z6GDV#^vjoR$aN0Be}4hvbSYL*4;RSpWN%*Yb+`Fn3<`m;z`+x{%03 zv(S)`Ty1ui6kbh_v;QuPuOFV#p@{+`2@pmg{0vv*$?2%HPQ2@T^=g|2*ONomFC5&EoJ7MdSNNrR1tS?`_jH)!!{OF5D8KoX;tBJ8O%vK6q zEtE{PoPox3a*)e4e2a5(MiwW>#_A`%5U%6nCOj7 zFWm(29fzo1fu#QFMDZKYi=9WuE`_>TEeBRyq|MPQYzzB~jY`m7+_Q7z)d%H=eOVA@ zMM{$>gDd=ed?Vh4%b5lrUR;+Y=12)!ikR}iC#Pm*o&6$?d@&gb=IrF+FN_r)JCUS) z5I(jt>wimDk}%7JkW8HIsuJyKGz{Wid3daNS8_b+)ggu{NU?{*5a|(I@k17o7}|ks zz{SIprR;UC5mqPW3s8osVfcqVKa5-=M*Ex|l!Et}e2XeHWY|}iYk;K|c1_=|~Wz!des-6%7E$Ac}b1)fp z{SGJ_GAVTME8M2L$$%#?bwfcgc${dzKoRKfC}dQa7XariXg_3!4;OoPiH`pWRB@@= z1DX1prh={O|HZV@$TAUk=}$`)ZkXY*HvHZ~ZB7FqYCt z5QpDO+{MaCUyKvVly;c=F#XemShOk|yHI$LNy9yBfS4oXe%jet1T>NcbsWgAzNJM) zzTmOnZ*M|+$Lprw7IV0`x@L|MRs*h%b+g${B?0089zci|T$x454geS=gmnx{ytdl$ z_8AdULJTKf`r0uf(GQD4%4?AVcdme{ZM9(4+%g*JUm{k6Y2IMi1sA~Ni3AprxStGx zAJ+udjDap1oNdB_@$;*+pq$JnTn?aJ0ODn{N>`!j{CB#YFhvBp(85|fJ8xqo1w!8; z_fBjcr0pu#`XSLC#B(Ibn|tKHmSiE5$7T7X(Z}Y$srN5((bn zNCq9K=$1E0{Bl0O%T&qF>Pz0gdzY(Z&S;5&A8IwKH^cg4G(h#C9~ko?Cb8iNvrgqo z>>MOyN(exfknGA$sS{FC=)h`1ESE3wUl5iNoAovO`d?tWWW76yEatt4cEkDdx_`$I zwy&5hRoI)GlW0c=6cqgW`XU zS;W&C5%hv5e-rErk4)%DmSzJA9V;p?Ev?78>qg)K7D?*+4FR1STLa~3IAr!9p+(3l z<<4#OC{tKHQ>MF!0i_Qfx9e6JEUH9Vsze_xYRd`>?|?r}gm*EY*vMu{j}MlIPL5|b zP+`syacmAqb(=|^|66ukt%*oG;^vv7{`P-9mrN}PCj!V>9^+6p-N(el3iau5_)PW# z1vfB)1K8w@7&y|;r5`C-%mf_{{TrmVC#1XdysmtwcZQ41)U*2TX0Ue+x z7-zdpq)xLpmfMChT?!R``c2Q<`F& zjs54`-)WjAB8W5s@Q7U%Oa1EAs|G9~2t9R<7yhQ6hw*&v(~K}CVi0rI(b)85+rqUR z!#K{ScX-DqjrVwBh;q$rCz0UQ@^yz)?FI#wh{{8$nC;K6e2kk(AZJ`2WJQsn-b_D= zF12Obwg$9=o^tzhA*;~bN56ihAvt+?sJOV48vh;yr%nZ_6PZ~3_Sv=Q^F| zjm1rYeEVGJ6UcT(kx_?Uis27-VIr^o{CoR@KLw9z#Ewc@d7bb)Dt1a#p_l54wb#}s zdcBKR7jq`b6zLm9uIw{4|NUpgf`c;NB6^|Lw5#DqYlo@5uZ{oYaM{YAf}h_Gp6bZe zTw|_4S4W!)N3^J@s0hPb(?jobqEZ($%oNsAtkG^6oOdxYTI$urEM*_8~?Mb1FJH`7{cB;I+18eh%_y=5?De^hd-}PoPv`*x_j2 zVaw*jf6F#7IB_qyj81l=JI9-QMs1~gtn=#pa0FB{NZwTH^(G4P@`Mke|MI0(IB#TF+AX@GpLmEUojlfUo>wAwmFoV@*U;Xx;hUJK&O zEI5N_m-j*-gUn~5_BU4@3mLM9z}87X1>#vN(#Mq(tbEkG2jZpXG&$h#fbDjKvxsWt z_d|gb^_VjzY)x!jxEalF-^Rh0xpV)%G8`JX*%#4U;lvWZK=sWFA3nk)OUcb>g+VEx zKjom=T|0LYS#M}ih(s!9>MZ>EHP6=n^azK~cQORTVH&+b3jlhK2xU6RLB4`{tWxlD z5KhP!`oqtt#A**n+fURC#vG6q{pUYwJQo(lE+rq0(p8Mh9cv}Ld!XaYuI0Ip58sv9 zeDa7OVdNWQZ_j$CklLcq`U1Y)&4qTV_!`&d}K&(Y?g=lxg1}iW*7C4ubR3h+GT8}Ms*vvwLlo@J4Sl?x^rf}N(gDbd+u=Gc0F4D)>K!=2ao@0 zM{es1K={Ja(gZ3(20VbiLZfrMBj?h4oDh{r|FlglhP|4K-D3dm7`I8b!^GR)gXQ+S zp=IMZ$+?4aGiL`1F|Is?2Z&IPOvagIq4Kp4=c;F>VeUfzbR-GZI^hE2z({ynSL$)^ z*ZuwaTfaGetP(@hlZbnV058Ful9Kkav$Nx+ksBKu)b3I%L#`l^Y`@N`#w_j7yGD0J zP%s=&|IvX_Z`>Ek`Idp*Ywog73=iR5?JJXv?!-MpIldSF1oHQ^V%9rk8N@n4roHBC zR#Y`K6f$+3G09%jV}H1IHLY_6Qv-c!?fgj{qt}aHpda0P@n;F`y06&mQ_lJUHE;3c z9LY;GO>Q{SSftIIrn~n;qvsP6Dq51@wd_bdaTkFZ&E|x~1Dgm_lW!|2P}@ zEtnN9kcx|ogF|o#kxbM&qCf@2yj}j<0rI|D#*@9uLuICsM1*>HGQk zf-&y(5GG77L@??P=*`JsCP!Im(e2FF7AGZU#@FG#6MPBA5CMrmn6t0{{nMYP8+L>bB*#i-|Qk~8wQLc_LO9fs$ysElQ?zDR) z`X)58+WAD(ynUp8c%gJj8(Fbu9Ke!|I!bp0L&6ct3aBlWPNSQk8bTAvSN6q*D22|f zo^p^a=prAhBQm%|ls_l3UGV&45~N3Lt$W2#ctkM{K&_^N4>iza_jrn#VhAe`GqChi zm78KQhZZ-ywNy}7C4J}a-E8H%KVni8fH1bWSF8pc)3MYLXR)fu>hTmw9^}3o;W;gQ z|4z^?i4WOXSz~y75kjF@y@Du@UUS%{h&b;=i~!brNMxk)mXnyPM2{xsBTB=_WW)hx#z^Dm#EMS znC=2|Bo!EzQ=_60wG0;2qWDWBix+9RmdwdKa_gRYA1ptZ((3>GiOUW4If4poTmJsn`)#$J3!KQd5v7EZ7&a7_kT`

2n$BzK?-gY_aF&_}2JYiL$-ANHBP&fn zI1-G+#-=7RZhmRtQE%i=OYqP#N*ZQ=&_G~*iMVm*P|<_5Pr%8ddq#J`_-=;44dDVy zl9<;9PLR-0hh$AecW%?L5VY>zhXX-0ENQpC0x8`EHn6gq@O^PvEk<+dMoUs``|H>G zF8ej!4G!XoT$|-^Ct)E@L1zP5cmCYLVomqe&$isq)N^!mQi(bXqs>K!qpbdT1R6%~ zDMoOn)l0n^L|C17_H}1xBqY}#?`%?L4x|$CBs?!h$h5i@eFbY_AlE1+LuD%UqupSJ z8Y7CiJ3GOJkeDqztAV^YfC4cnjL^sqGqX>u5jK3Rg${|x3$kLb=XVbe*0e14*@;;; zhg(3Km555g%n0s1kw6&s`EhD;0a^wEH<$~Lk*dC*(bA#ta37XPk6k&+Fu6aBLvUkd z;CJF7bl@)fJWbHd_-$^c9$@{35|TII3Cr*z`Y9@z>+f~5`RLIG5CJZQx*#P30_TtH%p?*m3&!x2Su0X^fUH^FJnr#2-S7#WpeLV*ZT7#8w~ zi^rq;^g>ZV7%4%@>j*ptC`_SnoZu}R;MoCqBMf|2?GZ;l)VWGezlm4pu~Oud^Y31 zb@esHC0nmSk72JM0BqL&D2QQr=v^kihG^^HdmxHX^-P`nw;jRBkX9K9J6x;v6a}KY z^1M502jRn^O+0UQM=*gN>U8q;KVBGp^@sR?Sftq8iuMDDdgu(rE|Ll_j51$cAfN*p zDJF94ds#DiAGXE$)|g>jBCm&G+nG>I5a^sg--?Wy8Bt*|*{|W|c9eu*FM%Zu%hiR1 zh|o8Z>7zhic|Gxn24HwD9LFA$kN`Tm9fC6CpHPHH`&Y%JsbP6f;h^{J-#=RW3u50z zv}Y1Bn&HG6LtIlgmQQ-KX4Tg(c#26B%IE2vZ?b>a&H(z88eY{x)hzXxH+^J9Uw~nU zZp6J%fV%C{jw79u=+-hE1d=pB@;0D!QTId)!k8JLBm@YGkjfC^6%+`O zLYbK(ni1+it$W0kSd9@dZZ;~+E=t6(N+Fh7G9eOi3nIW7KxRL0f9>Bezsvi3-{<*0 z-{<>$&%7+p`2)&Y1p>-E%r ziQI}!5x@1~S+8{}S)zAvAvH&I4ArS!Jhkvtsv4WpIl z5F3CADv6xL9!_877$rl}AHS^Y=^WZsGu5n@Sr(jZa1vR*krd}-gZupbeS zD)o9jl4!L=euOqQ4wFljl7}Q)YYE11B}3kAiPe!+33=F*Ib{(;%Z5$p0=VBb*6pEY zLrlp1#v3<|P%+JPQ?dm$^jGZJ;!bj#q)Ag!$ob&8;@y}AcBiT%4ZmcnT-IhGORXkc zHy~l=T4fR9i5%-gid$x=4#w$5}4F5 z^=iwN5;^*(BSeffHg2dh|M_cc@v-+GKSQF5iq_mY^lMz7a*n}O9jC_7 zGEIU=!k&l44+x^o6ADQsu}nM|ht3fuAezE1& z-?5XXB~+sskVmfzL|^gdldC$N;P3nPdrD}fKHH*VfC+9-UA z=0Cm*878!nT{^VPVx*bhC+_|1ldP<)>CQTzz8ifSbSbt8=-ALxWQN~t=`DGgXtM40^Nw_<2LvLY@g`CJDQY6U_G&G#Q* zAcagJkUwDxU7Gx7E$`qFu_!8)gpBr4n!#y|3S7dlnkyD}Sy@(sRe+HYnBP2d`)$m( ze&KKt64mT3V!_TZ%fI5cZMzO3c<~>qrJkN~cp5T9blFhDv_skc@`DXW9sHUenI5DW znaH`|bDl(ltt0>O9^4pbww|1W^lr_)U}O6iBO{AWPmh|?PWnU^`FvBc~hPxLJ*kJcT=pGa;)5>EMk9BrnI zqKBNbkG0SDiY@CeK8`kw_7 zjg}{|ngPfdTB%jT=ETLQgc-XQ?OO1HQmu|ixQdb7)YxVH@6;w@nuR`K0v3tfSzuf- zuk_cs-k*-71m+g>KJqsxVhgPaeerxM1T2Fg1;gKpsa}Gdn1R4MZEsRi2TR5x7}E;n zHr&nhbGEH%!f4rDpIF?eiXI!C9e$^M>h=Qs33GkN-|8+p`}ex(U`LeOVOP2r%T9w@ zWqA;$|9*bYHPKI9+ZxM^3A!ex5$js*{aPynmQIY%5-mZ>jLbHL&;D2A|GR!_^X*z> zcx%#KYQhfvlzr;OfYw#Pf($+IoX?Hmb?Y=*XTWmXh2Kil2fY56_DsyfeI#;V**m2V z4LD$aywmH)=CO(=t9I?dUIrTQD>BZ_vh0h2P&le-B}En1ii~?PH3b7M;Th?30n?$& zznKxr4QyZYhkosGTlm)hf$m=RR!fB85L`yyluPbwE1rG&ox)df^|uOG9sEX_{N2O< E1K#l!rT_o{ diff --git a/doc/src_intro/rs_driver_intro.md b/doc/src_intro/rs_driver_intro.md index 52f03ebf..04ffb6f2 100644 --- a/doc/src_intro/rs_driver_intro.md +++ b/doc/src_intro/rs_driver_intro.md @@ -627,8 +627,8 @@ cos()查表返回角度的cos值。 以RSBP为例, -+ 一轮发射的时长为`55.52`纳秒,这是Block之间的时间差。 -+ 一轮发射内,`32`次发射的时间戳如下(相对于Block的相对时间,单位纳秒)。这是每个Channel对所属Block的相对时间。 ++ 一轮发射的时长为`55.52`微秒,这是Block之间的时间差。 ++ 一轮发射内,`32`次发射的时间戳如下(相对于Block的相对时间,单位微秒)。这是每个Channel对所属Block的相对时间。 ``` 0.00, 2.56, 5.12, 7.68, 10.24, 12.80, 15.36, 17.92, @@ -701,17 +701,19 @@ SingleReturnBlockIterator实现单回波模式下的BlockIterator接口。 ##### 4.4.6.1 SingleReturnBlockIterator() -单回波模式下, +单回波模式下。 在构造函数中,遍历Packet中的block,并计算az_diffs[]和tss[]。 + + Block之间的时间差是固定值,也就是`BLOCK_DURATION`。 + 1个Packet有`BLOCKS_PER_PKT`个Block。 + + 对于前面的Block, - + ``` Block水平角差 = 下一个Block的水平角 - 当前Block的水平角 ``` + 最后一个Block的水平角差,认为等于`BLOCK_AZ_DURATION`,这是雷达理论上每个Block的水平角差。 - + + 相邻Block可能跨`角度0`,所以它们的水平角差可能小于`0`,这时需要将它修正到[`0`, `36000`)内。 #### 4.4.7 DualReturnBlockIterator @@ -878,7 +880,7 @@ void DecoderMech::decodeDifopCommon(const T_Difop& pkt); #### 4.6.2 SplitStrategy SplitStrategy定义机械式雷达的分帧模式接口。 -+ 使用者遍历Packet中的Block,以Block的水平角为参数,调用SplitStrategy::newBlock()。应该分帧时,newBlock()返回`true`,否则返回`false`。 ++ 使用者遍历Packet中的Block,以Block的水平角为参数,调用SplitStrategy::newBlock()。应该分帧时,newBlock()返回`true`,否则返回`false`。 ![split strategy](./img/classes_split_strategy.png) @@ -930,7 +932,7 @@ MSOP使用UDP协议,理论上Packet可能丢包、乱序。 + 那假如只有丢包呢?举个例子,如果编号为`1`的Packet丢了,则可以加入检查条件,就是当前Packet编号小于`prev_seq_`,就分帧。 + 在乱序的情况下,这个检查条件会导致另一个困境。举个例子,如果编号为`300`和`301`的两个Packet乱序,那么这个位置分帧,会导致原本的一帧拆分成两帧。 -为了一定程度上,包容可能的Packet丢包、乱序情况,引入安全区间的概念。 +为了在一定程度上包容可能的Packet丢包、乱序情况,引入安全区间的概念。 + 以`prev_seq_`为参考点,划定一个范围值`RANGE`, ``` @@ -1085,14 +1087,13 @@ DecoderMech处理机械式雷达的共同特性,如转速,分帧角度、光 + 成员`split_blks_per_frame_`是按Block数分帧时,每帧的Block数。包括按理论上每圈Block数分帧,和按用户指定的Block数分帧。 + 成员`block_azi_diff_`是理论上相邻block之间的角度差。 + 成员`fov_blind_ts_diff_`是FOV盲区的时间差 -+ 成员`lidar_alpha0_`和`lidar_Rxy_`是雷达光学中心相对于物理中心的位置参数。MSOP格式中的点的坐标是相对于光学中心的,需要借助这两个值,将它转换到相对于物理中心。 ![decoder mech](./img/class_decoder_mech.png) ##### 4.8.2.1 RSDecoderMechConstParam RSDecoderMechConstParam基于RSDecoderConstParam,增加机械式雷达特有的参数。 -+ `RX`、`RY`、`RZ`是雷达光学中心相对于物理中心的坐标。`lidar_alpha0_`和`lidar_Rxy_`由它们计算而来。 ++ `RX`、`RY`、`RZ`是雷达光学中心相对于物理中心的坐标。 + `BLOCK_DURATION`是Block的持续时间。 + `CHAN_TSS[]`是Block中Channel对Block的相对时间。 + `CHAN_AZIS[]`是Block中Channel占Block的时间比例,也是水平角比例。 @@ -1147,7 +1148,7 @@ Block间的角度差 = 360 / 每帧Block数 + 解析得到FOV的起始角度`fov_start_angle`和终止角度`fov_end_angle`,计算FOV的大小`fov_range`。 + 计算与FOV互补的盲区大小。按照盲区范围比例,计算盲区的时间戳差,也就是`fov_blind_ts_diff_`。 -+ 如果用户设置从DIFOP Packet读入角度修正值(`RSDecoderParam..config_from_file` = `false`),则调用ChanAngles::loadFromDifop()得到他们。 ++ 如果用户设置从DIFOP Packet读入角度修正值(`RSDecoderParam.config_from_file` = `false`),则调用ChanAngles::loadFromDifop()得到他们。 + 一般角度修正值不改变,所以一旦解析成功(`angles_ready_ = true`),就没必要解析第二次。 #### 4.8.3 DecoderRSBP From ec6a64c031facc89085ef7d2d8d29d00fb5a058c Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 24 Aug 2022 10:01:25 +0800 Subject: [PATCH 351/379] feat: remove option ENABLE_RCVMMSG --- CMakeLists.txt | 5 ----- src/rs_driver/driver/input/unix/input_sock_select.hpp | 2 +- 2 files changed, 1 insertion(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 696da938..65175605 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -24,7 +24,6 @@ option(ENABLE_TRANSFORM "Enable transform functions" OFF) option(ENABLE_DOUBLE_RCVBUF "Enable double size of RCVBUF" OFF) option(ENABLE_WAIT_IF_QUEUE_EMPTY "Enable waiting for a while in handle thread if the queue is empty" OFF) option(ENABLE_EPOLL_RECEIVE "Receive packets with epoll() instead of select()" OFF) -option(ENABLE_RECVMMSG "Enable recvmmsg() to receive MSOP message" OFF) option(ENABLE_STAMP_WITH_LOCAL "Enable stamp point cloud with local time" OFF) option(ENABLE_PCL_POINTCLOUD "Enable PCL Point Cloud" OFF) @@ -148,10 +147,6 @@ endif(${ENABLE_TRANSFORM}) # Build Demos, Tools, Tests #============================ -if(${ENABLE_RECVMMSG}) - add_definitions("-DENABLE_RECVMMSG") -endif(${ENABLE_RECVMMSG}) - if(${ENABLE_DOUBLE_RCVBUF}) add_definitions("-DENABLE_DOUBLE_RCVBUF") endif(${ENABLE_DOUBLE_RCVBUF}) diff --git a/src/rs_driver/driver/input/unix/input_sock_select.hpp b/src/rs_driver/driver/input/unix/input_sock_select.hpp index 56845520..151ceb9f 100644 --- a/src/rs_driver/driver/input/unix/input_sock_select.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_select.hpp @@ -252,7 +252,7 @@ inline void InputSock::recvPacket() if (FD_ISSET(fds_[0], &rfds)) { -#ifdef ENABLE_RECVMMSG +#if 0 #define VLEN 2 struct mmsghdr msgs[VLEN]; From 748f429e61571172a40613e846df7a03c48cb9f0 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 24 Aug 2022 10:02:52 +0800 Subject: [PATCH 352/379] format: remove unused code --- src/rs_driver/driver/decoder/decoder_mech.hpp | 12 ------------ src/rs_driver/driver/driver_param.hpp | 2 +- 2 files changed, 1 insertion(+), 13 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_mech.hpp b/src/rs_driver/driver/decoder/decoder_mech.hpp index 2de950c7..92743256 100644 --- a/src/rs_driver/driver/decoder/decoder_mech.hpp +++ b/src/rs_driver/driver/decoder/decoder_mech.hpp @@ -95,11 +95,6 @@ class DecoderMech : public Decoder uint16_t split_blks_per_frame_; // blocks in msop pkt per frame/round. uint16_t block_az_diff_; // azimuth difference between adjacent blocks. double fov_blind_ts_diff_; // timestamp difference across blind section(defined by fov) - -#if 0 - int lidar_alph0_; // lens center related - float lidar_Rxy_; // lens center related -#endif }; template @@ -135,13 +130,6 @@ inline DecoderMech::DecoderMech(const RSDecoderMechConstParam& con break; } -#if 0 - // lens center: (alph0, Rxy) - lidar_alph0_ = (int)(std::atan2(mech_const_param_.RY, mech_const_param_.RX) * 180 / M_PI * 100); - lidar_Rxy_ = std::sqrt(mech_const_param_.RX * mech_const_param_.RX + - mech_const_param_.RY * mech_const_param_.RY); -#endif - if (this->param_.config_from_file) { int ret = chan_angles_.loadFromFile(this->param_.angle_path); diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index 360a5338..b35729c5 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -294,8 +294,8 @@ struct RSDecoderParam ///< LiDAR decoder parameter RS_INFO << "------------------------------------------------------" << RS_REND; RS_INFO << " RoboSense Decoder Parameters " << RS_REND; RS_INFOL << "wait_for_difop: " << wait_for_difop << RS_REND; - RS_INFOL << "max_distance: " << max_distance << RS_REND; RS_INFOL << "min_distance: " << min_distance << RS_REND; + RS_INFOL << "max_distance: " << max_distance << RS_REND; RS_INFOL << "start_angle: " << start_angle << RS_REND; RS_INFOL << "end_angle: " << end_angle << RS_REND; RS_INFOL << "use_lidar_clock: " << use_lidar_clock << RS_REND; From d787ff26e14cc0322b39b7277398793764623dfa Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 24 Aug 2022 10:30:22 +0800 Subject: [PATCH 353/379] Revert "fix: fix input_sock_epoll MSOPTIMEOUT error" This reverts commit a4fb3497111c629c7cb688b9a71df39411f0c63e. --- .../driver/input/unix/input_sock_epoll.hpp | 51 +++++-------------- 1 file changed, 13 insertions(+), 38 deletions(-) diff --git a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp index 8b186ccd..d01e5316 100644 --- a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp @@ -61,7 +61,6 @@ class InputSock : public Input virtual ~InputSock(); private: - ssize_t readSocket(int fd); inline void recvPacket(); inline int createSocket(uint16_t port, const std::string& hostIp, const std::string& grpIp); @@ -110,7 +109,7 @@ inline bool InputSock::init() struct epoll_event ev; ev.data.fd = difop_fd; - ev.events = EPOLLIN | EPOLLET; + ev.events = EPOLLIN; // level-triggered epoll_ctl (epfd, EPOLL_CTL_ADD, difop_fd, &ev); } @@ -238,40 +237,6 @@ inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, con return -1; } -inline ssize_t InputSock::readSocket(int fd) -{ - while (1) - { - std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); - ssize_t ret = recvfrom(fd, pkt->buf(), pkt->bufSize(), 0, NULL, NULL); - if (ret < 0) - { - if (errno == EAGAIN) - { - pushPacket(pkt, false); - return 0; - } - else - { - perror("recvfrom: "); - return -1; - } - } - else if (ret > 0) - { - pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); - pushPacket(pkt); - } - else - { - // never reach here. - } - } - - // never reach here. - return 0; -} - inline void InputSock::recvPacket() { while (!to_exit_recv_) @@ -296,13 +261,23 @@ inline void InputSock::recvPacket() { if (events[i].events & EPOLLIN) { - int ret = readSocket(events[i].data.fd); + std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); + ssize_t ret = recvfrom(events[i].data.fd, pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret < 0) - return; + { + perror("recvfrom: "); + goto failExit; + } + else if (ret > 0) + { + pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); + pushPacket(pkt); + } } } } +failExit: } } // namespace lidar From d8f7c2b1efa11b9321d5c31c732bdf80563a42b7 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 24 Aug 2022 10:56:29 +0800 Subject: [PATCH 354/379] Revert fix: fix input_sock_epoll MSOPTIMEOUT error --- src/rs_driver/driver/input/unix/input_sock_epoll.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp index d01e5316..d6f2c9c9 100644 --- a/src/rs_driver/driver/input/unix/input_sock_epoll.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_epoll.hpp @@ -94,7 +94,7 @@ inline bool InputSock::init() struct epoll_event ev; ev.data.fd = msop_fd; - ev.events = EPOLLIN | EPOLLET; + ev.events = EPOLLIN; // level-triggered epoll_ctl (epfd, EPOLL_CTL_ADD, msop_fd, &ev); } @@ -278,6 +278,7 @@ inline void InputSock::recvPacket() } failExit: + return; } } // namespace lidar From effbb621bb412a27d830cfed7b93139fea2b64cf Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Tue, 30 Aug 2022 09:22:53 +0800 Subject: [PATCH 355/379] format: update doc links --- README.md | 2 +- README_CN.md | 2 +- ...rt_your_app_from_rs_driver_1.3.x_to_1.5.x.md | 4 ++-- doc/howto/how_to_decode_online_lidar.md | 6 +++--- doc/howto/how_to_use_rs_driver_viewer.md | 2 +- .../img/11_rs_driver_point_cloud.png | Bin .../img/11_rs_driver_point_cloud_vector.png | Bin .../img/11_rs_driver_queue_thread.png | Bin doc/{ => howto}/img/12_broadcast.png | Bin doc/{ => howto}/img/12_multi_lidars_ip.png | Bin doc/{ => howto}/img/12_multi_lidars_port.png | Bin doc/{ => howto}/img/12_multicast.png | Bin doc/{ => howto}/img/12_unicast.png | Bin doc/{ => howto}/img/12_user_layer.png | Bin doc/{ => howto}/img/12_vlan.png | Bin doc/{ => howto}/img/12_vlan_layer.png | Bin doc/{ => howto}/img/13_viewer_menu.png | Bin .../img/14_rs_driver_viewer_point_cloud.png | Bin doc/howto/online_lidar_advanced_topics.md | 16 ++++++++-------- .../01_install_pcl.png | Bin 20 files changed, 16 insertions(+), 16 deletions(-) rename doc/{ => howto}/img/11_rs_driver_point_cloud.png (100%) rename doc/{ => howto}/img/11_rs_driver_point_cloud_vector.png (100%) rename doc/{ => howto}/img/11_rs_driver_queue_thread.png (100%) rename doc/{ => howto}/img/12_broadcast.png (100%) rename doc/{ => howto}/img/12_multi_lidars_ip.png (100%) rename doc/{ => howto}/img/12_multi_lidars_port.png (100%) rename doc/{ => howto}/img/12_multicast.png (100%) rename doc/{ => howto}/img/12_unicast.png (100%) rename doc/{ => howto}/img/12_user_layer.png (100%) rename doc/{ => howto}/img/12_vlan.png (100%) rename doc/{ => howto}/img/12_vlan_layer.png (100%) rename doc/{ => howto}/img/13_viewer_menu.png (100%) rename doc/{ => howto}/img/14_rs_driver_viewer_point_cloud.png (100%) rename doc/img/01_install_pcl.PNG => img/01_install_pcl.png (100%) diff --git a/README.md b/README.md index 781edb7b..9998a802 100644 --- a/README.md +++ b/README.md @@ -103,7 +103,7 @@ To compile with VS2019, please use the official installation package [PCL All-in Select the "Add PCL to the system PATH for xxx" option during the installation. -![](./doc/img/01_install_pcl.PNG) +![](./img/01_install_pcl.png) ### 6.2 Installation diff --git a/README_CN.md b/README_CN.md index a0365a88..448377a4 100644 --- a/README_CN.md +++ b/README_CN.md @@ -99,7 +99,7 @@ target_link_libraries(project ${rs_driver_LIBRARIES}) 安装过程中选择 “Add PCL to the system PATH for xxx”: -![](./doc/img/01_install_pcl.PNG) +![](./img/01_install_pcl.png) ### 6.2 安装 diff --git a/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md b/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md index 3fd63bf3..0db3641a 100644 --- a/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md +++ b/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md @@ -1,8 +1,8 @@ -# How to port your app from rs_driver 1.3.x to 1.5.x +# How to port your app from rs_driver v1.3.x to v1.5.x ## 1 Introduction -This document illustrates how to port your app from rs_driver 1.3.x to 1.5.x. +This document illustrates how to port your app from rs_driver v1.3.x to v1.5.x. The interface of rs_driver contains two parts: RSDriverParam and LidarDriver. diff --git a/doc/howto/how_to_decode_online_lidar.md b/doc/howto/how_to_decode_online_lidar.md index 8205a7b2..9c959265 100644 --- a/doc/howto/how_to_decode_online_lidar.md +++ b/doc/howto/how_to_decode_online_lidar.md @@ -13,7 +13,7 @@ The driver is designed to achieve these objectives. Below is the supposed interaction between rs_driver and user's code. -![](../img/11_rs_driver_queue_thread.png) +![](./img/11_rs_driver_queue_thread.png) rs_driver runs in its thread `construct_thread`. It + Gets free point cloud from user. User fetches it from a free cloud queue `free_point_cloud_queue`. @@ -108,10 +108,10 @@ For mechanical Lidar, it may be useful to explain how the layout of point cloud Here is an example of mechanical 5_lasers Lidar. The Lidar scans block by block. It starts from b0c0(block 0 channel/laser 0), b0c1, b0c2, b0c3, b0c4, and then go to b1c0, b1c1, b1c2, b1c3, b1c4, and so on. -![](../img/11_rs_driver_point_cloud.png) +![](./img/11_rs_driver_point_cloud.png) At the same time, it saves the points in a vector, point by point, as below. -![](../img/11_rs_driver_point_cloud_vector.png) +![](./img/11_rs_driver_point_cloud_vector.png) ### 3.4 Define the driver object diff --git a/doc/howto/how_to_use_rs_driver_viewer.md b/doc/howto/how_to_use_rs_driver_viewer.md index fbe2bdf6..11041047 100644 --- a/doc/howto/how_to_use_rs_driver_viewer.md +++ b/doc/howto/how_to_use_rs_driver_viewer.md @@ -4,7 +4,7 @@ The rs_driver_viewer is a visualization tool for the point cloud. This document illustrates how to use it. -![](../img/14_rs_driver_viewer_point_cloud.png) +![](./img/14_rs_driver_viewer_point_cloud.png) ## 2 Compile and Run diff --git a/doc/img/11_rs_driver_point_cloud.png b/doc/howto/img/11_rs_driver_point_cloud.png similarity index 100% rename from doc/img/11_rs_driver_point_cloud.png rename to doc/howto/img/11_rs_driver_point_cloud.png diff --git a/doc/img/11_rs_driver_point_cloud_vector.png b/doc/howto/img/11_rs_driver_point_cloud_vector.png similarity index 100% rename from doc/img/11_rs_driver_point_cloud_vector.png rename to doc/howto/img/11_rs_driver_point_cloud_vector.png diff --git a/doc/img/11_rs_driver_queue_thread.png b/doc/howto/img/11_rs_driver_queue_thread.png similarity index 100% rename from doc/img/11_rs_driver_queue_thread.png rename to doc/howto/img/11_rs_driver_queue_thread.png diff --git a/doc/img/12_broadcast.png b/doc/howto/img/12_broadcast.png similarity index 100% rename from doc/img/12_broadcast.png rename to doc/howto/img/12_broadcast.png diff --git a/doc/img/12_multi_lidars_ip.png b/doc/howto/img/12_multi_lidars_ip.png similarity index 100% rename from doc/img/12_multi_lidars_ip.png rename to doc/howto/img/12_multi_lidars_ip.png diff --git a/doc/img/12_multi_lidars_port.png b/doc/howto/img/12_multi_lidars_port.png similarity index 100% rename from doc/img/12_multi_lidars_port.png rename to doc/howto/img/12_multi_lidars_port.png diff --git a/doc/img/12_multicast.png b/doc/howto/img/12_multicast.png similarity index 100% rename from doc/img/12_multicast.png rename to doc/howto/img/12_multicast.png diff --git a/doc/img/12_unicast.png b/doc/howto/img/12_unicast.png similarity index 100% rename from doc/img/12_unicast.png rename to doc/howto/img/12_unicast.png diff --git a/doc/img/12_user_layer.png b/doc/howto/img/12_user_layer.png similarity index 100% rename from doc/img/12_user_layer.png rename to doc/howto/img/12_user_layer.png diff --git a/doc/img/12_vlan.png b/doc/howto/img/12_vlan.png similarity index 100% rename from doc/img/12_vlan.png rename to doc/howto/img/12_vlan.png diff --git a/doc/img/12_vlan_layer.png b/doc/howto/img/12_vlan_layer.png similarity index 100% rename from doc/img/12_vlan_layer.png rename to doc/howto/img/12_vlan_layer.png diff --git a/doc/img/13_viewer_menu.png b/doc/howto/img/13_viewer_menu.png similarity index 100% rename from doc/img/13_viewer_menu.png rename to doc/howto/img/13_viewer_menu.png diff --git a/doc/img/14_rs_driver_viewer_point_cloud.png b/doc/howto/img/14_rs_driver_viewer_point_cloud.png similarity index 100% rename from doc/img/14_rs_driver_viewer_point_cloud.png rename to doc/howto/img/14_rs_driver_viewer_point_cloud.png diff --git a/doc/howto/online_lidar_advanced_topics.md b/doc/howto/online_lidar_advanced_topics.md index 092e6a62..ed544d8a 100644 --- a/doc/howto/online_lidar_advanced_topics.md +++ b/doc/howto/online_lidar_advanced_topics.md @@ -17,7 +17,7 @@ The simplest way is broadcast mode. The Lidar sends MSOP/DIFOP packets to the host machine (The driver runs on it). For simplicity, the DIFOP port is ommited here. + The Lidar sends to `255.255.255.255` : `6699`, and the host binds to port `6699`. -![](../img/12_broadcast.png) +![](./img/12_broadcast.png) Below is how to configure RSDriverParam variable. @@ -34,7 +34,7 @@ param.lidar_type = LidarType::RS32; ///< Set the lidar type. To reduce the network load, the Lidar is suggested to work in unicast mode. + The Lidar sends to `192.168.1.102` : `6699`, and the host binds to port `6699`. -![](../img/12_unicast.png) +![](./img/12_unicast.png) Below is how to configure the RSDriverParam variable. In fact, it is same with the broadcast case. @@ -53,7 +53,7 @@ The Lidar may also works in multicast mode. + The lidar sends to `224.1.1.1`:`6699` + The host binds to port `6699`. And it makes local NIC (Network Interface Card) join the multicast group `224.1.1.1`. The local NIC's IP is `192.168.1.102`. -![](../img/12_multicast.png) +![](./img/12_multicast.png) Below is how to configure the RSDriverParam variable. @@ -75,7 +75,7 @@ If you have two Lidars, it is suggested to set different remote ports. + First Lidar sends to `192.168.1.102`:`6699`, and the first driver instance binds to `6699`. + Second Lidar sends to `192.168.1.102`:`5599`, and the second driver instance binds to `5599`. -![](../img/12_multi_lidars_port.png) +![](./img/12_multi_lidars_port.png) Below is how to configure the RSDriverParam variables. @@ -100,7 +100,7 @@ An alternate way is to set different remote IPs. + First Lidar sends to `192.168.1.102`:`6699`, and the first driver instance binds to `192.168.1.102:6699`. + Second Lidar sends to `192.168.1.103`:`6699`, and the second driver instance binds to `192.168.1.103:6699`. -![](../img/12_multi_lidars_ip.png) +![](./img/12_multi_lidars_ip.png) Below is how to configure the RSDriverParam variables. @@ -124,7 +124,7 @@ param2.lidar_type = LidarType::RS32; ///< Set the lidar type. In some user cases, The Lidar may work on VLAN. Its packets have a VLAN layer. -![](../img/12_vlan_layer.png) +![](./img/12_vlan_layer.png) The driver cannot parse this packet. Instead, it depends on a virtual NIC to strip the VLAN layer. @@ -132,7 +132,7 @@ Below is an example. + The Lidar works on VLAN `80`. It sends packets to `192.168.1.102` : `6699`. The packet has a VLAN layer. + Suppose there is a physical NIC `eno1` on the host. It receives packets with VLAN layer. -![](../img/12_vlan.png) +![](./img/12_vlan.png) To strip the VLAN layer, create a virtual NIC `eno1.80` on `eno1`, and assign IP `192.168.1.102` to it. @@ -159,7 +159,7 @@ param.lidar_type = LidarType::RS32; ///< Set the lidar type. In some user cases, User may add extra layers before or after the MSOP/DIFOP packet. + USER_LAYER is before the packet and TAIL_LAYER is after it. -![](../img/12_user_layer.png) +![](./img/12_user_layer.png) These extra layers are parts of UDP data. The driver can strip them. diff --git a/doc/img/01_install_pcl.PNG b/img/01_install_pcl.png similarity index 100% rename from doc/img/01_install_pcl.PNG rename to img/01_install_pcl.png From 8f56c49ed12fb14cf418b59ef975211824ce8731 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 31 Aug 2022 10:47:01 +0800 Subject: [PATCH 356/379] feat: add howto_CN docs --- ..._your_app_from_rs_driver_1.3.x_to_1.5.x.md | 40 ++- ...ur_app_from_rs_driver_1.3.x_to_1.5.x_CN.md | 202 +++++++++++++ doc/howto/how_to_decode_online_lidar.md | 89 ++++-- doc/howto/how_to_decode_online_lidar_CN.md | 283 ++++++++++++++++++ doc/howto/how_to_decode_pcap_file.md | 69 +++-- doc/howto/how_to_decode_pcap_file_CN.md | 251 ++++++++++++++++ doc/howto/how_to_transform_pointcloud.md | 8 +- doc/howto/how_to_transform_pointcloud_CN.md | 46 +++ doc/howto/how_to_use_rs_driver_viewer_CN.md | 102 +++++++ doc/howto/online_lidar_advanced_topics.md | 4 +- doc/howto/online_lidar_advanced_topics_CN.md | 202 +++++++++++++ doc/howto/pcap_file_advanced_topics.md | 85 ++++++ doc/howto/pcap_file_advanced_topics_CN.md | 84 ++++++ 13 files changed, 1397 insertions(+), 68 deletions(-) create mode 100644 doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x_CN.md create mode 100644 doc/howto/how_to_decode_online_lidar_CN.md create mode 100644 doc/howto/how_to_decode_pcap_file_CN.md create mode 100644 doc/howto/how_to_transform_pointcloud_CN.md create mode 100644 doc/howto/how_to_use_rs_driver_viewer_CN.md create mode 100644 doc/howto/online_lidar_advanced_topics_CN.md create mode 100644 doc/howto/pcap_file_advanced_topics.md create mode 100644 doc/howto/pcap_file_advanced_topics_CN.md diff --git a/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md b/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md index 0db3641a..a50e9628 100644 --- a/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md +++ b/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md @@ -1,17 +1,25 @@ # How to port your app from rs_driver v1.3.x to v1.5.x -## 1 Introduction +## 1 Why to port ? This document illustrates how to port your app from rs_driver v1.3.x to v1.5.x. -The interface of rs_driver contains two parts: RSDriverParam and LidarDriver. +Why to port your app from v1.3.x to v1.5.x? Below are several reasons. + ++ Obviously reduce CPU usage. ++ Add compile options to solve packet-loss problems on some platforms. ++ Remove the dependency on the Boost library, help to port rs_driver to other platforms other than x86. ++ Refactory the Network Input part and the Decoder part, to support different use cases. ++ Improve the help documents, including [understand source code of rs_driver](../src_intro/rs_driver_intro.md), to help user understand it. -Here are the changes to them. +## 2 How to port ? -## 2 RSDriverParam +The interface of rs_driver contains two parts: RSDriverParam and LidarDriver. ### 2.1 RSDriverParam +#### 2.1.1 RSDriverParam + RSDriverParam contains the options to change the rs_driver's behavior. RSDriverParam is as below in rs_driver 1.3.x. @@ -24,7 +32,7 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter std::string angle_path = "null"; ///< Path of angle calibration files(angle.csv).Only used for internal debugging. std::string frame_id = "rslidar"; ///< The frame id of LiDAR message LidarType lidar_type = LidarType::RS16; ///< Lidar type - bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet bool saved_by_rows = false; ///< true: the output point cloud will be saved by rows (default is saved by columns) }; ``` @@ -43,14 +51,14 @@ typedef struct RSDriverParam ///< The LiDAR driver parameter Below are the changes. + A new member `input_type` is added. It means the type of data sources: `ONLINE_LIDAR`, `PCAP_FILE`, or `RAW_PACKET`. -+ The member `waitf_for_difop` specifies whether to handle MSOP packets before handling DIFOP packet. For mechenical LiDARs, the point cloud will be flat without the angle data in DIFOP packet。This option is about decoding, so it is shifted to RSDecoderParam. ++ The member `wait_for_difop` specifies whether to handle MSOP packets before handling DIFOP packet. For mechenical LiDARs, the point cloud will be flat without the angle data in DIFOP packet。This option is about decoding, so it is shifted to RSDecoderParam. + The member `saved_by_rows` specifies to give point cloud row by row. There are two reasons to remove it: + Even point cloud is given column by column, it is easier to access row by row (by skipping column). + The option consumes two much CPU resources, so not suggested. + The member `angle_path` specifies a file which contains the angle data. It is about data source, so it is shifted to RSInputParam. + The member `frame_id` is a concept from ROS. It is removed, and the driver `rslidar_sdk` (for ROS) will handle it. -### 2.2 RSInputParam +#### 2.1.2 RSInputParam RSInputParam is as below in rs_driver 1.3.x. @@ -97,7 +105,7 @@ Below are the changes. + The member `read_pcap` is not needed now. `RSDriverParam.input_type` replaces it. + The members `use_someip` and `use_custom_proto` is not needed now. `user_layer_bytes` replaces them. -### 2.2 RSDecoderParam +#### 2.1.3 RSDecoderParam RSDecoderParam is as below in rs_driver 1.3.x. @@ -148,22 +156,21 @@ Below are the changes. + The member `config_from_file` is added. Only if it is true, the member `angle_path` is valid. + The member `num_pkts_split` is renamed to `number_blks_split`. That means to split frames `by blocks (in MSOP packets)` instead of `by MSOP packets`. -## 3 LidarDriver +### 2.2 LidarDriver LidarDriver contains the functions to run rs_driver. LidarDriver is as below in rs_driver 1.3.x. ```c++ -template +template class LidarDriver { public: - inline void regPointCloudCallback(const std::function(void)>& cb_get_cloud, - const std::function)>& cb_put_cloud) + inline void regRecvCallback(const std::function&)>& callback) { - driver_ptr_->regPointCloudCallback(cb_get_cloud, cb_put_cloud); + driver_ptr_->regRecvCallback(callback); } ... }; @@ -172,14 +179,15 @@ public: And it is as below in rs_driver 1.5.x. ```c++ -template +template class LidarDriver { public: - inline void regRecvCallback(const std::function&)>& callback) + inline void regPointCloudCallback(const std::function(void)>& cb_get_cloud, + const std::function)>& cb_put_cloud) { - driver_ptr_->regRecvCallback(callback); + driver_ptr_->regPointCloudCallback(cb_get_cloud, cb_put_cloud); } ... }; diff --git a/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x_CN.md b/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x_CN.md new file mode 100644 index 00000000..dcde0ee7 --- /dev/null +++ b/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x_CN.md @@ -0,0 +1,202 @@ +# 如何将基于rs_driver v1.3.x的应用程序移植到v1.5.x + +## 1 为什么要移植? + +本文说明了如何将基于rs_driver v1.3.x的应用程序移植到v1.5.x上。 + +rs_driver v1.5.x是对v1.3.x较大重构后的版本。它主要做了如下改进。 ++ 明显减少CPU资源的占用率 ++ 增加可选的编译选项,解决在某些平台上丢包的问题 ++ 去除对Boost库的依赖,更容易移植到除x86以外的其他平台上。 ++ 重构网络部分和解码部分的代码,完整支持不同场景下的配置 ++ 完善帮助文档,尤其是提供了[源代码解析](../src_intro/rs_driver_intro.md)文档,帮助用户深入理解驱动的实现,以方便功能裁剪。 + +## 2 如何移植? + +rs_driver的接口包括了两个部分:RSDriverParam和LidarDriver。 + +### 2.1 RSDriverParam + +#### 2.1.1 RSDriverParam + +RSDriverParam包括了一些可以改变rs_driver行为的参数。 + +在v1.3.2中,RSDriverParam定义如下。 + +```c++ +typedef struct RSDriverParam ///< The LiDAR driver parameter +{ + RSInputParam input_param; ///< Input parameter + RSDecoderParam decoder_param; ///< Decoder parameter + std::string angle_path = "null"; ///< Path of angle calibration files(angle.csv).Only used for internal debugging. + std::string frame_id = "rslidar"; ///< The frame id of LiDAR message + LidarType lidar_type = LidarType::RS16; ///< Lidar type + bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + bool saved_by_rows = false; ///< true: the output point cloud will be saved by rows (default is saved by columns) +}; +``` + +在v1.5.x中,RSDriverParam定义如下。 + +```c++ +typedef struct RSDriverParam ///< The LiDAR driver parameter +{ + LidarType lidar_type = LidarType::RS16; ///< Lidar type + InputType input_type = InputType::ONLINE_LIDAR; ///< Input type + RSInputParam input_param; ///< Input parameter + RSDecoderParam decoder_param; ///< Decoder parameter +}; +``` + +变动如下: ++ 加入新成员`input_type`。这个成员指定数据源的类型:`ONLINE_LIDAR`, `PCAP_FILE`, or `RAW_PACKET`. ++ 成员`wait_for_difop` 指定在处理MSOP包之前是否先等待DIFOP包。对于机械式雷达,如果没有DIFOP包中的垂直角数据,得到的点云就是扁平的。这个选项是与解码相关的,所以把它移到RSDecoderParam中。 ++ 删除成员`save_by_rows`。默认情况下,点在点云中按照扫描的通道次序保存在vector中,一轮扫描的点在竖直的线上,也就是按照列保存。成员`saved_by_rows` 可以指定按照水平的线保存点,也就是按照行保存。删除这个成员有两个原因: + + 在按照列保存点的vector中,按照行的顺序检索点,也是容易的,跳过通道数就可以了。 + + 这个选项的实现方式是将点云重排一遍,但是复制点云的代码太大了。 ++ 成员`angle_path`指定垂直角从指定的文件读取,而不是解析DIFOP包得到。这个选项是关于数据源的,所以移到RSInputParam。 ++ 成员`frame_id` 来自ROS的概念,rs_driver本身和rs_driver的其他使用者并不需要它,所以删除它。适配ROS的驱动 `rslidar_sdk`会创建和处理它。 + +#### 2.1.2 RSInputParam + +在v1.3.x中,RSInputParam定义如下。 + +```c++ +typedef struct RSInputParam ///< The LiDAR input parameter +{ + std::string device_ip = "192.168.1.200"; ///< Ip of LiDAR + std::string multi_cast_address = "0.0.0.0"; ///< Address of multicast + std::string host_address = "0.0.0.0"; ///< Address of host + uint16_t msop_port = 6699; ///< Msop packet port number + uint16_t difop_port = 7788; ///< Difop packet port number + bool read_pcap = false; ///< true: The driver will process the pcap through pcap_path. false: The driver will + ///< Get data from online LiDAR + double pcap_rate = 1; ///< Rate to read the pcap file + bool pcap_repeat = true; ///< true: The pcap bag will repeat play + std::string pcap_path = "null"; ///< Absolute path of pcap file + bool use_vlan = false; ///< Vlan on-off + bool use_someip = false; ///< Someip on-off + bool use_custom_proto = false; ///< Customer Protocol on-off +}; +``` + +在v1.5.x中,RSInputParam定义如下。 + +```c++ +typedef struct RSInputParam ///< The LiDAR input parameter +{ + uint16_t msop_port = 6699; ///< Msop packet port number + uint16_t difop_port = 7788; ///< Difop packet port number + std::string host_address = "0.0.0.0"; ///< Address of host + std::string group_address = "0.0.0.0"; ///< Address of multicast group + std::string pcap_path = ""; ///< Absolute path of pcap file + bool pcap_repeat = true; ///< true: The pcap bag will repeat play + float pcap_rate = 1.0f; ///< Rate to read the pcap file + bool use_vlan = false; ///< Vlan on-off + uint16_t user_layer_bytes = 0; ///< Bytes of user layer. thers is no user layer if it is 0 + uint16_t tail_layer_bytes = 0; ///< Bytes of tail layer. thers is no tail layer if it is 0 +}; +``` + +变动如下: ++ 删除成员`device_ip`。rs_driver接收MSOP/DIFOP包时,其实不需要这个值。 ++ 成员`multi_cast_address`改名为`group_address`。这里想表达的含义是,在组播模式下,rs_driver会将主机加入`group_address`指定的组播组。 ++ 删除成员`read_pcap`。 既然`RSDriverParam.input_type` 已经指定了数据源类型,`read_pcap`就不需要了。 ++ 删除成员`use_someip` and `use_custom_proto`。它们的功能已经被新的选项 `RSInputParam.user_layer_bytes`所取代。 + +#### 2.1.3 RSDecoderParam + +在v1.3.x中,RSDecoderParam定义如下。 + +```c++ +typedef struct RSDecoderParam ///< LiDAR decoder parameter +{ + float max_distance = 200.0f; ///< Max distance of point cloud range + float min_distance = 0.2f; ///< Minimum distance of point cloud range + float start_angle = 0.0f; ///< Start angle of point cloud + float end_angle = 360.0f; ///< End angle of point cloud + SplitFrameMode split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; ///< 1: Split frames by cut_angle; + ///< 2: Split frames by fixed number of packets; + ///< 3: Split frames by custom number of packets (num_pkts_split) + uint32_t num_pkts_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 + float cut_angle = 0.0f; ///< Cut angle(degree) used to split frame, only be used when split_frame_mode=1 + bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp + RSTransformParam transform_param; ///< Used to transform points + RSCameraTriggerParam trigger_param; ///< Used to trigger camera +}; +``` + +在v1.5.x中,RSDecoderParam定义如下。 + +```c++ +typedef struct RSDecoderParam ///< LiDAR decoder parameter +{ + bool config_from_file = false; ///< Internal use only for debugging + std::string angle_path = ""; ///< Internal use only for debugging + bool wait_for_difop = true; ///< true: start sending point cloud until receive difop packet + float min_distance = 0.2f; ///< Minimum distance of point cloud range + float max_distance = 200.0f; ///< Max distance of point cloud range + float start_angle = 0.0f; ///< Start angle of point cloud + float end_angle = 360.0f; ///< End angle of point cloud + SplitFrameMode split_frame_mode = SplitFrameMode::SPLIT_BY_ANGLE; + ///< 1: Split frames by split_angle; + ///< 2: Split frames by fixed number of blocks; + ///< 3: Split frames by custom number of blocks (num_blks_split) + float split_angle = 0.0f; ///< Split angle(degree) used to split frame, only be used when split_frame_mode=1 + uint16_t num_blks_split = 1; ///< Number of packets in one frame, only be used when split_frame_mode=3 + bool use_lidar_clock = false; ///< true: use LiDAR clock as timestamp; false: use system clock as timestamp + bool dense_points = false; ///< true: discard NAN points; false: reserve NAN points + RSTransformParam transform_param; ///< Used to transform points +}; +``` + +变动如下: ++ 成员`cut_angle`改名为`split_angle`, 以便与成员 `split_frame_mode`的名字保持一致。 ++ 增加成员`config_from_file`。只有这个成员为true,成员`angle_path`才有效。 ++ 成员`num_pkts_split`改名为 `number_blks_split`. 因为在v1.3.x中,分帧的最小单位是packet,而在v1.5.x中,分帧单位改成了更小的block。 + +### 2.2 LidarDriver + +创建LidarDriver实例,并调用它的成员函数,可以运行rs_driver。 + +在v1.3.x中,LidarDriver定义如下。 + +```c++ +template +class LidarDriver +{ +public: + + inline void regRecvCallback(const std::function&)>& callback) + { + driver_ptr_->regRecvCallback(callback); + } + ... +}; +``` + + +在v1.5.x中,LidarDriver定义如下。 + +```c++ +template +class LidarDriver +{ +public: + + inline void regPointCloudCallback(const std::function(void)>& cb_get_cloud, + const std::function)>& cb_put_cloud) + { + driver_ptr_->regPointCloudCallback(cb_get_cloud, cb_put_cloud); + } + ... +}; +``` + +变动如下: ++ LidarDriver类的模板参数从点 `PointT`改成了点云 `T_PointCloud`。 ++ LidarDriver在v1.3.x时需要一个点云回调函数,用于rs_driver把构建好的点云返回给调用者,在v1.5.x中则需要两个回调函数,除了返回构建好的点云,还需要给rs_driver提供空闲的点云实例。 +关于这两点,可以参考[Decode online Lidar](./how_to_decode_online_lidar_CN.md),得到更详细的说明。 + + + diff --git a/doc/howto/how_to_decode_online_lidar.md b/doc/howto/how_to_decode_online_lidar.md index 9c959265..3ad7d1c9 100644 --- a/doc/howto/how_to_decode_online_lidar.md +++ b/doc/howto/how_to_decode_online_lidar.md @@ -1,4 +1,4 @@ -# How to decode online Lidar +# How to decode online LiDAR ## 1 Introduction @@ -16,7 +16,7 @@ Below is the supposed interaction between rs_driver and user's code. ![](./img/11_rs_driver_queue_thread.png) rs_driver runs in its thread `construct_thread`. It -+ Gets free point cloud from user. User fetches it from a free cloud queue `free_point_cloud_queue`. ++ Gets free point cloud from user. User fetches it from a free cloud queue `free_point_cloud_queue`. If the queue is empty, then create a new one. + Parses packets and constructs point cloud. + Returns stuffed point cloud to user. + User's code is supposed to shift it to the queue `stuffed_point_cloud_queue`. @@ -24,20 +24,20 @@ rs_driver runs in its thread `construct_thread`. It User's code runs in its thread `process_thread`. It + Fetches stuffed point cloud from the queue `stuffed_point_cloud_queue` + Process the point cloud -+ Return the point cloud back to the queue `free_point_cloud_queue`. ++ Return the point cloud back to the queue `free_point_cloud_queue`. rs_driver will use it again. ## 3 Steps Below is the steps to use the driver's API. -### 3.1 Define Point Type +### 3.1 Define Point Point is the base unit of Point Cloud. The driver supposes that it may have these member variables. -- x -- float type. The x coordinate of point. -- y -- float type. The y coordinate of point. -- z -- float type. The z coordinate of point. -- intensity -- uint8_t type. The intensity of point. -- timestamp -- double type. The timestamp of point. It may generated by the Lidar or on the host machine. +- x -- The x coordinate of point. float type. +- y -- The y coordinate of point. float type. +- z -- The z coordinate of point. float type. +- intensity -- The intensity of point. uint8_t type. +- timestamp -- The timestamp of point. double type. It may generated by the Lidar or on the host machine. - ring -- The ring ID of the point, which represents the row number. e.g. For RS80, the range of ring ID is 0~79 (from bottom to top). Below are some examples: @@ -74,7 +74,7 @@ Below are some examples: Here user may add new member variables, remove member variables, or change the order of them, but should not change names or types of them, otherwise the behaviors might be unexpected. -### 3.2 Define Point Cloud Type +### 3.2 Define Point Cloud The driver allows user to change the point cloud type, as long as it is compatible to the definition below. @@ -130,7 +130,7 @@ int main() Define a RSDriverParam variable and configure it. + `InputType::ONLINE_LIDAR` means that the driver get packets from a online Lidar. + `LidarType::RS16` means a RS16 Lidar. -+ Also set the local MSOP/DIFOP ports. Please use a 3rd party tool, such as Wireshark, to get them. ++ Also set the local MSOP/DIFOP ports. Please use a 3rd party tool, such as WireShark, to get them. ```c++ int main() @@ -147,42 +147,75 @@ int main() ### 3.6 Define and register Point Cloud callbacks -As said above, user is supposed to provide free point cloud to the driver. ++ As said above, user is supposed to provide free point cloud to the driver. ```c++ -std::shared_ptr pointCloudGetCallback(void) +SyncQueue> free_cloud_queue; + +std::shared_ptr driverGetPointCloudFromCallerCallback(void) { + std::shared_ptr msg = free_cloud_queue.pop(); + if (msg.get() != NULL) + { + return msg; + } + return std::make_shared(); } ``` -Also user is supposed to accept stuffed point cloud from the driver. ++ Also user is supposed to accept stuffed point cloud from the driver. ```c++ -void pointCloudPutCallback(std::shared_ptr msg) +SyncQueue> stuffed_cloud_queue; + +void driverReturnPointCloudToCallerCallback(std::shared_ptr msg) { + stuffed_cloud_queue.push(msg); + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; } ``` -Note: -+ For simplicity, `free_point_cloud_queue`/`stuffed_point_cloud_queue` are not implemented here. This is NOT suggested. -+ The driver calls these two callback functions in its `contruct_thread`, so **don't do any time-consuming task** in them. +Note: The driver calls these two callback functions in its `contruct_thread`, so **don't do any time-consuming task** in them. + ++ User process the point cloud in its own thread. + +```c++ +void processCloud(void) +{ + while (1) + { + std::shared_ptr msg = stuffed_cloud_queue.popWait(); + if (msg.get() == NULL) + { + continue; + } + + // Well, it is time to process the point cloud msg, even it is time-consuming. + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; -Register them to the driver. + free_cloud_queue.push(msg); + } +} + +``` + ++ Register them to the driver. ```c++ int main() { ... - driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback functions + driver.regPointCloudCallback(driverReturnPointCloudToCallerCallback, + driverReturnPointCloudToCallerCallback); ... } ``` ### 3.7 Define and register exception callbacks -When an error happens, the driver will inform user. User is supposed to get it via a callback function. ++ When an error happens, the driver will inform user. User is supposed to get it via a callback function. ```c++ void exceptionCallback(const Error &code) @@ -193,13 +226,13 @@ void exceptionCallback(const Error &code) Once again, **don't do any time-consuming task** in it. -Register the callback. ++ Register the callback. ```c++ int main() { ... -driver.regExceptionCallback(exceptionCallback); /// + class PointCloudT + { + public: + typedef T_Point PointT; + typedef std::vector VectorT; + + uint32_t height = 0; ///< Height of point cloud + uint32_t width = 0; ///< Width of point cloud + bool is_dense = false; ///< If is_dense is true, the point cloud does not contain NAN points + double timestamp = 0.0; ///< Timestamp of point cloud + uint32_t seq = 0; ///< Sequence number of message + + VectorT points; + }; + + typedef PointXYZI PointT; + typedef PointCloudT PointCloudMsg; + ``` + +使用者可以向这个定义增加新成员,改变成员顺序,但是不可以改变成员类型,或者删除成员。 + +### 3.3 点在点云中的排列 + +对于机械式雷达,说明点在点云中是如何排列的,可能是有意义的。 + +为了描述方便,假设有一个5通道的机械式雷达。雷达一个block接一个block地扫描。竖直方向的一轮扫描对应一个block,5个通道各一个点。(雷达每轮扫描的通道次序是不变的,但一般不是严格从上往下。下面的图中是从上往下,只是为了描述简单。) + +如下图,它扫描b0c0(block 0 channel/laser 0), b0c1, b0c2, b0c3, b0c4, 然后扫描b1c0, b1c1, b1c2, b1c3, b1c4, 如此下去。 +![](./img/11_rs_driver_point_cloud.png) + +相应地,rs_driver将对应的点保存在点云的成员points中,这是一个vector。如下图。 + +![](./img/11_rs_driver_point_cloud_vector.png) + +### 3.4 定义LidarDriver对象 + +LidarDriver类是rs_driver的接口类。 + +这里定义一个LidarDriver的实例。 + +```c++ +int main() +{ + LidarDriver driver; ///< Declare the driver object + ... +} +``` + +### 3.5 配置LidarDriver的参数 + +RSDriverParam定义LidarDriver的参数。 + +这里定义RSDriverParam变量,并配置它。 + ++ `InputType::ONLINE_LIDAR`意味着从在线雷达得到MSOP/DIFOP包。 ++ `LidarType::RS16`是雷达类型 ++ 分别设置接收MSOP/DIFO包的端口号。如果不知道端口是多少,可以用第三方工具(如WireShark)先查看一下。 + +```c++ +int main() +{ + ... + RSDriverParam param; ///< Create a parameter object + param.input_type = InputType::ONLINE_LIDAR; /// get packet from online lidar + param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 + param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct + ... +} +``` + +### 3.6 定义和注册点云回调函数 + ++ 如前面章节所说,使用者需要向rs_driver提供空闲点云。这里定义第一个点云回调函数。 + +```c++ +SyncQueue> free_cloud_queue; + +std::shared_ptr driverGetPointCloudFromCallerCallback(void) +{ + std::shared_ptr msg = free_cloud_queue.pop(); + if (msg.get() != NULL) + { + return msg; + } + + return std::make_shared(); +} +``` + ++ 使用者从rs_driver得到填充好的点云。这里定义第二个点云回调函数。 + +```c++ +SyncQueue> stuffed_cloud_queue; + +void driverReturnPointCloudToCallerCallback(std::shared_ptr msg) +{ + stuffed_cloud_queue.push(msg); + + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; +} +``` + +提醒一下,这两个回调函数都运行在rs_driver的点云构建线程中,所以它们不可以做太耗时的任务,否则会导致MSOP/DIFOP包不能及时处理。 + ++ 使用者在自己的线程中,处理点云。 + +```c++ +void processCloud(void) +{ + while (1) + { + std::shared_ptr msg = stuffed_cloud_queue.popWait(); + if (msg.get() == NULL) + { + continue; + } + + // Well, it is time to process the point cloud msg, even it is time-consuming. + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; + + free_cloud_queue.push(msg); + } +} + +``` + ++ 在主函数中,注册两个点云回调函数。 + +```c++ +int main() +{ + ... + driver.regPointCloudCallback(driverReturnPointCloudToCallerCallback, + driverReturnPointCloudToCallerCallback); + ... +} +``` + +### 3.7 定义和注册异常回调函数 + ++ rs_driver检测到异常发生时,通过回调函数通知调用者。这里定义异常回调函数。 + +```c++ +void exceptionCallback(const Error &code) +{ + RS_WARNING << "Error code : " << code.toString() << RS_REND; +} +``` + +再一次提醒,这个回调函数运行在rs_driver的线程中,所以不可以做太多耗时的任务,否则可能会导致MSOP/DIFOP包不能及时接收和处理。 + ++ 在主函数中,注册异常回调函数。 + +```c++ +int main() +{ + ... + driver.regExceptionCallback(exceptionCallback); /// pointCloudGetCallback(void) +SyncQueue> free_cloud_queue; + +std::shared_ptr driverGetPointCloudFromCallerCallback(void) { + std::shared_ptr msg = free_cloud_queue.pop(); + if (msg.get() != NULL) + { + return msg; + } + return std::make_shared(); } ``` -Also user is supposed to accept stuffed point cloud from the driver. ++ Also user is supposed to accept stuffed point cloud from the driver. ```c++ -void pointCloudPutCallback(std::shared_ptr msg) +SyncQueue> stuffed_cloud_queue; + +void driverReturnPointCloudToCallerCallback(std::shared_ptr msg) { + stuffed_cloud_queue.push(msg); + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; } ``` -Note: The driver parses packet and constructs point cloud in its own thread. It also calls these two callback functions in this thread , so **don't do any time-consuming task** in them. +Note: The driver calls these two callback functions in its `construct_thread`, so **don't do any time-consuming task** in them. + ++ User process point cloud in its own thread. + +```c++ +void processCloud(void) +{ + while (1) + { + std::shared_ptr msg = stuffed_cloud_queue.popWait(); + if (msg.get() == NULL) + { + continue; + } + + // Well, it is time to process the point cloud msg, even it is time-consuming. + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; -Register the callbacks to the driver. + free_cloud_queue.push(msg); + } +} + +``` + ++ Register the callbacks to the driver. ```c++ int main() { ... - driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback functions + driver.regPointCloudCallback(driverReturnPointCloudToCallerCallback, + driverReturnPointCloudToCallerCallback); ... } ``` ### 2.6 Define and register exception callbacks -When an error happens, the driver will inform user. User is supposed to accept it. ++ When an error happens, the driver will inform user. User is supposed to accept it. ```c++ void exceptionCallback(const Error &code) @@ -162,7 +197,7 @@ void exceptionCallback(const Error &code) Once again, **don't do any time-consuming task** in it. -Register the callback. ++ Register the callback. ```c++ int main() @@ -181,7 +216,7 @@ Call the initialization function with the the RSDriverParam object. int main() { ... - if (!driver.init(param)) ///< Call the init function and pass the parameter + if (!driver.init(param)) ///< Call the init function with the parameter { RS_ERROR << "Driver Initialize Error..." << RS_REND; return -1; @@ -190,8 +225,6 @@ int main() } ``` -Please **register call callback functions before call init()**, because errors may occur during the initialization. - ### 2.8 Start the driver Start the driver. @@ -200,16 +233,16 @@ Start the driver. int main() { ... - driver.start(); ///< Call the start function. The driver thread will start + driver.start(); ///< Call the start function. The driver thread will start ... } ``` ## 3 Congratulations -You have finished the demo tutorial of the RoboSense LiDAR driver! +You have finished the demo tutorial of decoding PCAP file! -Please find the complete demo code ```rs_driver/demo/demo_pcap.cpp``` in the project directory. +Please find the complete demo code in the project file ```rs_driver/demo/demo_pcap.cpp```. Feel free to contact us if you have any questions. diff --git a/doc/howto/how_to_decode_pcap_file_CN.md b/doc/howto/how_to_decode_pcap_file_CN.md new file mode 100644 index 00000000..d1d0a5e7 --- /dev/null +++ b/doc/howto/how_to_decode_pcap_file_CN.md @@ -0,0 +1,251 @@ +# 如何解码PCAP文件 + +## 1 简介 + +在阅读本文档前,请先阅读 [连接在线雷达](./how_to_decode_online_lidar_CN.md). + +PCAP文件可使用第三方工具,如Wireshark/tcpdump,抓取并保存。 + +本文说明了如何使用rs_driver解码PCAP文件。 + +## 2 步骤 + +### 2.1 定义点 + +点是点云的基本组成单元。rs_driver支持点的如下成员。 +- x -- 坐标X,类型float +- y -- 坐标Y,类型float +- z -- 坐标Y,类型float +- intensity -- 反射率,类型uint8_t +- timestamp -- 时间戳,类型double +- ring -- 通道编号。对于RS80, 通道编号的范围是 0~79 (从下往上)。 + +如下是几个例子。 + +- 点的成员包括 **x, y, z, intensity** + + ```c++ + struct PointXYZI + { + float x; + float y; + float z; + uint8_t intensity; + ... + }; + ``` + +- 如果使用PCL库,也可以简单使用PCL的点定义 **pcl::PointXYZI**。 + +- 点的成员包括 **x, y, z, intensity, timestamp, ring** + + ```c++ + struct PointXYZIRT + { + float x; + float y; + float z; + uint8_t intensity; + double timestamp; + uint16_t ring; + ... + }; + ``` + +使用者可以向点的定义中加入新成员、删除成员、改变成员的顺序,但是不可以改变点的类型。 + +### 2.2 定义点云 + +如下是点云的定义。 + + ```c++ + template + class PointCloudT + { + public: + typedef T_Point PointT; + typedef std::vector VectorT; + + uint32_t height = 0; ///< Height of point cloud + uint32_t width = 0; ///< Width of point cloud + bool is_dense = false; ///< If is_dense is true, the point cloud does not contain NAN points + double timestamp = 0.0; ///< Timestamp of point cloud + uint32_t seq = 0; ///< Sequence number of message + + VectorT points; + }; + + typedef PointXYZI PointT; + typedef PointCloudT PointCloudMsg; + ``` + +使用者可以向这个定义增加新成员,改变成员顺序,但是不可以改变成员类型,或者删除成员。 + +### 2.3 定义LidarDriver对象 + +LidarDriver类是rs_driver的接口类。 + +这里定义一个LidarDriver的实例。 + +```c++ +int main() +{ + LidarDriver driver; ///< Declare the driver object + ... +} +``` + +### 2.4 配置LidarDriver的参数 + +RSDriverParam定义LidarDriver的参数。 + +这里定义RSDriverParam变量,并配置它。 + ++ `InputType::PCAP_FILE` 意味着从PCAP文件得到MSOP/DIFOP包。这里的PCAP文件是`/home/robosense/lidar.pcap`。 ++ `LidarType::RS16`是雷达类型 ++ 分别设置接收MSOP/DIFO包的端口号。如果不知道端口是多少,可以用第三方工具(如WireShark)先查看一下。 + +```c++ +int main() +{ + ... + RSDriverParam param; ///< Create a parameter object + param.input_type = InputType::PCAP_FILE; /// get packet from the pcap file + param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file path + param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 + param.input_param.difop_port = 7788; ///< Set the lidar difop port number, the default is 7788 + param.lidar_type = LidarType::RS16; ///< Set the lidar type. Make sure this type is correct + ... +} +``` + +### 2.5 定义和注册点云回调函数 + ++ 如前面章节所说,使用者需要向rs_driver提供空闲点云。这里定义第一个点云回调函数。 + +```c++ +SyncQueue> free_cloud_queue; + +std::shared_ptr driverGetPointCloudFromCallerCallback(void) +{ + std::shared_ptr msg = free_cloud_queue.pop(); + if (msg.get() != NULL) + { + return msg; + } + + return std::make_shared(); +} +``` + ++ 使用者从rs_driver得到填充好的点云。这里定义第二个点云回调函数。 + +```c++ +SyncQueue> stuffed_cloud_queue; + +void driverReturnPointCloudToCallerCallback(std::shared_ptr msg) +{ + stuffed_cloud_queue.push(msg); + + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; +} +``` + +提醒一下,这两个回调函数都运行在rs_driver的点云构建线程中,所以它们不可以做太耗时的任务,否则会导致MSOP/DIFOP包不能及时处理。 + ++ 使用者在自己的线程中,处理点云。 + +```c++ +void processCloud(void) +{ + while (1) + { + std::shared_ptr msg = stuffed_cloud_queue.popWait(); + if (msg.get() == NULL) + { + continue; + } + + // Well, it is time to process the point cloud msg, even it is time-consuming. + RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; + + free_cloud_queue.push(msg); + } +} + +``` + ++ 在主函数中,注册两个点云回调函数。 + +```c++ +int main() +{ + ... + driver.regPointCloudCallback(driverReturnPointCloudToCallerCallback, + driverReturnPointCloudToCallerCallback); + ... +} +``` + +### 2.6 定义和注册异常回调函数 + ++ rs_driver检测到异常发生时,通过回调函数通知调用者。这里定义异常回调函数。 + +```c++ +void exceptionCallback(const Error &code) +{ + RS_WARNING << "Error code : " << code.toString() << RS_REND; +} +``` + +再一次提醒,这个回调函数运行在rs_driver的线程中,所以不可以做太多耗时的任务,否则可能会导致MSOP/DIFOP包不能及时接收和处理。 + ++ 在主函数中,注册异常回调函数。 + +```c++ +int main() +{ + ... + driver.regExceptionCallback(exceptionCallback); /// Date: Wed, 31 Aug 2022 11:21:18 +0800 Subject: [PATCH 357/379] feat: add option ENABLE_WAIT_IF_QUEUE_EMPTY --- src/rs_driver/utility/sync_queue.hpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/rs_driver/utility/sync_queue.hpp b/src/rs_driver/utility/sync_queue.hpp index 039ca667..f47388be 100644 --- a/src/rs_driver/utility/sync_queue.hpp +++ b/src/rs_driver/utility/sync_queue.hpp @@ -47,18 +47,24 @@ class SyncQueue public: inline size_t push(const T& value) { +#ifndef ENABLE_WAIT_IF_QUEUE_EMPTY bool empty = false; +#endif size_t size = 0; { std::lock_guard lg(mtx_); +#ifndef ENABLE_WAIT_IF_QUEUE_EMPTY empty = queue_.empty(); +#endif queue_.push(value); size = queue_.size(); } +#ifndef ENABLE_WAIT_IF_QUEUE_EMPTY if (empty) cv_.notify_one(); +#endif return size; } @@ -125,7 +131,9 @@ class SyncQueue private: std::queue queue_; std::mutex mtx_; +#ifndef ENABLE_WAIT_IF_QUEUE_EMPTY std::condition_variable cv_; +#endif }; } // namespace lidar } // namespace robosense From f46b8e571bbfd03c81110d1f86e0228b8ee4285a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 31 Aug 2022 15:27:37 +0800 Subject: [PATCH 358/379] feat: update docs --- README.md | 5 +++-- README_CN.md | 7 ++++--- .../How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md | 2 +- ...ow_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x_CN.md | 2 +- doc/howto/how_to_transform_pointcloud.md | 2 +- doc/howto/pcap_file_advanced_topics.md | 2 +- doc/howto/pcap_file_advanced_topics_CN.md | 7 +++---- doc/intro/{parameter_intro_en.md => parameter_intro.md} | 0 doc/intro/{parameter_intro_cn.md => parameter_intro_CN.md} | 0 .../{rs_driver_intro.md => rs_driver_intro_CN.md} | 0 10 files changed, 14 insertions(+), 13 deletions(-) rename doc/intro/{parameter_intro_en.md => parameter_intro.md} (100%) rename doc/intro/{parameter_intro_cn.md => parameter_intro_CN.md} (100%) rename doc/src_intro/{rs_driver_intro.md => rs_driver_intro_CN.md} (100%) diff --git a/README.md b/README.md index 9998a802..fce04333 100644 --- a/README.md +++ b/README.md @@ -128,7 +128,7 @@ cmake -DCOMPILE_DEMOS=ON .. For more info about how to decode an online Lidar, Please refer to [Decode online LiDAR](doc/howto/how_to_decode_online_lidar.md) -For more info about how to decode a PCAP file, Please refer to [Decode pcap bag](doc/howto/how_to_decode_pcap_file.md) +For more info about how to decode a PCAP file, Please refer to [Decode pcap file](doc/howto/how_to_decode_pcap_file.md) ## 8 Visualization of Point Cloud @@ -147,7 +147,8 @@ For more info about how to use the `rs_driver_viewer`, please refer to [Visualiz For more topics, Please refer to: Trasformation function: [Transformation guide](doc/howto/how_to_transform_pointcloud.md) -Network configuration advanced topics: [Advanced Topics](doc/howto/online_lidar_advanced_topics.md) +Online Lidar - Advanced topics: [Online LiDAR - Advanced Topics](doc/howto/online_lidar_advanced_topics.md) +PCAP file - Advanced topics: [PCAP file - Advanced Topics](doc/howto/online_lidar_advanced_topics.md) For more info about the `rs_driver` API, Please refer to: - **Point Cloud message definition**: ```rs_driver/src/rs_driver/msg/point_cloud_msg.hpp```, ```rs_driver/src/rs_driver/msg/pcl_point_cloud_msg.hpp``` diff --git a/README_CN.md b/README_CN.md index 448377a4..8050cc52 100644 --- a/README_CN.md +++ b/README_CN.md @@ -122,9 +122,9 @@ Windows下,**rs_driver** 暂不支持安装。 cmake -DCOMPILE_DEMOS=ON .. ``` -关于`demo_online`的更多说明,可以参考[在线连接雷达](doc/howto/how_to_decode_online_lidar.md) +关于`demo_online`的更多说明,可以参考[连接在线雷达](doc/howto/how_to_decode_online_lidar.md) -关于`demo_pcap`的更多说明,可以参考[解析pcap包](doc/howto/how_to_decode_pcap_file.md) +关于`demo_pcap`的更多说明,可以参考[解析PCAP包](doc/howto/how_to_decode_pcap_file.md) ## 8 可视化工具 @@ -143,7 +143,8 @@ cmake -DCOMPILE_TOOLS=ON .. 关于**rs_driver**的其他主题,请参考如下链接。 坐标变换: [坐标变换](doc/howto/how_to_transform_pointcloud.md) -网络配置的高级主题: [高级主题](doc/howto/online_lidar_advanced_topics.md) +在线雷达 - 高级主题: [在线雷达 - 高级主题](doc/howto/online_lidar_advanced_topics_CN.md) +PCAP文件 - 高级主题: [PCAP文件 - 高级主题](doc/howto/online_lidar_advanced_topics.md) **rs_driver**的主要接口文件如下。 diff --git a/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md b/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md index a50e9628..ccf7cadc 100644 --- a/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md +++ b/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x.md @@ -10,7 +10,7 @@ Why to port your app from v1.3.x to v1.5.x? Below are several reasons. + Add compile options to solve packet-loss problems on some platforms. + Remove the dependency on the Boost library, help to port rs_driver to other platforms other than x86. + Refactory the Network Input part and the Decoder part, to support different use cases. -+ Improve the help documents, including [understand source code of rs_driver](../src_intro/rs_driver_intro.md), to help user understand it. ++ Improve the help documents, including [understand source code of rs_driver](../src_intro/rs_driver_intro_CN.md), to help user understand it. ## 2 How to port ? diff --git a/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x_CN.md b/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x_CN.md index dcde0ee7..72c27288 100644 --- a/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x_CN.md +++ b/doc/howto/How_to_port_your_app_from_rs_driver_1.3.x_to_1.5.x_CN.md @@ -9,7 +9,7 @@ rs_driver v1.5.x是对v1.3.x较大重构后的版本。它主要做了如下改 + 增加可选的编译选项,解决在某些平台上丢包的问题 + 去除对Boost库的依赖,更容易移植到除x86以外的其他平台上。 + 重构网络部分和解码部分的代码,完整支持不同场景下的配置 -+ 完善帮助文档,尤其是提供了[源代码解析](../src_intro/rs_driver_intro.md)文档,帮助用户深入理解驱动的实现,以方便功能裁剪。 ++ 完善帮助文档,尤其是提供了[源代码解析](../src_intro/rs_driver_intro_CN.md)文档,帮助用户深入理解驱动的实现,以方便功能裁剪。 ## 2 如何移植? diff --git a/doc/howto/how_to_transform_pointcloud.md b/doc/howto/how_to_transform_pointcloud.md index a390c24a..78b4d462 100644 --- a/doc/howto/how_to_transform_pointcloud.md +++ b/doc/howto/how_to_transform_pointcloud.md @@ -2,7 +2,7 @@ ## 1 Introduction -Before reading this document, please be sure that you have read the [Decode online LiDAR](how_to_decode_with_online_lidar.md) or [Decode PCAP file](how_to_decode_with_pcap_file.md). +Before reading this document, please be sure that you have read the [Decode online LiDAR](./how_to_decode_online_lidar.md) or [Decode PCAP file](./how_to_decode_pcap_file.md). This document illustrate how to transform the point cloud to a different position with the built-in trasform function. diff --git a/doc/howto/pcap_file_advanced_topics.md b/doc/howto/pcap_file_advanced_topics.md index e2ab70ec..0f70dd77 100644 --- a/doc/howto/pcap_file_advanced_topics.md +++ b/doc/howto/pcap_file_advanced_topics.md @@ -47,7 +47,7 @@ param.lidar_type = LidarType::RS32; ///< Set the lidar type. ## 4 User Layer, Tail Layer -In some user cases, User may add extra layers before or after the MSOP/DIFOP packet. +In some user cases, User may add extra layers before or/and after the MSOP/DIFOP packet. + USER_LAYER is before the packet and TAIL_LAYER is after it. ![](./img/12_user_layer.png) diff --git a/doc/howto/pcap_file_advanced_topics_CN.md b/doc/howto/pcap_file_advanced_topics_CN.md index c70e3b40..e1cd201c 100644 --- a/doc/howto/pcap_file_advanced_topics_CN.md +++ b/doc/howto/pcap_file_advanced_topics_CN.md @@ -6,9 +6,9 @@ RoboSense雷达可以工作在单播/组播/广播模式下,也可以工作在 本文说明了在每种场景下如何配置rs_driver的参数。 -阅读本文之前,请先阅读 [在线雷达-高级主题](./online_lidar_advanced_topics.md). +阅读本文之前,请先阅读 [在线雷达-高级主题](./online_lidar_advanced_topics_CN.md). -## 2 一般情况 +## 2 一般场景 在下列场景下,使用如下配置代码解码PCAP文件。 + 广播/组播/单播模式 @@ -27,7 +27,7 @@ param.lidar_type = LidarType::RS32; ///< Set the lidar type. ## 3 VLAN -有些场景下,雷达可以工作在VLAN环境下。这时MSOP/DIFOP包带VLAN层,如下图。 +有些场景下,雷达工作在VLAN环境下。这时MSOP/DIFOP包带VLAN层,如下图。 ![](./img/12_vlan_layer.png) @@ -47,7 +47,6 @@ param.lidar_type = LidarType::RS32; ///< Set the lidar type. ## 4 User Layer, Tail Layer - 某些场景下,用户可能在MSOP/DIFOP数据前后加入自己的层。 + USER_LAYER 在MSOP/DIFOP数据之前,TAIL_LAYER在MSOP/DIFOP数据之后。 diff --git a/doc/intro/parameter_intro_en.md b/doc/intro/parameter_intro.md similarity index 100% rename from doc/intro/parameter_intro_en.md rename to doc/intro/parameter_intro.md diff --git a/doc/intro/parameter_intro_cn.md b/doc/intro/parameter_intro_CN.md similarity index 100% rename from doc/intro/parameter_intro_cn.md rename to doc/intro/parameter_intro_CN.md diff --git a/doc/src_intro/rs_driver_intro.md b/doc/src_intro/rs_driver_intro_CN.md similarity index 100% rename from doc/src_intro/rs_driver_intro.md rename to doc/src_intro/rs_driver_intro_CN.md From 407f67c6981caaa62c3d1a9d7acba9bf06c1af95 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 31 Aug 2022 16:48:03 +0800 Subject: [PATCH 359/379] feat: update src_intro docs --- doc/src_intro/img/class_trigon.png | Bin 9436 -> 10086 bytes doc/src_intro/rs_driver_intro_CN.md | 12 ++++++------ 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/doc/src_intro/img/class_trigon.png b/doc/src_intro/img/class_trigon.png index 3f368fdd993ca0269d6bde88a857dd2d72d224fc..99b6972f4f5329d3b330c2a8ef520a9970b2a31b 100644 GIT binary patch literal 10086 zcmZviby$>bl*Um+kd{v?k6Qi&6p)euQDP_s zsXg=Uw|njGwSNd+%sX#9&pG$G&+oi357ZTj@M-X|u&{`fmE<(xcQgEJ$GZ$aTaj0; z!mlf?O8OpHSj63!e;3j?iD|L0ZeS_P-FxJly_w@@H2L}LJg@843uZR_u;^+L=4nA! z`FMPvCy8Zt&P@f@_V%b326GiwxAKEMx`t41*sUW<8eiq#vcEUeHMzo3z{MQHEORM) zfze1(D$+}VDnewm&w^njdsKhkCU7rnPh`z&UJ(&aO7XqpDXyUNT%&LGRR3=ENsWPV zT5hg!=Mp0MeXPp-l9gW&hYPy9PKBk8bRA9BA|u)?SD8r6JI-0urMiz_I6;=dYw{e4 zTqoCkk(0wcIJkR9XMT7%J~R}od^bHa-KgI2dQwu7ubWD&`Eng> zl!j`$f7GAdUGw#c;?LHvdLi#N+J-KMZ8)&jjeEx{*E#mcO zd+XsBJ#Y1E(EIzB7Eu`{Iuiv21rLyq0#A1O;M0rP*fFuOoeK+j+im9zp@SK`pUMq| zXasFTGcu^-sCgBNHFq`}7A~UEOS1F+zqmIxH~9nv3Jn{a<>chp?g|SFztSl?`dL=_ zuBs|uIpr3YadYEp+cVKH&qEbcbMuSRuCBLTns+YWRD8~rWV6zrlr84-JVEL#6OOI& z-ZY4>{@#~hGyLMtrOTIh^UhDAhKBB6CZg$fX*(@h`QY`73bx5=Z*^EtU;iovg`A_K zBhf*%GZTF)K6-D@V!qiAv9A~t6Vu(>JJAy0gSkV6=X4(vnPfx5@|FVrY+a?IQb=Hs z(0gZk0k+2aYqizN>T0#q?A_wrjSWYgN@KP2v(v2GW*0+uahb-6*3sIbH8mc{b)W5d zoL5$Z=_&?gI_0T<8l1mfY@eSuR^}WEIR5Q~7#bP zXqVO_g(hb^J7sBUtmEIC7N~(V*qC%K{V)iI@4fK>vFX!~SLj=59wHw(&ejtN2?@;y z{dw%YHTUsLl|`BZ7F^8w=Ops2L0#vbmTkYlb)O&LV;*8kH$S8DoZ3&fF@?w3qffpj$alZMw zp`jssF8^z)+|A1?Xr^QxF|kyZ1z%4VS_n+hudy~WHI>fbd92suj({f$`1gqG0RhLF zcZ8Blp9b2d{h*v!Lik5``o2mf7XP3JcJoq9i6$@BYCS5z!RYhvf0 z$jHc(gJ}~Lf26;!wEZ%o4&Uhj%}<(AG<6f3PnpH)2EB2Cu2NLSf1Xo5Uif6|+lQmQ zQ7NyH<6c^qcedlqIWrT*L)0dL`OOJ&aTe{N7X+PVQmMENZad8gy1Tn$^?&?m*8A*w zt?hVNiQ3DFwvZ5zo_vpxf#tD$+02(O_d0MHZHxMPdkZv?nNlIG3jWT{71i?Z5;HTe zot&Ol)z%gnxA=eg`jyXag2if@vc0Ubb)eaAPo<7YSom6+N<>o9!59jQ3LG39$bMn}eKstQwGpdB^wNMAM3A_Igz6CC?~Si1EdhUYzSQ%GCv_>x%O_=L zzx6tkkE62NM9c35pB=4Po#CcM)LW5}lOO#kOh_G-jU>#66V0^*WPJIe7ksj#C?g|- zb%^dF5eYdHhy7p{5y9*oB)Hd>hW=Z_hUcS_$ImePc5)IJ?~tCJ{??=|S2cqtP5*4J z$zy-xD|wy4a0CIh@5vz_?7g`Eel)D%LkouY;_tmTRh*rjW2S#qwpD2RiHV8H$jYh~ zxqN$1X=pg>K6nd(s0u#yFP}jYYOJ91LeBhR)Vifk_sMg_e0qC&aBy*PL5Ad=oq5hr z)})$(Peo7v9%z*$=)Bc?QdoHN_wV10A3l)N(-S>l-X6*l&~FVCdGPLr&b5)w-rmTs zH8vTp#L|UB;aA9g*K&NW-F3W{o0|(cqMj@M5#(cis+{)Y$B*!bipL*%H@?^{VXC0qE zr!fW}-uvzkI;!97%a_8c!Bf|UwcYZE0siuR;rvXf+_0f{Y>bqZm9^ewVFaSq;eOWo z`nvM{`_HP?t}gDcf6C0tGPASOcm7Jrsq@ZtNhZg+NJA!#$ZmBgt7{Ue)#SZN1J&x5 zghb9l@Uhxaj9B2|?aG$lG??|eckf=ds8{Uaq3_AbNv60TzjREqJZ3pS@3oElp3_@= zd+&vsv2=7Cnl=d;o~d&X3HmDtB4M$!+#_f^CVj=v4K+XsnS4#mn~R7>P#UkJCyx5) z?09=;Zx0(^aC21Zyjj!5*H<{`?>-VO#$G8E;W*cr1f|Tv(y|+t_{%%9r@aSrb4J!f znfKJy)sa5!+1YgJIilJ>AAcDedtmX&*UQ4zwjWXj)HE)+-f9pdv1$+>O;%#w8~v{z z7G{cgSl7+GuIq}5h%j?etXu4{m6s_ z5^5f!Mfipa1Jfl46vr>`o?vp#5icrCy9XW}bsQeXB)4>)R##W2W8unnjV9~G3;SmL zLKfS>!=3M#89`(3KU-{LQd~Mh<5k%T)1+U+FZHFb7YudyChQdQ;jqTATo8o}%ppGBm? z`=+KQvbV^@eAy^6T3S^{N3M#B3i03*JpegCNEHP^4{N*g$?sI-)`^2ZNbj2^XIxrBp*i78@w(IUr-Lbq?fa#?5% zJVIrtwEjK##p&Z?Vey@#N}C#@Y4kb0*q8TSoZw9&)vZoXPuIUx-BeBILQ>6^buW3i zyQ9(Q#pRwj>5iNU5Dg}O-#5J-VE`Z--W3WWmi$`vLlsXX|)_r{kF0^Vk< z_Vd$)^Q6?&Zg6;Mq<%9Gj6;^ce-{Zp5r$LJti!5^AN-nLgQP0Nv zdJPuFp#MIG3Hq`_4)L=_lB zJ#Ay6re*NAL*=95HfQR-pB(MYwS_QhXlNi@9aL2CA(tN%(93o(D(?9GhLy)EC@fUX ziJJDtuTO-kgUKm~*vO=$tq)3@8ykAnmN8Qf^zUD(XlP7lZkm9&f^A8$S5_{+SFTe7 zxu$7x1Y2!?!ZCP=PBuv3*;%rh3{!dM^-D+cc%z2Dl2P23l$Q1-P3`Ny5Z8)X0<5jA ztq9AjqZ|`UoE?x)*95GGKHV);5cXJw-}x$u_R2BFO#k>6KlFLx?&6CST;0iS2w@9n z=aCq4R>29-FV)dpiNVL*m81`!L6*cKRMROmrWQf&D3q0zQLF5+DJdz3-xH)fM_%UU z^6>NX*E%a^@cV4dUF9~ceE{y{R(q!Dk95jicfwgR()6L?W44 zSrwl#N*P0$Qd~PrjmXQ(!y_W1grY{}=jW&54^<3yhk}ZVY8irG zq|BnC2AEA6dMTta*XSmTxsKG?p)4Vzq!E7!u9 z!y6iWVjM?Ay4skqb6#Pw!_!2?#CbzPP`-PZ!A*xMCF;#FNNSR{T8E@01*jO*}e z8zL@}gmI)aFL(eF1Ofv0Q>jK}t&=7L7pg;B-4CvEd^%<5vb4Hd^479azb4Y6@A(d- zn(n||c9QhnMVd6sX}*2%@%S;u6mJp&3ju1DCF*5g9Q+l<9tz2c8Y@XO>nQoTUeGXP;5tCx35Oe&EHcpi*BNWCqCs_GSKhvT+vu@I4ExK&g!?%y zHI)MNr8McT^PKQVo|FmF-^*+;og2JgP47&~BVKJPi9^UmD3$EvUS(m0iU}OVj0_AT z)mDT3{r!tz6YsweM7qDX<@VdGn?Bt7u>GcmUU~QdVs{Z9iqB*9zVkw>+6QopT!h); zewsPq4aKO|X_g9_VkjIH+Ig@(Y4Y542Ic+C-rMu>m6g0$v-M7eCT+n( zIbs>G*H^)xA&R_%gC!vq+sDVRf+~rNiyy9+=6N2QBR*@m@wMEgl?EfI5`6?I#6I`! zTiPi2(B=N5o6OwYY5*hj=tMo0@R;OeWWvB{WNEfSF)`noYm&iZf(jrHO=(YS&~Z4a z43|;kgJ;ljAw8BlBg}hZDGMB?E0(9q4G|ln{`;?O=bM|{H_=O7oe(N>AABn3&Md91 z@nvOYuToR9hLd8BG)FIXFmrOMVv1Ggr%zhzg;iBm(Xp{)GI*GRW(FP=>_#_4Y6Pf2 z^;b+yH=lZ|kE-WH(s+KwDmbXM)YHqXPR+~B9ohNb$H&LF)U=kXMUhhMw(*7Ug^-In z7$z*+uhj@>gKvq8(}C{)-d?DjLvnL-yZQL=YVm*{cwSlQl4bD|tl84qT2xLB{exE) zE;F_4U?!UX{w%Yav9-5Xfd|)b3zh(DRq8ZbAM5&77{W_u1|#(%A|fmZgqej!7liZI zdM8>*Nl8LF;lwA{xanU@R@NU_?Jia;DJ!$*^VHVXK1xksRnImZdv(uqeImm7+k1G_ zul%S^sCb~i6Tl&QkY09WT!e&#!hX9ff3_E(>`7uwK|HNc`iq9fxoi0Q-@tco`qsNbn<-T8EiP=KG&wgudX4cWL z5IhL#0>1i|f`UTe{V*`W%%^5$QaSRUi)f2M4=4JHxhHk1INz?CC{4+Xn{;Ai2Ux;nva6D|~|D zQNDH(MMSG$X~{xNOnmM7bu%-w{DUb`_;H}uijw{X1F5(`@jwiJ zP--%qNP&h7FLpeI4CojiPpWMF`=(QLFy&GPrJDY3Dmzczq@v$DQW=1GG0@t?K{vYt z0ul$*C>qnv8rt|JF9H&XgI)!SA5;$WjW1Qqw{Dflh_SrCiRus?cnWIU2W9t5lLsqD z8h)LDT412~>gsCXP7k%!)cVTGqY{?J+b^nt(?A0|g~!D0=da{IdwS7pDj9@(Om7+6bLRq=sz#mrk-wxoU8i#`$u^B zgN*_lWpB>`!fM^0$Q1f}JQZ;#E)`dc^yJg0Pbu1EI!SqX8b(HRyv^u~(8Qpo^wU`y zn{5Y@OW~;Vgw5Fo0k5Br9G#r_?%c70{T|>GvigiU##Rso>hg$#652YmKI^Ml?J4F!;q3{e&`z8D9J)<|HD#tl3=RM*A93{ASvXUB)mzfPv-ldmUS{H zZz{U1bgYf$Rk~hK(fotd+FktMv(4|iD4m_1?ds}k3Q`rz^$OU-fVI7%q9Uk}EW{M} z<#u=kU`)~j{=Y=E`HTEeX}TCF1UJ1lkj6>lb0~FwLM|mG1${vyG{K6`>6T2+|7P$v zXWn(9+1lEgYxYY4mk5eJe0F-g14wotmHqJWkd%@#qNz!Qn%CG87%g-QrcO@f*$R)9 zfGq;XFlr0VX>1gR>=g+-biEP~A0HnR9lZz&Y1HU?K|nwN^cA-qlRctd9AHbn@1h2w zZE!eoQ?(cJQekkku~F31yM{|l2Wb#@w6~UFHw|i?ChH;Q^;0e|uvs%I^j+=h_AKU*)rt?0&bUO-*lrbAf6Z1;&#<;J0JW zfU3UBw-WV_PeJfr3zuePU3Z$P9k;ux25Th=_izGKP5|hX$zKr~_l;;J9UG!&x4S)6g zI}HMi_&79lX(0Vl1~t8&rWj_c zfq3jLMKO|Hzpe~52b#0kPLIjg4;!1B+%{+K@EAAu15P>o({@gj%6&x=XqMCo8XNkH zRbaY{Pe~*fF@z|#^8Rk>YdD)k!0*Lhzf{3uT+oBoBjo&42uvu3a6o;)eo$#F(Hl?O zXOkDC@ZiCNtmH)iBIQFr+LLFLbCPkPggeM#RhYC%LffliD8I>OFRP!txLbg&YR`(< zH!G{+@hM0pOfZ4ahgy3s7F-SeM=Ab&98-{JsB)N$IyyQU%9G0T+gk-Vqr5%eq7S~} z!MjE(8kzyX#RF-eFYv7ZSOinh|M`&fpufL2RjsXWVRA7)KOYO&YdqM^rRC)?m11+K zTHrMrjFizB(YN9_PR8<`$v)bF+1N0mS z5R&reEaxDY;OippEYNsjq5|9n)Yk4;O3pWRk3ZI^riHJ+j;0lIM$dVSR=J~8xVX82 zjadTx;xcKaV-wb_2B#=2BC@o-Jqj6eUC5aZ3p5&2xayr|mzS42LoZ-Ax_!U=;2rY+ z7&;;|UC4N2V`I4P1q@lc>-gmXbIEhLkk?6k&47pgoyimx7u$vJkjmWl-p~Uu(F2d8 z4+9|B!+~$-g$a_&AOI(Se^nZN@Qw$r#pl0o`)X0JwZC7kl^GY%?-(8mI$+=FSzlw1R1^oD_0Ajk#;o}Qs0Ihf>kW?k!eIyIMd}xQ4BGR04OnmWjj$6lRQ3ecb&uZ?f_?{ z?c7(@u7QEr=4NpywxvnA$;n}9Y1)*3WOfDF-$e0Fc2KvD_V%;$ zkdui@yN(Zkb$ae^FXREf@J}18HBpz<*aB}n(X1`3r@K%Ww0LB;qCf{awIDF$#pafTtIK z{D_8ahT1EqsED1Im?#Zg9z!?h=jR*Wzvs7~WV1@D5RdVA2y=(){FZoN_ z1zd?FrdQF?Nq^*_bF*%hqHXySF0O^0-A72bn7FtuFaw|z8T~enj`!u{E?YUjm~*$k_>h6asFpum82_<$AbscV8bi4zckg$vJ2`pb;tNx__{}&=$@e zVQ>O@ytJ|cJ|HlHY)uBzP8gsZ#yVHiNy7LizL7(-)u_c*f`pNjR2oKjSeOw<7QYof ztRZDO=P!!3@bF8oZoFLp59D`T!&67I2)MhRHaF!Ha(?s zHUU`e3;1_i7QlePFwq?*oaPo%_!C%IxP+K@0W2)M>J4`-Cug)yZh?QHQ5RsfFZ z`8-NLP(TR`Ei^Jvxs97MLH;o=6Gb5faST6U&Iu$>zsej3vf3ItEW&HIL*cdo z8Wj`D;`<$MHegyzXxd>4&1U7551k#&ca(_7s_Wly*p~?xTmH-!g5*MjSv=>D zj~IbzZf8$V1ZDyaX_WeY+!BBU><1AzSvoqpM%SgV-9T)dUDWa{83I)p$H4GEXk0}K zD5SKWo?bNEk&bc@AhUtvk14EiJ_|v*rMqA;I){hVFmrir^MqDtM|%K$Z~>{4Q&5Oh zQc=;Ix3RLaTlwr@_XHdu#1IdLID0u&EV9?HH&rYekSHQx}Y+`>j!e>Iv%?#%CBxrE&yW!2vi7P+?c5&fR0zb zRwuQ_W)w5S$2e0c2BR>ZNps+zal7*%kj&&|L@9LBZY%v)<7=TM!}sy=LDjUhv;f_X zhG_;lhyYa-F+Jdtq{PGZz`&iO9&v&}($fhco?ueWe00A}EyI z(6gl79jM{HefvSJ{bv=J%F<~3U8=k-EKo3Xx6Y$lwYUj1Mqh~g0x&-O z`*)(+N)>7=#$ZEEG6U>@b=?8tc;R1zU0MtDs}ER}aKLY_-riovuhkLYaMEd<8kuK- z!k4n$iyL^JKra>vAPx9`&)8TZyH-i+(KnbN$;Ff`E-r?`%q-yd#=~8uCfCoJo8wOh zlX0mz*fg?*J6_#;`eUM)0Lbfiz=#NzreYXg-~UvimNp8NpbxrIWP@+_Qs+LLdA!O( z5eCwBFt`IW&cw=EI%(TQ`Bf)_6$7eiVgSGyGJ$Vmb!Ow1szq@ZvaWB}fq zXqpU!SvxG?%=>I(bZ{-rz|zjqA{Lh#m&B1ZvludC~6lgFC5xp`+84uS9K!89}=L_9n^V4yKBGTydJI-)+U51?gQ zRt5y;cN7XIwOI?GPbM1eis>eyX+P|fI=h#0OATHkdYY^_5K%^@?eG7-w;~1vSqoy5 zCV}CE>w)-;s}+DDt-Efl{~$bBYwHsAy<`5FDsKSEK#Zf|#h4feFqHs_*z$;Igq-h> z>yD3g{#Dqq?a~-n|5RF4SBC=ngasoo25=lX)HRm17MpA|jIFotdoLYBCAB+jm@h-b zX$sDu;rKk?y3b$};D4Mi>*(p|JkuE&guY`zG~s{Cl6>gigT;2 g{PbJj51dOmAMv?Oweje~i*s1Y^6GLGGNxhw0Yv>75&!@I literal 9436 zcmZu%1yGcIw_hZsL8Jww3_?Ic8VOkdiJzO1e8G1SO@Fkd%@x5eX4gM7(F; z`_4Dtow>~53bX7!&;OkBtFzIn%CZEw)VK%)f&eKetqzZg@ZEuf1^>oOaPq;!RTnuu zcLaj45A}_f%0@_oKrkSX(hoI#vcKkdYifQZALuH;qzNr#&@!dO;=;fn3&UiJ3TGtt z*QqDQ)J)C~Wg(@v;Me8(Z2tqnmH8|wX^g966ck17J7dYo4Zjw3pRlwkSlXV{5A-q$R3Fz5 z5!j2cyY*5N#V(c0J->bTF7Dpmo|}%kw)Vib^Y*X6z`*0RNcwl0oMq+Za{E<&nwn&s zCY|^c6cjITt!)L#$jR4_)_PmrcM=qTX)<^Gt*WZ(?eE8A)2{YO+-~4~%)`U;?AbHb zLqlTW@!mog-3_xOnpq#+%?Lg^@;0;hNExT%%pEh^Kg1-)T~9c^y?OUeK5555X8d_h z4gq1L#vutcwf-#?CnwGaw1ki1sb?@aoNhG5e~%a^zoaC*H{`qA4gSwEG-i5fc;p`LXK~Grw{%Au1|3A%XC<_hCYf!7E7v0~#+c zFGbPEW7#3kpI;O5+{3W2uo%e_Ai8JLiGdi&;6|q<#6CVg-kqtUfcL|pr>9RzN#VUD zuw~W{KbDhJQX)VQQ&3vew!Ku&gbQTk;UP8Tq`^a~IPatuzgW$B0}F?c zkkDL}uYaAD&*Gu8vfA?N`m)f> zhG4jL3mfq)H5D^NqC3FZ(y}kRjui?hFE1b0)6BP!avatB>C+8Fy~8{YGc&VkPblUH z6CUE?&!2+o>NpmKwAJYf4c!(8s)OZ@Slg-60;4xxN;CVcG8L_@l>*i~I>_tn_^ zv9-0eJ6WQTbFy#og`U%}HJH=rb@$ZNHCtO-93moYL>#T)%V>ky0JHcVdMrZPsKd_R zgl%nYl)N^?P@kjIk0wkE4EYsVvktZzCnCu|_Z!EL<{#(rdEVE@cNqWg8D*NuxFsm4 zw`tC(@Fl;#o*3SlXXm+JH+wh@eHwY3NLQWaK(Eue{U=LHO9nA9dHfJ8`z8 z8}nU3;<$KtR?5PT3%u4n>iU+$jh6aTzac_14BbG@-#L#Y|;)T~#sS*wz-t*UVdf!9> z&&jHE>a4|npP#>-m>?O?743yda9MkcDJ?6Dj?k{r54ZnVyLR?1q0w zpL9W4StMNc)tvY5-n}&m`oq#<=;-L!*VnfS&s1+N;{Uemn1nc?H*c1gmv@)tJ&D04qU(kx{Qct)8&PfWiqP8Hnv0)5qN77} za&i)pue`9jYAP)wgH}F?HJ&F$z^Tu}R6wV%OHzwt64ZAxyi2(NOc- z)ZAQ9S&1tyF22+iWU?Me>iM<#`1|)h74bjJyoaPTGP^c(@!ciyrxiDCP)V|GM}Jn`CXa#^Aw|iwEr;9cT!tNWy+u`oO*v z8hZMB$AhUJqBC>z^A7CuFPBhNC4Tq*J;}9eObr|{5>6Y@ zv9V#bwVWQFo+R}2iQE6w{{3XNNatuAO&Wh&_z<51;KuRYOKPo=D^t!J~& zhM(V3)zAnF3qxmB$;DSu85goGEGlw6SQ4x@dZTUrX_6=K+~eZsMj|43dRo(C_rt>> zU73f{s=$@dXC!oVV>rKPNZaBE$H$3a#!)RA8HxSm_g8_NKm&9hf*&|r?~^yzgt zbk0o<4y8R#9q3PAU*D0P_I8mZ=R4n2b#k0Yc8hd=ApsC2wL$cv=TGMKakH^ z3(CuJ9*^f*`SHjU6cvR%48t;8=?r|}wu!^4n8BcNIW#0^*ye_LOC^_V0jB)ZGHWkCvRqYy54e_R561Kjg^&k_1I_Ct?lT?kI3X?(t&syY#kjP zhox4MSaOcHB?{@?J15*g6;<$sk z7^KCAj~^pLLeOeWx)QG4QeN#2K?fqnN`Ei&#_Q|RC+`(BM2q8M1au#2^gyYNsHv(l zv=F*})W`xYunx?Y!S9%9_;F)n106c8t(biBty71Y*{kJxUa|dytC)Ztu>>^y)4u~H zC9iz{{++r(h5*lA1lRIi%AGiYmo13jbLRglv{cLKd=?~6`Xh#_VrzO))Vb^sG zDj3@i*}~c~{^jLmGD=E0fJ0_toQ#vCq$FPV?Gd4YM&}hVYEeJl)YMcp;PSnTp*oW; zRy;hsnCR$&FCXikr=^jXl$Cv~_<=eXb8|^SK|#jE(9kPMEd|eVWmAs7fBBf`b+Ck# z))M~?n(H$l1nRV}bYJ`^DJ@Noh`fV`}@xVT-Q6KQF(>(^z_vG5rf3-3Q3d)C?cB7%&!f#E=XpW1IfyN$13mBcTO(Dn57)!p29+;ayv)S%cmHe6j@3joNkkxX3t zI zq?|%i7Ai)YgXFlEFM0X~2G+a&{z3IphQ*)r)49$-;pYcqIl@sGhuhVhgXF6Z3*D zsqiQ``&NSfa(HI-8z(a2!rjEP4M#;slT?JvPEARHHz0w54#%T-3ly-M3uPk$;O;L* zKJOE&EeTJxtglbTPaB9d($Zn5W)1^6h{VE+P5H< zu#CGUCPv4mQ;R}sm(x8h3=E9hmIsogD4o$@F-YB>n-(k?SJsjq*Z6px@xcSi`T6-l%vkxV{?+dL+G1}zRDsj1i5+1XctP~aSpo=U>r2bQc1zXHS>n_dR} zePSKr`s3geSSMKLiaYJ9cpn}Oqkr8z7doPPDVS|VR0}7Fxo7Pg#eCw%N@cuggl@J z(m0Le0mm)h8NT+o0|qhy7+xWfUc7dywy#eb^}Lf$6&hu7Qc__kg?#1*)FlUg1;8b$ zTt04VZS7%6Ny&HcG)aw(_ub=xiad_jWf&P>yKUiCR8*+h+TH==iD@FJpy=C`rFo>6fK8ZcYfo6yeAZudh0dgDvZ7^p>||BnMj zOHp)mbZ|@H9Oyueq6m8`%*NincX_$fI2xsX+uPgsZiJx}7oZLoFE57b7Ig`LVXMzE zBRF%GvrKTX2^krbC>IRSHd1Kg=y$e1Jnj7WaU`HQ5UzxZ3K2@vAAEYV_W5%(3DYCf zz9^E@+4*VB-#a8SzP^Ie^T;qH&mPmgdv#-Xn_61<8zpnIv*Uo<3ZYkB+}z#*-tMK^ z0QrNjqXJ1C7c!)-69^Ju4N$-bT-(yp637yD=cq3Wq(u4hY)e41ef|AwKURXUL3@K5 zas52W(s0_sOC6Z3s-yF2EHOPV4^YxCKR+J<_lB~=_iM`!3doGonV})5e5K^&aU%$5 zupU2t{9@1B(=)uPiVfhp-f@xt=lQuj?^2p{(fA2I6%Pg`Cgua*Z_L4!I6aU8933A& zbamwhn!uKol|^VdYYI3oTVAX~<&Z3o%LhOw4kp~NU?k0Z;CclTgg)T={_QuuC#+aR zbR+w2t0%vHu7(j=x;1oJ3=%@~p-h%4=)Kfbttz~p{Aam4pl#L5W+o@!0;x3EOfX_# zV@rYMf*BkLMngv+z}UEWcsvC=9uN>v4TnaA4A|tfC$4T z8i={hwt8@o0Ap=qYr8hrV4*m2a$eui5E2`UM@vg9Aq@h#_odZ)Q%6UR)9gu*)z4B= zFaXQIJ)zuk*X4PYhd@O*0IDuPjl#whtIiCd6x*!UqK-*m$x#m03>?x7Nrg@km^R2_ zuqs~Nw0S;YVPzE#ISw!K)6D%3HE3rI{r|>OY{RBWG}_5M@FQ~(-OI*C(8_3{qM{iu zUaalp1*PehKA?IO7-Fc;o1FG#>oj>HnT1MPi|#ffBcmJx@dp4=B&gLgPzkXd8rk?o zVs$r1(R@2B%OMqu<*Nk{4>;<<_8fa+t^(+PfA!zQY9BL}q5@+-pz! z4lB2|B|j_58DpvH>gv_qUEN!y+8R=S`xZ&VL2^pZM=u?>=r=MK`CVwcC$>W8YHDis zrQK1ExLNb@S!tnO|6(PPEi=`_hYwr*PVd$lw!N*cXM4@*y1ToJ2v%M0`g=(uBO^ol z9*mBRp&{+JlM`;=ZE)*?la3cv|(Q&0S2T4InDtUf>Zt3W#1m{Rb zL!&@VP5m8o+T=`?P6bReN{K*|sW)4I)w8sl9&;#~? zg4zZwY*zYd$n#`c2yd1sQLFs>-|#?(hW`yDr>t41Vr*0l%0}gRYK`8oy1slSBT}QE ze7rw@KaP_73gl&=6^@RMOw-6|Z``1|`5M5x^Y?*p>zg;dJw0e+V`Dz&-|qx#-z`xk zCipf-&0~o(TW3OKZ*RZ!##^O)=MFpj(^szqz?Gr20qBrbI0S3Dn;{_~5Fri%F}wUZ z_uOCUqL)peMRou7$P0886&1sF9};MZR?jcw+SR%t;E8tk_GYh2bh&Ok0=V1&JvB5m z6bxt$l1;0u0}%T`;5n~y_Ja^`%II*~D1VPIohX#a5ccMroSFhcG6F?(^-ocg)#ei| z=c~#1pmb4))fauu#nqLBrWo9WtEyVX>l=LNnY`Y2WHbsj4Gr;KWq~P%;y4~AbAwu9 zH*6(d2{<8u+N^!~61%_ekYqJO@u9d);SL$*pQ0TSPXw_ojoTOB%@S@FDg>ARnFBKm z%NkJV?p#BW>L#_VO}sj;S`&__iiJE6L~bwW^`)fH!Qb!G*(DpBMh1Vpd6s;$ZlW3EA5FHpwS@^3i0IxP%{m6D3#y-qg$47U z7zl+B8DJ~;9p-|ex&Q;-2TQhUJ#y5U+BaI61q5`4rce$ozo4LJTC4E}-=bp(K@GPQQFawI$RDO_R#avrcnrN~Rf~2?Ai4;-hchP!i+{I=X=) z7pa}%Uy*N<8Oit%A=3)Fp+rB}SlxCXZn&ZRnwogfk>)U?h|0@{pwzFLn3y#1#Ld#i zNz;j{RHa#hQ8k}`X+C~iy}@nkU4#>!!Znbvw?A^~ zR$!0RSh1$c@P51KRHsUWxe-Rr#S9M(NdyG6kNleBhCRc7Ru4)=Uwm~lZ;d`0KRFEg zO9PBL(zE9BR4i7VMmdY0004^TBMTc6iL7sKMq%Rl_s?OkoLBgLayUX*r%qrLljaK$ znzpf3IbvcyM~Ln1ZB*vc(&ClVekB9}nPe8fV{-YpuZeMIKy>uATkGFHPoa|ev0TyE zqaznc_i7)0ajfATnx#QPu1O4{ts9(90i14`N*+q1s;Q|VDwmcP78XL^Z@nEH#D?=i zbpj&4sfi2~4upqe`iRg)5YZ<9jb14y^=W(a1{E%cVG&$Oe}7%S2}YL*IuB*`5#5j! zHw6AZ6Y?L^EiOW0jevvqIoT$F)ki#-uL7kI>8BtE%_obIK1Zu)V6LK3nS96O-b@t= zCLnUY_WASY`o_jy@FHlMzI;mZ@^2xDMJee0`9^GDJHZVdSI{_=!d~ne>5!1_fBowE zeRtwf`}u6x(!e#?Js24o!FVx((6bnb3xRBHWMqVSyT;2`*mkm5=)l?C&Fu)7l}8j5 zZ~TYZOi1r~R#x(;Vn;!Mq;nccs;Q9#-yJ`g`TTW%9~HEK;RiC^7#IKB2ey`7)8y~v zA20`ZcZ_TndCzCFGCe>6jJ3fXB8ZbkGcz){f<7+4)(}moT<%d_th$5H)YfLacaI1n zAI||JSYhm2C@5!opVfu<1&x-{GkFgB*UHku*B zPaXIro*96v-hD?I0}IO>9OUlet9t{9^od}`5E8n&l#r8~Sy-Smh61W+8qb57z=s`C zacL=JrCEY`$;phoQPxSh)^AQ9F%WZEq=CJag3XluY_)G4PuKY#8^pKturxtKz+MDH zTU#4a-erH$Gku{NyDy{lX1(9}@27QbOuIsv_Mngk$TyR;A zv~Ke^-x!F;!NCazM}!JvVMk!LIh1s0R101l6>LF!gXFmaF0Hpemg4${^%i6!FP&K4 zimCV>h(uRlGkDE9=dkGsZJV@2jezXLR-bfgNZ#`ZdREMLG*G7J_dK88_5mIU%!4WZ58N<#A4Vd&{DhK8XX<|^UseJE4nJf zH(mtEwT+q0_8%od4QiAsCY43w_6`loHtUuw ze7=CE0fB*LW@cz?Y;5d$FP~0G#?y&XgKrx3n(6AtD*xy8!QYZXR1b<8QE9mM=+Pra z0CyDVo}CR;>osP$LGwLJPmcs!R$NlD20$SvFQ0sytzsA^&CJFo3QW@4LbE;m_AQb4 z1tPyvfD$OCQFCg^#seAgz_}dZvN=Q|{pit^XZr-rtPv3raOu5Jm80!Z8d!z2F3YL} z_Sk^RXJ?*A85ua+7sx)ysAp^yn$yZP%9J5R92yx(fj2D$C$ck^(@S9zfCi~P;SC`M z28Q6{NnBp%;i#n(kta`{9G#q?BLdDpmu1|4ObDmKvRyS!V+VdTxUyyxBA!9;um#1% zPrrZnsIX3l7sG>`3AHz*6mX&ij|5@r=!5ENBwW+Uw{IE7*yV1)RCII+O-;N&4Jm19 zv&SQME33~fS)7;KN!}T7V7hvFS&wOHYT^t(vJ>8NQ06_a@{__U4_q;A3a%Hi=#ROM zQbk}oBjGh*`68zk!K{bm^YimVRPy7C_B$f1 zxZR%tp1}wNMkwmD0I~NvpWW$_V8}P_@SA`@==x;t`7?ntj5i``=mZ1=0muCmx-cRB z=_NRN!$AD`fZEK)_R94G8nFPov|u|WHwb;_fNRv%)lF?|a8Op&ibYRP52YB+4n8e9 z@Xd~@Cr?0kv28$i9~zDQekYGlKtSVYq+mRk`|qYOi<~~crJ&-hQqA8>R}ED&TEa*@ z{F+2C+}1lYQa3MsGv6>v8Qb~I*Z|8EP3zIa0$EN@&W5XwjyW|P{9h+K&*Aoqi<$RePi$*r zqY4}%)3WjVuNMtZRvbMS||zAE4c%qi*x@rP{`V z-@wGio`NVMD#`|yxx7%PXh$YSRF)hb5itpCkU|dDJ7((VfzNFe2n5g0wO;J?^KHMMm@lwTns$*-)80l@5;oz*VZAwW91dwV}7L+2}@1J@P~ ztCH7VUvWXdL!wZ&>_1haK(XE60GTBC8(1R+Bd4;NsX2rs9F@p!#A&CXUZ6^454CBS zZpkzjw=N+x>XYna!jy%e6eX78dY24yX8)l#~X7h#B;A(KL~~ zkfON$K67l?;!CI6(PkP}MLo@!kGWZi7MvQiPdD%b12N7KlqN>;$MCH@_@qGO)dSdi zq4rDG&lx|oGgH?*N>;m1S(BSf2d7FIHs9ed;Iz_7K$jSqD0YqmQNL&C1T7`c35$F@ z2M31?-ce-XghPiVFSeckj1T=?Ha04>0A*!DSeK}(t20hrs7d*r+GrW`Wa2e<*bTjh zB@cWYA`!X*A)%;<50=|9*T=!hSaeRylY9DmB`R-fd;B6NCx_d4S>(~K6RhqUH#gv_ zM#rkK!3>#!w2mkGhmL15b|A-ch?~$>4C|*f>I@JBV%qzJ&Z1NT3x7yop0~L=Tn-Gc z6i8tgoZh!x1MAqKvpH`^@ru2Mf{%|cNtv3t(-BQehb@xSPJZI>81x<72-<4OpmjIwmCq-p5?07W_Yp8x;= diff --git a/doc/src_intro/rs_driver_intro_CN.md b/doc/src_intro/rs_driver_intro_CN.md index 04ffb6f2..0e511fbc 100644 --- a/doc/src_intro/rs_driver_intro_CN.md +++ b/doc/src_intro/rs_driver_intro_CN.md @@ -1,12 +1,12 @@ -# rs_driver v1.5.5 源代码解析 +# rs_driver v1.5.6 源代码解析 ## 1 基本概念 -### 1.1 机械式激光雷达、MEMS激光雷达 +### 1.1 机械式雷达、MEMS雷达 rs_driver支持RoboSense的两种雷达: -+ 机械式激光雷达。如RS16/RS32/RSBP/RSHELIOS/RS80/RS128。机械式激光雷达有控制激光发射角度的旋转部件,有360°扫描视场。 -+ MEMS激光雷达。如RSM1。MEMS激光雷达是单轴、谐振式的MEMS扫描镜,其水平扫描角度可达120°。 ++ 机械式雷达。如RS16/RS32/RSBP/RSHELIOS/RS80/RS128。机械式雷达有控制激光发射角度的旋转部件,有360°扫描视场。 ++ MEMS雷达。如RSM1。MEMS雷达是单轴、谐振式的MEMS扫描镜,其水平扫描角度可达120°。 ### 1.2 通道 Channel @@ -586,8 +586,8 @@ Trigon用于计算指定范围内的sin/cos值,并用于查询。 ![Trigon](./img/class_trigon.png) -+ 成员变量`MIN`和`MAX`保存角度范围。这里`MIN` = `-9000`, `MAX` = `45000`。 -+ 成员变量`o_sins_`保存所有角度的sin值,`o_coss_`保存所有角度的cos值。`o_sins_[]`和`o_coss_[]`是两个大小为 `MAX - MIN` 的数组。 ++ 成员变量`ANGLE_MIN`和`ANGLE_MAX`保存角度范围。这里`ANGLE_MIN` = `-9000`, `ANGLE_MAX` = `45000`。 ++ 成员变量`o_sins_`保存所有角度的sin值,`o_coss_`保存所有角度的cos值。`o_sins_[]`和`o_coss_[]`是两个大小为 `AMGLE_MAX - ANGLE_MIN` 的数组。 + 引用`os_sins_[]`和`o_coss_[]`计算三角函数值时,需要减去一个偏移。为了免去这个麻烦,重新定义了两个指针`sins_`和`coss_`,让它们分别指向`os_sins_[9000]`和`os_cons_[9000]`。这样就可以用角度值直接引用`sins_`和`coss_`了。 ![Trigon](./img/trigon_sinss.png) From 80178882e533d9b6121111f7a95be3cccec95d9a Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 31 Aug 2022 16:54:49 +0800 Subject: [PATCH 360/379] feat: update CHANGELOG --- CHANGELOG.md | 28 +++++++++++++++++++++------- 1 file changed, 21 insertions(+), 7 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index fb4e0df1..0f5a7c04 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,18 +1,32 @@ -# ChangeLog +# CHANGLOG ## Unreleased ### Changed -- Make error code different for MSOP/DIFOP Packets -- Rename error code CLOUDOVERFOW -- Recover M2 decoder's coordinate -- Update demo_pcap and rs_driver_viewer with cloud queue -- Add option ENABLE_DOUBLE_RCVBUF + +## v1.5.6 2022-09-01 + +### Added +- Add option ENABLE_DOUBLE_RCVBUF to solve the packet-loss problem +- Add option ENABLE_WAIT_IF_QUEUE_EMPTY to reduce CPU usage. +- Add option ENABLE_STAMP_WITH_LOCAL to convert point cloud's timestamp to local time + +### Changed +- Make ERRCODEs different for MSOP/DIFOP Packet +- Rename error code CLOUDOVERFLOW +- For RSM2, recover its coordinate to ROS-compatible +- For RSM2, adapt to increased MSOP packet len +- Update `demo_pcap` and `rs_driver_viewer` with cloud queue +- Accept angle.csv with vert angle only +- Update help documents ### Fixed -- Fix timestamp of Ruby series' cloud to follow new format instead of old one. +- For Ruby and Ruby Plus, fix the problem of parsing point cloud' timestamp. - Fix ERRCODE_MSOPTIMEOUT problem of input_sock_epoll +### Removed +- Remove option ENABLE_RCVMMSG + ## v1.5.5 2022-08-01 ### Added From 12f6b757aa8d56ac18884db1142a1898c57e872b Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 1 Sep 2022 09:36:27 +0800 Subject: [PATCH 361/379] fix: fix demo_pcap in case of wrong pcap path --- demo/demo_online.cpp | 4 ++-- demo/demo_pcap.cpp | 5 +++-- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index fecfe245..3b1436ec 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -114,8 +114,6 @@ int main(int argc, char* argv[]) RS_TITLE << " RS_Driver Core Version: v" << getDriverVersion() << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; - std::thread cloud_handle_thread = std::thread(processCloud); - RSDriverParam param; ///< Create a parameter object param.input_type = InputType::ONLINE_LIDAR; param.input_param.msop_port = 6699; ///< Set the lidar msop port number, the default is 6699 @@ -132,6 +130,8 @@ int main(int argc, char* argv[]) return -1; } + std::thread cloud_handle_thread = std::thread(processCloud); + driver.start(); ///< The driver thread will start RS_DEBUG << "RoboSense Lidar-Driver Linux online demo start......" << RS_REND; diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index daee7958..fbf738bd 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -114,8 +114,6 @@ int main(int argc, char* argv[]) RS_TITLE << " RS_Driver Core Version: v" << getDriverVersion() << RS_REND; RS_TITLE << "------------------------------------------------------" << RS_REND; - std::thread cloud_handle_thread = std::thread(processCloud); - RSDriverParam param; ///< Create a parameter object param.input_type = InputType::PCAP_FILE; param.input_param.pcap_path = "/home/robosense/lidar.pcap"; ///< Set the pcap file directory @@ -133,7 +131,10 @@ int main(int argc, char* argv[]) return -1; } + std::thread cloud_handle_thread = std::thread(processCloud); + driver.start(); ///< The driver thread will start + RS_DEBUG << "RoboSense Lidar-Driver Linux pcap demo start......" << RS_REND; #ifdef ORDERLY_EXIT From bc0ef3e66708ae3fd58add8f067f35703661f342 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 1 Sep 2022 09:37:01 +0800 Subject: [PATCH 362/379] feat: change version --- CMakeLists.txt | 2 +- src/rs_driver/macro/version.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 65175605..a2f8a494 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.5.5) +project(rs_driver VERSION 1.5.6) #======================== # Project setup diff --git a/src/rs_driver/macro/version.hpp b/src/rs_driver/macro/version.hpp index f80de532..2f00a4bc 100644 --- a/src/rs_driver/macro/version.hpp +++ b/src/rs_driver/macro/version.hpp @@ -1,3 +1,3 @@ #define RSLIDAR_VERSION_MAJOR 1 #define RSLIDAR_VERSION_MINOR 5 -#define RSLIDAR_VERSION_PATCH 5 +#define RSLIDAR_VERSION_PATCH 6 From eefd6fce4322e6d271ba374a5d915c3eb5d11f51 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 15 Sep 2022 08:54:32 +0800 Subject: [PATCH 363/379] fix: fix msop packet --- src/rs_driver/driver/decoder/decoder_RSM2.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSM2.hpp b/src/rs_driver/driver/decoder/decoder_RSM2.hpp index 17a5b97d..4d8824c6 100644 --- a/src/rs_driver/driver/decoder/decoder_RSM2.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSM2.hpp @@ -76,7 +76,7 @@ typedef struct RSM2Block blocks[25]; uint8_t reserved[4]; uint8_t crc32[4]; - uint8_t rolling_counter[4]; + uint8_t rolling_counter[2]; } RSM2MsopPkt; #pragma pack(pop) From 6338040fd69f08e7afc65f4a42c119e2df1f62a4 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 15 Sep 2022 09:56:04 +0800 Subject: [PATCH 364/379] feat: print points in demo app --- demo/demo_online.cpp | 9 +++++++++ demo/demo_pcap.cpp | 9 +++++++++ 2 files changed, 18 insertions(+) diff --git a/demo/demo_online.cpp b/demo/demo_online.cpp index 3b1436ec..093962f2 100644 --- a/demo/demo_online.cpp +++ b/demo/demo_online.cpp @@ -104,6 +104,15 @@ void processCloud(void) // Well, it is time to process the point cloud msg, even it is time-consuming. RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; +#if 0 + for (auto it = msg->points.begin(); it != msg->points.end(); it++) + { + std::cout << std::fixed << std::setprecision(3) + << "(" << it->x << ", " << it->y << ", " << it->z << ", " << (int)it->intensity << ")" + << std::endl; + } +#endif + free_cloud_queue.push(msg); } } diff --git a/demo/demo_pcap.cpp b/demo/demo_pcap.cpp index fbf738bd..fe2bca6c 100644 --- a/demo/demo_pcap.cpp +++ b/demo/demo_pcap.cpp @@ -104,6 +104,15 @@ void processCloud(void) // Well, it is time to process the point cloud msg, even it is time-consuming. RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; +#if 0 + for (auto it = msg->points.begin(); it != msg->points.end(); it++) + { + std::cout << std::fixed << std::setprecision(3) + << "(" << it->x << ", " << it->y << ", " << it->z << ", " << (int)it->intensity << ")" + << std::endl; + } +#endif + free_cloud_queue.push(msg); } } From 62eeed9c305fc90e776a9af50727c85f69f194af Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 15 Sep 2022 15:46:27 +0800 Subject: [PATCH 365/379] fix: fix distance range of helios series --- src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp | 4 ++-- src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index 770b0102..bbc8ad39 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -129,8 +129,8 @@ inline RSDecoderMechConstParam& DecoderRSHELIOS::getConstParam() , 32 // laser number , 12 // blocks per packet , 32 // channels per block - , 0.4f // distance min - , 200.0f // distance max + , 0.1f // distance min + , 150.0f // distance max , 0.0025f // distance resolution , 0.0625f // temperature resolution diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp index 97602fbe..e61c9410 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp @@ -76,8 +76,8 @@ inline RSDecoderMechConstParam& DecoderRSHELIOS_16P::getConstParam , 16 // laser number , 12 // blocks per packet , 32 // channels per block - , 0.4f // distance min - , 200.0f // distance max + , 0.1f // distance min + , 150.0f // distance max , 0.0025f // distance resolution , 0.0625f // temperature resolution From 103ead715570733a52e3c96acb95ab8de632d686 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 16 Sep 2022 08:52:48 +0800 Subject: [PATCH 366/379] feat: update distance ranges --- src/rs_driver/driver/decoder/decoder_RS128.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS16.hpp | 4 ++-- src/rs_driver/driver/decoder/decoder_RS32.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RS48.hpp | 4 ++-- src/rs_driver/driver/decoder/decoder_RS80.hpp | 4 ++-- src/rs_driver/driver/decoder/decoder_RSBP.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSP128.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSP48.hpp | 2 +- src/rs_driver/driver/decoder/decoder_RSP80.hpp | 2 +- 11 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index 41aaf06e..f49682cc 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -115,7 +115,7 @@ inline RSDecoderMechConstParam& DecoderRS128::getConstParam() , 128 // laser number , 3 // blocks per packet , 128 // channels per block - , 1.0f // distance min + , 0.4f // distance min , 250.0f // distance max , 0.005f // distance resolution , 0.0625f // temperature resolution diff --git a/src/rs_driver/driver/decoder/decoder_RS16.hpp b/src/rs_driver/driver/decoder/decoder_RS16.hpp index 5b33b415..be0b2132 100644 --- a/src/rs_driver/driver/decoder/decoder_RS16.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS16.hpp @@ -142,8 +142,8 @@ inline RSDecoderMechConstParam& DecoderRS16::getConstParam() , 16 // laser number , 12 // blocks per packet , 32 // channels per block. how many channels in the msop block. - , 0.2f // distance min - , 150.0f // distance max + , 0.4f // distance min + , 230.0f // distance max , 0.005f // distance resolution , 0.0625f // temperature resolution diff --git a/src/rs_driver/driver/decoder/decoder_RS32.hpp b/src/rs_driver/driver/decoder/decoder_RS32.hpp index 9ff0435f..ffc76c5f 100644 --- a/src/rs_driver/driver/decoder/decoder_RS32.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS32.hpp @@ -145,7 +145,7 @@ inline RSDecoderMechConstParam& DecoderRS32::getConstParam() , 12 // blocks per packet , 32 // channels per block , 0.4f // distance min - , 200.0f // distance max + , 230.0f // distance max , 0.005f // distance resolution , 0.0625f // temperature resolution diff --git a/src/rs_driver/driver/decoder/decoder_RS48.hpp b/src/rs_driver/driver/decoder/decoder_RS48.hpp index 48e39fca..ab6e06c1 100644 --- a/src/rs_driver/driver/decoder/decoder_RS48.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS48.hpp @@ -74,8 +74,8 @@ inline RSDecoderMechConstParam& DecoderRS48::getConstParam() , 48 // laser number , 8 // blocks per packet , 48 // channels per block - , 1.0f // distance min - , 230.0f // distance max + , 0.4f // distance min + , 250.0f // distance max , 0.005f // distance resolution , 0.0625f // temperature resolution diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 2a1f8ed2..52aecb75 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -116,8 +116,8 @@ inline RSDecoderMechConstParam& DecoderRS80::getConstParam() , 80 // laser number , 4 // blocks per packet , 80 // channels per block - , 1.0f // distance min - , 230.0f // distance max + , 0.4f // distance min + , 250.0f // distance max , 0.005f // distance resolution , 0.0625f // temperature resolution diff --git a/src/rs_driver/driver/decoder/decoder_RSBP.hpp b/src/rs_driver/driver/decoder/decoder_RSBP.hpp index 0adbe344..a3caa249 100644 --- a/src/rs_driver/driver/decoder/decoder_RSBP.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSBP.hpp @@ -119,7 +119,7 @@ inline RSDecoderMechConstParam& DecoderRSBP::getConstParam() , 12 // blocks per packet , 32 // channels per block , 0.1f // distance min - , 100.0f // distance max + , 150.0f // distance max , 0.005f // distance resolution , 0.0625f // temperature resolution diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp index bbc8ad39..5d41b259 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS.hpp @@ -130,7 +130,7 @@ inline RSDecoderMechConstParam& DecoderRSHELIOS::getConstParam() , 12 // blocks per packet , 32 // channels per block , 0.1f // distance min - , 150.0f // distance max + , 180.0f // distance max , 0.0025f // distance resolution , 0.0625f // temperature resolution diff --git a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp index e61c9410..1f64c635 100644 --- a/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSHELIOS_16P.hpp @@ -77,7 +77,7 @@ inline RSDecoderMechConstParam& DecoderRSHELIOS_16P::getConstParam , 12 // blocks per packet , 32 // channels per block , 0.1f // distance min - , 150.0f // distance max + , 180.0f // distance max , 0.0025f // distance resolution , 0.0625f // temperature resolution diff --git a/src/rs_driver/driver/decoder/decoder_RSP128.hpp b/src/rs_driver/driver/decoder/decoder_RSP128.hpp index edc0b3c1..078464a7 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP128.hpp @@ -115,7 +115,7 @@ inline RSDecoderMechConstParam& DecoderRSP128::getConstParam() , 128 // laser number , 3 // blocks per packet , 128 // channels per block - , 1.0f // distance min + , 0.4f // distance min , 250.0f // distance max , 0.005f // distance resolution , 0.0625f // temperature resolution diff --git a/src/rs_driver/driver/decoder/decoder_RSP48.hpp b/src/rs_driver/driver/decoder/decoder_RSP48.hpp index aed4e8b2..75dd1c17 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP48.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP48.hpp @@ -116,7 +116,7 @@ inline RSDecoderMechConstParam& DecoderRSP48::getConstParam() , 48 // laser number , 8 // blocks per packet , 48 // channels per block - , 1.0f // distance min + , 0.4f // distance min , 250.0f // distance max , 0.005f // distance resolution , 0.0625f // temperature resolution diff --git a/src/rs_driver/driver/decoder/decoder_RSP80.hpp b/src/rs_driver/driver/decoder/decoder_RSP80.hpp index b138a0c9..765bc871 100644 --- a/src/rs_driver/driver/decoder/decoder_RSP80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RSP80.hpp @@ -119,7 +119,7 @@ inline RSDecoderMechConstParam& DecoderRSP80::getConstParam() , 80 // laser number , 4 // blocks per packet , 80 // channels per block - , 1.0f // distance min + , 0.4f // distance min , 250.0f // distance max , 0.005f // distance resolution , 0.0625f // temperature resolution From 7aa0a31e9c9da00e04379d77105f834433cf9747 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 16 Sep 2022 10:19:49 +0800 Subject: [PATCH 367/379] feat: disable blk_id error to be compatible with v1.3.x --- src/rs_driver/driver/decoder/decoder_RS128.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index f49682cc..cda54464 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -240,7 +240,7 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); + //this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); break; } From 4d8aa8e4d4c294eab57e87d397b270d2c738f165 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 23 Sep 2022 11:41:45 +0800 Subject: [PATCH 368/379] feat: add tool to save point cloud as PCD format --- CMakeLists.txt | 13 +- tool/CMakeLists.txt | 16 ++ tool/rs_driver_pcdsaver.cpp | 282 ++++++++++++++++++++++++++++++++++++ 3 files changed, 308 insertions(+), 3 deletions(-) create mode 100644 tool/rs_driver_pcdsaver.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index a2f8a494..b6e6d78c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -32,7 +32,9 @@ option(ENABLE_PCL_POINTCLOUD "Enable PCL Point Cloud" OFF) # Compile Demos, Tools, Tests #============================= option(COMPILE_DEMOS "Build rs_driver demos" OFF) -option(COMPILE_TOOLS "Build point cloud visualization tool" OFF) +option(COMPILE_TOOLS "Build rs_driver tools" OFF) +option(COMPILE_TOOL_VIEWER "Build point cloud visualization tool" OFF) +option(COMPILE_TOOL_PCDSAVER "Build point cloud pcd saver tool" OFF) option(COMPILE_TESTS "Build rs_driver unit tests" OFF) #======================== @@ -167,9 +169,14 @@ if(${COMPILE_DEMOS}) add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/demo) endif(${COMPILE_DEMOS}) -if(${COMPILE_TOOLS}) +if (${COMPILE_TOOLS}) + set(COMPILE_TOOL_VIEWER ON) + set(COMPILE_TOOL_PCDSAVER ON) +endif (${COMPILE_TOOLS}) + +if(${COMPILE_TOOL_VIEWER} OR ${COMPILE_TOOL_PCDSAVER}) add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/tool) -endif(${COMPILE_TOOLS}) +endif(${COMPILE_TOOL_VIEWER} OR ${COMPILE_TOOL_PCDSAVER}) if(${COMPILE_TESTS}) add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/test) diff --git a/tool/CMakeLists.txt b/tool/CMakeLists.txt index 001895b1..8e412da9 100644 --- a/tool/CMakeLists.txt +++ b/tool/CMakeLists.txt @@ -13,6 +13,8 @@ if (CMAKE_BUILD_TYPE STREQUAL "") set(CMAKE_BUILD_TYPE Release) endif() +if(${COMPILE_TOOL_VIEWER}) + if(WIN32) cmake_policy(SET CMP0074 NEW) set(OPENNI_ROOT "C:\\Program Files\\OpenNI2") @@ -44,3 +46,17 @@ endif() install(TARGETS rs_driver_viewer RUNTIME DESTINATION /usr/bin) + +endif (${COMPILE_TOOL_VIEWER}) + + +if(${COMPILE_TOOL_PCDSAVER}) + +add_executable(rs_driver_pcdsaver + rs_driver_pcdsaver.cpp) + +target_link_libraries(rs_driver_pcdsaver + ${EXTERNAL_LIBS}) + +endif(${COMPILE_TOOL_PCDSAVER}) + diff --git a/tool/rs_driver_pcdsaver.cpp b/tool/rs_driver_pcdsaver.cpp new file mode 100644 index 00000000..0fe7b39c --- /dev/null +++ b/tool/rs_driver_pcdsaver.cpp @@ -0,0 +1,282 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#include +#include + +using namespace robosense::lidar; + +typedef PointCloudT PointCloudMsg; + +SyncQueue> free_cloud_queue; +SyncQueue> stuffed_cloud_queue; + +bool checkKeywordExist(int argc, const char* const* argv, const char* str) +{ + for (int i = 1; i < argc; i++) + { + if (strcmp(argv[i], str) == 0) + { + return true; + } + } + return false; +} + +bool parseArgument(int argc, const char* const* argv, const char* str, std::string& val) +{ + int index = -1; + + for (int i = 1; i < argc; i++) + { + if (strcmp(argv[i], str) == 0) + { + index = i + 1; + } + } + + if (index > 0 && index < argc) + { + val = argv[index]; + return true; + } + + return false; +} + +void parseParam(int argc, char* argv[], RSDriverParam& param) +{ + std::string result_str; + + // + // input param + // + parseArgument(argc, argv, "-pcap", param.input_param.pcap_path); + if (param.input_param.pcap_path.empty()) + { + param.input_type = InputType::ONLINE_LIDAR; + } + else + { + param.input_type = InputType::PCAP_FILE; + } + + if (parseArgument(argc, argv, "-msop", result_str)) + { + param.input_param.msop_port = std::stoi(result_str); + } + + if (parseArgument(argc, argv, "-difop", result_str)) + { + param.input_param.difop_port = std::stoi(result_str); + } + + parseArgument(argc, argv, "-group", param.input_param.group_address); + parseArgument(argc, argv, "-host", param.input_param.host_address); + + // + // decoder param + // + if (parseArgument(argc, argv, "-type", result_str)) + { + param.lidar_type = strToLidarType(result_str); + } + + param.decoder_param.wait_for_difop = false; + + if (parseArgument(argc, argv, "-x", result_str)) + { + param.decoder_param.transform_param.x = std::stof(result_str); + } + + if (parseArgument(argc, argv, "-y", result_str)) + { + param.decoder_param.transform_param.y = std::stof(result_str); + } + + if (parseArgument(argc, argv, "-z", result_str)) + { + param.decoder_param.transform_param.z = std::stof(result_str); + } + + if (parseArgument(argc, argv, "-roll", result_str)) + { + param.decoder_param.transform_param.roll = std::stof(result_str); + } + + if (parseArgument(argc, argv, "-pitch", result_str)) + { + param.decoder_param.transform_param.pitch = std::stof(result_str); + } + + if (parseArgument(argc, argv, "-yaw", result_str)) + { + param.decoder_param.transform_param.yaw = std::stof(result_str); + } +} + +void printHelpMenu() +{ + RS_MSG << "Arguments: " << RS_REND; + RS_MSG << " -type = LiDAR type(RS16, RS32, RSBP, RSHELIOS, RS128, RS80, RSM1)" << RS_REND; + RS_MSG << " -pcap = The path of the pcap file, off-line mode if it is true, else online mode." << RS_REND; + RS_MSG << " -msop = LiDAR msop port number,the default value is 6699" << RS_REND; + RS_MSG << " -difop = LiDAR difop port number,the default value is 7788" << RS_REND; + RS_MSG << " -group = LiDAR destination group address if multi-cast mode." << RS_REND; + RS_MSG << " -host = Host address." << RS_REND; + RS_MSG << " -x = Transformation parameter, unit: m " << RS_REND; + RS_MSG << " -y = Transformation parameter, unit: m " << RS_REND; + RS_MSG << " -z = Transformation parameter, unit: m " << RS_REND; + RS_MSG << " -roll = Transformation parameter, unit: radian " << RS_REND; + RS_MSG << " -pitch = Transformation parameter, unit: radian " << RS_REND; + RS_MSG << " -yaw = Transformation parameter, unit: radian " << RS_REND; +} + +void exceptionCallback(const Error& code) +{ + RS_WARNING << code.toString() << RS_REND; +} + +std::shared_ptr pointCloudGetCallback(void) +{ + std::shared_ptr msg = free_cloud_queue.pop(); + if (msg.get() != NULL) + { + return msg; + } + + return std::make_shared(); +} + +void pointCloudPutCallback(std::shared_ptr msg) +{ + stuffed_cloud_queue.push(msg); +} + +void savePcd(const std::string &pcd_path, const PointCloudMsg &cloud) +{ + RS_MSG << "Save point cloud as " << pcd_path << RS_REND; + + std::ofstream os(pcd_path, std::ios::out | std::ios::trunc); + os << "# .PCD v0.7 - Point Cloud Data file format" << std::endl; + os << "VERSION 0.7" << std::endl; + os << "FIELDS x y z intensity" << std::endl; + os << "SIZE 4 4 4 4" << std::endl; + os << "TYPE F F F F" << std::endl; + os << "COUNT 1 1 1 1" << std::endl; + os << "WIDTH " << cloud.points.size() << std::endl; + os << "HEIGHT 1" << std::endl; + os << "VIEWPOINT 0 0 0 1 0 0 0" << std::endl; + os << "POINTS " << cloud.points.size() << std::endl; + os << "DATA ascii" << std::endl; + + for (size_t i = 0; i < cloud.points.size(); i++) + { + const PointXYZI& p = cloud.points[i]; + os << p.x << " "; + os << p.y << " "; + os << p.z << " "; + os << (float)p.intensity << std::endl; + } +} + +bool to_exit_process = false; +void processCloud(void) +{ + while (!to_exit_process) + { + std::shared_ptr msg = stuffed_cloud_queue.popWait(); + if (msg.get() == NULL) + { + continue; + } + + char pcd_path[128]; + sprintf (pcd_path, "%d.pcd", msg->seq); + savePcd(pcd_path, *msg); + + free_cloud_queue.push(msg); + } +} + +int main(int argc, char* argv[]) +{ + RS_TITLE << "------------------------------------------------------" << RS_REND; + RS_TITLE << " RS_Driver PCD Saver Version: v" << getDriverVersion() << RS_REND; + RS_TITLE << "------------------------------------------------------" << RS_REND; + + if (argc < 2) + { + printHelpMenu(); + return 0; + } + + if (checkKeywordExist(argc, argv, "-h") || checkKeywordExist(argc, argv, "--help")) + { + printHelpMenu(); + return 0; + } + + std::thread cloud_handle_thread = std::thread(processCloud); + + RSDriverParam param; + param.decoder_param.dense_points = true; + + parseParam(argc, argv, param); + param.print(); + + LidarDriver driver; + driver.regExceptionCallback(exceptionCallback); + driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); + if (!driver.init(param)) + { + RS_ERROR << "Driver Initialize Error..." << RS_REND; + return -1; + } + + RS_INFO << "RoboSense Lidar-Driver Viewer start......" << RS_REND; + + driver.start(); + + while (1) + { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + + driver.stop(); + + to_exit_process = true; + cloud_handle_thread.join(); + + return 0; +} + From d2335257743b0150d03dfc1dfa6c84923aa39523 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Fri, 23 Sep 2022 12:39:25 +0800 Subject: [PATCH 369/379] feat: add tool to save point cloud as PCD format --- tool/rs_driver_pcdsaver.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/tool/rs_driver_pcdsaver.cpp b/tool/rs_driver_pcdsaver.cpp index 0fe7b39c..ec59c4fb 100644 --- a/tool/rs_driver_pcdsaver.cpp +++ b/tool/rs_driver_pcdsaver.cpp @@ -249,6 +249,7 @@ int main(int argc, char* argv[]) std::thread cloud_handle_thread = std::thread(processCloud); RSDriverParam param; + param.input_param.pcap_repeat = false; param.decoder_param.dense_points = true; parseParam(argc, argv, param); @@ -263,7 +264,7 @@ int main(int argc, char* argv[]) return -1; } - RS_INFO << "RoboSense Lidar-Driver Viewer start......" << RS_REND; + RS_INFO << "RoboSense Lidar-Driver PCD Saver start......" << RS_REND; driver.start(); From 229ef6955840112458653019c111a6f14598d0ab Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Wed, 28 Sep 2022 15:35:55 +0800 Subject: [PATCH 370/379] format: remove unused code --- src/rs_driver/driver/decoder/basic_attr.hpp | 78 ------------------- .../driver/input/unix/input_sock_select.hpp | 35 --------- src/rs_driver/msg/pcl_point_cloud_msg.hpp | 1 - src/rs_driver/msg/point_cloud_msg.hpp | 1 - 4 files changed, 115 deletions(-) diff --git a/src/rs_driver/driver/decoder/basic_attr.hpp b/src/rs_driver/driver/decoder/basic_attr.hpp index 159d6920..74b6e8c2 100644 --- a/src/rs_driver/driver/decoder/basic_attr.hpp +++ b/src/rs_driver/driver/decoder/basic_attr.hpp @@ -95,55 +95,6 @@ inline long getTimezone(void) } #endif -#if 0 -inline uint64_t parseTimeUTCWithNs(const RSTimestampUTC* tsUtc) -{ - // sec - uint64_t sec = 0; - for (int i = 0; i < 6; i++) - { - sec <<= 8; - sec += tsUtc->sec[i]; - } - - // ns - uint64_t ns = 0; - for (int i = 0; i < 4; i++) - { - ns <<= 8; - ns += tsUtc->ss[i]; - } - -#ifdef ENABLE_STAMP_WITH_LOCAL - sec -= getTimezone(); -#endif - - return (sec * 1000000 + ns/1000); -} - -inline void createTimeUTCWithNs(uint64_t us, RSTimestampUTC* tsUtc) -{ - uint64_t sec = us / 1000000; - uint64_t nsec = (us % 1000000) * 1000; - -#ifdef ENABLE_STAMP_WITH_LOCAL - sec += getTimezone(); -#endif - - for (int i = 5; i >= 0; i--) - { - tsUtc->sec[i] = sec & 0xFF; - sec >>= 8; - } - - for (int i = 3; i >= 0; i--) - { - tsUtc->ss[i] = nsec & 0xFF; - nsec >>= 8; - } -} -#endif - inline uint64_t parseTimeUTCWithUs(const RSTimestampUTC* tsUtc) { // sec @@ -191,35 +142,6 @@ inline void createTimeUTCWithUs(uint64_t us, RSTimestampUTC* tsUtc) } } -#if 0 -inline uint64_t parseTimeUTCWithMs(const RSTimestampUTC* tsUtc) -{ - // sec - uint64_t sec = 0; - for (int i = 0; i < 6; i++) - { - sec <<= 8; - sec += tsUtc->sec[i]; - } - - // ms - uint64_t ms = tsUtc->ss[0]; - ms <<= 8; - ms += tsUtc->ss[1]; - - // us - uint64_t us = tsUtc->ss[2]; - us <<= 8; - us += tsUtc->ss[3]; - -#ifdef ENABLE_STAMP_WITH_LOCAL - sec -= getTimezone(); -#endif - - return (sec * 1000000 + ms * 1000 + us); -} -#endif - inline uint64_t parseTimeYMD(const RSTimestampYMD* tsYmd) { std::tm stm; diff --git a/src/rs_driver/driver/input/unix/input_sock_select.hpp b/src/rs_driver/driver/input/unix/input_sock_select.hpp index 151ceb9f..c105995b 100644 --- a/src/rs_driver/driver/input/unix/input_sock_select.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_select.hpp @@ -252,39 +252,6 @@ inline void InputSock::recvPacket() if (FD_ISSET(fds_[0], &rfds)) { -#if 0 - -#define VLEN 2 - struct mmsghdr msgs[VLEN]; - struct iovec iovecs[VLEN]; - std::shared_ptr pkts[VLEN]; - int i, ret; - - memset(msgs, 0, sizeof(msgs)); - for (i = 0; i < VLEN; i++) - { - pkts[i] = cb_get_pkt_(pkt_buf_len_); - iovecs[i].iov_base = pkts[i]->buf(); - iovecs[i].iov_len = pkts[i]->bufSize(); - msgs[i].msg_hdr.msg_iov = &iovecs[i]; - msgs[i].msg_hdr.msg_iovlen = 1; - } - - struct timespec timeout; - timeout.tv_sec = 0; - timeout.tv_nsec = 0; - ret = recvmmsg(fds_[0], msgs, VLEN, 0, &timeout); - for (i = 0; i < ret; i++) - { - pkts[i]->setData(sock_offset_, msgs[i].msg_len - sock_offset_ - sock_tail_); - pushPacket(pkts[i]); - } - for (i = ret; i < VLEN; i++) - { - pushPacket(pkts[i], false); - } -#else - std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); ssize_t ret = recvfrom(fds_[0], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); if (ret < 0) @@ -297,8 +264,6 @@ inline void InputSock::recvPacket() pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); pushPacket(pkt); } - -#endif } else if (FD_ISSET(fds_[1], &rfds)) { diff --git a/src/rs_driver/msg/pcl_point_cloud_msg.hpp b/src/rs_driver/msg/pcl_point_cloud_msg.hpp index bb6e5f5c..37a53c2c 100644 --- a/src/rs_driver/msg/pcl_point_cloud_msg.hpp +++ b/src/rs_driver/msg/pcl_point_cloud_msg.hpp @@ -57,7 +57,6 @@ class PointCloudT : public pcl::PointCloud typedef typename pcl::PointCloud::VectorType VectorT; double timestamp = 0.0; - //std::string frame_id = ""; ///< Point cloud frame id uint32_t seq = 0; ///< Sequence number of message }; diff --git a/src/rs_driver/msg/point_cloud_msg.hpp b/src/rs_driver/msg/point_cloud_msg.hpp index 4126b81b..0904fda0 100644 --- a/src/rs_driver/msg/point_cloud_msg.hpp +++ b/src/rs_driver/msg/point_cloud_msg.hpp @@ -64,7 +64,6 @@ class PointCloudT uint32_t width = 0; ///< Width of point cloud bool is_dense = false; ///< If is_dense is true, the point cloud does not contain NAN points, double timestamp = 0.0; - std::string frame_id = "rslidar"; ///< Point cloud frame id uint32_t seq = 0; ///< Sequence number of message VectorT points; From 4fdc2c7bc4d0321183c2b433e7bab80f62ac1f80 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 29 Sep 2022 12:11:33 +0800 Subject: [PATCH 371/379] format: format --- .../driver/input/win/input_sock_select.hpp | 16 +++++++--------- 1 file changed, 7 insertions(+), 9 deletions(-) diff --git a/src/rs_driver/driver/input/win/input_sock_select.hpp b/src/rs_driver/driver/input/win/input_sock_select.hpp index 7f2ff562..939ac9de 100644 --- a/src/rs_driver/driver/input/win/input_sock_select.hpp +++ b/src/rs_driver/driver/input/win/input_sock_select.hpp @@ -46,8 +46,8 @@ namespace lidar class InputSock : public Input { public: - InputSock(const RSInputParam& input_param) - : Input(input_param), pkt_buf_len_(ETH_LEN), + InputSock(const RSInputParam& input_param) + : Input(input_param), pkt_buf_len_(ETH_LEN), sock_offset_(0), sock_tail_(0) { sock_offset_ += input_param.user_layer_bytes; @@ -71,13 +71,13 @@ class InputSock : public Input inline bool InputSock::init() { - int msop_fd = -1, difop_fd = -1; - if (init_flag_) { return true; } + int msop_fd = -1, difop_fd = -1; + WORD version = MAKEWORD(2, 2); WSADATA wsaData; int ret = WSAStartup(version, &wsaData); @@ -104,8 +104,6 @@ inline bool InputSock::init() failDifop: closesocket(msop_fd); failMsop: - if (difop_fd >= 0) - closesocket(difop_fd); failWsa: return false; } @@ -229,15 +227,15 @@ inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, con inline void InputSock::recvPacket() { - fd_set rfds; + int max_fd = ((fds_[0] > fds_[1]) ? fds_[0] : fds_[1]); while (!to_exit_recv_) { + fd_set rfds; FD_ZERO(&rfds); FD_SET(fds_[0], &rfds); if (fds_[1] >= 0) FD_SET(fds_[1], &rfds); - int max_fd = ((fds_[0] > fds_[1]) ? fds_[0] : fds_[1]); struct timeval tv; tv.tv_sec = 1; @@ -248,7 +246,7 @@ inline void InputSock::recvPacket() cb_excep_(Error(ERRCODE_MSOPTIMEOUT)); continue; } - else if (retval == -1) + else if (retval < 0) { if (errno == EINTR) continue; From 98c6d1fc5ab705e60e8e74bcd35cddd25006bc68 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 29 Sep 2022 14:17:04 +0800 Subject: [PATCH 372/379] format: format input_sock --- .../driver/input/unix/input_sock_select.hpp | 40 +++++++------------ .../driver/input/win/input_sock_select.hpp | 40 +++++++------------ 2 files changed, 28 insertions(+), 52 deletions(-) diff --git a/src/rs_driver/driver/input/unix/input_sock_select.hpp b/src/rs_driver/driver/input/unix/input_sock_select.hpp index c105995b..3857425f 100644 --- a/src/rs_driver/driver/input/unix/input_sock_select.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_select.hpp @@ -250,34 +250,22 @@ inline void InputSock::recvPacket() break; } - if (FD_ISSET(fds_[0], &rfds)) + for (int i = 0; i < 2; i++) { - std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); - ssize_t ret = recvfrom(fds_[0], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); - if (ret < 0) + if ((fds_[i] >= 0) && FD_ISSET(fds_[i], &rfds)) { - perror("recvfrom: "); - break; - } - else if (ret > 0) - { - pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); - pushPacket(pkt); - } - } - else if (FD_ISSET(fds_[1], &rfds)) - { - std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); - ssize_t ret = recvfrom(fds_[1], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); - if (ret < 0) - { - perror("recvfrom: "); - break; - } - else if (ret > 0) - { - pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); - pushPacket(pkt); + std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); + ssize_t ret = recvfrom(fds_[i], pkt->buf(), pkt->bufSize(), 0, NULL, NULL); + if (ret < 0) + { + perror("recvfrom: "); + break; + } + else if (ret > 0) + { + pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); + pushPacket(pkt); + } } } } diff --git a/src/rs_driver/driver/input/win/input_sock_select.hpp b/src/rs_driver/driver/input/win/input_sock_select.hpp index 939ac9de..5bb38d15 100644 --- a/src/rs_driver/driver/input/win/input_sock_select.hpp +++ b/src/rs_driver/driver/input/win/input_sock_select.hpp @@ -255,34 +255,22 @@ inline void InputSock::recvPacket() break; } - if (FD_ISSET(fds_[0], &rfds)) + for (int i = 0; i < 2; i++) { - std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); - int ret = recvfrom(fds_[0], (char*)pkt->buf(), (int)pkt->bufSize(), 0, NULL, NULL); - if (ret < 0) + if ((fds_[i] >= 0) && FD_ISSET(fds_[i], &rfds)) { - perror("recvfrom: "); - break; - } - else if (ret > 0) - { - pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); - pushPacket(pkt); - } - } - else if (FD_ISSET(fds_[1], &rfds)) - { - std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); - int ret = recvfrom(fds_[1], (char*)pkt->buf(), (int)pkt->bufSize(), 0, NULL, NULL); - if (ret < 0) - { - perror("recvfrom: "); - break; - } - else if (ret > 0) - { - pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); - pushPacket(pkt); + std::shared_ptr pkt = cb_get_pkt_(pkt_buf_len_); + int ret = recvfrom(fds_[i], (char*)pkt->buf(), (int)pkt->bufSize(), 0, NULL, NULL); + if (ret < 0) + { + perror("recvfrom: "); + break; + } + else if (ret > 0) + { + pkt->setData(sock_offset_, ret - sock_offset_ - sock_tail_); + pushPacket(pkt); + } } } } From 9c9ee00260db435cb00bf13f079f5648011ff463 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 29 Sep 2022 14:27:33 +0800 Subject: [PATCH 373/379] fix: report ERRCODE_MSOP_TIMEOUT if only difop is received --- .../driver/input/unix/input_sock_select.hpp | 15 +++++++++++++++ .../driver/input/win/input_sock_select.hpp | 15 +++++++++++++++ 2 files changed, 30 insertions(+) diff --git a/src/rs_driver/driver/input/unix/input_sock_select.hpp b/src/rs_driver/driver/input/unix/input_sock_select.hpp index 3857425f..248eace9 100644 --- a/src/rs_driver/driver/input/unix/input_sock_select.hpp +++ b/src/rs_driver/driver/input/unix/input_sock_select.hpp @@ -223,6 +223,7 @@ inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, con inline void InputSock::recvPacket() { int max_fd = ((fds_[0] > fds_[1]) ? fds_[0] : fds_[1]); + bool msop_recv = true; while (!to_exit_recv_) { @@ -268,6 +269,20 @@ inline void InputSock::recvPacket() } } } + + if (FD_ISSET(fds_[0], &rfds)) // receive msop + { + msop_recv = true; + } + else // receive difop + { + if (!msop_recv) + { + cb_excep_(Error(ERRCODE_MSOPTIMEOUT)); + } + + msop_recv = false; + } } } diff --git a/src/rs_driver/driver/input/win/input_sock_select.hpp b/src/rs_driver/driver/input/win/input_sock_select.hpp index 5bb38d15..3de8e185 100644 --- a/src/rs_driver/driver/input/win/input_sock_select.hpp +++ b/src/rs_driver/driver/input/win/input_sock_select.hpp @@ -228,6 +228,7 @@ inline int InputSock::createSocket(uint16_t port, const std::string& hostIp, con inline void InputSock::recvPacket() { int max_fd = ((fds_[0] > fds_[1]) ? fds_[0] : fds_[1]); + bool msop_recv = true; while (!to_exit_recv_) { @@ -273,6 +274,20 @@ inline void InputSock::recvPacket() } } } + + if (FD_ISSET(fds_[0], &rfds)) // receive msop + { + msop_recv = true; + } + else // receive difop + { + if (!msop_recv) + { + cb_excep_(Error(ERRCODE_MSOPTIMEOUT)); + } + + msop_recv = false; + } } } From 9f128b1b8e548a84b0459ea378e2d17e0862d88d Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Thu, 29 Sep 2022 15:42:41 +0800 Subject: [PATCH 374/379] feat: support RSBPV4 --- .../driver/decoder/decoder_RSBPV4.hpp | 259 ++++++++++++++++++ .../driver/decoder/decoder_factory.hpp | 4 + src/rs_driver/driver/driver_param.hpp | 8 + 3 files changed, 271 insertions(+) create mode 100644 src/rs_driver/driver/decoder/decoder_RSBPV4.hpp diff --git a/src/rs_driver/driver/decoder/decoder_RSBPV4.hpp b/src/rs_driver/driver/decoder/decoder_RSBPV4.hpp new file mode 100644 index 00000000..29ea86e8 --- /dev/null +++ b/src/rs_driver/driver/decoder/decoder_RSBPV4.hpp @@ -0,0 +1,259 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#pragma once +#include + +namespace robosense +{ +namespace lidar +{ + +template +class DecoderRSBPV4 : public DecoderMech +{ +public: + + virtual void decodeDifopPkt(const uint8_t* pkt, size_t size); + virtual bool decodeMsopPkt(const uint8_t* pkt, size_t size); + virtual ~DecoderRSBPV4() = default; + + explicit DecoderRSBPV4(const RSDecoderParam& param); + +#ifndef UNIT_TEST +protected: +#endif + + static RSDecoderMechConstParam& getConstParam(); + static RSEchoMode getEchoMode(uint8_t mode); + + template + bool internDecodeMsopPkt(const uint8_t* pkt, size_t size); +}; + +template +inline RSDecoderMechConstParam& DecoderRSBPV4::getConstParam() +{ + static RSDecoderMechConstParam param = + { + 1248 // msop len + , 1248 // difop len + , 8 // msop id len + , 8 // difop id len + , {0x55, 0xAA, 0x05, 0x0A, 0x5A, 0xA5, 0x50, 0xA0} // msop id + , {0xA5, 0xFF, 0x00, 0x5A, 0x11, 0x11, 0x55, 0x55} // difop id + , {0xFF, 0xEE} // block id + , 32 // laser number + , 12 // blocks per packet + , 32 // channels per block + , 0.1f // distance min + , 150.0f // distance max + , 0.0025f // distance resolution + , 0.0625f // temperature resolution + + // lens center + , 0.01473f // RX + , 0.0085f // RY + , 0.09427f // RZ + }; + + INIT_ONLY_ONCE(); + + float blk_ts = 55.52f; + float firing_tss[] = + { + 0.00f, 2.56f, 5.12f, 7.68f, 10.24f, 12.80f, 15.36f, 17.92f, + 25.68f, 28.24f, 30.80f, 33.36f, 35.92f, 38.48f, 41.04f, 43.60f, + 1.28f, 3.84f, 6.40f, 8.96f, 11.52f, 14.08f, 16.64f, 19.20f, + 26.96f, 29.52f, 32.08f, 34.64f, 37.20f, 39.76f, 42.32f, 44.88f + }; + + param.BLOCK_DURATION = blk_ts / 1000000; + for (uint16_t i = 0; i < sizeof(firing_tss)/sizeof(firing_tss[0]); i++) + { + param.CHAN_TSS[i] = (double)firing_tss[i] / 1000000; + param.CHAN_AZIS[i] = firing_tss[i] / blk_ts; + } + + return param; +} + +template +inline RSEchoMode DecoderRSBPV4::getEchoMode(uint8_t mode) +{ + switch (mode) + { + case 0x00: // dual return + return RSEchoMode::ECHO_DUAL; + case 0x01: // strongest return + case 0x02: // last return + default: + return RSEchoMode::ECHO_SINGLE; + } +} + +template +inline DecoderRSBPV4::DecoderRSBPV4(const RSDecoderParam& param) + : DecoderMech(getConstParam(), param) +{ +} + +template +inline void DecoderRSBPV4::decodeDifopPkt(const uint8_t* packet, size_t size) +{ + const RSBPDifopPkt& pkt = *(const RSBPDifopPkt*)(packet); + this->template decodeDifopCommon(pkt); + + this->echo_mode_ = getEchoMode (pkt.return_mode); + this->split_blks_per_frame_ = (this->echo_mode_ == RSEchoMode::ECHO_DUAL) ? + (this->blks_per_frame_ << 1) : this->blks_per_frame_; +} + +template +inline bool DecoderRSBPV4::decodeMsopPkt(const uint8_t* pkt, size_t size) +{ + if (this->echo_mode_ == RSEchoMode::ECHO_SINGLE) + { + return internDecodeMsopPkt>(pkt, size); + } + else + { + return internDecodeMsopPkt>(pkt, size); + } +} + +template +template +inline bool DecoderRSBPV4::internDecodeMsopPkt(const uint8_t* packet, size_t size) +{ + const RSBPMsopPkt& pkt = *(const RSBPMsopPkt*)(packet); + bool ret = false; + + this->temperature_ = parseTempInLe(&(pkt.header.temp)) * this->const_param_.TEMPERATURE_RES; + + double pkt_ts = 0; + if (this->param_.use_lidar_clock) + { + pkt_ts = parseTimeYMD(&pkt.header.timestamp) * 1e-6; + } + else + { + uint64_t ts = getTimeHost(); + + // roll back to first block to approach lidar ts as near as possible. + pkt_ts = ts * 1e-6 - this->getPacketDuration(); + + if (this->write_pkt_ts_) + { + createTimeYMD (ts, (RSTimestampYMD*)&pkt.header.timestamp); + } + } + + T_BlockIterator iter(pkt, this->const_param_.BLOCKS_PER_PKT, this->mech_const_param_.BLOCK_DURATION, + this->block_az_diff_, this->fov_blind_ts_diff_); + + for (uint16_t blk = 0; blk < this->const_param_.BLOCKS_PER_PKT; blk++) + { + const RSBPMsopBlock& block = pkt.blocks[blk]; + + if (memcmp(this->const_param_.BLOCK_ID, block.id, 2) != 0) + { + this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); + break; + } + + int32_t block_az_diff; + double block_ts_off; + iter.get(blk, block_az_diff, block_ts_off); + + double block_ts = pkt_ts + block_ts_off; + int32_t block_az = ntohs(block.azimuth); + if (this->split_strategy_->newBlock(block_az)) + { + this->cb_split_frame_(this->const_param_.LASER_NUM, this->cloudTs()); + this->first_point_ts_ = block_ts; + ret = true; + } + + for (uint16_t chan = 0; chan < this->const_param_.CHANNELS_PER_BLOCK; chan++) + { + const RSChannel& channel = block.channels[chan]; + + double chan_ts = block_ts + this->mech_const_param_.CHAN_TSS[chan]; + int32_t angle_horiz = block_az + + (int32_t)((float)block_az_diff * this->mech_const_param_.CHAN_AZIS[chan]); + + int32_t angle_vert = this->chan_angles_.vertAdjust(chan); + int32_t angle_horiz_final = this->chan_angles_.horizAdjust(chan, angle_horiz); + + float distance = ntohs(channel.distance) * this->const_param_.DISTANCE_RES; + + if (this->distance_section_.in(distance) && this->scan_section_.in(angle_horiz_final)) + { + float x = distance * COS(angle_vert) * COS(angle_horiz_final) + this->mech_const_param_.RX * COS(angle_horiz); + float y = -distance * COS(angle_vert) * SIN(angle_horiz_final) - this->mech_const_param_.RX * SIN(angle_horiz); + float z = distance * SIN(angle_vert) + this->mech_const_param_.RZ; + this->transformPoint(x, y, z); + + typename T_PointCloud::PointT point; + setX(point, x); + setY(point, y); + setZ(point, z); + setIntensity(point, channel.intensity); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); + } + else if (!this->param_.dense_points) + { + typename T_PointCloud::PointT point; + setX(point, NAN); + setY(point, NAN); + setZ(point, NAN); + setIntensity(point, 0); + setTimestamp(point, chan_ts); + setRing(point, this->chan_angles_.toUserChan(chan)); + + this->point_cloud_->points.emplace_back(point); + } + + this->prev_point_ts_ = chan_ts; + } + } + + this->prev_pkt_ts_ = pkt_ts; + return ret; +} + +} // namespace lidar +} // namespace robosense diff --git a/src/rs_driver/driver/decoder/decoder_factory.hpp b/src/rs_driver/driver/decoder/decoder_factory.hpp index 46327c76..7c8bca04 100644 --- a/src/rs_driver/driver/decoder/decoder_factory.hpp +++ b/src/rs_driver/driver/decoder/decoder_factory.hpp @@ -36,6 +36,7 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include #include #include @@ -80,6 +81,9 @@ inline std::shared_ptr> DecoderFactory::crea case LidarType::RSBP: ret_ptr = std::make_shared>(param); break; + case LidarType::RSBPV4: + ret_ptr = std::make_shared>(param); + break; case LidarType::RSHELIOS: ret_ptr = std::make_shared>(param); break; diff --git a/src/rs_driver/driver/driver_param.hpp b/src/rs_driver/driver/driver_param.hpp index b35729c5..4a1bcc52 100644 --- a/src/rs_driver/driver/driver_param.hpp +++ b/src/rs_driver/driver/driver_param.hpp @@ -47,6 +47,7 @@ enum LidarType ///< LiDAR type RS16 = RS_MECH, RS32, RSBP, + RSBPV4, RSHELIOS, RSHELIOS_16P, RS128, @@ -96,6 +97,9 @@ inline std::string lidarTypeToStr(const LidarType& type) case LidarType::RSBP: str = "RSBP"; break; + case LidarType::RSBPV4: + str = "RSBPV4"; + break; case LidarType::RSHELIOS: str = "RSHELIOS"; break; @@ -153,6 +157,10 @@ inline LidarType strToLidarType(const std::string& type) { return LidarType::RSBP; } + else if (type == "RSBPV4") + { + return LidarType::RSBPV4; + } else if (type == "RSHELIOS") { return LidarType::RSHELIOS; From 5da9d79914bd74b5c5e33e1a4763ae30253b4ead Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sat, 8 Oct 2022 12:07:22 +0800 Subject: [PATCH 375/379] feat: add demo_online_multi_lidars --- demo/CMakeLists.txt | 6 + demo/demo_online_multi_lidars.cpp | 190 ++++++++++++++++++++++++++++++ 2 files changed, 196 insertions(+) create mode 100644 demo/demo_online_multi_lidars.cpp diff --git a/demo/CMakeLists.txt b/demo/CMakeLists.txt index 0d258784..6420c2ce 100644 --- a/demo/CMakeLists.txt +++ b/demo/CMakeLists.txt @@ -23,6 +23,12 @@ add_executable(demo_online target_link_libraries(demo_online ${EXTERNAL_LIBS}) +add_executable(demo_online_multi_lidars + demo_online_multi_lidars.cpp) + +target_link_libraries(demo_online_multi_lidars + ${EXTERNAL_LIBS}) + if(NOT ${DISABLE_PCAP_PARSE}) add_executable(demo_pcap diff --git a/demo/demo_online_multi_lidars.cpp b/demo/demo_online_multi_lidars.cpp new file mode 100644 index 00000000..c8c07fd1 --- /dev/null +++ b/demo/demo_online_multi_lidars.cpp @@ -0,0 +1,190 @@ +/********************************************************************************************************************* +Copyright (c) 2020 RoboSense +All rights reserved + +By downloading, copying, installing or using the software you agree to this license. If you do not agree to this +license, do not download, install, copy or use the software. + +License Agreement +For RoboSense LiDAR SDK Library +(3-clause BSD License) + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the +following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following +disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following +disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the names of the RoboSense, nor Suteng Innovation Technology, nor the names of other contributors may be used +to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, +INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*********************************************************************************************************************/ + +#include + +#ifdef ENABLE_PCL_POINTCLOUD +#include +#else +#include +#endif + +//#define ORDERLY_EXIT + +typedef PointXYZI PointT; +typedef PointCloudT PointCloudMsg; + +using namespace robosense::lidar; + +class DriverClient +{ +public: + + DriverClient(const std::string name) + : name_(name) + { + } + + bool init(const RSDriverParam& param) + { + RS_INFO << "------------------------------------------------------" << RS_REND; + RS_INFO << " " << name_ << RS_REND; + RS_INFO << "------------------------------------------------------" << RS_REND; + param.print(); + + driver_.regPointCloudCallback (std::bind(&DriverClient::driverGetPointCloudFromCallerCallback, this), + std::bind(&DriverClient::driverReturnPointCloudToCallerCallback, this, std::placeholders::_1)); + driver_.regExceptionCallback (std::bind(&DriverClient::exceptionCallback, this, std::placeholders::_1)); + + if (!driver_.init(param)) + { + RS_ERROR << name_ << ": Failed to initialize driver." << RS_REND; + return false; + } + + return true; + } + + bool start() + { + to_exit_process_ = false; + cloud_handle_thread_ = std::thread(std::bind(&DriverClient::processCloud, this)); + + driver_.start(); + RS_DEBUG << name_ << ": Started driver." << RS_REND; + + return true; + } + + void stop() + { + driver_.stop(); + + to_exit_process_ = true; + cloud_handle_thread_.join(); + } + +protected: + + std::shared_ptr driverGetPointCloudFromCallerCallback(void) + { + std::shared_ptr msg = free_cloud_queue_.pop(); + if (msg.get() != NULL) + { + return msg; + } + + return std::make_shared(); + } + + void driverReturnPointCloudToCallerCallback(std::shared_ptr msg) + { + stuffed_cloud_queue_.push(msg); + } + + void processCloud(void) + { + while (!to_exit_process_) + { + std::shared_ptr msg = stuffed_cloud_queue_.popWait(); + if (msg.get() == NULL) + { + continue; + } + + RS_MSG << name_ << ": msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND; + + free_cloud_queue_.push(msg); + } + } + + void exceptionCallback(const Error& code) + { + RS_WARNING << name_ << ": " << code.toString() << RS_REND; + } + + std::string name_; + LidarDriver driver_; + bool to_exit_process_; + std::thread cloud_handle_thread_; + SyncQueue> free_cloud_queue_; + SyncQueue> stuffed_cloud_queue_; +}; + +int main(int argc, char* argv[]) +{ + RS_TITLE << "------------------------------------------------------" << RS_REND; + RS_TITLE << " RS_Driver Core Version: v" << getDriverVersion() << RS_REND; + RS_TITLE << "------------------------------------------------------" << RS_REND; + + RSDriverParam param_left; ///< Create a parameter object + param_left.input_type = InputType::ONLINE_LIDAR; + param_left.input_param.msop_port = 6004; ///< Set the lidar msop port number, the default is 6699 + param_left.input_param.difop_port = 7004; ///< Set the lidar difop port number, the default is 7788 + param_left.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct + + DriverClient client_left("LEFT "); + if (!client_left.init(param_left)) ///< Call the init function + { + return -1; + } + + RSDriverParam param_right; ///< Create a parameter object + param_right.input_type = InputType::ONLINE_LIDAR; + param_right.input_param.msop_port = 6005; ///< Set the lidar msop port number, the default is 6699 + param_right.input_param.difop_port = 7005; ///< Set the lidar difop port number, the default is 7788 + param_right.lidar_type = LidarType::RSM1; ///< Set the lidar type. Make sure this type is correct + + DriverClient client_right("RIGHT"); + if (!client_right.init(param_right)) ///< Call the init function + { + return -1; + } + + client_left.start(); + client_right.start(); + +#ifdef ORDERLY_EXIT + std::this_thread::sleep_for(std::chrono::seconds(10)); + + client_left.stop(); + client_right.stop(); +#else + while (true) + { + std::this_thread::sleep_for(std::chrono::seconds(1)); + } +#endif + + return 0; +} + From 3c74b493943df6a09e0108fe6009b39ab66c8856 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sat, 8 Oct 2022 12:15:35 +0800 Subject: [PATCH 376/379] feat: disable blk_id error to be compatible with v1.3.x --- src/rs_driver/driver/decoder/decoder_RS128.hpp | 4 ++++ src/rs_driver/driver/decoder/decoder_RS80.hpp | 6 +++++- 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/src/rs_driver/driver/decoder/decoder_RS128.hpp b/src/rs_driver/driver/decoder/decoder_RS128.hpp index cda54464..bbc21ee7 100644 --- a/src/rs_driver/driver/decoder/decoder_RS128.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS128.hpp @@ -240,7 +240,11 @@ inline bool DecoderRS128::internDecodeMsopPkt(const uint8_t* packe if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { + // + // Disable error report temporarily + // //this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); + break; } diff --git a/src/rs_driver/driver/decoder/decoder_RS80.hpp b/src/rs_driver/driver/decoder/decoder_RS80.hpp index 52aecb75..0c0b6d99 100644 --- a/src/rs_driver/driver/decoder/decoder_RS80.hpp +++ b/src/rs_driver/driver/decoder/decoder_RS80.hpp @@ -235,7 +235,11 @@ inline bool DecoderRS80::internDecodeMsopPkt(const uint8_t* packet if (memcmp(this->const_param_.BLOCK_ID, block.id, 1) != 0) { - this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); + // + // Disable error report temporarily + // + //this->cb_excep_(Error(ERRCODE_WRONGMSOPBLKID)); + break; } From 8abe0e9dc9a260b4a8a588b100f726df2539bc53 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sun, 9 Oct 2022 16:54:52 +0800 Subject: [PATCH 377/379] feat: update docs --- README.md | 1 + README_CN.md | 1 + 2 files changed, 2 insertions(+) diff --git a/README.md b/README.md index fce04333..a06d3a54 100644 --- a/README.md +++ b/README.md @@ -13,6 +13,7 @@ Below are the supported LiDARS. - RS-LiDAR-16 - RS-LiDAR-32 - RS-Bpearl +- RS-Bpearl-V4 - RS-Helios - RS-Helios-16P - RS-Ruby-128 diff --git a/README_CN.md b/README_CN.md index 8050cc52..e472dba0 100644 --- a/README_CN.md +++ b/README_CN.md @@ -13,6 +13,7 @@ - RS-LiDAR-16 - RS-LiDAR-32 - RS-Bpearl +- RS-Bpearl-V4 - RS-Helios - RS-Helios-16P - RS-Ruby-128 From 91afc5e65286d19fb8c1cdf6ed98e7865cd062b9 Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sun, 9 Oct 2022 16:55:26 +0800 Subject: [PATCH 378/379] feat: change version to v1.5.7 --- CHANGELOG.md | 14 ++++++++++++++ CMakeLists.txt | 2 +- 2 files changed, 15 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 0f5a7c04..9cf6eee8 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -4,6 +4,20 @@ ### Changed +## v1.5.7 2022-10-09 + +### Added +- Add tool to save as PCD file +- Seperate RSBPV4 from RSBP +- Add demo app demo_online_multi_lidars + +### Changed +- Disable error report in case of wrong block id for RS128/RS80 temporarily + +### Fixed +- Fix distance range of helios series. Also update distance ranges of other lidars +- Report error ERRCODE_MSOP_TIMEOUT if only DIFOP packet is received + ## v1.5.6 2022-09-01 ### Added diff --git a/CMakeLists.txt b/CMakeLists.txt index b6e6d78c..648647b5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ if(WIN32) cmake_policy(SET CMP0074 NEW) # CMake 3.12 required endif(WIN32) -project(rs_driver VERSION 1.5.6) +project(rs_driver VERSION 1.5.7) #======================== # Project setup From 9774fbf83c0e5c6c17cabb565ba28e5757ce751f Mon Sep 17 00:00:00 2001 From: "ron.zheng" Date: Sun, 9 Oct 2022 17:32:40 +0800 Subject: [PATCH 379/379] feat: update docs --- doc/src_intro/rs_driver_intro_CN.md | 2 +- src/rs_driver/macro/version.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/src_intro/rs_driver_intro_CN.md b/doc/src_intro/rs_driver_intro_CN.md index 0e511fbc..3df7c1ad 100644 --- a/doc/src_intro/rs_driver_intro_CN.md +++ b/doc/src_intro/rs_driver_intro_CN.md @@ -1,4 +1,4 @@ -# rs_driver v1.5.6 源代码解析 +# rs_driver v1.5.7 源代码解析 ## 1 基本概念 diff --git a/src/rs_driver/macro/version.hpp b/src/rs_driver/macro/version.hpp index 2f00a4bc..051b8468 100644 --- a/src/rs_driver/macro/version.hpp +++ b/src/rs_driver/macro/version.hpp @@ -1,3 +1,3 @@ #define RSLIDAR_VERSION_MAJOR 1 #define RSLIDAR_VERSION_MINOR 5 -#define RSLIDAR_VERSION_PATCH 6 +#define RSLIDAR_VERSION_PATCH 7