From c47a95799e674a5d9fe8c25da2119e99ae7cbddb Mon Sep 17 00:00:00 2001 From: robofish <1683502971@qq.com> Date: Mon, 7 Jul 2025 21:07:50 +0800 Subject: [PATCH] point_lio --- src/FAST_LIO/CMakeLists.txt | 3 +- src/FAST_LIO/config/avia.yaml | 2 +- src/FAST_LIO/config/mid360.yaml | 2 +- src/FAST_LIO/launch/mapping_mid360.launch | 6 +- src/FAST_LIO/src/laserMapping.cpp | 18 +- src/FAST_LIO_LOCALIZATION/.gitignore | 0 src/FAST_LIO_LOCALIZATION/.gitmodules | 0 src/FAST_LIO_LOCALIZATION/CMakeLists.txt | 56 +- src/FAST_LIO_LOCALIZATION/LICENSE | 0 .../Log/fast_lio_time_log_analysis.m | 0 src/FAST_LIO_LOCALIZATION/Log/guide.md | 0 src/FAST_LIO_LOCALIZATION/Log/plot.py | 0 src/FAST_LIO_LOCALIZATION/PCD/1 | 0 src/FAST_LIO_LOCALIZATION/PCD/map.pgm | Bin 0 -> 209248 bytes src/FAST_LIO_LOCALIZATION/PCD/map.yaml | 7 + src/FAST_LIO_LOCALIZATION/PCD/map1.pgm | Bin 300664 -> 346848 bytes src/FAST_LIO_LOCALIZATION/PCD/map1.yaml | 4 +- src/FAST_LIO_LOCALIZATION/PCD/map_test.pgm | Bin 0 -> 2616297 bytes src/FAST_LIO_LOCALIZATION/PCD/map_test.yaml | 7 + src/FAST_LIO_LOCALIZATION/PCD/mapc.pgm | Bin 0 -> 6466278 bytes src/FAST_LIO_LOCALIZATION/PCD/mapc.yaml | 7 + src/FAST_LIO_LOCALIZATION/README.md | 0 src/FAST_LIO_LOCALIZATION/config/avia.yaml | 0 src/FAST_LIO_LOCALIZATION/config/horizon.yaml | 0 src/FAST_LIO_LOCALIZATION/config/mid360.yaml | 0 .../config/ouster64.yaml | 0 .../config/velodyne.yaml | 0 src/FAST_LIO_LOCALIZATION/doc/demo.GIF | Bin src/FAST_LIO_LOCALIZATION/doc/demo_accu.GIF | Bin src/FAST_LIO_LOCALIZATION/doc/demo_init.GIF | Bin src/FAST_LIO_LOCALIZATION/doc/demo_init_2.GIF | Bin src/FAST_LIO_LOCALIZATION/include/Exp_mat.h | 0 .../include/common_lib.h | 0 .../include/ikd-Tree/README.md | 0 .../include/ikd-Tree/ikd_Tree.cpp | 0 .../include/ikd-Tree/ikd_Tree.h | 0 .../include/matplotlibcpp.h | 0 src/FAST_LIO_LOCALIZATION/include/so3_math.h | 0 .../include/use-ikfom.hpp | 0 .../launch/PointsCloud2toLaserscan.launch | 4 +- .../launch/align_pcd_map.launch | 0 .../launch/gdb_debug_example.launch | 0 .../launch/localization_MID360.launch | 19 +- .../launch/localization_avia.launch | 0 .../launch/localization_horizon.launch | 0 .../launch/localization_ouster64.launch | 0 .../launch/localization_velodyne.launch | 0 src/FAST_LIO_LOCALIZATION/launch/move.launch | 5 - src/FAST_LIO_LOCALIZATION/launch/nav.launch | 8 +- .../launch/r_serial.launch | 5 + .../launch/sentry_build_map.launch | 2 +- .../launch/sentry_localize.launch | 0 .../launch/sentry_localize_odom.launch | 0 src/FAST_LIO_LOCALIZATION/msg/DataAI.msg | 11 + src/FAST_LIO_LOCALIZATION/msg/DataMCU.msg | 8 + src/FAST_LIO_LOCALIZATION/msg/DataNav.msg | 5 + src/FAST_LIO_LOCALIZATION/msg/DataRef.msg | 3 + src/FAST_LIO_LOCALIZATION/msg/GoalPose.msg | 8 + src/FAST_LIO_LOCALIZATION/msg/Pose6D.msg | 0 src/FAST_LIO_LOCALIZATION/msg/Ps2Data.msg | 20 + src/FAST_LIO_LOCALIZATION/msg/position.msg | 3 + src/FAST_LIO_LOCALIZATION/msg/serial.msg | 1 + src/FAST_LIO_LOCALIZATION/msg/underpan.msg | 2 + src/FAST_LIO_LOCALIZATION/package.xml | 4 +- src/FAST_LIO_LOCALIZATION/rviz_cfg/.gitignore | 0 .../rviz_cfg/loam_livox.rviz | 0 .../rviz_cfg/localization.rviz | 31 +- .../rviz_cfg/sentry_build_map.rviz | 9 +- .../rviz_cfg/sentry_localize.rviz | 0 .../scripts/global_localization.py | 103 ++- .../scripts/publish_initial_pose.py | 2 +- .../src/.vscode/c_cpp_properties.json | 23 + .../src/.vscode/settings.json | 10 + .../src/IMU_Processing.cpp | 136 ++++ .../src/IMU_Processing.h | 59 ++ .../src/IMU_Processing.hpp | 0 src/FAST_LIO_LOCALIZATION/src/all_move.cpp | 274 +++++++ src/FAST_LIO_LOCALIZATION/src/chong.cpp | 226 ++++++ src/FAST_LIO_LOCALIZATION/src/chong0.cpp | 230 ++++++ src/FAST_LIO_LOCALIZATION/src/commands.cpp | 225 ++++++ src/FAST_LIO_LOCALIZATION/src/controlpid.cpp | 198 ----- src/FAST_LIO_LOCALIZATION/src/flag.cpp | 127 +-- .../src/laserMapping.cpp | 0 .../src/mbot_linux_serial.cpp | 361 ++++----- .../src/mbot_linux_serial.h | 15 +- src/FAST_LIO_LOCALIZATION/src/position.cpp | 130 +++ src/FAST_LIO_LOCALIZATION/src/preprocess.cpp | 753 ++++++++++-------- src/FAST_LIO_LOCALIZATION/src/preprocess.h | 38 +- src/FAST_LIO_LOCALIZATION/src/send.cpp | 195 +++++ src/FAST_LIO_LOCALIZATION/src/test_goal.cpp | 84 ++ src/FAST_LIO_LOCALIZATION/src/tor1_serial.cpp | 87 ++ src/FAST_LIO_LOCALIZATION/src/uart.cpp | 180 +++++ .../src/underpan_serial.cpp | 74 ++ src/Livox-SDK2 | 1 + src/Point-LIO | 1 + .../config/MID360_config.json | 4 +- .../launch_ROS1/msg_MID360.launch | 10 +- src/pcd2pgm/launch/run.launch | 6 +- src/pcd2pgm/src/pcd2pgm.cpp | 8 +- 99 files changed, 2924 insertions(+), 896 deletions(-) mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/.gitignore mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/.gitmodules mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/CMakeLists.txt mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/LICENSE mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/Log/fast_lio_time_log_analysis.m mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/Log/guide.md mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/Log/plot.py mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/PCD/1 create mode 100755 src/FAST_LIO_LOCALIZATION/PCD/map.pgm create mode 100755 src/FAST_LIO_LOCALIZATION/PCD/map.yaml mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/PCD/map1.pgm mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/PCD/map1.yaml create mode 100644 src/FAST_LIO_LOCALIZATION/PCD/map_test.pgm create mode 100644 src/FAST_LIO_LOCALIZATION/PCD/map_test.yaml create mode 100644 src/FAST_LIO_LOCALIZATION/PCD/mapc.pgm create mode 100644 src/FAST_LIO_LOCALIZATION/PCD/mapc.yaml mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/README.md mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/config/avia.yaml mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/config/horizon.yaml mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/config/mid360.yaml mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/config/ouster64.yaml mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/config/velodyne.yaml mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/doc/demo.GIF mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/doc/demo_accu.GIF mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/doc/demo_init.GIF mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/doc/demo_init_2.GIF mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/include/Exp_mat.h mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/include/common_lib.h mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/include/ikd-Tree/README.md mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/include/ikd-Tree/ikd_Tree.cpp mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/include/ikd-Tree/ikd_Tree.h mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/include/matplotlibcpp.h mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/include/so3_math.h mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/include/use-ikfom.hpp mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/launch/PointsCloud2toLaserscan.launch mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/launch/align_pcd_map.launch mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/launch/gdb_debug_example.launch mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/launch/localization_MID360.launch mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/launch/localization_avia.launch mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/launch/localization_horizon.launch mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/launch/localization_ouster64.launch mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/launch/localization_velodyne.launch delete mode 100644 src/FAST_LIO_LOCALIZATION/launch/move.launch mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/launch/nav.launch create mode 100755 src/FAST_LIO_LOCALIZATION/launch/r_serial.launch mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/launch/sentry_build_map.launch mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/launch/sentry_localize.launch mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/launch/sentry_localize_odom.launch create mode 100755 src/FAST_LIO_LOCALIZATION/msg/DataAI.msg create mode 100755 src/FAST_LIO_LOCALIZATION/msg/DataMCU.msg create mode 100755 src/FAST_LIO_LOCALIZATION/msg/DataNav.msg create mode 100755 src/FAST_LIO_LOCALIZATION/msg/DataRef.msg create mode 100755 src/FAST_LIO_LOCALIZATION/msg/GoalPose.msg mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/msg/Pose6D.msg create mode 100755 src/FAST_LIO_LOCALIZATION/msg/Ps2Data.msg create mode 100755 src/FAST_LIO_LOCALIZATION/msg/position.msg create mode 100755 src/FAST_LIO_LOCALIZATION/msg/serial.msg create mode 100755 src/FAST_LIO_LOCALIZATION/msg/underpan.msg mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/package.xml mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/rviz_cfg/.gitignore mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/rviz_cfg/loam_livox.rviz mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/rviz_cfg/localization.rviz mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/rviz_cfg/sentry_build_map.rviz mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/rviz_cfg/sentry_localize.rviz create mode 100755 src/FAST_LIO_LOCALIZATION/src/.vscode/c_cpp_properties.json create mode 100755 src/FAST_LIO_LOCALIZATION/src/.vscode/settings.json create mode 100755 src/FAST_LIO_LOCALIZATION/src/IMU_Processing.cpp create mode 100755 src/FAST_LIO_LOCALIZATION/src/IMU_Processing.h mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/src/IMU_Processing.hpp create mode 100755 src/FAST_LIO_LOCALIZATION/src/all_move.cpp create mode 100755 src/FAST_LIO_LOCALIZATION/src/chong.cpp create mode 100755 src/FAST_LIO_LOCALIZATION/src/chong0.cpp create mode 100755 src/FAST_LIO_LOCALIZATION/src/commands.cpp delete mode 100644 src/FAST_LIO_LOCALIZATION/src/controlpid.cpp mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/src/flag.cpp mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/src/laserMapping.cpp mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/src/mbot_linux_serial.cpp mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/src/mbot_linux_serial.h create mode 100755 src/FAST_LIO_LOCALIZATION/src/position.cpp mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/src/preprocess.cpp mode change 100644 => 100755 src/FAST_LIO_LOCALIZATION/src/preprocess.h create mode 100755 src/FAST_LIO_LOCALIZATION/src/send.cpp create mode 100755 src/FAST_LIO_LOCALIZATION/src/test_goal.cpp create mode 100755 src/FAST_LIO_LOCALIZATION/src/tor1_serial.cpp create mode 100755 src/FAST_LIO_LOCALIZATION/src/uart.cpp create mode 100755 src/FAST_LIO_LOCALIZATION/src/underpan_serial.cpp create mode 160000 src/Livox-SDK2 create mode 160000 src/Point-LIO diff --git a/src/FAST_LIO/CMakeLists.txt b/src/FAST_LIO/CMakeLists.txt index a1ac27e..1f27df3 100644 --- a/src/FAST_LIO/CMakeLists.txt +++ b/src/FAST_LIO/CMakeLists.txt @@ -66,6 +66,7 @@ include_directories( ${EIGEN3_INCLUDE_DIR} ${PCL_INCLUDE_DIRS} ${PYTHON_INCLUDE_DIRS} + ${CMAKE_BINARY_DIR}/devel/include include) add_message_files( @@ -75,7 +76,7 @@ add_message_files( generate_messages( DEPENDENCIES - geometry_msgs + std_msgs geometry_msgs ) catkin_package( diff --git a/src/FAST_LIO/config/avia.yaml b/src/FAST_LIO/config/avia.yaml index adcc03b..8c030ef 100644 --- a/src/FAST_LIO/config/avia.yaml +++ b/src/FAST_LIO/config/avia.yaml @@ -1,7 +1,7 @@ common: lid_topic: "/livox/lidar" imu_topic: "/livox/imu" - time_sync_en: false # ONLY turn on when external time synchronization is really not possible + time_sync_en: true # ONLY turn on when external time synchronization is really not possible time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 diff --git a/src/FAST_LIO/config/mid360.yaml b/src/FAST_LIO/config/mid360.yaml index 20c0e01..d503357 100644 --- a/src/FAST_LIO/config/mid360.yaml +++ b/src/FAST_LIO/config/mid360.yaml @@ -17,7 +17,7 @@ mapping: b_gyr_cov: 0.0001 fov_degree: 360 det_range: 100.0 - extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic + extrinsic_est_en: False # true: enable the online estimation of IMU-LiDAR extrinsic extrinsic_T: [ -0.011, -0.02329, 0.04412 ] extrinsic_R: [ 1, 0, 0, 0, 1, 0, diff --git a/src/FAST_LIO/launch/mapping_mid360.launch b/src/FAST_LIO/launch/mapping_mid360.launch index 0fe04fd..74c7985 100644 --- a/src/FAST_LIO/launch/mapping_mid360.launch +++ b/src/FAST_LIO/launch/mapping_mid360.launch @@ -7,13 +7,13 @@ - + - + - + diff --git a/src/FAST_LIO/src/laserMapping.cpp b/src/FAST_LIO/src/laserMapping.cpp index fbed297..2c0f5b7 100644 --- a/src/FAST_LIO/src/laserMapping.cpp +++ b/src/FAST_LIO/src/laserMapping.cpp @@ -488,6 +488,7 @@ void publish_frame_world(const ros::Publisher & pubLaserCloudFull) { RGBpointBodyToWorld(&laserCloudFullRes->points[i], \ &laserCloudWorld->points[i]); + } sensor_msgs::PointCloud2 laserCloudmsg; @@ -538,6 +539,7 @@ void publish_frame_body(const ros::Publisher & pubLaserCloudFull_body) { RGBpointBodyLidarToIMU(&feats_undistort->points[i], \ &laserCloudIMUBody->points[i]); + } sensor_msgs::PointCloud2 laserCloudmsg; @@ -764,8 +766,8 @@ int main(int argc, char** argv) nh.param("publish/scan_bodyframe_pub_en",scan_body_pub_en, true); nh.param("max_iteration",NUM_MAX_ITERATIONS,4); nh.param("map_file_path",map_file_path,""); - nh.param("common/lid_topic",lid_topic,"/livox/lidar"); - nh.param("common/imu_topic", imu_topic,"/livox/imu"); + nh.param("common/lid_topic",lid_topic,"livox/lidar"); + nh.param("common/imu_topic", imu_topic,"livox/imu"); nh.param("common/time_sync_en", time_sync_en, false); nh.param("common/time_offset_lidar_to_imu", time_diff_lidar_to_imu, 0.0); nh.param("filter_size_corner",filter_size_corner_min,0.5); @@ -847,17 +849,17 @@ int main(int argc, char** argv) nh.subscribe(lid_topic, 200000, standard_pcl_cbk); ros::Subscriber sub_imu = nh.subscribe(imu_topic, 200000, imu_cbk); ros::Publisher pubLaserCloudFull = nh.advertise - ("/cloud_registered", 100000); + ("cloud_registered", 100000); ros::Publisher pubLaserCloudFull_body = nh.advertise - ("/cloud_registered_body", 100000); + ("cloud_registered_body", 100000); ros::Publisher pubLaserCloudEffect = nh.advertise - ("/cloud_effected", 100000); + ("cloud_effected", 100000); ros::Publisher pubLaserCloudMap = nh.advertise - ("/Laser_map", 100000); + ("Laser_map", 100000); ros::Publisher pubOdomAftMapped = nh.advertise - ("/Odometry", 100000); + ("Odometry", 100000); ros::Publisher pubPath = nh.advertise - ("/path", 100000); + ("path", 100000); //------------------------------------------------------------------------------------------------------ signal(SIGINT, SigHandle); ros::Rate rate(5000); diff --git a/src/FAST_LIO_LOCALIZATION/.gitignore b/src/FAST_LIO_LOCALIZATION/.gitignore old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/.gitmodules b/src/FAST_LIO_LOCALIZATION/.gitmodules old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/CMakeLists.txt b/src/FAST_LIO_LOCALIZATION/CMakeLists.txt old mode 100644 new mode 100755 index 7b4cac1..d565070 --- a/src/FAST_LIO_LOCALIZATION/CMakeLists.txt +++ b/src/FAST_LIO_LOCALIZATION/CMakeLists.txt @@ -55,7 +55,9 @@ find_package(catkin REQUIRED COMPONENTS message_generation eigen_conversions fast_lio + serial genmsg + Eigen3 ) find_package(Eigen3 REQUIRED) @@ -72,27 +74,67 @@ include_directories( add_message_files( FILES + underpan.msg Pose6D.msg + serial.msg + DataMCU.msg + DataRef.msg + DataAI.msg + Ps2Data.msg + GoalPose.msg + DataNav.msg + position.msg + ) generate_messages( DEPENDENCIES geometry_msgs + std_msgs ) catkin_package( - CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs message_runtime + CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs message_runtime DEPENDS EIGEN3 PCL INCLUDE_DIRS ) -add_executable(fastlio_mapping1 src/laserMapping.cpp include/ikd-Tree/ikd_Tree.cpp src/preprocess.cpp) +# add_executable(fastlio_mapping1 src/laserMapping.cpp include/ikd-Tree/ikd_Tree.cpp src/preprocess.cpp) add_executable(flag src/flag.cpp) -add_executable(controlpid src/controlpid.cpp src/mbot_linux_serial.cpp) -target_link_libraries(fastlio_mapping1 ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) +add_executable(uart src/uart.cpp) +add_executable(send src/send.cpp) +add_executable(test_goal src/test_goal.cpp) +add_executable(underpan_serial src/underpan_serial.cpp) +add_executable(tor1_serial src/tor1_serial.cpp) +add_executable(position src/position.cpp) +add_executable(all_move src/all_move.cpp) +add_executable(chong src/chong.cpp src/mbot_linux_serial.cpp) +add_executable(chong0 src/chong0.cpp src/mbot_linux_serial.cpp) +add_executable(commands src/commands.cpp ) +# target_link_libraries(fastlio_mapping1 ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) target_link_libraries(flag ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) -target_link_libraries(controlpid ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) -target_include_directories(fastlio_mapping1 PRIVATE ${PYTHON_INCLUDE_DIRS}) +target_link_libraries(uart ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) +target_link_libraries(test_goal ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) +target_link_libraries(send ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) +target_link_libraries(underpan_serial ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) +target_link_libraries(tor1_serial ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) +target_link_libraries(position ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) +target_link_libraries(all_move ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) +target_link_libraries(chong ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) +target_link_libraries(chong0 ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) +target_link_libraries(commands ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES}) +# target_include_directories(fastlio_mapping1 PRIVATE ${PYTHON_INCLUDE_DIRS}) target_include_directories(flag PRIVATE ${PYTHON_INCLUDE_DIRS}) -target_include_directories(controlpid PRIVATE ${PYTHON_INCLUDE_DIRS}) +target_include_directories(uart PRIVATE ${PYTHON_INCLUDE_DIRS}) +target_include_directories(test_goal PRIVATE ${PYTHON_INCLUDE_DIRS}) +target_include_directories(send PRIVATE ${PYTHON_INCLUDE_DIRS}) +target_include_directories(underpan_serial PRIVATE ${PYTHON_INCLUDE_DIRS}) +target_include_directories(tor1_serial PRIVATE ${PYTHON_INCLUDE_DIRS}) +target_include_directories(position PRIVATE ${PYTHON_INCLUDE_DIRS}) +target_include_directories(all_move PRIVATE ${PYTHON_INCLUDE_DIRS}) +target_include_directories(chong PRIVATE ${PYTHON_INCLUDE_DIRS}) +target_include_directories(chong0 PRIVATE ${PYTHON_INCLUDE_DIRS}) +target_include_directories(commands PRIVATE ${PYTHON_INCLUDE_DIRS}) add_dependencies(fastlio_mapping fast_lio_generate_messages_cpp) +add_dependencies(underpan_serial ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +add_dependencies(commands ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/LICENSE b/src/FAST_LIO_LOCALIZATION/LICENSE old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/Log/fast_lio_time_log_analysis.m b/src/FAST_LIO_LOCALIZATION/Log/fast_lio_time_log_analysis.m old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/Log/guide.md b/src/FAST_LIO_LOCALIZATION/Log/guide.md old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/Log/plot.py b/src/FAST_LIO_LOCALIZATION/Log/plot.py old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/PCD/1 b/src/FAST_LIO_LOCALIZATION/PCD/1 old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/PCD/map.pgm b/src/FAST_LIO_LOCALIZATION/PCD/map.pgm new file mode 100755 index 0000000000000000000000000000000000000000..43028b1d1bc1b155d2e98c1a21ebe0e1f230f33b GIT binary patch literal 209248 zcmeHPORp`vQO-EO;!4azgc3l^5Mm69n4<_WU=S$+3GwSA>Z`Kdew5pfc6Zyo-RIu5 z>~dB4d$fD4z3)l>_4mL2t6%=<5C8m+|Mo9`_=jKq^v6H{`~Up$fB*BpfAb%I{_`)t z{mpNG|Jz^w^w)p>umAh?@Ba4hfBD_-{_fX*^ZVcb`Y-$13Vcn0U;X7Tzrr87FxuBw z6o8}l+QxpwRh&_}_yuqK$bP_BHkB;pQ)(W;cp7hWmo`^9oH)4qS-iBX+M$H0+t|fz z-SD>pTY;^>R$wcz71#=F1-1fPfvvz+U@Nc{*a~a~wgOv$t-w}bE3g&V3Ty?o0$YKt zz*b-@uoc(}Yz4LgTY;^>R$wcz71#=F1)u=`jpr@JcNDPylOp*aD13+4Ph@g<>5umR zKw;r~!8cMHFHG&HLJw^;|I@!Ph}ln-XGz|^eL}#G1Y=s>-mYLWyA}ZroYW@U+eopw zrm!rrh=Yt%bM#o9i^@i06@aH_SJqXoJFh+KyVq`0pykjRd!sK>W_laK-MCc&^_XT) zU+&Oye1C;%75}FEHc!d6^NUetZ;6{Y?6#o-nx|)(##!pJBWLrshpX6w4h1rvo^+y$lU0AonHm;g z#!K5%U#)TDc2Bd9%G7IXss@)g_RaRkTEULhDxi2u-gN0pt>Rscsd1R*ys|$^6=kl6 zR8PBHRXT}tsny0)dG^wcklYK`dHvuH=D36kXzqj=+Kj5SaPC7B_l>(SREu}8T>(}# zD$`<7O4C%e%h~A+JUSgHw;Dx!eg?B`GH+k95;0r1rr4aL&@yHiBTI!o7 zJ5U>MlVI4l!>;lbU_t#rB=>DcCvei6;0sfHmxcKDte`;7Q|}-ZI&?03Hu^)^ce~oD zDwjdesGdU-WVNH^VN-6dzidyhsLTci4LIU_P8<(%uS`@oZ+|>oLA*#U3majj7)6|` z(Q0nmnvX3`uiQpEUQj^s6rn&yN?u=9c#lRj*o1fJD6N|eMA}hUVN8^;_4~r-UDxrcXRp%BGWalF+&&4Fv@EcEi?AKQ__Mudr}|1gv5Z$xh^hG`c6U*_8{%IcKIfz?baGEY*Wh`D*7v-Tp!ljUv%R8!HZ+p zGZlx!D&$_f5Du&n4;OC^WR6bqN&Kx&gH&`il>!wnb-*L=XZWRyi0d&j;-|3RLW~2f` z8Rq@TSx0rl1>)O?0debN%A1YfZ#aPm8$zaFJJ!vH;>9DA>!MP(nv1)Hz5zpXAMyfJ zUiA z<6(W*ZrC7&~Exd6>c(O7J3?PIHLcmJyK88h{g>H z%0JpFVuy*MeJ<}x+;*1tW5+8!*RNF^q)>)ev{3ugj8QzQ&g{__mMy&dsISd8s!~r8 z(Yb~3d>*RPCTT?9r6KC!1RA;;ia(pG2vH{u$*0tMI%Va}E_lVYL(fD;Loc1g8s>H#xY6{jB2VEIT?N>%h5wvpX1WBPW^xMq>&wQ} zkuCL&CXccX0md{EEYrk@R!)oyaldfPs^8NhZR#Sntqc6n0qNi~H?sI4bxeni|4|pu zg1pLFm}tP1A4hwoZL1q5NK<*WHuCtfGeRR!)3FnajBAbg#3}+)wSaXM!ucY zdf9%nXbk+gqVUg|rtCR#s)#I}%2trn*81C=emwIrE;Kz%LwmZ8z|R_`+*uA|TUHAw zcBb0dT5u!-;WZl!9C^#)i55&z6#XevW=|>~e4U8ir{1wjBiM;QngcfRbdgO(BhC)C zmKY#l8>C>&mjvtvg?Cp|$ot~5df;Il6Ms0M^ z$Si+23}aY9k0XS2s(Nv6XpfH<8Zs15sk=qs-D|BISPHFm>*reoQzog|CI@1%<`)D{ zw+kZt1TfnK3oR3CDmQB>Ts+qt47N$eo>3gt2s+7clZzVTp29!w^2aWCILlzd>2Y%M$gV8b(tyGu@z$e|XRnuZKD4g()Sh>qcU5F#Nr`?XPGriH**nygwP~7@ zJ=s4DgtN4d9yz+}>mQ7ILe+bUBZ_n76{f`;KB%%xR1O<5{>9iEsqVN{@h;PM<=LH_0Y#nB5{pNj{%(bs{r7Cs? zrohrBb8sv0{a_2Z%hcR~w29-?Y_i~(CA-l~S3H!{YCo=cmfh_A1K)3l>)5%qus zf;B0!%jArw)|}>kkVd{B@vYBes1;t#ZJ#J0h)-yw{3GL#@1XlX92hz7cgQr4(rid zM!0ier2OIiuqO`&Zre^^EbaFF2Uf(I^L$``YQ<{dKC!*!o{=!NB7gY+kKMMh8zAtV z)>t=TI_u0YBDoC50=0XfD~;uh%F&eZ*zJ0|3C!N=iR!H0keL5PU@*Sm5K417n!F=y z9lc{00hR)lQ=sXh;EKdno)Q~2U@)tw9d^M+xWrF>i?STP#|P5@xx!r3r4DjnAoaZ$ zdB_{c#(2f%_wHHWeHtM3kd;gpm375PBv#T!hG-Ms3SK_7XB~dh;RCL+yh50z_U3gm z^knf)u5c<9`LW@kEjsW_e9qKEEBh!uA}^1=U@93Is+a`A<>9kv`{Df?8$M0H5nfgL z7dTWAtxbyW@!GnH@;*Reu$q%SINI6mW14EVx~bdK)Kl}by0WlB===xL)$iAC2d4Wn zUdx0|s9c!>TFk6`KD;V(>u47L5B7A`-zGUvbEhujX(pWOvS>Ver_aqt%sF|!W|n?} zsl+kEeritvn{YQnH+55Uy9`dWx!mUQ25f2bu54-ZjnKT!y9GbXQaad6K9$<;k%c|| z`f+PB(#z(DkvCsuDEH#FRrQNaT~3>AscNPRl0I&{%7E|0wSTeMDRre+?CD~^B$UTX zdOI4*>4KGTnj1I|(Lz<B2OM}mNl=UN%@oQtXkGKd|lf^fxTMxqBB8buuR zH9wmDB9!!sT2D3wr#?u%b$z?lR{0)<2+fLO+)<svfo+X?}Die8!RT$VsI;Ognm}GGW=8xXO$pcOS2qa18~d6-K?lk`*B8# z-2!|_Q=P+*)-N{cW@QUQXVXsHo zSfr|G+D#f$^zXevSlI)2W_aS&&$bxPuI&Ru5KUW?_^|kusxFfWF> zpp1|zBq_^Q1=O4Wrrg^~>Hb(qFoVOFF2|~g)**t?;|Q!I&OyG3{qz()UO8g!D5hjg zH67JlaauD^#N$2>s8L8PIlZ4%D7W2K-Hqjbw0C8}w8C;Xh$joHOkzEjeJBCFe17ovfpc{~ z;c3xSe6bKyAxSa)T(TEd4R*YhcdyGT_jxs=$P_H?eQw9EB5vK>gI`e!u8Ut~3M|R- z)mIc+i8T>y%x8SY3+2ZS5R+d<*hR z1s?FLNLxDv96^)0@_04Uu&LgsmfTgHWksTwwYV7Yb)b=4m$_~hb7Y!)Tt%O?=m_Ro zr`EN!207&zIcPvOy2+O<<g;p8xVLLx@0Xvh=@_^%c>0By^r`4ENq85-cz|S5?@HARa zBSF(iCrl)!lEs>k&SuWGz{ufPv}35k_D3Kz3ps1xfKdc zA75t7)p#Al$8iqXFtsddnbPsP+s#*ATeBi25YewL@!QX|rg{wbJR(f&YB z%`bix@g@y59@C}1DqNOaj_Gorrvw|+tB+rG;$=Z6XuzH_j-_aub6P8)xdm#|7tgbv z)_&QTgl?-zOWm*+HD*hVpDWqg=xJm6MNwZaXHQ?o(6K#Wx0E%ex3r!w*YmVVq?eg& zPxA(NmY)8{oP39OR$9+pYyLZ|#_Z~Qy4X2w65ywL+9cAu$+#7p5HuGwb)PHQaBUN4 z0t(yHtO={$zRkE>?}4mh(=UY5EOb~y;1xPI7gY4TKcyWtDi-q5m#`UmbAi9xOJiWh z)v|qSeoOD0a~qlRU(;&R=4Sjg?O_kDnp~IDT;M9-9<(EGuXvjy|3!{=*i_*m_s3p% z#$h{EC^RFJ6HFl4{+Dz^o(pkiwkL9=OYIeDk4uq8b%EDhZQD}OQQ!@a;G`q4ZG+Zc z(bm6^-H28`|3R{YXaUNs%k2)eR}ADXjyBzfz-z8HAXMZP_+u|T<1hqX^Q|_nc$^if z+aj>>6K_pWTl1Tm-_${822AO z2iyql@IAO;c&Z=SatskzN>|cMi`k^JHJfwe`#YZANN99x7)n>#Rt-wp$x_;9d<0+> zz{*B-SxO;7FSE>`stFTvzS7*hAXJd1KNkVsn%!#iGQBEy$yC1?264I+2wIHOGWkl2 zTSCB<#pdsr!>O|M3uRoHmKMGq0dcxYI5@%n3{jC^>UU|qYJafOc@@brIKB1~?x%`{ zdWmL0FsId1kgN6)UM96fPwN;^))MB8b$GhOw+G)-8n+wJQ`5f7Efob%RWZ6Wx&?i{ zsn1Kps}l3tEo>>yoJQGWmkyf?(iXQzn3e^K|IFs^XulZvv1l9?M2nM8nfocmKn>2c zQk|APyO@Bqo|=VdO5g(1f{EeyEP;W$fopTSo|@)O+6od9)Ogc~4RN;&zs4BWO3D(3LXlK{UIc#JR!t(hTddSa*-Ij(5oNw~PszwB{6P*5< zKW4Zmbx+W_vd1~=T<5;3T(=={d?AWXDo|#u$;BO%VuH(@Z*ao<1Z-ZclcKwqVo*#C z-e|tkBH__i1ZIBaZW`D7Gx6p&v3$)9ZYUs=g2QDjWmCmLe^W%_ieTNJEH-B5&6xYD znzv~xV28Zp#Tea7+zJc$a!ar3l?ki4(*?7v&XDG{IIFsME%Fo)>Eb;DgLpzO)>75g zpyFQK{Dz=a9nH+%cv2ZBXxT4CWoX^i_3i zR9ONV{^dLB@$-i4XwK6vO)8<@p9Ud1cIm6?*r>9^_{kpe5%te$*u&8Uajpy3G3(MK zZSzhf!>I^nHcy>7AS4r}##3SAyfox^F1ZQaI5$a{Il#o*0d|(PZ&Y1Dh~)b%zcW7j zVo#kjF>H#oFk%a$=qgj@-40gKp}on_3MK+?*joR|D`s1tQsg2*U~6LXP^h;zBS!6e zhz#v@cUHhl`ePiDcQ?bvhuHxPF;r2-z#F?}95n-OZ)W2Oow#pLQyS$XO!9?GmX>0ybdE*F%r0y|A<;7(Jk*vGJdLzjDTN4-A zgh|!!hxGdFM=}`_c?yG^Urej;0(2;O1my#p_|~u}m3y}2R<^vFW<4o5s4UaYr90F% zzY6k!`p_DtTeoXiSXXmrmURjT)IX&D*yiv_b`x>4;OSzP25_NB)dfka5}!&ECshl5 z`*>_WKFx$7dThL*K|dMSQ%!wRl9=+*8=z8Oc_Ru#^LEB7K*-F&fmxKOl-A$ioY_-| zC5tt7acNTdS|IDFGw;Y?kV0L%FE#(P*lS!%8)xjxg#B(1#h<@8#$f}T!!|qO1$!td zhtmvFQ$e$kM>vz@X{gqy3?bAjyI`{+i5llE!OX9r7eqzC*wZkKV6&tl# z67y%1k9~?ERIE7m;S$eE>q^OeAqN${vUk=%?8#6Cuefi37=97WXezmC(6pKD4NNnb zM2XBIg-=TJMfa=_1>Y<|ZeFn?an#s=IWGmMG(ogjP&Cuz+?X>eEYc)YjD5%5X##MP zA=-J07b`(Dn#!6Q49X^&#Ej~pu}t;pw`P*$d=kwj=2Y_8^h10qLm)_vBjKE9agvfU zO(?lb>yce3t>2_JGxmjVIJxWWk_n|9ZGx=m?u9vNkEtTWv=aD%Gj)1X+{B_vw zMPMrs>zrmKYPtFESA4lr>tncK%!abDwz&gaawp?ysm$*4{yTH;h2doCZE#y1ozmcY zFdtCetQbQkYaL7dFA*`h@_b@XU%Ctgzs&2qba?IlO6%wqH ze-x%6C0`Q)PpgPBqghyVprUlj0?|S4>%L`1Kye&&PvDutQrV?dacTil31rG zHo??zQamk!o0L%zcbH%V=rNT`!)`OoEThoVN@P^5WvW3fagvzRpcT)gp1Kdy#2#x{ z>X3^hHLapdli%Y`_pNX{Yr`h`K*hGsx&VV0wXO&2i%uXzBXm}-xvFuKzI32sM+105 z(7t+09`g_0HaIEzHdp}}%kZ>?Xt9!~Ov?fWeBpobT7@9t6tEVt2i?(dgN0aSpu!uEVkRpLOHFH4*yGii^%fxPxLJi)8DuvXH{~^( zq%5$fN_^?i!ndfWJDW+jX)~MlyTIFZ(&0Ba^|L^wePm5)Q7f#|36G<(MA-DY3&+{Oak_Iq%x@zM_w?xk>}|-}zec z5iS>Le9F@H-+15m%(&8dd+Mq8jYrPq-&y0Je&yl&5hj;uz*4%rn|@eVZ{|uH!Hr04KcaT2oD3;@nxF zJ~zS+bl}8)z>crFCX`y2ICmBp6T%ZNCrg*8-6&wxI-2HDS10CMOt4b^T`%#x3gsc zmZn{%O*S-6*xbuBGBuiZ%GL+@E1nu2=X6dC?-V^MlkMqMxlX^og?+4*=n}3}&HAdU zT0fc8Lw!6x4+WXQ|Af!w$}O#zo#xo`%H8Ho^YnZNWF7!CKCTLMlFXmd71?nLRmY({ zAFP0JNd77XCg=TmS<;HRYNyf$YSE0rf>2LD&O@-?z$v+MczBf-OL@6^#J}R{XdZcg z&eSZfQCsVlvV&ccHZm)=j1ssiiY+=NDnpU?30eig`_|;=%Z_-ZD3jrcpHeZFE)|Ij zq=*y)fr>bI9oY0}W!k%6PuuyC;ZC$4DvqU3F>Q$ia2W{HNbKGQwzjQY?_*$>@P3@s zCSKgk@3Zh2T*ko{nU9aYk-a^XvWkNRD(cif@YdKPIeIBWLq+F&XywP|+%MRlw4VeaFyba?tW z#@jZu`roj@iyaFi!GOMG!pxgr{DQ+5z!scdQPMAm8YM&KRqMVV|wx_bF$=h zU1K-{mpd@1p5`7(jc0mxXD2wPw?NQs((fMludmGRo{nzmXk0VEN(wNBky5 zbM=OM>LojQTReAY@G(}|-(m|-kp3KFcNa0c57NtZEQ_t?w+S#xqtJXTISz< zhlie}pLq!9?#+PfM{SMoXX5;cPnw*ko{gWi7oNuC;<=~8GQ*UWgKp`aq`2HQ2MV*` zX>1i(i=D#C5^#i0a%}FR?;0~XxwInJg3Jhb4z*hWxm?oPag~?(xm+y0O#E_#c7^Ng zQn|NpHd{rBJZ!y+`ErAH0Cih}+;w{G=x(kkaVo9f4DaUlu#~QwcX_&fiBW0&X}n|i zgQ0YdZTfn*0;9t6>+r7vfTLft6#u*1GhGVHXQk=dg!&ETmok1OQjoc@+z5GWx5mx& z^rbz`oW^sR&sTMoa#8fcm0REOb_F1&2b$c9R>V%;RL2_Q-fLwA_}bi0=6UYfAzYQ~#-~_8b=-FRuMC==r-jy^v@sxM?Ni@_ z%tt4D(twF~{qZg}YR|{vIGVn(Ux*BtbZSn0!EFiue@i!#jQg=Gs;5j8y z4_^TB9Nob?1ulk@!8>)fBQvd^_Pw){QZ~M$vdQxy<$xM%pT}~x;~ny+kApJ=Yps!9 z!4dU8%BEp5-c)d&hTc6u4qIb~?S9{qfcaW#pMDqL4u9R~^}{>-OcAwDTN#scRz`z3 z@2UCEQvW_x`Ik76r#!uH%iZ}21@L?_zS?)09zSCIut(Svsz0#@jHP|FLyOo05T4lM z0U8r-LH6ms-ij5Q%1w3aHb1_(YVB>R@I&IZ?z^#5z#Q86HufA1jo zJRW5L_o0_ZKDY0cYPIgl(|8C4*Vld19@2I9(2=CkBkJZW}Ay{@{{xsc=2I9Onajt}e2v4}^ zd3P-ALmFxJ@>KnhRh=^)TDCH|1M!Tmm$0>`;?BmYa)F&5ay)6rj!yxVCmd6q@v z+)M}jwOI}&>n@&B0RN1-2DTan=@WfYJCg`LK#$-!)}s&oIAmYwba>{Oci0$?h7qQ= z!+PyTsRE*|eWmx%$6%ILw?@!^=>HN|#+bLIL;?c%rlLMa1K0%yeSPg|JOhLzGQ)><7(+?8gyg2?Jb}lGuG2|92=Gn1W>>TvK|tg7!lkK z2EF=qNVd}wnoRJ)N2j7~%b4=vEZJ~KOA(2I3soQaHts{y3Ba0~PK1Z4EdkPW+Z8?- zT@eZRez5*CrmXiqhoooJ#~1fRn%4R1MVi)$^hJ)yc^m?ILS#)t)Z>(P*-W%fY5F?` z=315`Ha;T(D0;@KF1;rl(@U3s(#_+^W75Jdye(*Y;o{G^bv#ecS=Xg^g>!o8@=v*W zXnM-BuDmHcd#qgjN%xL(deXwKyDgm4>(+kSokP^qmUh*RLDH*Me%^f>P2)$H<}L4v zJ0nR$(<@ef;ytsbq3Ve%yx!LMpoXT`EBwSehNdSj?wVVJq}Qzb)VqeLr!Mc3nqUlE&a3`$2mQ1X;OyTG?gy1xYVk`dK$l-y_btH|%Ro0{9kj&ALy$Ydm{QUEU=(M+Y^YK9(%~w3~*e zr!DQW8-u2oE&a3`XHDbbW7_(zxG~W*M7?6|C*3niTIv5vHz^@(>vII4=+Bi53EvRl z5AyKnaYG5iUm^fGf2mr?HH!fL#3c(8oIXSV2la=Fg;aA0;F!*#1fLHPfTTZEETo!6 z0GiIi1g8%Xpg(fK1p+e>z~6J3shZde5x^fKLI<-Ez_Z6}6~%t=^GndcYy|Kv;%pUN zeLwt@rmI81{-+`UO;1%$Y{n3PrXhpr2;gIn=}Nl#hHy@=u7LUWk7Ihiny$VhXnJ)8 z%(s7NdcK;jz9VRQbp_0~|AeNEDdUt4kOv4H3GCJBrF+{r#z7whMj;St`Y7b^d_Ihgl0NbPfg=HuD*x1n)$eiK z^o;{QfUpPsw6*jSo-l#H2n6=$?`cLXe3r9uA(7((fl&$UG@VM)3fLdcbg)CxDN?Wv zLO?W4PZ%WD%ja|w4 zX2Q}yvH8~t+-q9Sh8G-C`TK-Umo;u`F7b_HxIkb;0$Gx#1KP+~9;9gob#Z~fm<0HozEvoxn6*6M!}M+PV}eIk%?OB6 zufo#_&1bYdoX64-zuT_T$JlZNSksp>HL5XG=$Ph*4|=8kAfzO%L6Qm5z|&a(qjS?L z^=4J0VAk>|N)FQH4Fvr`nuDe_2%WZR5c^xDl7n+(dAH4}EP6)%WdT*ZbFiu`gdhR}-$JF#7 zSq+lLv1o1IX|(B#jT@J}SJOAz5y54DpVy^p$H4=xjw|n%8kNpIOWhu^H`h(jz0baP zGqv^bP|0kY9VM;X(rzhtY#BNYSEJ~+3vhuX3u(5^sbstSRpxdBB@uOenUhYaM^VP9 zRJe_{Suy)NO;8Ht!#AE0CirqYm5)6I=*DTA^d(E`QHu@KqK4bPz0)q)TgJKRUSz=a zF78=ekMpymA19vosdVFAZL<>gH@jvhTm0Pw$IIPKoS;c<+m%gtzM+#{JI|Cz)FmfF zHa)wZktLQJjngW|N4cMl;;SE#GG+2bQdM4tXA=n_uR|-IUU?z9cpY-QS#u-gTJG+#Zk#EW43muuU~g1F<|8lc zCW+Yf4_Rqwmgn{dnmmh463%zU zYxjCOb~@mvQ!bq4byD8{oyIP?cTz~Ky2~o+mRA4!yC+e9;UlkZG*bp zbXMxd7v*QHbUR#ZOAQ?SD!P(eoJ=~AiUrbBZZ;znEVF%b>3FYL!^B=mAh~Fm)xPc2 z#azu?mZ>v_v5q2i`m=UhJh_=yYDg@;v)W~43Tj()b8FeQ>Dpf|g!pqfYF1s8(CJkb zQG3!cJMH)n;_Xs<5J!3HF0H6T>JbgnvRr?^KG|h7yt9$#aBI`MxXUnW)6XIwUfIrw zvbZ)RG)bm|*)HJ+4#VjsI7L52(%iP}Hb8dMrr-R^e$o{i4^+QIsZ~ePpSa6SKYV4x zT~c@Ma7y2c2U`KXmvuu-Ii?1+`;>pb>gjsEEvm61U+qQDhw8qV1Tbn^5Y?ECi z@o=&2B3uDkYRlpM7G*y|7Ka>$$jZMvd~%eQ{g0cWbc~_nh99oLVR3iEiOO;zEG zZj{^$IovEcN>YbBtfX&}FBoR@jz1T|bmX1FMY2OS4f}SYnkCjS*7vSNJ};OyTq!`k z6XG1UL`-pdXOLX)kcR0VEXi4|jcGc2E2TeEBu#$ob}m?Cj7<+U9ke zDmx|9+m}zyHr~#M)_0_~#voaRX^c=jW)*2DGK6WLw=QDChy+ zW5hg4i;S;d1V?_ks=l6*N#I=##jD4b&XmR!&#;<4;_6(j~v0k9w)Jkz01Ey>0vd7)kqHJD*P)eJ`iM>Ij8BLVXzg=H&WTI7oziP^Qx zuTm^qdLffRwGBp>%vi@*i~{Rljka1@|l?pO%~k_6my2R$^~XJI2#d6wp9 z4t@xs7oP4U?0oH0OENT!AOHd&00JNY0w4eaAOHd&00JNY0w4eaAOHd&00JNY0w4ea zAOHd&00JNY0w4eaAOHd&00JNY0w4eaAOHd&00JNY0w4eaAOHd&00JNY0w4eaAOHd& z00JNY0w4eaAOHd&00JNY0w4eaAOHd&00JNY0w4eaAOHd&00JNY0w6FO0sGH6&$cb> zXI%pJUm;%?0CqkZ0s05^C)*OXvo-<#e?+W}0K1=z05m;WL9reAzYBr`2uwr(=k!Fy z#8#L9Gz}rlMgW?gt)kcuGz|^RMgW?gt)kcuGz|^RMgW?gt)kcuGz|^RMgW?gt)kcu zGz|^RMgW=~rK0%pNUcgh(^@1S$C+8wMrM!sWCwtzvr#p7>{|HdyLoQ`X!dsvITk;zbvzAZ`xANZ9&u3rD`;>XZ0Ix;Sjd>j-cs70nk+@(DS=P zNgbM2F5&ZVy^po$8DB=|za41$vLJ5^_7_3RUG_hw@%Is1))TP}f&On%oYTVzufGTy zBj~*$Xu5Ghi^KO;KyiX)6JFR3G+kDr4&E=Qpu?^@E&)wgaPd6pe54uuBXnMG6L(&gR0!=>z zSUMeNa4E53e`vZG872%)0GjSpAUsiY0&RZ6gsyI@t-R1rFZ?vmn!KUuPIdPu2TqXI z#G&cugmYBtCH;IkM7SXUP2T{@8qQQ~j`*|IgVPlOX!?py?wFyN;c9$x+%h7;<%$3_ zeMKjCEKk!E4WiCvTJHx<*Ru;|LaG6bx0}$kN(J&Xo%MvGlF!mXpy`g~&r^QKgyvid znr>ZJ2)Q-kV|-}(NJP0$fP;`>J20cENC28vgqaF;&~(ZLHeCYHv@Xvm+FsM;@T+Cv?|UxSmXM|3x2?2n6%6inr=zg#D=D0z>S$e(=l>Q z3-djkN{6oIa^HvrO@E_KXIZA|x4NiPOwRaK*!di(n1?C11Vp(p;Isc!c=|FXK=%0ul`=DXCy*#3OP~*&?Sb1LMx}oXIIB zso_{Cu`!4M#p5eNnxyhIMK z7${HkTYlN|+TGeE6kte#Qd*gpQHr&E7y~n65Y~~}k;6)c07kTJVxvQcSBc`oP(>gm z*`SQntct5Yi8A4AIwnNh->zs+G!z-D47^CyOiYRh?5n~Ra-U2y=lyszy{{nABGwN#B!S_J?6W;Y{Mh8{JXA0GQ?)%5Q4Ic)1Xcsyo^q$wWCPA zA_ijiuhICs1`(0dl9HrOwv?gilbNMvXu6cxi9ZPG*ZAFe^nsuU4t(4{YxUni3|_MTw_ukyDO=q9@|# zOodM#fid~Un#$Xaj#r9F%2v0Ui3Cm8q05{Fz7eRT=JYsG_;=s4(T?XbfNxySBojRy zQg~=O#;#`p--u;Wb9$U8JTx6qS2Tcc1T&>MvMC8sF;tW~3`9V!RP*3WicXJHGW$eyS_}8M0e@% zY!I4$#t*YA2td;n&@g3a0?_o()x8TK4(pCxo0Z4a5P@9s?C)uv8Apeed5+ zDC2^2x{TMd-d_mPjs)&!1U@8Z+5*n$vqHko`e2O=|G2R$7Bs!XfzC!?JDrV4 z$h;Xgry*N-_877(10=;tCLQzd&j^|lrfUF#NMT3&$FMZlfAEHBa6 zjnZz0OX#`9OXiTTnO8ftbSe0Mj==t5Ls70-Br1i8XOAqp%Q|@(bHn$NJk02|Lvq%Y z(TDSmD{nUjO*;~}M+AcBXA)JBu%ci!hPs0qnyz7uIX49Q%Rfj6nhs!~IRyb|dWte) z69EBeI)H)Z6a=8@DawdV1O%Yz00x>&;MH&N6lwrXD?mhup$I_JLzQEQWP*>ShsdWi z323^M*b@Gqe*A!@m(XbbCh3pvKCNi_5hl9ww+zq82~3~|-U2i|xljwXH-Q$Q>4JK% z;0jHzQ02Au2u-h5Z|wFH1n}(fi83L{0s_!<0W7$Ff&euAi83L{0s=ieTmoGAU^k4ujZ5Q z80Yll1zvD_(DZ^upM1+-|7YPRFAug?LjcdyHPkR?Xae|okD<$h z^w8x&a^(c@JYCKVGsY$WO^;n4WLH4|&mI-fFlA^0(DcydL2?xYpy>)|m@+g0XnN@K zAh`+x&~ybfOc|O0G(B{AkX!`;Xu1L#rVLHsO-;YK_RvK^a*qhSs4Mfs+j7wcUd&_9 z&n99r+uPCm41xD5=M?SlBQW#H_{IoXNe-NnX}(voaadet@){s7nyqn}XrI9?8Q1Ew z?#(JLneBcv;e}z7+Y75EmV7x6LxKOQjY(q+B%5e_D?zQh$tU9*-BU;|=+m){q*Hg} zAnz@b^a!bNZOj|Z<}yfDOovnRFWrTbSkNcq8wsc0Cd#GvnrG_`k;*ZNQ2@ETwzt|D z#-4Vfv%7jOo?6Q#lNx)&X7YJs+1;9P4zXo7p;L!y6)t6ZyM8#2&`p4;TvmOSV@aF=PB%{ZHD zxN-SbPsW{3Fmr2qAjgJrk++vjr@)dKok`rW(P<)CY}$0=OY#$|v$+x1m)P{0zHF%N zX54I6n=NcfU>80dQEdDDyO@%^>%DbnHpj&qqc|=X_KAx0g-^fNFpHqwFM-RIf{dtn z>DzZO%)PoS6DYl~x7H-UVMlcgRlNGtdpxyy-JJCBhYyReZa*lCh3?PN1@D|(^% z{^DrTlV)J>PGMsk-&)~#Mw=#HXO$78olBTnyH!dfhgsQnQ3$D)QHPnu?Vw4b5}O+# zm9f#km^Fi{i8XVa)B@BCT4DPdCM&iKU;!sF%+oRRO%Wf_h zwGOm0Tek@m$XuJj&N{pKOv1*Qb9Z}~RQ8sdXSvJDb(*i5T)?bOc9%qSrx7=N?j;H) zKk@ONn<T4dt0LCg_{^-6FJ;EB_{KxtVSt<)w8J842r_Zi!{FVc%Hn(x+gbwmWH_P zUwI^vkC^tpZ}!3zd**RY&SViLwQF;cqFD5rYcWyg_3*h@4>p0CC`L;{q z^$w-vlCX`?AZ^K;J?VuAcp)F!-c>Mh_wXWb9SY%Bb{W|FVZxi;Fta!F*sUEVb!1a1}WJ5$r23l)(>8R zCnKO8@+|g~8MI+<3@5P9=?hH@E|ZC8$7b6LT)fB5rqBsIZ9K+sp=|5`G5Z$=XLu`{-H0s=_DMRG!=TVFMJV@=4E>3Qwgg6(RAO=lS5&S?*kNst7=G`yc(k0V4` zTty@yxQnF1nhFeLvOe49I3UfFrAQ&{w{_XqShuCAO;fHfapBO$(fV^78gUD`fh`uh zxEbt97BbivJbClyk(`8fQ<`=JUehINf^#KnCWdo-5kg~Gdn+W*J9Nupm3p70Ut6-X zcx8D>lzptRBu#I>u7%13C|T{vWlr^O3i~?3d6tmR>{;WO)U#+BvqzKAc!Y>DW%X1* zj{|TXyP7{uX&0=vqkyJ%>63ZGW%OJ;Cp&#)R>-P_riT!9*7Niu`h}B6)bv%QuEq+t zUgG{-)6XNAd=Kx7mtY*h9kMzO_wTE)R!sXQpV~6gykKt7%*y>HtDG36OQvEDryfdD zflX?!^){1`2JHF-%4Sl!l&|D`l6q=GJdr*HGIOLYfpV8m#mt>6ekaKm1}Ssz;!QZa zER?$l*EiSsbw961ktUxJjMQ-z2a_l7ONN4ux4OpbJDMN?raaU>Y;}jq=`tB}Ch%!X zvbGmBp}~K6hoR*}4q$cH$R6>S5ai?5RV|9YE8XH1A`5O4Rq;8PNlh?p_sEb@x?QS`eb{UG0e< zs(Yh6Sr3{%0n^M3O*ca;feqlsDYn$AI0=>ttyf~%i~ zbGn{g)=X$R3zMc39`-b8CSpO;2`EiXcn1hNjDzJ)D7uy@vpArW;8E@eL#8 zVE|VK8ij+VBP5Lt&~#(K^v^Q1UIOuV1OR-8qd^CnZUFT%Bs6`AM`I9(H7FLu0Pq4> zRjxRvtFS$o1WiAHmo*id&cdYV1WhZ#OooD{lUQ0B@lAP4x+XR>-578j9-5Ass9K5&UG{Rm&hWN5kqTG13}x(JtoGc>IL@iGK7eTk>RAT-?oY8cW;8sD;n zKsvMmyfI{Gx-sA=JPwfviLwEjRt9<-4w}A2^w0sCeh9E=x}go=MZ_wcfw%%%{S=lo zo~P>pX3fO0k%dXg37S>{c^L+pzQm(DD3ZoGtxGkE22Dpu8X9m;H-zg#6J*!My*UB< zzc6mT&e{t=(;e$C$21O+#>k=R#(;O>MbtYJI_dM9$Knxq- zz}$m+<^fGV<5xBt=X4pbDsO^ZH4&3)2td;{)C%W7(}lpExkJ;>_~p&UIi1Hz$IE<8 z1aKXc=TUG@pR;K&f^)h7)F>p5jR;9Q1HlIHc6=o=9UQIKKzv7lVFS3s(drIOw<4R0 zOGgMaog$-Y17b~@cd=N~_`-OH>ESpu{SaW$bZEK=SEVyFT?wvg8qvnHM-{q)Nzilw ztf#JWOyk+(DaV`n(DV%;)nPuSp=nj7Q7}3=A|ni~2*^R*Dmvl{0cg6T5=7ECMA{-J z%57Ib^o;<)2JnqXqZSZ10-FqLXajhXjHVHYHEG_(BHH-Ect`2!I5ho~V8MI?o34Tx zaIGK!#1+u0r?8}<>1uv?6QSumPC8!Dv<}DXDA4pZAJtKjG|p*Ns8KMY92sF~M1WWW zcq6zzEHv#=bZ8K5b9Gp0KK3A4YlcLum;eaJOxjuGpl%l*kqrSH8$D$plEyjR zm^r=_HU_*4FApC(6FT|?@bIC}^eiII=`%8_cAV3yIIn|2)7N~IMxkjXkXd0w)LE`@ zswMzUSEH+#XgwP=C z(DaTpVc8i}J0^D91yr;BUNC|yjK7zAyNn4*y9>bEv8BkQXj8wYHEg?s2GNB{gTNA! znS*#cz9MH34hhrSyx~DDAA2-hAl%D}Z9b-PPVY-EQ1&*xo;*%N(|SaYk@$#iTg2m% z!}r^M*)p){8lJ*;6SSKC?gkoU-d1oTX=u7Z;ao_9i(|vl;Covfq-i|u?SLzH>^Y5N zBjDOr({zF~ULn}aN1M+8;hc`j{tRdo?qJ|ky6xl5Va4xtAHC`MQ>#Z2z6b0+jdRhy-m2*gKt^*E1_5`C#xb-@x5r!zf!*UP(sVoV37enStAh>S%k zdfOE;k{H^B&RM>$vSf(q!-uteAK@zcd}C*C@H2ZE0ciS;mlgH3n~3(PY6sVi>Xhs{ zlYvK>B;{v#B+_I`345uDf~Qv~jWn&l73B5)h+(oOWV8o8wbs7e{uxSyB5jS_ZVi_B zt>4NH#5zZgv6~ziY?qg%G4i(*<_*qo@t8yw<9J$Zp+IWE;_x$AM2+rrdl$RV-vFaUC{F+Y literal 300664 zcmeHwOAqx(l2xz!SG2@_XfYHEb_lTsjo70RV!>jh7D$L+-p%U+zx>NT|LuSL-+%sp|Lgz!!~gu- z-~RH~fB5SkfBnn9{M*0%@BjbjKmNnN|H~i$_>X`7cYplx=fB4l327-ZLAQ%V+f`MQl7zhS}fnXpQ2nK?IU?3Ry zVFv#6_xMj9ez^VTN{^8_$J?()#Ub;nosYVMfnXpQ7?XiN#SfV=8#5}Z^g|{_X4K}4 ziYq2&)Xt2GD<)>t&WwsHCT7&m42dhoWyrRS4Jv;6j@_R?7Yqag!9Xw&327-ZLAQ%V+f`MQl7zhS}fnXpQ2nK?IU?3O>27-ZL zAQ%V+f`MQl7zhS}fnXpQ2nK?IU?3O>27-ZLAQ%V+f`MQl7zhS}fnXpQ2nK?IU?3O> z27-ZLAQ%V+f`MQl7zhS}fnXpQ2nK?IU?3O>27-ZLAQ%V+f`MQl7zhS}fnXpQ2nK?I zU?3O>27-ZLAQ%V+f`MQl7zhS}fnXpQ2nK?IU?3O>27-ZLAQ%V+f`MQl7zhS}fnXpQ z2nK?I2^on0?^7piT0jm4=3*d@nYsEk2--iz+zir*fDsJ5n1MKFUfkR-mG-CjI(>=R z7pIMxd2w^URN9~Z9-pT#QTyJsanQWCw_mF)&Y7=K``W~D(7d*_-zzK*n(uM@+RSm% zytcL9E9|PFxhl{1Dvit+F_8YeebM(R{t@9tEg3(}b*;WG)A+3YIKqpLnZKt4>#|fo z-jWH*zo^yMedZ?M?AIZlpP6*BxL}+!Zu#r9zPbL(+MGU4@p*dlq+C#2YuH-43$}_B zZ(yK39C6URp|@YEA%^2i#75d+AQ;$Zp#9C-j|-1rAQ%V+f`MQl7FIg#Nsy@kkg|%4j2-<=)bUw znfc8rDXXR_NP|&od1dqBgqC0Eev1Jehi270O6tPTrepkZs!huawQd^Lt8-3CZ1}ac z4aZPT&j1et{X@L1TAW*ZI@;Q;lwq5c0h)z<>^w3!UseKQWcEpXhsVkQEdN0-{h6C< z=J6@(hpyDb>U|8@k+y zey29;a~a&2fy&v)G+~)#ehn2pe;Ma1;1`B_PeZZ#2DJ=`^LtAkdU*YdTSSHZLv@AE*e^}fWRSLTHK8GYOwa+8BO zpkIO#JCAMN!9AhBE`&Bq`mBin<2gCrc#>q{(1|uhV2lPR~~?<@$l;TWiF_!YOW%I zJ^fvl(AOBWldj}0LXoCe(0FKG^JYPoYL#bpstj{4QC3+2bs)8%)Q-B6xBMJj>ZuDw z)g>JzJ9$Nsi(5%j%0%dB8cWl}D=De0K$s|%|_QJKOvnZagy*=#6vAsJldN3@j|A-!Q9{W^Lk=ccl(Rd(mJQ3m2XjR*H=u6t6cI zM54GzSdp}Loo8LKVZ{jva}>g0k73m=)3XTGqa!Qfa+sy(Xn3I!C>+R+^m0%}uE-&HNw``936511- zqq*f}NknaH5=dF9?C_BB!vk0t4pS?$lApsdnfm;2r^(%kvUEkr1zNp}Yec_n9-TANI$L!oxfg5TQF1K6sw{&MG$M5|xPllM`_l#F~i1tp+K z;Z4Mp9^}tiVPa{%dlR_hqG_M6%mT45ub7dvaJC}GEec9_EL6qOc;W1&OOv8ju zGXstqmzCT$HzJ->H4E5=BYoBf8cCNvvDnDqj5-?dMhHbxF1cX_Mavm2wF#`B>AoaK z2PVH0W7k8yIx^h8r_{MhvD-~?$YDwlG?)+@J`>!W2~={^z*(NYjEtFP$m&^6RQ4P~ z;(_UflIm()auQgl_p^bzb|O|cj4mk?&+$$@gV>x0tt35%uOT%#H7CLBgxctGOVv}i z#lcw@1V$I~WFzh_Ez9iT)WeIuh61cqw`wn(pIgwWfG+g{t(w_h_SSO;X|Cz3GUKhQ3+e zP>8u_oqVgad%Ct}?V$=W54ftJoJ}N}FFkzNnPcR>Oi^VVdkGqVu;yVz)CprR+t$YB zpqTYw)iN@RDC8q-Dx_VRR94hvwzaj_v+G5X1P5i(|FCMiJPW(pUD{A-8%wl=FK(o@ zQ`P!x#BQo6uHnJtX;yxcn-hK5S|0E7sEn7R0f5!?<}|G1sZtGz>JD7oC-`z}Y+VW+ znHDa{uuz)9<)^Lj95 znMW@@MSfb?%q&tQv*jO8XoKVW@EU;IkuO5mGcsI~yUV0yjlA_J`oN{`plUNLZ$zw; zKkF>e5|Dl~+h9g1jyOHW-xGz&tXjrFztoPP zX~R2M>khE!-i5P5sY1!8(ha*zV}!qO z4U18M5mrL0n#Pk#k=vqgrbpoEf{}$NYi#dTvKv40b`sYB8zVWN8 zEz5?_%aU9hFm#VRGLTeDm~0^eC9Rd?t*IiRc06=7B4QoP)&{qhZt?@~fd#3>IiD6S z*A^7Yo;+n}F){pCGLVv<9s`^Qzo>G+ry2$at2A%2s=b60Hwz7etk*SF9?QnwOf+EO zqG7JVB*$7c*xE?N(2RW%Kx%%%xsFy_$<$-zriGSQl_@)Qr4!#`|5QU-SK)<6WgBA2 zr{nN2{e;ko*d`Bk$VFqqFLKfpL(`5uqt(6oVig+j=*9f&ip%tNv)n6WfUSMCkd|#6 zov*<$UINro>{1VjvLFAX9XS$aUW0BCIif!qqsIEw_8;8u{w0jNlTQ>m;8 zW*?%tz7hG!ZhFo4`O_%l+-?F|xoISD6C{-n`ruXMc}s0t>(pm;^3b5!vTsVaz-4&J2M+A)w`P1^gG{(8-F?e?hHYnnB52QHGc0=o zcuip0jh+s)mchl8cWEP(dwU$SdpNe`S_;}8HDsvC)gfBqTWZ#lU$4)#Epk%@9{Iv! z2nDERuA6YIVJg^*;DcO$npw7$jcD#EvCI3=_G@X_$ipr&T)8xosx8Q=(yb-GNuMAQ zwKr||!8Ra|$fc(yGB#n}zEVi4RRd2wvB5G>v~FS=P7+2CNhV42z={vE2k<<)zEy?L>}E5vnB6>Ohrp z8K!z%0A#B5!}ss&g%thQ-FSAa2IfEClbbB?RQ^A!loIOx^5ji)FKvG1l$QoY;c)}Z z0qJbP!ctQ?+`8m?YmB!-=-dpvdG454H%n3qKdgha)H%7JPUNc)^NzexWoj+e5ovO$ zd9o^*Ov7$&`Lw7NJdI<2e;yC=<3l5fnR7_R5=K?PQ~sv-Pj0kPk-&i{^lJ--%2tVG zd{7ByfEN!a(A~`nn?yLfuQ^DF^k6v(X2pcGm}zgA3c0TV@}y4 zq$LB~6`BAy2hyvhd)8F#bd7L6Sv)7{Cg-A4l$3{&(M3`vb-C93WI~K8;@M(=StXiG zRO(v(qRYNuKV1!)xib=Q?tyL2MM@OmOyIO6Ub8XlYzu5gdw#a7<$Iw(46fZ;W566J zv)llBXP4xlPZu!%X$oM(%#>5ZSp`4Cl%mM<3gAmdUZA0-5^Za@%_1de&4D7%n!l&NyMcS$&D%Or7Krs5i8S(>*>zqf#q zcB?pI=G-0P8eVfNzdWR-IEuuLR%>Z)(K7 zF<4^Z>DQKRW&56u&IG5J=5e2KBjKpG;hG5cUy5NlWf2 z(|Vd4EQ}yw1G);FTap*2h7w?_j_Vy0Uf3; zqtm9Q6U477irB>dbkFu=(nXmduhjm`lW^$Pd1id^G)(G}o(kQmeoV|fB`)MuBVrso z)zB0SAxc=p6B+Ua8?Ru4^c~g z;yBaBxbO64RR}ztxVjw+y5hfk&YGzDbV3aE4Z758?u|SuZ1hiHcs!JADD^GYb zF{}}iMCq)O%5wW|48<%8l9F82R9)7Wh=~-${op0U(8CyDWooguTg>(lqS9K%i5|Q( z8qJ#p#Hea8qBB5X#Q*eK8yPMDUW1kLeK<@FdTBI)HBs|G$SOZPERF-SupgVhVqdPla&oRCA|!)CeHu|uu3 z5CN5eZ=;0Yw#SRCnUqq(=%g}L>5u6qJ8&dg@T5bhBuNuBgG<+ER}3^`pmkoZNpM@U zy-CmXtln*4oJYHSj0sEX= z!%@=&BtrZ!@Cx@r?OeQmuSy%gJ;#CVF*8+j+$@l&BU28N_eu%evPxGilOu+Y0xHuy zOH_LlEi-g9Y7&1gPVWgci2$#<;+fP`m?>$sc9UGncQ9%e_dFMZ7>Xojy+}nt7%Orqw95r0;{;3NESiM> z1XL>hMBD@++)z)8$Yx-nEF~LD{bFT~3(G``RKy9iDE&m(1R>VcTwhk1R2O1~996r> zT0K|HQ>dwi<46&9JZgprZK{=L3KH-IT9#oxOH-v`&q_Jl5=ETAd@}6BPB({eQ#~oB zVWL`ekxTJ!eAiI3=bCjEJ*qg4^<32PeQuASrWVzihG}ZC)zaOL{KgH5lH>aov>p#1 zHbN&P0~Ad@Mozq9Ioms=lig2Y@2J13f=8rK7Nz2k)jxj`Nyk}0*zu_0BUa1OYF8bG zFYQWzVBtjj&qZAc{2RIUs)GFlS>J&AXwGviypp_~qF_$fqum;0^K&%3lD!QoI{yX1 zAU*vyjC0*T7xnF0KFhyV6KuFX+u=3Q=a_gQfg41iTDo4-_0I|c7soT4i#oo~jS-tX zys+L+s69u=xu{QYemiz^W_a^6Z`ZeBKa;u&&^Ew&mjhGt{L-QgEQ$_m}bhzv% zd4~rk;9w>EAHg1tI=IQ5?j00#xZH{O;k`}_O+tJw>fut?w%>niURCZI4F~k6UZFRU z_@-J8^!*c8PI3AGDpOZiGti#Bi$rr-JURs&}uC3;8%fFVdm>&QyISW~ibC z4C?sk=R76&EX9bt>|#2@+nJbMAP+d49vMuU49pLX4Ap+LT`!uM6Xy*6U9C>coBq+m zktsOwwp}VWzeaDFuGE56E-(`ol(p0E$l`AO~k1W3y(<-#k!Zf*Z3W+ znMr#=`DeP##rr8alVyJLj#a&6ZCVC=>vxJ^SE(JpXxx>wZuKMLv7+BIGzWSOSNtU* zMWia9ot6U94Nx!!{oBABSAWEqo<~aHg6U3$7sW&Uc!_soI9fFP)Acw{9|AZ~0aZ&y zb5K$H09-J%5BWG2PFo%d8Gxrlcw5e?{YCFvKBVK0#l|^DKAELB%OnIBxMnu7M=yCUWm-lgFGz|omCuQ*-Z$)U5Mpsg z3=LcfTO0X?H&H=-D1A3F4=VNL_?nl(py$_iX(!&>Q?Sw7g$#TC?On#v0)HnO?CADEQmu-J@8&%k>wggSQ7&pemfedB7YgZnRfxLE$^=#OD z)k??;>!y3*Ipkui*bEq-VfxKrs>Bg-F;4jg=K)Bxw{cSng3Bpc;}nyL3I9G~_%sS_ zsP=Px&x7GS0}8vYROSG&i@t3u{^P4Rip}8VkO4249y1Ufwt8CN=E(hSFxa-eCj%lI zc?iHY_jZz@w5z2$lvX8#q)&fK7+IX>vm&99+wDk*k>=QVM3D8&ZaUwN`^<(^#9pA3 zO%MKIlS-E}b}#lmyGMC{L)M67(v$^$=@_Z%rhBfHS`@-HR(E+{3dd&`1;D$Z(B`d8 zVJP$pvrx{os0(Ui*D}jz+xH=@9D9oJ0Tk6}2m%7+(BOoY%W3Bl+m)6zXp!kDzh)qf zcX^!mqg$Z_pa_iIp9OgZEmqNHGO3e&c(LjKkWt(5(Dv#HtwS*^U@qo3M9a zOis?vi5;=Gxkx*1+pljUHzfM!22=HA7|*L`0D62zsI2b=xEHAn2)&!MqJLJw(!E$N z+O3P`E~kqCeUhf<$owS#saP70JR#uHjnAo+&jz8E4g_6J9eIAyg~o+$sd{|lg>Y5P z#tCrGhIu}`G#$#cJ~2SJrYmPg%+rw!z;eD|Lclps%9JCM56USUF(GIfnwXghd-o({ zJ>2Q+neyZGBzwQMHyibk*oNIUVr10W0lzXXWsj zr=STT&qMAy(oFk=LzBU;7Z{f78NlJf+)vkm38(z}{(Uv$?nq450>GW`bNba5U!HuI z;a!KzA$^t*c&Gab_F2hyM-#qp)`QvbPB(5kGBGpL zweI_XSB4_ZOgc&EuZ)5I8L(SU_T~a^Mjz4{2DS*~aai@Be-2DOt1f2{eK&?{`tBaD z&W^5E$B3^t89}jEIa#bcG;2=Ie+)5Z=CeL@wR>%5+$n=RpCP#~I%eiGuDfQYy@iC@ zqwO`ImS<*~5g(4h^D|?!V#096tpH-c^bZMEJVL$6fOdS-sb$o_{A_uRsLO~Ujfik? zOhTZb>}Rkf9@J0M046-&2#7p!{GgBasbLP}g%BZAA`L6+>*ti_^ z@*jHQsM!b@#pHnRlsF3F0dYvDiNG{Big24y&%8!pW-Q#4qX{1Q6hl55fxttJrbEWi z(Q0#O;KAoodgQnXnxHd7=nZ)YoeUJsb|aE$T}zZbT-ciPV0y)l=U~t#fRjmM9u;!A zQmuQkLt>oI8naB%1OdNWq*WDyV<6GSE5{!+v~+$AkzLr?eVn}5h#Er0#mapML^FYq z#w&>mo!7c*KJ)oPQ^&KHL|Qc?hEZy@9aRp4c_1J}oBWc6%+Q$3y#dJn6lJjkmA3*# z>Z8YsOQ=^FNVM^XNPd@a;yk*=K6X*z>mTladR0Bd}RO+ zOLyd8wRw@hct{3>Z^jH_1oSC@4#HQ4LCk?XA+Vg7jw2({&dlSUqIvA{2E$5J`LO7Q z1_tU3m%Si=c9rjsfr}{TG-8N z@Hul=X&QP(sE0;4FgP0&u*g4R(;zee%RntGJTn-cg=t`gpdJ|Ez|j26@WIk*KI@uu z0aMd3aM5x+j*M_@Z2Zb$cFF^$m>nIOWhoNAG>oia&?6%p7n{xtJ@h%w|2G%%0DuSfr^b7XP&yo6rWT((L74IQoM&z8_bN)TM(vzNC zJS!kWI`ijb$}l&ROoCD}cP&?=S8n*p*`0ibGzz~O=iT{~m%I0!U_Yfsp7tl?v_6iW zLO9d$;K3q{kil?04o8T|4?%Rk?-V)ZAC&55a3x8b-h>nHPo3^H>pUzXq1)hyuhlvm z9Ht0~qsMCKGzOvoghG0oq_eoJ;?MytAI&#^ZlM&x8* zc7z;#rw+`F&C7w9vDpDSu!0vrgz*7?8KF#xQo~ES_iU_VCB8YjCwLkklm)PKeolk> zTR^SJV8kvtXJpfAE}&JFKGoAQ$a^XJ=^v>suEB)qOFCVE@3F{fUSxb+)@nAyQV~cA zlBrU=G_#7R4299VG;0yp;HD*N|KDh?X%FEyL`Os$rs_LvM1mn@AW7G6@-nKFb43?4f|VE!j)9|mZ}ccLDeIMK0|!U(5J-)U~NeJM(m8q zYkPa&>1Ac+7iw)bOS;Y9Aj}Pqjq##EHVY)ctQLw$OUq=2mkP#Brr@QOu9ao&=P5`$ zU>=kgi^4F`1viUPmFPHy#k^BcYCzMkUN!(ihMXIY5^&=Q%8uZSRjgeF^p`2ywZ_%gq zGhaV(v=;s61+kDsK1`Ss95vA3^1O(z*m$ zPTnWY1?JCz5DR+yJl*seXeNYX&{7t()Rgv7S9Kkq;RFkIeU|DS(P>KPpy98ye3&pg z#CxJ@#xk!3ZSw+QMmi2)?y8UnMkXdlC^=bkVB@D<6X*+ji)?Z|UD&txr!sdpffxOt zqbF`ScK8O~Nwb?}IEO1|hJNNH9zex~qc|LATIU`xW`ewALTFx~uu+(| z_%j_BCG6PqHWyzUl?Mg>(7cDB4Aj+L)bMsxf5oMQT$S$%OjqS_wL#2ZCr4eg?kbR$ zSAlvm&*d}oWHDdbyV-jvZNKI?EW^k@M_Kq}f-C$Z)eZLhDM3Ob8bFb=()NyEO}l?Oukew z{Uojm=NP@e=8R!_s#;r|?dy~qqHy1RG7qWFO-$18mxfKL9On_f(tjPFIW4l-Y7deJQmaWNk7RJ5Gb}nX(-K9PLzYY>LJkaRivh=*xUnWNtK@El zk6|;YguTMVy5gX5MO(xq??zSJBTG*o0bm7v`Nj4KuI^2J0d2rZtACoN*T8?K5YfHW ztcB{c}o^pJ!qi|LYWE=~eyNGTA@N4*zZ$%6x`pxXPz>&sq`g73s9C}rNnG9ZbJ ztZF`#8N5R+btq%Hq^EOxzo-m+Txmg}E>cz}e!R!k2^8D%nQ+&ev6D_y5mLLxx|4x| zMOh%!iJh5lb8A6PIssk4U{|vgk%i+AEEccR>6!}~b)ge;-8QH3wE`7p`Q$?;LC&a? z1C=86=#OE=37 zz>v@|B&&eRetCk-cq{O?Y?c{SNh?#%b)BBM5l(rxs5lo-J~{Z;iy%!kV9kHglcMg1 z{JQ;W?onW4Ubya6!)>(GaNSxkhz4cw#ZO(u8S{Cs9O**w=Q+QaVF4EkK1lSVBrY-} zbkg9!QT6&8@kQ9LO3h3fqiMNO9@#cMHi9oQY3t>Q2cySu=$!a^oFjbW`j~-|QCe;1 ze4O?cV(17q8*O-GX(O~Coyv%zv+nB(AO%>*xTDg@8LuAx)`f6lWKcz}2bgOxT@ONPg) z)Vt@%m>oG%-3WX(4ViwqUO-@YTbW_tDBSFw2aIbY?a5EEpiq$SQ1H!|h|ft{|}J@P06 z10SR-+@nPOQm<}( zn|WWLqm6Zm1s^L4Y_EW@f5?Cm?Vj5iyB)XF9JkWO9EOvHj+YV)ua0Mqh=U9`+C|(< z;N3SJzhI=jId2kaZWIoVJZJvG=8-Zppsc%RHZG;?W?v@#HY}abXt2RrTsCDGBE`h4 zk@gM!g8tQ(VR!FsXh?ZY*DOD8Wm~Y2tR%n-0(qx<)0so!{tX6*_~N#{i*vJcrWzzP zlRLYfX3gT#7vj=i=S0Q@-b<&@e2amiJG`K+L|<%M_^PE)x&&(PeKzuls?H#r&_hp~ z+9%fEV;~VWwwyz( zHh@T*$WO*t>S%Qwd?SfdE%G_r$qg4NLve_KL_1AG9*HcWB{>;2DBtjQ=arLkM3>|u zn_``$a;nX-zJYe+w zygy(-XCpmzPS6i)rlmHGMPw&uGyg8Z1(K*KHMkxP^|wJ*$9Ue!fVP2WhMQ(H%>qNLY8Zd=xD2vr$R ziNceXg>^e+SijGJZUYZS~queo{JgUni<4x zC-gfPu6fI~9L>a`{3-)=S7=@C2o-fzePO1PK@~-x%V3+XT1{(BK0QW_{0Mz0N2OLPno-!@|ld;)QjjFQxjI@K?k{;>unMd)h;LttBfb>*agNZ1h z;EcgV(^N^UFWeUk3ZeK_lep;E+Ws19ibaM{Ji`EYhF)wLkK7~lIxAVPYwh$lYVCW& z%STM;M@`6Tp;m9^@#sES?lBNlIfec%0DEru}Ge zcmp2PGCEd|Ga%iU9;J3J5aqtBlf*1MRY7(;qZS#$Aoq>_9zGD&HNjie}oVlff}(jn<2dRJYrK*b(CDGOXAf}#2CRcwXrRub)Y*9_= z7pw6Z(9Y%O5_7hZv~Z~Gy7Ydkqn|Wt5T!2TIST{UO%rP5W~h72Cq`|ywaa5VJ!HsM z=W_uej?92-r-~I^RoheSwq6q~k9SB)`Z%TOVYPXMFbxB~q3tfNcr4YmhB+{8TDo(F z)zi=vKs^K2Qx&{1$*T5GxcGHb<~(eYX-NzIXL}sZ9&w+Jfn~qT5|(!PxHJq-#YtGf zpQEHn%XHImEBA@jL=3n_ON&eJ3p-|JsdO4SRVYnT+sGhHl`NDy#cCP`wA*vqTA;BueY938*3N^%YHU_Mf3qcMWo|TRRr&T#6WdrALIfZUE1{SlTid;z2?4L5~ zUYsMyB?c#|Ydj}q0KIHqxuDedwu@=AZz;inH2N&fv6_w7I&IlHHfc`gN+6+La1 z4xyQlfqGQ(glI7fk5Zv-#lrFbZ(@aY_6oua?N+sD~yvepzY;Zp(1E{lBB;$)WttH zt5wHMr!daTfHc_6OsWMxRg!^~>8Vp-&Rg|%Ic+5f+u#gvhj~mARQ_R0_vNgp?^a1M zFIuSG*X>RI|(%#5$F3s{PnxYub05#ex z3R%X0ABAPHP}hYa6mMf-b!Kp0=p3v%Wj4e$D?)lN13C}xo0305d1!VBh>_VL=v`*C zyQnBDWD+WS;Y2M5}*D+AdOy9)tz;w;l>j;a2_AtDh0UiJ<65@WfGBF*V z`?z|3^ylS8J%GhE)xfDTO>o1HSV=Z<5T-_8I= zp{GV3nJ(9!bm22G1AQ|S6Eks(uZP}q&hW@wzjtJulYx$dCPrq?)_xE5-a!)+^F8jT z&Ak01m_}yW+5-4@7}z>!Vq(6-`Se*=hlc;j@AUOW0bgKX?dyb7<_p_J%J~^+e}H=a zd%gKEUJV@{I!D`7M=#b+o+=2v=uy3T57Vq#7+`CEbfdl#oo8kyfJJ*qv) qfKEyrGA9ZA!7!Q?+~Sn^!S0_eISoq;%vth&G>*=g_$l*2_x}|oxntP? diff --git a/src/FAST_LIO_LOCALIZATION/PCD/map1.yaml b/src/FAST_LIO_LOCALIZATION/PCD/map1.yaml old mode 100644 new mode 100755 index 7af667e..a80b0e8 --- a/src/FAST_LIO_LOCALIZATION/PCD/map1.yaml +++ b/src/FAST_LIO_LOCALIZATION/PCD/map1.yaml @@ -1,6 +1,6 @@ -image: /home/cmrt/ws_livox/src/FAST_LIO_LOCALIZATION/PCD/map1.pgm +image: map1.pgm resolution: 0.050000 -origin: [-13.175220, -3.068274, 0.000000] +origin: [-17.402567, -15.452375, 0.000000] negate: 0 occupied_thresh: 0.65 free_thresh: 0.196 diff --git a/src/FAST_LIO_LOCALIZATION/PCD/map_test.pgm b/src/FAST_LIO_LOCALIZATION/PCD/map_test.pgm new file mode 100644 index 0000000000000000000000000000000000000000..46f9af23fe26cfed8187dd3b9b068992afe3e4b6 GIT binary patch literal 2616297 zcmeF4Nw4n8l2FgMe#MiRLly9Z#0(+EAjBM%5CaA!l|VxL`X@3XGO}~JZ$3B6_Z&Mj zGP+#$7qPwfzW4r@zy967_{)F%um9;k{I~!7U;q7I{^=k8`M>|4fBe7y^MC)#|MAcN z{FlG~mw*4)zyHfW{i}ceU;pp#{^8&K+kf+yfB5U)|HI$?>%ac>@BYRC0SG_<0uX=z z1Xd9E^S8hK`4dhY5P$##AOL}f6Oe93M|=29Bz*`#00LhpKqLG56Tto<009U<00Izz z00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_< z0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb z2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$## zAOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;| zfB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U< z00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa z0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV= z5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHaf zKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_ z009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz z00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_< z0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb z2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$## zAOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;| zfB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U< z00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa z0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1R(H40)L*E zG&w^60uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV= z5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHaf zKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1fEOa&vR2Ja|l2H0uX>eBJd|PGcuAw9B^(SO009U<;2s3zJBZSrmbWNX zzen<90Rad=00Iy&0^w~-4|qTT0uX=z1RhL)X7=ElN9quO00bbA3Gi~3SulbC1Rwx` z2NU3zJ05)VNF4$YfB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHaf zKmY;|fB*y_009U<00Izz00bZa0SG_<0uX?}V+kz(uR=a{izE&K2tWV=?y-RZXmFlfVQ)A`WrQ2H9-vSL4Zg19`}JPAn-c^sg=b+$b`c1 zyW2tJZ3Ot1`8IA?LEvQs+Kwi3dfLlw^4qt=|Fib(cbNS_U^xNlVe&u!v_pTG#%tPg zd}#ib0PXCz{D}^M`w{SVrtfF8v-{m3G8!Sk!#V;6F$6wKpnOG(FKVAjA#(id&5P$##UQR&2;V9pCj}s=9qoAiR@oo~AOHafyqkdhUPx$Z@7^T4g8&2|0D%t>;5&{VxXEl00uX?} z7YOin_JzC59w7h$2tWV=5P$##AOL}f5a8!$54lmK2>}Q|00Izz00bZa0SG_<0uX=z z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV= z5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHaf zKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_ z009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz z00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_< z0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb z2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$## zAOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;| zfB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U< z00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa z0SG_<0uX=z1Rwwb2tWV=5P$##N&y z&MF*CAOHafKmY;|fB*y_009U<00Izz00bZafz1T?Rglf-FoXaEAOHafKmY;|fB*y_ z009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz z00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_< z0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb z2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$## zAOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##mJ#@~Obsmv zKmY;|fWVyz(9Z6BcgPI_5P$##mJy(vE#rh11Rwwb2;7;#pFi}oJKrC2g8&2|0D(mW z=w^#Bp#%X4KmY=_CLk|oyq?|q7LgnTAOHafEFeHHTL1|a2tWV=5V#A0@ERs>Vt@Nv z{oO^n*X`MA_O3?ngG8Ruo@W#5P$##AaFYZ;agC*%ZY>_009U<00L_X z(9YHpLmvVVfB*#UM}Tg2zk5PP5P$##Ah4PM?QAtN3?Kjj2teR|1o+9>{q6}FK>z{} zfB*y_009U<00Izz00bZa0SG|gi3Ipw;}h>1IYR&f5P-md01a(`1OWsf009U*jR4K; zX?Ki#ApijgKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P-lP3GiDe zcf2d)1OW&@00Jusg#TJ39c?8u)FA)?2teR&1ZZY=yCdWS0SG_<0xJo~TN&+aB{b9_ z009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz z00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_< z0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb z2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$## zAOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;| zfB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U< z00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa z0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX?}_Xzy?vvkjk z6_+|h4+0Q?00ba#5P?5(Eb_HbZILgOAOHafKmY=V5(rI7JKB7+n%6iqF`PjF0uX=z z1eO!X?QG^9ZRtzg^3Z5P00Izz00a&r5V}}=J(J7dWZLshH|tSB1_1~_00MU+Am4B- zn_91-@x8`7-7#{300bZafe`}5D_ZYOtS1}sgct%4fB*y_@IwOi3!1)-<<~UY*$?jw zp&}7`v$UILd2L!ty44b$YqKUA1Rwx`&l9lsGkZt- zJPZJwLxBE&4p+QF00IpG`8nFizgyjCGKIie0`h3-1Gd%>eF#7R0uVTl0Ph(q+4|f6 zN;A|U009U<;6wtsnWf(dJu%ulTnjV(b)$D|hh0Db0uXp1f!y6*xVeM2WPKk}2jRpG z1Rwx`V+l~67xLsSb|EO#AOHafKmY;|fB*y_0DK0uX?}Zwb)Qe#@We5P$##AOHafKmY;|fB*y_ z009U<00Izz00bZa0SG|g=LGnH(a&!I2|xe>5P$##AOHafKmYN1RhR6`j`EGJ|4ai(uV*9AOL|+6X5?@_37Ks<{>?`E&Lm23n8 z5P-n93Gf56Z{L4*4*>{300Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;| zfB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U< z00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Q45!2i4G zd-t3jLjVF0cp-s5fBr^Cd*OX$OAvqn1inQ;|4-@P+A_O^00bZafj1KHh8Et@cujlb z4Q5XefB*zOLO}bOH?@!KnQcM<0uX?}8wr#hjaRfc-eL9x0SG|gUIfA~Zk%-Fjuw75 z1b#~({5K+gn*h-l5eT=58?}fON)Uj+M+wM(^5_>^|54aq zZ1s?sa-YJX|1tcZ+^|D-ffEQo00L(b&=Pr;^9jGaY)ruEEon3Je%4b!1_1~_;JXCE zSNXqdXS`ypd+@xU{pMwQU9MG}#ISAOL}P6Y#o!zg=24Th));Bwp>`N4W0}@5h{sAOHaf zJe7bH{=4RGO=(Sbv5gfM{TIgNUmNFu00bZafmaidZg$A;TO3bmeLIUe6zxohcirIe z$nXdO2teS&1oRg!?)v%?+R?UKGiYhs+#G4OaVJNnfG-F@00NIA5Nqe661ur(+?h(# z&+eQmxj_H|5P-lK0eR(;wMCsuEB~0Mhsv97wy3S2yVV<{aP9{24gm;2;0yvqIiGd^ z#&#BetMOJ_qoK_{iYPz;0uX2j6y0q8r%$)4`OQYQPaVN_4_HC~0uX?}4++?>c6c$@ z*<3b3c~0et>tXL9?N@H?iMNBCApijgtRs*bSsF~)Yq5W4JG)hnrm0Rng{(mU0uUGw zXx`11G%9U-14mC6$g7#Xo;`ghSC%t8q74NIEdte?9n2!Z?LbfZ-6 z1BFZ=009V$5=dRl2BUh#LMZz8s{BQ6dxkgKln~yt6>K2@0SJ77fV88u&rrjqbgCdr z({gv9CgH?!A_4H82p887fWS)#6t5x0P&OB9=u9b<1{jW)(75L|pnK2zLRJufz`Y3M zUgV?n!d8?~UmNBgR>l{H>PS`+&==;FHmE}Y0ucBjf!wtGB`db4x=UrX29k8M(ZxoW z=}H2CT?q_z2tWV=fq=IqZBU_*$~@K6v6kh^5Ilu|;624LP9XpR2)vmY^$UT0SG|g zI0DkAtTly;wX&*Ld2ua&+0N9q=0G=_B$scMPLC{#?EX|-1UoUK{0NUe}L1Rwwb2pmhGuGz=>zO6UuWyMkF z85hdm1gRC)&BWb03$!5s0SG`~9f1#**`k>ZDEQhMm;)!tn0A&>Fn|CAAaD`^{dU_) zzVGeUJJv|A(d9Ke@NOnAVm@~J;LL|yApijgK;R?-R%yRiZ_9pG?mqHZ--7hFCBzV@?i?^Eus_8DfS|8vI|hB|j6c!vN4 zAh3qOXNzCecuETKxAP}j&_r|UdKKZCd$LFO!ccqC#1;Y&fWXlNiaJ{i<4=F|yJts7 zyoo<+Jetg~1=y?Gj!X;hSN@j1hTV}irVxMt1RhI3I+pgas+m1@JDU>kw6n>+und)T zw4f`4O?j<1x-iuG`{C&+HE&&YE3Hm`8NmoHaPCdT6l z#F~>!_v3f8d;_tajh9_-V}9+s9=Gr7A0VAh=zsvnxcC8?V-mlg7aH3A?g<&)jer!K zuNIxzZkEvKPaZ2w)#Un{`s47|Z}^!JkNT=3+-`kXpGkqNA@BnNpR19x)h5)C_$wY^ zpp))xnf24P+9CYho!Y_bEvDm--&=ObJ|M7;`B054w>soZu zTBowU%i1H7JQvoH2#)l1?ym6;f!`6}bJDUmBJx6}E7r!eoAp`srLEV)<`;+ClJ^5r z+_J5eHiuF;)Y;07pbmk@5vV^f_3Uw*IUr&Eky-F#jVzvfenB;)0+S&VBoKhW`2=F^ zp#%x)hC*m#^9}9%TSNp1KmY;|fWSfm-nf!_Y-D9S^Y1_=9R^(j%@+k-o%ai&@cw(u z4sS<*kDcBUZ(nwQ@_SkCXKgnFT>n{yOP>o;2teRk0`fznj~?<9GTFMnsL4DWDv5&< zj*C7@i)~L3uxI15pQH&gEI|MQR}ipXmfyytCRu~aKU6C#lq{C>D{>^pBM8WY!PD`G zTSbzuA>hT>ufDN%?($DuwTY$E)RsSuX$lN$_B*j~fB*!pCeW7UFn{HHhren~@=c9Q z2kpRw>{1JY6`C?!V1Wt*x&(N7x>yiG;0gk7 zuHDw97W}ZwUQ87Q<>-p1ju;St00fRCFsR&UOSqdE=c`xoGxHO2nav`0_PAYDsC}6C)N+W=Dq0~ zn!KcOKmY;|fWQk0NO`YH{LHuID%~gX&_;GuJ9{jpC*4tUg#ZK~kO*kiwbC04@SE$f ze#aO;815vv zmLq1C23s@54gwH>00dSMkos#i*ekJ_7r(bY@HhP{f&=v=xIv9SDuvdM^|IW~qCA<)C{L_o<0h!&#>%Djc!r6Vt;r z1Rwx`69{xGUlg{jKuWiLe{E?ZQt6lKo}+hA0?u+gmTUkwD^kJ8UP|f3I%CEGu9~aj%KCiYV+nivy+hMKtZdu(w zpL{Fx=>A#n$?%R(@1Ff&3xPQT&1c&>Sz*+yr4Y`b%!b0 zQ4mSv#)C&Ee+butz^M<-A;})&b(az26BOjV( z|C!kJqYbHiOn+(Q@TBhLPIGdbnD=%uLLM;cDn-q z&!CXKZhA;Dg20;yq)&kl;`bV*yJyk?AveWF6RmX z2)vPiG%x+s`_(ro!qm-F!&lyXZNIW#yYW`v37*Kzzx-%JpBVCb)%JT8yQsofG$7UTv4hZuP8gHpr4Uwf12eAZituLjVG=B4AZe&-U>T zXZs_sX4d4s(adze@l@Pmhf#>u3}ZW6W3pD)?%P_c7wPvpxkC9onHSw;wgQ1g1mcH2 zT;z|P`j(jSf}sqq5yzSBmUv&f^MQcW6@ zFHIG5`L)D{$mo|%OPlK!)|J)6C@BRfs$W@MsO!YRj79=5EV>3d5)m)n%jrNGGZPojy>=_mJo z`LjpB2N95l72DRxr^Cv}gSNCeRpl^3!JJAR>AN2h_m!7RzXN}aNlV})&|~56C=Up% zp~2#gw}+g5KtSuVd@$mdx-zdm9!XG1e~{^wAt(1b+RH+QlZFd-Ah$wXmA=aHLN_l{ zgFyF&%GX}q1%wdzDgmva^2vxF4ZVhO`lR?kuRi%GEr)dC_8Y=BZG= zg}^2P+PA_fKgWUkF@Z;{nEU}rxO?Bh#&F@GE%+lRo%2w26?vo^Fe z4+AZ_ALDV&cI_($;VYQ+U5_szu0c-}2teS?1Y$Fjx@sNF&bno5Z*SiH5B8RzI{BF# zXmvAyScU)uAdm@^uL#oDLQ9iBsq$t`MtcZ&2g_eFM8*@OXuCiP@cXUbB%qLnb!}e2{>C+bfhxt1()A^C?Jm z@*FPu&AFKFeOj9ljgSkx%eYn@ZJEiPwI23F-5DjhK>z}gfPTSmuL@FPd>Y33CLmYQ zd{j%*(y#l|+;#NRlcZsN)l=J$Shxjt{B$cv1b@`Sbi{`70RaeHK)`xcD3j8)~WCJYSHFgxFB%o6K%n^aXHiYPQMMJJpRH0I1=0{WNj7J~R;_0D)H%u<9b6Ope$M zWTGNzX{r&|Rq4dj>MGynA{(%_xZ73hdfPmwAtdFHbC#-T(Mi78SfqGoCA~d&PLSLn z0D39}s{51nxrM zoN66Prc}-7TxRlaCf)9wcr8t7pt~YPW6QerF7u00?^3oU0XH6{amUR*=WBBkWRgTUSuS?%nU)e^F7^6-z23IhokG~RB8>C3@eQEkEE2Pjr!a)+=?r+ zpG${z2tWV=M-k|j>!X}Y*|h-D(4++Gb#pB~F0W}%MZxdpdNQ;!xs-|~l1|;UO1qJ< z+>hjPLk9)q%gm*8Em^FMZq88v$dOS$VUO%7XupAzAV__ zNKIsG;n-@99R#)$;JMq*4$DOZuBdEMKdlN&G_TK#()*E;Q}OHX(umzhTacB5eMLe2 z{dikHqDj~v69|u;Jb65QKfVv|4Zo%~?s*LLG4^Nq*9~p)Miwic`G9B=;bedIR|9Ei zXXcA<2#gZYhmXf^ln)EL2&}1WUQc%fjNd8qm$e<9cA7rs6Q$4tFZpv&A9~E*civ;n z??*r%VtbHz4DWY)9-h(CZl-$rC?2$7akw=2K_Lq_`gw}2wGh|Cn|$09l;-+7UNsnI z5ZFN=bu{a0J3L_ufttX=nr)9@ZMt_Bs&jC=*UMIW{VYvHx6CFKwgz5fCwxK*a?;Bh zTXZ3CO9EC)^7)oYlGGCkEG^gZ;X8JVQmlVlv7V&MS2oW+k0c-!QNPe%>(rmSwRZFRn~L-%qd_i{%}P3m^t^%9H3EyPXKQ7@ zO5~dD66He#!lN8}ntYvR2Vbpy=m9uvt4(=cUL)n9J1mRB(MGSQXYC7Y>OCe>wfM4GxIy%@%V-nm7X;)RkKr-T zE$tUc5c9zV>?0_b*xDh}2F6qzi^rQadO^`bTW(kD)l3&oY*vy)s0D(+E zAD=ueMx9P!-E6!IbxaC}gP}aUJCERCw~w7EoNsPB+z;#gOo;%2odnu`CJpWbpYfg4 zFrOjN>k{71dTZ)#UCBM5ok=$v&1PnY4_FRc(~tLx7w8A)FlIB|QinPM~OJT3J?Am&3Ec z;bRDN8bZ}<^ue;-bX3ze^`T3%s|H&0uL^c;9BI|sucxSAn-b9=a3KMC`pZMVQ*mK@ zLcN1P)z0)KVRm2Zy4ishy2*7m(I+TKC)4*%9Xugpa)iJc1hlMFE$zV4aYn-U{5^rT zYCfq&yzcRquSscUzyDBd&fs-VrGTRc5hy-_#qb#$2+#L35?z+1 zY{qx=s*Nq%K3Wjy5NI3P%Rcm-9V6OK!0YFB55Kg0S=E=D!N>KN4-~O)NWeZ7MPIvN zj-+%80$-}0*8GlZfk%HSU?139JQgGYfm;y>--s`cTct)acOc+p{pg~6<=%V`voS?+ zvGS}p^(CLK1)6JAj`p`E_Pul=aj*OF`)tA!5k7D7nLGY-_xs(E!F~c(j>js;>z*3< zAOvV*`(4X3@Hxtrh7QgS^|y9E&(;Usv+v*H?B!#}&0dV_JBp#aPi^)g56$v4Ww(<% zo}$rRJNAP$@;N;=`*7cn4jFxk0PXBccYEPpV{zN?Y#jf!(Qc2rnOv^N5LhphEg$%f zHXn8@9hEQJyCgj6rdkx$tS%Aai?~ViQf2kfN!ZQ1HuTW@a9!HVJ~G$kL!=uKxWmJ7 z!0W=IlBT6EY&a?}vYES8`<(P&EXC*0Z74g$ta#>DsO|!%p99&k2lVT9uWLVAO~hte=aCk}K*vSmaVug_ z>__dBnJ$Wgs)*SBNI%CAac%JD|8Ob0J!>n1`WE z_LASy8Rmley0jt5QRi~9kqoM|lUSr-qB-gIf}%Q54Kpf+m6O{~6o6%^SY)raPnrY| zCm>IEIPB3r+&c~-&?j(Zu~`~RKLz?}u$7 zPbuc>U)X7xmuer5OR^0?Vr!Ws7u#3T))YNyS+rzDGE7~!V+%Qm+Qgk^>2pVEe`)aC zy^#4z0@BHfW2H6f5Eu}U$4S4^AFRY;s|B>Pcmt7il$gF%!|Q5d>Ph1mVlq`u-nf)) zxgz7dn4A`k-LyS!n3d+q;5h@manDJYOiv)7AK&nd`}Kqnxcn3Wt)mmAWn106q}0aJ zt`{522jl#^r^p7)rwy!HjnK2p;y9`=x&_%$vmFuC+iRxv;@xMDPX6w2ACX^dW8Tmn zkuym?l0aE(%JH(zthZR^x73mt(ulo@>AX}}JDy2em%~ZoS==(fjIpb#{h%%RYVT@} zyY9Qfo)2UYxGMquFxe;St|^k&YY2F=Sh*po_h%peRh>rCCL<9~4IDpq62tzaJx*^| zR!w7CFS`r-u^6?1Bp`B?)=SCu(StYc>Crdj?BwN!>&J>ae>Q6TYvn9EgqG61oV?Mqr>vY3G9AILgg$AjJ1tKowNpcb*hxB>mU%fJA6lI% z3h^yF^B@}4L~%EghN_5`?=Y(Q)K*l}MM+fzvSO=AtW%FJi!y%QVVi#4w%E`tfmc4x zv%5xN4S`Veb`?FTnq@rkR|(3+W*qgF8#MMyrV>L_k|<%K`Py)ac~57!J@F^r<3-}6 zLt?5tNy5N{Q4*H*&@^>TU5QNeY_Y&B5@RNQeO+WSm9v@TmFVIfmzQqq9XIFHU2x}5 z#rq29S^+x`iqyr4qgX74T4!f08>e1_8}U(7NiNrU+pL@m|K+$4cZOaMR>pNN}0mQ6&*Hn2^EvFb=tGIpAkspt5PtM2z5TVWTg2yo|D;rgPo*1zt? zW7+OMLsmVtmNu2sN_E#`SC}ercl8LN>_C##%;LqmgL?O^OoR$5(kg6geIOIogC+4J z?qVm>m_RCsmEXQp zRjgiGVew*`ZPyo^^%gnWf|2wCJN&8=x0G%n9U*pwY7`gphKJjAH&fT_I%;V;+KX~% z2_i=nTh_8{*0KqYp?a!o1|pA!s-)}D&TZauO%UF)A@%_Q2pmWtRKJ0@TqlQ1so+Ml z*1F?v;G`7v;+O0D$J)?BeNQ#N4C#wj|C`OoRFs8>DQ?N8acVxJYjvzmD+nZroHZ94 zr==WNmn9ojjdBr+q5RR6tpB2s?2H2f5P-lKfliIkx;Uzzi)L4) zCH*6*Nx84~Co=sLmvTf+O?2}ii>vdk<9V3Esph3w#7uGyi$>;3QwziO2`&n91EpPC z+hu%%&65HIATUEfs`Wrc%Hu#71S*u1)z1x;bHs5k*pV_RWx7*KT=LIFU-l|K zUOCKgcZpJ83r;bzUGhX5m~BU$gcWxd263Mv6cbs~zpgTWmED@%w5~cA>BCp4)(3_P# zX9+2Z+C|;zMr3X>S++1y=3-NbYpW7jVk2Rf==B0yqP>+@$>bL8+mPN$aS;YPUF}N* zYY0H#1Ol@k>`o1_x*}&iqz>C?x+R!ef0O20(6wcRpT6k81U*~m7#jMlrA9hj>Nv8_)N3kX19F#-8ZFDeji zp_C$^f6ZRq%(*h9l$+Zm!36`48L!%=LfA&E)3ibD5~d+7?Zhk#?;+lbKtZ{%U17LV z)xyYqUuk%Zy5A;!^!BsP^`sa zsXkm?FOgC#A;Vvdt^Q@Chstb4cc;p6E(+`8t+en6W1)P#ajPjdvU8@wP2lO@b3#me zwYy>Frf7o6G>41R+ZyVNB-_kTY0WiH%eGxQa30x6961j3yv~&d*A({V zu-ATF-e^Mr0v8Zi@UiytkyT9+&dU>Ar5xOP(B%=A0}VqMbzbRSDHhZNIovJCX%OFE{2kLlAJLJ-sO)*3jQTnoZHG7F=u=# zvXi$xlLE^SfWXZONUf@lSU9YP`NXc3-o!+;C)RsQ9;vr>uq?KN!Or)FS<+^#AIN4k zTFgN%m9?}IJ+zm|sv4SIG}@c)xV@$mGSHkf)0pnK$@wccNa6fV5&;4b*iOKUL{TEG zj;8V%r{S_9$~tYULNt8u6VMRx- zdD>N?7wOti()TT#78%D7fB*zm6VS?Jr=m!C;S_g1w(FVzVzFGmjI+dQh3h5m_Um|? z>26vVLkw+2+QSl0qc3Z+nDWqdZ5>gT0m(f%v!~=FQZ|}ijv6%VPpQBd0uX?}j|oU& zvO4P3)GB94E0(RIlEz%a!t5bdvr0+9V z=WI_Zk&~{4lbWTeML8(tF*h;fU|Hmnz+eFZ1Rwx`-x5fLNs4ADQd+KJt<}1zRn-M; z6>I0sUaUGd!injsI=R;QMBGD{A~o}=J2Ix;0}@LeNRvw2mZ5bqU5h8}A0}6cX&jn! z?JVRId#64QzSsz7?!8-ag#ZK~a1DV_lwt`ji&(0rmP9iRLNQC7a5U3-jiKpcn+5TQ z-Y=1qTL@$Mqg~6+AqC}WXVs0JK~*h7(GUgyYrM@a$f`DT_?{$~{)u5?dK#x#&@9Te z!xO1 zY@@gco44d_6^1INo1zX1qvMCtr#yk=-R_Cxv*_+5I|dMd00gcipjA_fn6wftS)pjf zDk^ytLrY5qcG{e0uPlme5Ud{|sPz|aB$XVUq-@LfCL=p!F&v$ZgmqDF4czV*d$cS& zx&9&qrVSn6ar${HDFa;SL5lUP3BkgdouASwdcX?G85q6(&BsxBQd>U!EIj48@J>L#%wnX{!iwgSdM&|A%bSi9r3kBF7SbQzgRDeb z?PzKj_GtFkZ8l~o$!PSDz;(fi1OW&@U^4-)Rk@g2{Va-@RADcxUSzk$i>^!KB2Fpp zjKw&L^QfbD2T{$dNH=Yvo29ig#huoJ#k5hV zsFs~4I~iz}c9n#(79$8i00IzzfDzDMVa>ylgoa@)qv$p&+0aPD*F*!d!1?Sclx=181Rwwb2tdFINQ+2sJ=!s3MVnXbA7LCuu7BWFyHh-AtIEE8$s`)yPLeGL z1Rwwb2tc4qAh!tVBSr7hnRSq?({-^$D8bTEe=E_&(n;ly{)_X1 zTes4N=Iu%rZ0s$rcr`n^t?u6n9v}b#2teQ=1hm^}lQ}Bk*u=zL?vfIwI&x>t;-fOa z4+J0p0SJ7OfPX*G-l=vW2rfc<3NE5AnW)TP%3|}uLE;(A_c%Mi77i1R$`UfHtuFuHQOR7^g zoh?kMvjzbOKmY=-N|pkFLJ zi6md$Jn3#Nc?8k<9sw!yzH2M_GP8dLO%_rcC`%GIcrk&*G!D{yv4>wN){n!lviND-=iIEHVj}pB2^6*8O1|V8i+?c`wJ1&BO)7SE z%_m`L6v?$n&W4(ODJ=__Z_Q;x^U{*>1c8WffP2E^4oiOL?~uz+a_D_#ev$}5A+VW% zlpQxN##)VZF6%x>(qv-qHO16@{q(B&Y6f|8^2#}uRNj~9kE)HCBTod3okE=8oz!nL z2v5Lma`{OjU*G>vpcC|X0{KDqE+C)mvcl^)NRqH<4Y3YfQVf;{@vQRRCYzLPHg9iI z`S?5VCXYf~o|O2AEWc&Hg%BT@-zM?H=*0)+hglFB0=o&MkFr#C@fM$Lnf4FWuu2u{ zmRv4476;KSgyeHhHEt3 zYnyvL6H~n80hn5U{o2>}|N0yJtqscKJorqDVB`qON&mV^;B|8D-h`wFDjkvP1kK(a zX=nq2%LPOF%WZ$6*?VAqlE|-uejdQDz!Ud40!4|BCB5=(GWotydz6yOq(8a1yh*k( z5xa(I7L_TA-1p*Fu`N85>Wr5Xi2VIFEH(R;UjOO%RW`qfn?5nW2u@50>?aT^xs-D~ zq=1K`a%v(k?>O4Vrd28@Uy+t#bp)FC1U1tT4$_l&kBw`e~saNO(wn#T}Y?g+LDOD zD1pFmu;z>hD?R0b^|bCC-(wGHV+~oA7?wtq+J%SUi4iQ=GxQJN@>>_ ztAmbwi)c_EC!7ot55}?dx*OfngbS8t33L$}dZjJTN_8~TYV9WzdBnebe0~34zW49j zyVfH+6`L!h#W1~^X^V?ZZMGQ1zEXJKJDd%v0X%U{R+6yvWz8#?U46DUt&iFV&h5^V zAPriL`^-D(-zT{XG8x{z3xW~?0;dr0qThb1lRSM-E=hEt?LkH}S%vl3N@f(tm)j8S z+%2_lrirIp3Z%2;rlu=n&fJXaHUh%+5p3rl;cWmOV>SB`e#}lt^xFiq-gw<_i%*jK zAh1e98N}HPLjAO;-Hc*)x#~U=Q;s&%Xc@(Nk>rwIG?Vnzy0lMg(FvD=z#cf|-6&k% za9BPLH%#yBls>-wv+?5pLIT=n>@@_T}yIikr#cKViXX!LL z$WE4x)J$CZUo~rEn9xGR2IcO9s`q=};n8 zW$~%z@vC$h5506HuBYZ=Wq(}Pmwg^vZkjF_M9=0)Cku?erQ(Pd+_k|C5mI{Jx+^#1 z_=Fs9hKzI|a8m;MX%4lkNzb~7*R*CaPir%og}>@eO?7A^lV;2LQEZ1HlUN!p*f3Rb zRVOmz+_&WpE#VoXuPr;It^2n7w(7oY4TT*9AOL|#Kq^-Y!$j!~t6iR$OC8gm<^?fd zC#;4`$;_O&!XVSwKUZ|L!gKH{GdX(zu0o(-BsX+D9es3Q2>}Q|;93G!(aV@t&Ah6W zD-&bs3i8kJNYV-GW+^#o`_x!zU0!j6YfI8X%5+P?ZW4aiG~xIAxqf@fb-fuD*AN){ z999U6Ri-*vih*IYR{My*0aNyP}GxT<`SB9`7VWg$GT6z?EQNejaTl5d-%%R z%BH3XY$)`(80u$6`ciCfv60Pwl(fN!8_8`}dwK(%)#x^^$ZW$dJAU6H67q5j;$2f* z<=&Rwk%3|9gz--aEWL+6O_JacxB~(Cu!O&INIG#8FFKvcQp;&9hwderRAtg9eob2A z15u5c#etl!~KJhb5PQH!eWCY z_rW5>uFUn01cslRJ7!5v5IBUuNFiJ4yQz!KwCk+Uv2|%@GV0g=pkBF=c`d1y{guyD zR9OSoN~g_oW_fg4upN#Q9)T15)Y(Si4*!_`nm~O=f1M5SA#gH*@W3DQ%xk~sow^$+ z6yy4!pjI8M$x+rCQ5{AXqX$zA5o?uWX9MRV7zmGzd6>6&H)?+>tVPV8Mc~{={#h)@ z76L|KVPT6!ac~)8tWl7dG4ZHp_&(le z$W~y5Be!6kEeiFly)N3)E0mVs!B=dTO+a7?0r^5GX$Ln>gbJ~0?snY@;;Mk}~t_kk}j&bn|0^Gr0P$%Zi38X5w;PX-Hrtx5Z zX{GcS$J(Q!LN*jZo`sQWh(s6awWz2ndBvux9u>~HoFCzwywz)h^ypoj2hnh<_&uq#YgdZAhJ#>-{X zkU@@B472cwBjNhQyvf-KaQ~bHR|rG`xm`?-CSOXDWulrSHW0ZMPdVwg6~kvym$F3~ zm4m2NtCk8Uj#ITynV%T!a@Q2Y%aIch0uVTrK+|`or&F1@Wz_MhU6Y}Un_d>y^}Aoz zI8q<+&Zkz%$IKuo&uA=JPCgFtwj?4t5P$##Ah3gg_m_oNd&la>%WqO)z4a$1p+!h@ zkWS&tBF=~Pkg|ceUbtqp>Cs}vp_^o?gWO;>?V&mn2tWV=5V#M4s$mq9so{9`1FN!e zX-kq$5&nAbD_yCvEvq=_By(9SbcZ;*Gk%q=g>75nqE`DXxMK0yI5Ho}T1R!uz z0^UHRgII^@HllIi#J*aiR4z4?MU!)OAr?C8Q&~1NGSG=h!r2ZJ zUV~3E(5=MFHBoO7CBV*k2>Co?1OW&@;8_ILwKHu*)^Pkhx?NZB5-BZ1qFFaHsTR;U z)I~Si_Kvi!9BbTQqDlBREE%7@`r7O~aS#L_!tm;Q%;q5QIRf597F=U9sx`-eX~9fA zM%sq_m6II7%4TM+0$ey)Nm{}M{PC#8rn1Rwx`2NIBKw)q&@ zZ`seZdPmRV?{wI;ST+_FG7)e`W7 z)M|;$YRSL=0R$ibftwPr?y~tjRsFPnN~=oVg@H7$s;*X(b(GecYHUepU6_|>%kE#Y z6}ABZ2tZ&+AoZHgq!CjrFT2)Q*OfT zc1c1IfWR9Gq;}IAWDb4H-jchv+Au?#M)M^v9?;w z8v^l5kVeWB0uX?}QwXG%lLonQX*)>r`n@cR<0!t2>ArJQON-{KOC{)Zh966 zW4@4w+bs|P#iIZL2t1p>pev~$ceMU`R~kTwTrTAwmuWXFUwOHLV%#}Hh z_V|0fZM*tjVd1foDMhqg0`;RzJ+7(xI75P-n@ z33%TrdyI|il_=|7if&i%iVj7h!@N}c$nrI#+_mzEUbcoHx)6W>1YSp=ZZBb$`;+|| z$3S6RkXnj6iL|PwBjz4sC(XidaJkbN<`94Y1R(He0^{AuSG@W7ynj^)vXllsEb*AF zy|b0_onz^cJ6(L#Jl>>_?w)N!00J)~(CJU1g_T{b9JktW&6&i8C1p}Nj9ki2la?!~ z8*jWuryH#?g8&2|0D-pq}`Z<LKpX@uTC&6#{S@_??CMpCV@Kyr9{1W}G zOxNuzwU)6#)uF11e7iBWv%Eyq$S<0|uZUM+5zH16Gl<=``}5P$##jv>Gg&yL}^+lv+X1?OIKlXj*p zt7~86mesZ#Qd_neV zy19d0(#$OEMWH%(^mmav$smFN1YSiT)E6l+xvIWucWXD}?PlbvEvUbiA}PsQC#+c+ zPvWS3Hua8wPa)-d=^#YEG#CJxS#Z)^_f?i5lIt8we%6i6gZ$=NEK!yJ907x2+c*4%pLTZ?0IyG@&P6Eir)r z1Rwx`E&;8avXTZvwHv>i#bmuH46fc1%H4&rZ&1L; z;gDMS#9TbvF`*QeM5oY*Hu+MlF@yjFAOL{{1abxK6j=QM(*h?!rLkUSbbwZsf1GGC zpxEy>RN^U~C$SE_Ds-m&RO z?M*CZDMkrm#~u*`AOHaf%n(TRG*#g!(H1actjnfvzb=@($#jYFAv!6lwul&6#wjUj zYSu4gB*#QxRh?28+PXt^?WXZ+?p)}$QCb=J8dnHF00IzLPrwRlRo}hF>UGwmJ1DQg zNPCGIx0QU>;|7HoT;p0$kw{CGo!Or(m!<9z#oqe5I*m}G=pm78WM0Y;veeiyg#ZK~ z0D)r(#1dSUTaif=U7HDK_FlHBZjtEI_ZRsN^%*lx~R9-(KaWt)57bt z=b;xQ5P$##AaDo)uf&zJT$977S{Y8%L0Qntar8d4I!99Foin#B$h=IpN+B!9?o_RI zC)p(K@}SMm0q-V*5CRZ@z_$q$g;+p@sqzr9gGmDy)K~YAnphYN-&ZOp*>~+qXKLM% zFB0Xviw%Tr1!G5=;v%Z#$)k2s+A}^jiYLn2?QVj z0SH`ApsvhI;;V)BtT2*xQM8Q8o5_Pq(TJYSxa=~ONpE7x;$_8=l(WayIoE z2F+khzmTWI3K>HPKmY;|*iE2lM$$JH_|pwlHEUo=o;px)D?)Q_EkIPGdeakT zrpeD#svgT)Ve(j-Bw;Zq*QdsXi43D^F`O}$l%o+qB009WBAt04lk9ni4Y3)dQ zmUbp>PI|KX?p5Ag*0UrNaSZH^mt5!4%+bV~MTmagvS+`_rt!4>XugHL z3`g}w7TjExH<*ujMGOH5KmY1w*8nQEhzUXu)L5Db!J z!gz8iI_M`lX&Dz&29nJrkxx)98sMjTtzTO~CX&4t> zG|*iknB=s;kLRGkbu$Z$P=NphAOL}d1VWXa(41VHu$y0!>aK4)qX~#cb;xVhykpl8 z(=cv4`06jNA)P84oBSdZVnP4{5O^H{tNEkbTGKy9oumZ`7Hha&;yEeALA97B`a`f* zb-_G2kii1|Q&k+mt&%!*$2f-o1R!t)0j;WM2TG;8d^st`62JfEk}T6;Tdv7G47PbV z(yGix#{4wxNV@of00h2CK&$Ea)>jsPDa@%|NQ07p{KzAh*mX=^YvtKUwn1TJC5bJW zH2v+sH}u;qhzr?9O+H+#mpf z`x4ONKarkR*lJx$?ipQ5Gg*A9Qqp`Zr#7`l@7_~Gd+!{{4gwH>z+DN9z3N!L)?Yk# zoyqqU=la>)`r@|LRaEbulU_@;CU&KF|4G=%{gWg^2tWV=_aiV}K4Y8kw9BrsVB9vA z36n;3LQ|JS-IEH}Fp;?kJC>qQDBpbepj2;8lJp<|fo~D0`$D^SX%0cw?Gl~FaivI` zm*rb@u_)ENn{3*>#X0R`1Po#bKmY;{B4BSdqX~OM&=(({+~hiZ4@+65L7VF6Mp=LW z1Rwx`#}WvwOk2X#2HJjb@42?Is?AjsNq(@|p=6+f00Izz00izyAl3ERT5j#jx}J>} zor^9~3>TTMSF#_BnVs@3zW1ooCWUxUX7_&2dq-9ffB*!(MWFK@k^zJwpC?lz?*_O0 z;h7{S?_*83ihI-4$4+_A1&IDIt6n`S^0_)R@gM*J2;7B$mHM%4mUgq@H}A&!!`fRMS^8 z-p?*1PACXK;7S5k-lS(p86Flp6?#h71S76#@|W7=fxLOQCCPohckiMLk;i&rP7oqn<8QtBo$71#~H9k5@~! zr*nmjc6J42Vn6@_=Ms>L>Q&XQsQ{-zoq>sK*}hp0B(H-{IOekKuJ40%qIJ0M{s^2H z1=kRO00fR9U|)fE%2x9N78{Cu2g;8s0Ts$(CEYjiKu_srIbVfWPUE=5mzK3@9La4T z^=ut7%#-=iO7(e%Xg~l05LiY)%1^4PgTfWoN;id~56k7EPS@fcGmq0;i=3O4sp&SW zDUZ`@fnHE(q6&;rvmK;vVJaKDMIs~t0SJ7KKvh_M_gayp3~SxZ(n?t;b-T-T+HH1U zQ^@Q)ipG0FviZdzrsdiBHK!7g)!;i)eZ24*t9-8dc{FGMKNrN@!qzMm;nNHB-%UmD;0SG{#B(S!RMB88{ zma#6&HCAJ*$zGXL-7Z76W3AJzaAs~c;p|Poi@k`7@!W8Y?wqgD^$^5xb&@qB*=;m0 zHs0MyvCa?z5P-l}2{f-k(vbEX)=RXnNx7DKtd~@pbF*o}#K>xqwZ(qnA(r!pw}?`+ zCo9(v9j9QvE%$BwnU{ZZOOvZJ^Fq6?M&%ONwC-*tj@d%XKph zIs+jB2tWV=FD9TBQTCUsUus4hw{7jLXPnA!9+Ya@&{9IaA_5;zUZYdpNgN-48Mcxg zF^cUJUPNkJc446xhrSZ8t%8YZX)PD#5P-mo2}t3y?JesWOHhn?inX_MktU&yLQkGi z%uDqb#5KQC!_8MG&HF)GKre$+os9#zJp>9AxWG0*Agbs+zYjO z70|-C>0uLt8sdyv1kt#g0REeXK7u;%XVlw5vD#6)@M2bs=&?H&V zc}uDMEuVO>MHVZRyQ=YRSZPW?+mK(yq}XCLDdfZ9NbW;LBoKfA1a3p1taoEcEv$p$ zDt0rihkbWtz_o8@eUBy$NfuSuH49M@*i~JtcP%Yfj>|+=nl4t4F*I|7E~Y;9k&A4D z3-9B2`pdpl>Cr?60SG|gYyw4*9}TrcCmCDKOtm%1%R%9=7@EdFP#R8*rKU?%JEEdb z^_q+e#UvXHD$~7_BC}1df_>>Cj`iY+o8LGSbs2_J!852-b2n|TqbV-3ZoM&w00ba# zE&(ZXQr(JjcR;}8O-pCbVbbU=?v&*^oE;@u5Xo3ql5jj5=?Hf`23f_e#$2uANb(th zk5t7c6W57t_uNi+VhI8efWSor`ekoda4n-nFIeTwTF5GsQaRP(B&;N5IgblTvD4R+ z?QaKz{w0LRQu6)Cx{uRUg&lcPh=VcbDyN~fxR^r#0>3BF{Stm(T3Rfta=6Z)naPhbx1IeKiSN2zl%UMEen{_>9A|e&kgxZWbF>vQb3oVV4=-vGEk)Tq0@8c61)E zwx-IuivXdp3_~^2J=saM`ls4(Y}U6$3IPZ}U=sl?HJdDBqZyR`jm{b~tF)3`vv9^V zmFl^8O*#|mIe$_5$yD<==&B@VvO4qN)b8EV zudz956iyI;00edu(2}#+OK1ea_Soi9CKEhMf~Cl!S>Q^(eNva*Hr}M)31xfD$;EpR zBVcuAmyfA}w##ue zPX6QI&{iffltHM=UUOF@9s9zRg?s(YHEpU1uWiU>qe@E0SG^M@tFSP&aW!^jyGm4P zW#UpZ(7~J&)*%1^2rMBWg+=R<7Mvv(Nk@uVtV&7tyg{t3hCyi@vxivf6>Ik-rTl^; zhe;#7-*WS+!@7+0nfge2%|gNycbewapz#%^`poFX6erCqUrZnX0SHVG&~l?+DO=&0 zP;HmIV7Kx|&8>Q;lv6QJlEnjQh;|6cJZ!pvVgBhkWTffEByxf}%F`yvVAD#1pS0Du zveZPr;9Jk@VH6f!K5>mE z`YI=5bt(F_v8uJg3AZdk00Izb3B+GENdgx-mqM6;R~(x_-ZCUcWD_cU1Q*C}%C9QGhuJL_w7j1WNp0uXQl_7V|_ zh#W3lc3r8y%<1E`6y)zt(s(AL%c?*wm8wa(pkwVY>As|8HA>v^m3&UQ}J+ z6cq?S00NPK7Z)ucP&t5rkn|(C^WoLk(ZFFrc3I@3l49NtYbe!fy)-)uwi0+;Pr6+? zBvP6%fB*y_Fit>f#cY8YH~-;^Rk?fCx~2w8O}^7%eaz01SMdzkbeL>?qpS6LX?~WC zM|B5xbs!iuWdQ;Z_$Gl^CFJYny93Y!2U!jTx7tR^E>-aAjVMVM407-3D$gvpHnqAi z3mQonW>J*vBG%!CL?bRPzS!HDn7OH6Jt(T;r7xE6y>qRe+84A4-#S_28;gI)G>(>C)@di7U9+w*n-rNfPl4&UFmnzIcqJH8M>00JK*pf%}9HAMQvcul<39h5YuyNPXN{JhV4+;3V5yz+SX7=*P* zRJ3fE^s{Isb@wT;E7LI3FtxN&VFCdNK;XFqikfFbFR0tMq(yVP`4Y>Js^zH_I?X)y zc#S%ZbU2;Xn_eAy%M$t8Aa%4bXm=JgqtMWY^=vGo)?nqlv{!e#J+4dubqGKJ0v8hS zikd>kikjxD2W=f57E!IOtNmsJ$yuW4+4GIpHJ7G)tT7$ab(eOvl!NZDm&uYkk!!Sa zQFJaU+YfDKsiUQQw>!iV0uX?}JqcKeP4zClJxJjT<#k8Wt+9G6{YiukhZ(7@xC{gN zlbV6a)|_J(S!l9KTY8oBu;_bax4P=>Omtm8E{vEh64!`h9<^|hACw>f0SMfbfL1gu zw31+1-{M%y@Q&m|QLYaurIlnLs8-uavdsf=C{EJFCha^ohdfG}=MKUqBwY{E?#bt} zE@RV6>T&8?+pYCYhDy6j*(1j3M1iUwNc9 zr`n$eG1A)0F8g5Iwbu@1r^(I6Ma@|qWpA5kj~YcPqw6d{00Izr6ani7@hdRR_VEW}jRD+eZ=vRk!wu)9^UQHB5nAOHdD z2$4fmg-}s~4G#-^`GFQjf`wD{oy?SrfW`Z075P-lJ354PvwrzhyJ=V7|=@TMM4NS)MF)yg}2kO=8R76%i1H+L z5APvCFn%min$Zc%QA6^wac$zuizOZtVj3_HaIQ7FVVlt!ni>v{jF9tBNH|JKM?+I|xAFN&-@`R>fPXKI1z_PaP}t1~Iag*vYJU|y~DEY*D@JAC9-D@2tWV=HzBaTARSu6thP%d zkY*-Kv_^_p=ANBRL_y`cqNW>95@q4x5k)mWZbTZ)lCr(fT~O2T=2M!LNK_~uTp+bn>uJ$Xib6X*Y#Yx| zyVPjL#Z-ox*=Q1y^2|{NpHbD&b2_K54-?K0fC4!^0|Gz*0uWe8AXewa+6xsIs%g0l zx}j5Ouh5~kF)f?1iD@ell`xM5)~{u~ogS~SNUCXIu61gOc4CEv*(2qzJDXIG5his` zUaU81Uu*5@|D<=#`f-S)!+1M`Tv_0=Ry;Ijc35Bl{*}I1{fzP-?00IzrIe}dMIvbUW7{pp3 ztzlW;3R3w;yO@q_CIV42Bf0KBQgcd!Wj<3XuHM<+P!!YG4GdQciF-}WqgcCYSmz)! z*>uWXhQCbjDh$Md00bbQ1SV@hu>Pkzf+Eu4sGwR7IqnSytpK(zv zr!1!jQvW6Fw3g{udUKlRt!F$jM$9`V|LgS5+c=&f009UL2~5{KSrr>?8)h8l-b8%G z7No>mC-C)jwII4&G#Hm^kaBX|xQOOS&Rk``lJ~4yk>rf-Y0E_lDc_KLjAyH-1;;T2 zAn*tRv(@YoyI7KBtcWA3vKp4GKx&~3Llb(@)Z#DZQOR4F=|%UQOVMaLs|!TS9AvFj z=12CL#IljRyCiM~b%xF2MbkQmm~-mIvbta+7v)MA2teRB1ZZc*Jyyh6;H_S&EOd#W z5izOUbhLoVNsqafW?BcFbJLn|rdzT-Og>dXC2p*vmh9_59nJGaDFta-(z*P8=v7zG zPl5;#fWWN@gi3Jh{Eke{YGU7`tVyBNLwi&h1yL%TZkDuk&1$O_*hPKDQrL6Wh?;HR zi>2Y&&Rn}UKlm-oltmS)SiELfM%Rdf-VYs#h6~DTEA1+k28(&KH+6uc+eiU zr5bA4NYxAe%7PdW2_^fhyy`M2GtrkrJDKRq(5^Bb9-`uZ+f_BMtxXgc$|c!*Yp-+b zysj#08xQdoVkGN9w6t=~ppNe`+Z0`1U1cL25P-l-323Pbd(+SPT|ew+)>=N0gMN){>G9f@;*3=dxL>rn0DiMRC)i?n=wb|4!$n z-(_Pe_L2id0AsM;aqKT?=Sg7VqAOL|E5%}`wdt&cW5R1DUCQ%@xTt2;$swgdq zaj@1)I^}5|rNuO`wJD8ORkBR7!5}WlrP$88VRV{|>L423IV7Dk2NJ*7vV;k`>B6I;=6O~7rf}UsC!a7rC>_Aw10GNqM+^zMpC_sNwgA2 z=_rbDk}VskzgpFtX})aXVc)3~$Mm*h%zDn}CJfuwiYAz^bCl8($`_+ll=a%N^) z%x&n#d4UlGAn-f_ozML9HnBS6u5{F?!kSoA6ax{*qa3?z z_f->Uyojt3g=tQ8-Kg*s4GT#cuJgH5J4FqH;jKukZ4_H5rQ4~LUKm3F0=FRWl@Ih_ zpHkb>9SFlb5vi`4NYwO?Rl}%Rs|S7k;|?p=5-8f{L2~9R6W3(j(eY%9B~2pCTQg5? z<+boE!`iFO^xP0!8D*7vnMTLZGafAILYB7Eyut_q5O^K|DGbF?O$zzrhh^o`aVZG9 zlc`*6qiIp+Qo*gG$wkMeY*I7RGOzYFGDl)27R6tiX#_vX^2E_Dhj|idnATQ=L6(%_ zx~H`A+Iml()xQRckybk1u3n~OUi3yKhqCVXG6};#?J7YK^%P4T#t?wOLkQG$;2}wG zNYg5yc9&RuwdR>8Ths=S1w|0)3^J9{Hv&w{Vp@wuvhb_JSWsPT0rSj9MS?CGyK0in z;!vjBPRZ%|;#1?inU<-Jp;;Viv0|A-&q&vY3nH$i`F1u7wHh-BK;U5n@@M;DiTBbS zl&4q%rT*p`td?5kTpA?7R7J9=ZWN5zsUQwyk`GZ)wJ7qs8Dug{-ffT*kU+(vO;?;H zT&u1rm@uu$Af~qR(t0oEvSU5+Wu^0t>O~IqwrnP6Nv-y7nbxvm7M6<{LkK|NQ3UeG zS4KL^qDSpym~5{$dGSrfFm-}hj%C4IrGZWhp(zAGa2BKLHC9hs@D(#wUqx&<`n; z^lD|6A_QsjYI(&>qq_Kv`L4WF@%j^`5&UZoE8TBWFVbl3ab6U~VR(#juqo%!~g;ico>1V zeUPQj4v(Uv3@f4)$!H`+(e3j*5W)OhD%?adcaPvf$r8lhIvEcR! zp~-?{Erc3CM1x3LwzXgn*J@>5w}@8y#Y$X?-*EWVW^?DDJ!&9vqkWx1oVoAq#oRs2 zUK5!)I^9Iq2uD(>U5JvRF+lYqGYCKc0?!~Im8?BRYM_gQdN#`TE{oStAjNN(Nq=fX z4CYc#qjFTYa6xv=p%H_t(Of*tAho3e$zT7vC%YCqXf_xe&x2VSy`$G=BX=X_q=Adz zdXMB3j*cfp5P$##?oVJ?zC;qsUhmS>;9UQ-4*JQjv0%q8BGR+Sa>A9JfON=1^0SMfjz@UO@3+a@- zQ2120s(&UL*`k*1uqM@8|Mc{VmEc}y5=qQtszGHW;|)hJGCT1nqh1aobKhg@OXTiD zugRkX6^X|Plfqd!F2n~7HIsaDuUXQBuTpbut`L9#1nx(`ifWOUmf2$NLn(OLga(zb zu6U~FM#WXE)j=Vf88)t@&}tu$i;s(J(lGW7yTnOaOoQk_JarFO>@F@9x|6}ROisqO zrT^dFxu{Eu@(Q%y|Dop_l5iIkEi7@@^7NDtLM{s{+3xB2k!dYeE(`$`Mfjk6O1 z5P-mg1Y9|jS{i$jl-B(6vr@xqpQ*_>+fdHDir$(fTixf|!&nxi%IjT=y-ZXP{JH7% zE13@-v%4gu?wtKhe113-pE!$dB;WIXMt3ygiCe>36fl4Q1R(Gp0#ZCWVr zNjueIClhla|2PPObeE+}GcClCa}&m@XghS9$wT=~cjrbh7V^mxK{ICKFJkkAOHafe35|EQTgKwt5i^_X(56* z2m-xZ)w6wSAXiJmjE1{q5n~DB z^LOVabL;&E?-GMInMUV*jPDSK`PJAN0%|NFf&c^{us(sj#^vKy8+T~}sh5gNv9S?_#-J9;z;9LZ81&PU@S9PMf5JA69h9);X|A|H9|Z_Z+It}>YYEv!HQ0uXo)0awg(bxoKUligFp)-YjKYcsHkF)r;exP&+jVVR)Bv zi{4#E>PbY&s0_1dTKIGnLXrEYw%88=2tZ&l0$Sp%d}^5- zaS^VT;rXu3Y0DQf2tWV=(+Egm+ZeMtyAcP06+<_(LB2m)D}-UA)$lai9Z9pt*G)u-j9es=YyZp4+D)28PAJCO!3oZ!_Mg1>yfy3Pf6jKAXKj=-@A0SLT^fK=F% zmoLagGYBSR&BpNu{V>u&6(pAuVYbQ;0uX?}YY2pDdM02g##WB?v)JnFm2;cP z4lR^AC^Wj0OjT``hP&H>LwA>8G{N>qu3_U+&n$The)7pp5)uq{DGxW4dzPQ_^O8@T zwfBnaV#Q+d(lALHrE-!pf&c^{upEJ^ydB4<1z78!uYScAUl>*9D|5E)tK(3S98$_` z7em<`igWL7DxxQU{AJ3vHy4HVkM1EVXGDCOU;n9Vx%C)QF8p*X>E$*o-Nt9G^zpcG zY1SH|kKJGZ0uX?}83Ixc?H{ekWp&gZV%FTMymYwrpc3w9yj|3lV%ezCrO0$D4-%xt z>~y_??yA(TO^t}!_fGs+U(dv|{<&s+WS68;=xJ{GhphT}p~wUR5P-m+ARq(%m{ zo6g6jM{5ju9B%AA%cy@jI~rYOPo!xjbDRw~TSf&Irw>ovO9E=hdgd%? zZ{dWsv=Ss!@5W)ONsK`N0uT@a2ct`I{4@cppNAzT6u08O0oUvg8?74zskyoUz5OE8a^f3V&@2NIX*5zUeLj=$ zoC6<@`Vmp)QkFt*{@h<-!Fvia@l;-6CA;51LJzCWK6A_v0uX?}83Izxw6-2@3Ux13 zV%b<ihV{(DGP$bw8R6d>?g*eSE z#vtM#U%hLr&Yt6cS6bMG00f>T5bIb`=2|g%O|8CR*GA7R6f&KaqGEk#BD>D)47w?V z5M_2x-E7D6%}dh0G{_K_<|z|%Y@?9Q)L^0yZ&h3s*9C8G|G8b_(3l#yaJ#jVoGf(vfsU)}3-hctqqo}!enbT(k&J1Qrr zbcb{YHwb~+$X3=CNuoGm7U^KO1R*Mki-2 zpbr5EK;WGOVukgEu+Bp2bNlMa+uGNq+9MvaqEHICPmpIALPWLN5!>wXdnmyZjcR*X^uWWC8&QKp_60{bm%d-0p`j^|;p9 zN@|Vq`NsI+R_zd?rGxB41t#tp(a6J=p3+pgw2}~*#4N_$hl^o9(z!uM4CYS>Of`OJ zOmjZeLIDC0c#gmWg<*QKMP+Z79Vxu!ik9N(p^O;}McHYG*wbC(49%l!Px28nU4^*| zO3R$d(7TnJ1%BPza0Z#8MswX|W2dm>f&c^{@Hhc0{(FU0*2*yJdAWLiR+-;5pz&Hy zu%Po#-RZ2UtZgQ&#vF8TCW5xzzSKu7jV!nc;|>liNBa{Wx_o}MdRS)()y8Eb|-{@1`4ZYJK z{K&YI5P-l>6NtSbQBYBu z%1CRo4odm8nfYuL^-WEV;rW3!)De<$>A8MR2<*lNOtNT3l%!M#t_{ zQ+rF&6^Ch7j=Bq_+QG~h^=M2yx=VLO;em~8Ii%|?WGkx;Lz1h-MLZCIz)uj65>zyd zD(lHbG}PwcCC+O<8kYoiy_v=SEVjaxMnN+DF5bkAg)X-+zv3zo(!1KdV&yw~z5w?- ziQokS5V(zimc)Ck7v(Z9{OT?fd|s=htcNRF4}#KskY+oA$layOja<5AtK8q*Um0;1 zb>z65DT&lBnOti{S=Kg;P8dJ{0uXp5flwG{2k&d7bO^a>^9@n0a$+95m?!y+S8c^F zXfLv{?`+m2Hi6drb*>wwla!aAyHzjugE%kMFU-_%_%JW-^NM}XA-`qunCVQw5CRZ@ zz^@XpIw_SlRrid=l?t3~FNb+e*6N-KN=-M5mD)!ruQ%@UO)ai&_T>WInwiSiyfqW4 zVK*EzTbOB0l%_D%E8JU}hcZne|A=N~>qn*!eWL&Y2tZ(;z=fLWO8LIc%d5UpYM0m= z31xn}a$b^ZvUU>dpV58aUWg$yT-~DThfI>{*1UOka_v3d$*lI^TdxNAnN15beHIVG zS<{EWwwRDW00I!`5pX5tY!wnycQrIAl-kQ|P(`hamF$D5_>hvS_vlupeWP(nH_7I} z&+Uqf?frg>`OH*wTePPG_n~oRS|1I4WNP-BA%hZvvj$n^d)|6w;96wtf&c^{AOxfa zYmGXG_YM252)F_;$ z{n@HskXW?hU2_!EGStt34ZDXz=_(BmwtUI*-X?S9^B3pGR~?C(kdM8sl9gLm-CQqtjz)r&eRH{q<8g3eF<6qp z&%y2(m($C}Zdh!Tr9!YfIib31heZfL00N1Ct3tj?CE3wvtm+?Gsn?|-TAj0i%Joy_ zvfR2qQ)fx#LZ!8E4+3;{rQmP0WV3jeyIdg>-~Ph%!@H1ec|SI5QPrQCOTIY|J(u^# znrck9ug3}mAOL|80=}GBwHnxZ8}eg?Gs@T+a71h5!U0 zFq=RqJfZhYv+pXR*@`7IHysvp*+OH9xfPC++CqCdZLy@Ktg9XC9clToQ9KMuu$UAf zrIkV)Ce7?c7@%oG(~q!)I|LvAflmm8>auIYs?PMBsY`rR&MF zC{FtfMSUQA?FY_*=aAaNX{S3ILOeSv^^%0Hmvp2sj-sHghDEA^I0(z}zK1e9?x@cI z0uX?}?F3w5+N({c{ckF5sEuZ6vwYgYqZ`U(8lebIRf->4-KQc}w`VO%RPOSJZ4(oS zG+a80f;b4v;Vv7~rXbb3iRH7SP-ruO00bZ~hrs-bv#D}r-79Bvk{GfwDbtboRmXj3 zNq3*_KFRxGraOKlAPLD-Y-W-?I)8k@PSmeGtEngq>QUfKZe?ke5d9wR|QAxpVw)W?DIy#4lx$S{d?xp zYfFcF_|l*>21`Lx$s#=$p6))k1#JjG00JinxGHm|aB4N1_@nf;*4L6W|5knXIi7&n zQ&mgy;S>&|H!b~v!3}Lw&+sMrVFZ;`AGpMBTSZ`3rMW-NHt#F43IPZ}-~$4u3a6Ac zDYeJ7c`zbZ94pOQu+^wG+%cWxR7=110tI&vX{`Fv`s7#+^gmxd@L=Jqn;4tO&N+7K ze)r&0bJG5~XwZfL1pYLElO<|iGYf?-qr0h=8$qUg-|%eBZbu?uwVK;)1e~@px5;+4 z%}$dZHVz3yy%`S)%0?GL7}^>9U9is<2tWV=Rzb%&_~JaKd_`+hVN(^{EM2ibwkJ6q z({F28SCTbnPof`b1-eOhw2jV_N>E1;Rm_h!RN>|JD_fQ3;Hz7`i#Y@!0D+vqV3qRq z=+2*@Hzn_|;O2SE8|P*CvQ_O&mXX=pWVbafd!+jfwZ8546B0S}fq*KD=eC^ma6X(W zI;IeSz)us<0xCZn_lt>N(c8It)+F0?)M}Iy{56Bv6`m}^9a}=SK-baB#JWZLjJq=N z9YgbR)=M2$Juf4bEY5j2r(Jqu1_22CE&*3NV!0WuBXPrJY~4!TDve#`%kGCZj?&mQ zCU{R8k}Y;9XLs&K(pr>u){-B|%1t{)#DTkx?6D332teR-0(*b`I^%yYFb~VoyjHTR@<7+E`5l%)<%t@UaRM=jjPHe_I9e>h>d}^w39o# zCi@G`Q|PNVSN6`w^7knM4009WhCD1E5t_=A~G_S;VOPefI zmG8xMu*ziUyacxcy}>ZF`HWKc49*zQF#DDylW?6gi#7xx0DaDfB*#M5%7gZOU}0Fgi54u4D+1! zEd_@`=|O&ic*&I?-)_iNM#K9GqwnD&{{plKoe2aW@HBy2npj9m+gF&#T?F}DMU~($ zPbGV8Xt!eDC#WIptK_TodF5-nV>#;0Y47gv&&Oqt2gau^#|QZp(N0YrV-Q%Hz)fFC zXkpYdje#g#s@Jdj|+wV1D79dtq$;vt;S)GZZDsj(OuuvoA^k4Gi-c8;86nW zf3rJyw3=1XZ)Gni3mSBmWR+94ay)c7_JPrU22tZ&J0#ZG0isdf5KHN^^RX(?6Hw&7iA*B4x4L-5# zUs$xMePZWeuZ0|y)T<<5*NMON<2FPqItV7bv|257nLz*o5XcBvCCUV|hIdy~X#kB_ zC7(>ZDVN#W8bcSY1}t^_!-$*#vvE6nZ8~|hD#$vX%>=s?2qqEucq#!HZABLgX+Q)~M4!2j2iE~LYGeSk(EKe zg%9VsxW;U_EtR4ei6Wa6qPX_A2Z_Po&XepQa5I6tpxo?g*Zie2R&B~^GQ(xJr8Si`AP01hCwis?D`(DnjI>-LBGC0#m*z#-5O|otg9Rm&$g2d7tL0V8_w3VrcTMkSq)nyy@0ad9ME$j+9oCuO z2TC&c2DZy`-NpS=UN>$cgTU$p9{fqsD&+Nw_h9H3PxYvf9jpr~=@DCGTgk-;i*4Sj zyUCw};EJ6x5&cG}8@=BX+;dvL$B~R7P!VWUsV~(a@vK)B(eTu59@c${;%-I)%jHoe zt*=0pY*Mz#sx&6&JP8IoShNF*n$s!MV@8+N`lVc#Jp=;#iv%_WRO;53zHj2^18-l7 za-mZ{+fhCYJpz_ScJ`poJw+#5<%fx}9Rd*e5dvom*C$xS*TwFs`(nlYB#5`{-6M4` z2@71tz3Zj4E(#AQy?~;#k^Jqc<0&gc^o#G2wm?Qaga2Pylpeg9Z0)LA@sIPa{2`hZjlMYT%Ok4A9Ce0-)j}?Lh7?asXD@!JIxAuv& zrCU>1B+<9@C;6u`5+m0*L#UcirP-au*!1^_(7SiH!e176&fblOosDY_ zn?w-;5P(2NV7InrdRK;GJKLwON|CNML}`~;s1$;o+;-aVz{m&G@mxf&F`IrzUHZs# znVIvA|A<@%dLp9fu3i?kd|b2MY4c%6?d?b*0D+$%aATz?O-uFLR=~reSZ|RHdaZIg z`|-32x$Njh-&^U)yN1pzMB|oBxiusxQTwqd$aMG`R2@_sc8ekeAOL}T2uLxkEjL7& zivGSao7+o)*x6bt)V?>dV7lRK64uDtQn%Dy_+CO5MHWcRFbrI>I`lDRsw#1-*P?Ys zuWe)(1Rwx`?-Gz2Sb5aKSjqBfV~1FgD_47NEP;F_oO=_FG~GZlDuHT(<%hnViLz#I zciE&n)j(yVv{=l`clf0N!^Hiit*<7+qua}=mAR9X_u~sxJT}0*=Z&lBiqn{00e%EfR>6S zQkF=3AX)@{5eu?yj23#_6czl&IDdAqjqgf4kwSu0nlTuq?1q`TkHG{7Mm&BxaR|q$ zS}*fQYO}n#1si*J^}46P8U!E!0V_N!aF7D%w^d) zn~seRjE?q4Vo9hB$0YH<{5zS>Eq85d+Soh{H826oM~Sc*0ucCP1f=RLkdhTY3q;4| z$2P*aUM+cfC4Kia9Z(t-8GSWrZAs2!7J+s+3&Ovd#fVf*8lHB!@OCD>&01Y%g&_nW z0D%PwZfAgmV!6&EZ5eo9*R2{rzs)H zNBTb*`h-Nt1px>^z!PZJlV|B@>5@Wc*EX0|3EXI9+q2%Yv|F1livrz*+yT^SmdU zMXPsN^orC&u`7g|iE5P}8=a;=YUL_d7Kx>DAuzSkPs%O3&LI6k|6FizVv7&Ma?ww> zIZM);vJ;SX6UfcWL|ZzUE=tIL3pWTr00N<8tVu#kUaD(8NULW1kz1XM`!_av`Pz=& z>X+qNvA!OcG=P0psvtUHAc2XW?!FuELYO$7v<2Umr<)ToVZZbRx{Z zYU&LSiHotQ4WXMA!sY=b&C)_s*@Wt>a=4>@>rxi9<$9q)N{@1zdplL`K13yRcUM}$ zhurmQ#U=}N0F_Ml?j}|n`0~7p_sib@pgVy6!9$&$(pw%97iW>W#9fJs^)Rs_J*cdk zR5yGCGY{P*4DUJ)&V~|NRd1g-5aW99Db12AS2bpY#jQ9_mxYtdjDhH9TC&Yd6!N6; z_$Z6^@mT&s0Qvyr&%j?uiX0{rShX5dY3jpV$+QaBvhCb`1!T7?FJl!(RCR;y+1mT6 zL<0HDp(V4IyEsrc!-zhJC?+Hx$AYuLUUI0x6yYyRAOTSEpBO2aL>9(Llu9NbGI5lF5GVQYK90x|g=^ ztyB+E#5!mmNzB=Hi=w|Wa}sa7GC9M)Ng$l{-^`Az<`A$dHpkYTR@~G4f%#PX4vdH! z{o+Xd|H$Qmqv2&A#O3TI8_i_Lf>)8-?U%%pxygpfb*|u~x+Oafw@3cuSK7jC9qs63%6Ry zwHW^;0{WbkkHKF`k6eC=z@)OJJ!uD=xG9Te{tZei12uTZ%c&*b&x(3}%7DC>x!rvO zvK;b0XZdq&L3(JVR!Zlfqr?3uyq|zPC-M&$1l~_z-jlp%$*;LvbqPSL`m&%M?^{e~ zxDy-werEajjK7tZ`7xS@K2vzkKOqW^R|mH?X~8d1)Z(&6MW+Ir$)51KXsfxos5*O zuLCGvTEu-`KrNiF1Z8forXK_E8%TM5C7%$8I+GtRa<6WjPra^07`AzZ6m(jUk;zLL zvp+$gcnJPPMkMi*1oY?eM>3b{s5LS*vs5uf|7lB6~V=a}TY^J-*HBGcI-<7>J z%)DZs@+478to==*Ab;w{(%&&-#ppRp8eg&~@-(y2MxbI1*{dfF*`8*#CFUD1ikYW2u_ORlFQX`P5aB-f+1Bebuh*+pX{txrTpF@EsmTQx~h;%Be-yF=Eus zl;x=EJ#FN#CcxRg`uGT52wZ%K-L`rBB!=>Gr9Ttovw2>lCGiv|rv|=HxmbJKQWiT( zz0DuUHL{WY7GOs+MISP}jH=@S@hSx5tXGMJI3RF|z}07X^22XmB=;$H>nrbOZtYT@ z2b(S$^{*_>c-KHm<{*R{mRmv9{4Bnn^AvqH>M0|CGXXi^H^)!x5V-sZyGQ?~hd-;E zekjdC0xeh09Ns~wV*J|W_w~1DG2aEOA9*XSjZDdQY-G`A!;UiIR}+xufC~a|Ch*ZC z+<5#OqO*9ix+&i+HM~6<$TX5TuEd@2n=h=14Z{Lf3pAchkhJ!d6&Y6g@O9 zG%+A}s_WLEG5!nzcgD{+#w!Ho5LodME=p%sO?_S6l-FYtYO$@RUty`)?d2n>?cAvY zSu*m9d1P<;`o`n-#3jU@Us-Yg#4N(7r;q$S1gc}-dko%_6p{Wif$EWNq8QO>ZoDWI zf1!jr6Y@0+mrM#lT-fzxS{)U2R<3ocd#R=~(cRGx0j9fX?`&we_(Zhvl(8Jwu9_{OU{B&h|oEl&->jMk75T_*(m4Y}3xWA6T<}2X@uS8&9_LM8;xx&$z8ibUtPmhZ{e4 zNhI}^i6l~YMU6Nrq;Z+SYYCL+?9#}O{k2&U_%9RCM>v+OCW)-JHP`10y~pzFrQbgP z;aqA{aDmI8{AxyHEvLEE67KWZ?ATMcR3yL@=ElHR1ro~UN}|Lvpbg5FM3`}ZI{`h< zED1gNY|an@ZzJHI;e(J56%O`aSoR@pJ?l44Lw0Lf=s_;`w!iK|N4+hsrDoN+?09wh z)^;T@xiSO!I1}GJtfHvhX_VE6{lFlfwKnq?6WBZnPVnM%2ps}>Pw3Ei>>+PCmapLc z)yzV+G#5S=s$JKzx`u*di#n+Vd6Il-bl_OybfH+heim=N7!Qp0wjqCzfE;S>zMki6 zj3Mv>0>_VV@fP&ejLI*Ycdg+_)V-?}qHSueY-D0~r#Wr(MNkxlriONhT5n`q$J!_2 zCe~rqyA@V&a4|G<7w0~eVgncKjUiNZCrjf<5HF83c_Ux$e}G8 z9DzaL0)hP}TDpKd^6sDV$cyt*cca+=^(7TxO)oc6Xz)**ESZ ztjz51sg&nU1;);mEe95Qj~@*-UUA1NOY0GEr?y^DLSHTTr z5~d%7a%!tYmiv^k%ECt;k;z8vi)OxaXpbo6u{1UvEH`%CCXx(yE+t^=VJP?P+HBUf zjTFJ!1mx7#j*#deaFW2zBP|cRJo2q-Reu-0|HWv188y=U!?zhP8bG6(F5>}Jui{h> z)kSCA;?0@|(K-S#fH+J5qbMr5fl*UQ+MFveUXOqr+ImqD5d^LiNOh`d!$0rtRzLb_ z{?K=#@n!VMl(*1H8v5;&Q)bQeQfSHVBGAQMjnd@9vm*T%wlVF5CX3duPruoAEF!+2 zz~~p^{z&iufk_0cPQ|j-w(6EE4c*pO{*tu$ZM3i~Cwph`k~2Y7sSa#CsNzM37%=y! zN}H>P*@-Mm@I1VZO~f}7Xdd*b2dwAk+EULN@`nlZ5BlN2a1VjY1hS`EUox82Ou9nyAVZO4 zqO|y}QPX=2N>_CzA2J&a_KdE#dSLzF-R)bz#{4v~hOMIvgFg3l3D~z{-S~(M0%r+i zg;+|Jt7Ub?^7Bm5`*5nY?pg02={LQ{_(KnqPB!wz6}^yHHV(4x-FC&jUA^}#BoHCy z5q_KJCT!-uD1o6u0bU{%f`|mNuS%3LfWVIskjGzt zbGJmk$6rQkQSvzuuqmrzHXPXKRQByFwJ}3WXzgdy32_W^XEWjz2wXb%6#^#)2<#Ks zd9)WPT-_d(LbtZ0ib>eXTYgjKGxOUzinVy(ayQD_%-iPz?d>`IcKjURZ=e64&c0on zM7qdhKU653{{j_!#KgSK09LD#d`8)yI+4E;W1YakxNNvu0MvsBC zvy(3vJyWOTMP+c4SG=JaP>I(5^{CFn$6)%4JR5`2qE-;Fqc22EAn>;dtW&W>>i0Ebl>r^aXXydJ) z`2AnhvWja+J{;*}*2_eylYXF2u5>x(*&GCTKj?!1SpI-O`4E3#h^-KK3xS17mJ1~o zVHqrfunI-PlHWI4v^rQM(maevG8Zz200bcLcL^-hH4L$Y6Dsjj(4|jhzBi3kSAAEL zXkABJ?g|VS3~f191Ox#H{0#y{!9=K?Y&n3Qnr~=}FeD5J zKmY5Z&(Vt>xYg>9yYVGX70B{Wf2teR_1n6g5*7Ei>{=%j2XZnt|we+w=`q{%F z;2r`HfWVgsQ15!64;z8BJnLoJHV*ZBj&74nSnEY~Te=vA00e%PfWCpeu-<*4LJzo* zRu(TCulH9RX=gwC?Iv*u{1O3Ivb7xlQqJSK?zZ{Z#tfi#HhWPUckmre`q_6l;{^f` zc#?px$xnuG)wjM^Ufn!lU)j#2WdxW5uXPjrkDHL#xF7%l2>f{hQiNZao?jQgG2s}VQYw`nrKX!R{k>2kCp_S?1e+-j!|2Vsu2JR*`GgfRt z00I!WOu%aJ;EXz(k_A+@z z(aF;}Jm7z!7XCo?xP$-%o+dyI`uGI0c4oHpW$k0LZ!@sc8|mBF5ibNF@Hv4$T!X%u zn!b>QpA1gE+4Ip=l<7DoO~UDw?FpUvpOfKYqYZt9mIc{06)e3 z>Ek82CV{0Nw0<#&}qcfPaH|?K{jt;4Z!8kpJ0$K)uY- z^4u?T6a?~30_%+u3bDD0Mx4FX=@+eerv-C;`IySpu#s6iw|lAa)An_M5&Qmc>MP-XKNdBGX%nE2q&t4bXJau<&C9tajJ! zYt3&+9i<$VkH58a^(4)tn7(S^r}y3R?C6>NG}eCdw*c?EV+8_B6R`RntGAyn9dZaR zgg&+Ns8QNkV0`lK=$+hgtZv7AtoMr=ckup2j^zB82>2SV?>jCpt4Z?<(`;l`=%&UQ zYv)v}vlCy~-aY+n;e?+IO`g`T{13Z5nIyg;aGpT@&3M80B=(;3+4gp*$#4CyKlXw^ zUJ!V}lUT(2#ff}rxgY?6LjqFS50(C$g7q`^hWh6+BcZ=X;3vPLfA1K{=zapBu;1@# zB@ZF%Uu@+ooddCq5a1~tp@a?uev^Q9Gc6M5U(fha`Hp7>s(q@k>9b)40zXe6wzJcf zLU;Z=zxe=8AH@6+mbD0*WsioyAn-T=?Me1tcJ}Qo+xmDKj|XrT-cG=j>^>ZR*Vt#n z3IvV`{O#%@J<0zqkh7&iw;uCD<0OHz=Wx>eo7MmJck#_9L+tM$AVoV?{C9+WCd&M+ zA|H>~5H4I0_#y!wxi7-T)!!o^%}lSqm)ge}(asFv^sYYL;KxV3h5`3QTq6*ofWUhR zxGxdkqxT*kk^d0_w6i~QkfiY>f$*=Fo{XXI`@y$IntcCQSeZ_Mm$T_eF$jUh2=L3$ z#SVmUZXv+S*)3Qx3W1dfxF1>{`nmNXw@blaDVV<<3s2kMK3}qffFtnSul%0#yv)J# z%J8kDfb_RW;|BsW2~@v6q-)HCJJ%Mk40Cz*tN7x&*YH$*&OgS~pH2d+OJ` zKS-V*9DeZ7N%{2z-1pWuveeJkd_kkay#8T(O#<$_@S0c&6aw!iFz-F8Y-KikHyfgd zz{dn=XCEWP00hPegdX(SU(ApnK<%GkFW&Wq?ZLnGF@^yx2;4(Jz6keN#wr9LP!WiI z=j^x6Z*=DL>#G0Bw#l4e)7vVqOd;?a1n6eJan5A93W2Pno$6_+p-Cp%!+bxp%xb&* zl)B1^6UWyGxG%xieBlTJ5O4&Fzr-<0q-qfoe_QEJ%>d1w`4-s%*i66?AR3Wek z0pE?Pp41OczNq<^HSW*1=yzFHaw%g7{0srw+0Ps`i7rMU_N2T~bz(H#aSt#BAoDXvO`;H3ltAohz4)5lO#TI0Zv*ll zB+z+EevkwyLjVE~64)t z#PXC28ABi^;2sh`4Udc7a}~xAfB*!ZC6LO~vvJ^kWdf<4Nt8S@E1wmyLEt9|q_R|& ztDl5H(mMp=%URH|Ur;A;czFx!+#vt~2z--3(au~!O4aF`QQ&KN0==JhXkyDB9RWh% zM+iujDq7l)y`0?5Cz!C%?0D+kVtSaqUbajn}wg>1>t{wf9qrY&B zf2oKkr0CnqK$9p|mJ@A9=^3>>~VIK$DEJFYS5V(^- zs78g4vXuF5rkdK$_Ih7ohsob35PsN^$HP4xJR5)i$jJ}_s}hhmE`PZYvso%kVLhqw zmbU6~J`q>;(70#mi3sos0SG`K5C|PB^)@GQi~8fXy`G6`-q6BU?thiQ$<7p>Av)S$ zeIUpS06QUpQrQga8B} z@Ye~@%{C{@Z(lb^5I_I|5Lli7wR>|!AlV>6009Ul2`MZ_WrL8zcxI009UrPk`E89})jDu_nSC0uX?}(ggG`JW#tgXGDYF zAVB~D2tZ(Y0-FD%?$(Z_BW^4IC20@HU&@hO zAOHaf{1F1an}wd%%Ia6!8QrY)G$4Zj1R$^^0eK}$9jzJS4|TKR?{*57CJ=-WfB*y_ zupR-c+1k-Me^38+ih9w_^p~&nv-O@>B7y(}AkZQZdzHMUwG`aHQ)`R=p0s)$z{}fWQL;suJFc;Fn&`QvUL;`ZJlQv>8DF z0uXp90bb71!4<7tCbY8zhYaP@ahoVT8cGi9#kU{_g5Ll5wS;1F~ z@M|%Z-K^+rUyA`p5P$##AaISqaXUNKxaN7iUB8p*dhCe^0uX?}X9UVOl9sKXsqx1s zT6mB_00IzzzzPHgn$^$z){TC)!V^gh5P$##E)j4g{GeSOtzUAx;-*6qD+WzW5P$## zARq(=N;vI|M+E{9fB*y*Cm`=;yqtwYIv^3$xI+K}5P-mP1P;5|5B(1|@*hnv_jnQz z1Rwx`Q3A*9j8~RXmgqqM0uX?}V+01;8U5_B)4?$WAOHafj1f5QX8Z0uY!&V7H^u&ZaQN2m~Mi z0SMeoVE^Bq9sgC4o5RCA1Rwwb2teSNfHt$8-!|?n9UDgj0uX=z1R(Gg0`l@D9j)87 z`YT_F4<`_S00bZafnx&N$^1uCd#BMg^$|h<0uX=z1inrn?`EC%vyS-dq2dq%5P$## zAkZNo-OPT~sC})aMK^0vK?VT`KmYcE;mY(AZ*LhDkBI$00Izz!1DyMZr1E& zF2Yuedp>X?fB*y_009U@0{P2X6qWPL1Rwwb2&_k7pq;H3G!a1n0uX=z1WE$= z?;6XMI2%xjx(pxy0SG_<0uK=2WcE-Oud**QP3IPZ}00N@~241~rW}`6Cg8&2|0D*@HxRfB*!3p1{EG5eHO$9wPuC009U<00Izz00bZa0SG_<0uX=z1Rwx` z0RsH8aR3r35P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV= z5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHaf zKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_ z009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz z00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_0D;E{{CmtZjv)X62tWV= zQwaR~_wPUVhYJD_fB*y_@L~e4o7wf^90(l(5P$##AQ0M_-2dY(jRyh(5P$##UP?fI z*BGyt=0MmGfB*y_00AKodm1<(009U<00QqOz~2dZ_xTY$1Rwwb2tWV=5P$##AOHaf zKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_ z009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz z00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_< z0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb z2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$## zAOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;| zfB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U< z00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa z0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV= z5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHaf zKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_ z009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz z00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_< z0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb z2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$## zAOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;| zfB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U< z00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa z0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z z1Rwwb2tWV=5P$##AOL}<2>g4>F@7Nc0SG_<0&@ubbJu_LvpF!a0s#m>00NH@kbb6D zjDY4AQ80i21Rwx`HxUROE#BW0Jh4Im0uX=z1dM?EzOlMM0|5v?00IzrErHb2GzEU` z_}Y^sa0oyE0uV?&jdsS<009U<00M6&U>(i<2J+2G5IY1Q009X6Jc00r_VXYB009U< z00J*3Ab&lC|03<>he-GkfB*y_Kr7=JfB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb z2tWV=5P-lw0sogC_mxemq7Wyz~5D40Rj+!00bbgIDw+0Egmc3K>z{}fB*zK z1l;c&<$pIM{OVCh9aY2-fB*y_0D*-G=>On;=x4sYEgUYPK>z{}fB*#g1hRhShkadE zAOHafKmY>E63Bk%7#f=VM``?rY0I7%fk6NQ5P(3RK=zu(|Kra-CRQK-0SG`~Wdiay z9phgNvCdY8%gb8HgBb)M009UrO2B^UShh8O<+$i!5f%g>009W>60n|@{o+yn{v&T@ zyUbXG00bZafi(#f-7HMj43(%L009U<00LbC^}j}QEv>7|0t6rc0SG`~Wdh-~OnV!@ za9sJQhz$Y|fB*!#1oYpc#s3*B+F2JA3lM++1R$_50sR{w`j_`zC*yaG3!fCBK>z{} zfWRRE{g-C6vqMfOKmY;|fWX28TpwFFIzod01Rwwb2#gb;qm8pd69N!`00h<}Kp$K0 zOo#{q5P$##&J&=YooB`l2tWV=5Lk-buoQQlfK3Ufu#ui50#+QcK`qY literal 0 HcmV?d00001 diff --git a/src/FAST_LIO_LOCALIZATION/PCD/map_test.yaml b/src/FAST_LIO_LOCALIZATION/PCD/map_test.yaml new file mode 100644 index 0000000..ccb4a96 --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/PCD/map_test.yaml @@ -0,0 +1,7 @@ +image: map_test.pgm +resolution: 0.050000 +origin: [-45.092827, -36.606453, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/FAST_LIO_LOCALIZATION/PCD/mapc.pgm b/src/FAST_LIO_LOCALIZATION/PCD/mapc.pgm new file mode 100644 index 0000000000000000000000000000000000000000..ab94a1691e199980a412d9dda0994e78e61b5331 GIT binary patch literal 6466278 zcmeF)Pmk+Px)<=XzOP~=_Hen z{O^DJ+h6|iU;g7?|M4&X>tFrtfBwIJ_@}@A>wo)~fBNgc`M0I?*MIoC2LS>E2oNAZ zfB*pk1PBlyK;UVCKY#xIC;$I+OAQDRAV7cs0RjZ}BTy4viFWzF{fx^<2oNAZfB*pk z1YQv+6L#?^P2>L_1PBlyK!5-N0*4fc`>^AV7e?r3Lz67az2X zZ0A9M009C72oNA}Jb@w0P4UhbD2{g$jhFxd0t5&UATSC{u`X`K#=Tgxb|a1g0RjXF z5FkL{U;_0HY{t5Sjofev5FkK+009C7dV!pwiyx-ydKP5@1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkL{odSRUymN2%MSuVS0t5&UAh3-<33ZX{ zWV>y6^-6#M0RjXF5O|}&pL|5LtN(lBuI-8d0RjXF5FkKcRe^FRb_jRF?A@xp>x=*a z0t5&UAVA=40yWi5+3sySwj%-r2oNAZfB=DY1^QqY<#l`48vz0Y2oNAZfWVss+I`qQ z-o0tpc0+&w0RjXF5FoIkz@1#TV(+>lK!5-N0t5&Uc%MK&Q&o(%tapUtFh&9d2oNAZfB=DBV7M(?p8B=Q1PBlyK!5-N0!I@VbKTJfZoC8t5FkK+ z009EMKzuJY9^Kbt`_0M(2oNAZfB*pkhZ1lT_E4wGU`m<)VKV*>#K1PBly zKwvF_;oF95b*CQ!1PBlyK!5;&j|gl%SLgojM^3Aq5+Fc;009D*6WDmJF1o**sRJfJ zfB*pk1PFXWVB6HSZSSA(vQGj82oNAZfWQ?6%++1-tUG1`1PBlyK;U=+F&FpEe4P8Q z$2+A)On?9Z0t5(LQ=sIwZ&Tej8?OoGs0k1tK!5-N0{ayB<{oPad?xGmdDe`I009C7 z2oNA}D^P;l!|WFGcqZ#^#VivbK!5-N0t9v_P($6_U^i^~_JemjJR(CPK!5-N0t5(L zQD91SdB3$R#{68|cx_v*sN$Fj5FkK+009CA6KK&b)7-c)Cc0d6utPFj0t5&UAV7e? z!35U$#M_wW>I_{?abvoR!og4smjD3*1PBlya6y6LUTZn>xZ^sXp&J6;1yvj}0RjXF z5FkL{Z~`^Db;HgT;^4r%QbKcH3Usq(-6#)VS z2oNAZU?z~cF29~yZkEoryt)u~UAwk@xm&$K@qK&RVDP#mK!5-N0t5)WE->B|t*P$y zj&54MKVH3mk2i;GkpKY#1PBly@JWF#)@AXNV_Cd!$!;;B4hRq+K!5;&qYB)lx}zS3 zaT6dwfB*pk1THR6?!3-|-C;RqpX592QS5BsCO>y}LJWrh0RjXF{3KA{yuZBz`|;59 zQ^5FX`%eb8KM*LeY#-QIO@IIa0t9v|aP!^O7-zhpN8J1PJA0Qo?}m&VdkoZLC4qhx z_v5F3rDM_!0RjXF5V(xMmsB*qvwxZ(2l99jZL?7K*y#B!nWWo~=bLLmfB*pk1PFXk zpvJoR+1||a`GX@Gc0CMdHjpmDjU%2_u&_v=_};taB$?)_>m{d(zDvfe6eq>?)o!r+2Db zMSuVS0t5(rT%f&ke|#W!2GHGcZNnU&?^L&HRe=a_`Tx@+iF07009C72z*xHD3gnyRoZgzEy;a-{=lqRjdkU4y)L#q z=lUi2L7jd@yOZ!JfYF(#iea$5sLa2oNA}27&lH zP=@SrhQrz4F_g%B?_ug}f2Ycb2oNAZfWV;zW`X0-N3!?9&!o%3-p6Zv1PBlyK!Cup z1a7j18KjL*-{igVj&x6e009C72wY5HN*QD6VgjEy+?c4l%7->T;cK4+2oNAZ;Fx*|G&e7|qw*QBCgGU?0RjXF5FoHyfq9U-T{3C+p%W)b ze+b@g2@oJafWUzT;sai{VQ#+cUz~d5=`C@t>c4THc13^y0RjXFoJL@t;=U}M<~R>< zAanc!4A>9}5FkK+0D*l7#MDq5$vjZpE=~1Xea|ZkjPrDz{mQ%09RUIa2oNA}et`&g zU7EOGJU_$7kMIus$H!y<1PBlyK!Csz1@5GZ`Klux)WOC)2QU8+MgCh9d2a z5FkK+0D;d5#I3*|C+Tu`+-ZfqWj*Gw|Njy#`W4-0 z@|N%N537kuk@o00RjXF5Fl`M zfrt>d$zs0zgixJnx?U=26Q55|&8p79#kv`e1p)*J5FkL{cLJH}VovThS5k2+ijK!5FkK+009C|3A7ofK48qtKXrHI;8&zp3BGIf^V7Mqod5v> z1PBl~xj=~~-#$#*o%{vh@CXnfK!5;&lL>qq?HSGL~dxM*>0Ge=K=009C72oTt_z_;P9 zWxLymx90;gHUb0)5FkK+z*Pl)2zC+e;&D|T$4!6$0RjXF5IBxNOK#r=yyF~>krE(4 zfB*pk1gx&vF6-lDccddRRssYF5FkK+0D&qH-;n5M z?tBH-D}w+50t5&UAaG=XNOngazp)b_K!5-N0t5&Q0-5SWJFf=<1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72&^FR@aAi5c(`$e9qWPs0RjXF5FkKcO@Z&eFyXrtYf9^j z009C72oNB!p};p&a`CsHn6KN=Ue^Q&5FkK+0D%<+;_t5edaJdqi_qsmfB*pk1PBly zuzP{-FC(sFmE(4Q&J2(M0RjXF5Fl_*Apa`j40m!4AT32@oJafB*pk1X7@6yZU|DHettw009C72oNAZ;IINM(#7{B z@;ej0IC0o>Y2XA15FkK+00B|XYk&X&0t5&UAaE9elI(=Lvz$!FL4W`O0t5(LTR^J2 z_W5`81PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7e?+5&&_>l(hZv9_!J2oNAZfB*pk?-gi&CGvasYHtJx5FkK+009DP3bagDp4aSF zUjzscAV7cs0RnFo=u(|r_f~m3BS3%v0RjXFtSQi^x;6W~WM3vcFL~M>Gywtx2oTtb zKp*Segk5-2TC4-P5K?mj1PBlyK;U_SS*rWvU!{FsuxpW+<)8MAN4Hv$009C72oNCf z4uQ-d(~o!T^0fPy80EUto@56`fB*pk1okU1iz4Qj7M-Y>rJ2t~mKqZvK!5-N0#6H+ z8?Wslh&-(~Z_psybKH-e*RVu@009C72oTs%poI_#WGQkNksGS0ycAV?0t5&UAVA;= zff_-cXrSr?ffnZaXTk0Pmem9Z5FkK+z!m~!qRw318n6L*@3BVT`XE4n009C72>f0^ zw)?%+!MB0d0C)jO$ z-ltr*^`7)kfB*pk1PEMHAVQs3_pWmW?3GPd>%UE}w zQ|Cws5FkK+z&ZjM>CAhqgZaT;GSi)O*7Z)V^NRi8Yt60+5FkKcw*qB;r~bFw5gOPp z1!~lZpHt|WO26!6$JP2dyEw=*9ovrC4UGT+0tAjC5O0*;9*=Uio*8G%+nq7?v}ji> z&UkpwoMLqe5FkK+z+6D8n|qvPDH2Z&K=br-h9p#uAzrrian9^|mY1R9AV7csfwv0O zRM*}j-@0o%+g2dLPt0d!xGTHLlYEjh-Ht5;PjX1xz8LgQfB*pkR}jca5ATa-KGk`4 z`^l|S9c+E=dIg{Aq&gS^1PBm#MW9aOxQX?O-LcxlnJy!)C;V7L|7o-}wZ_3kP5JI8 zFWU(aAVA=x0{JFi-|tU)gbu3;l;j@aJvjleJ^d79&KAOr{yAVA=E0`*f?rs{sD zrPg5traz}lrNa!~KnV~aK!Ct&0yWpY)>bP5yB3HWvi``j>r-TK1PBlyu%e__eYh7qX;Nk-1PeuMH_f%SW^sF ze-$|Xr2=sc<+Zf5Bkc(gAV7e?0s%7&3-B~0FbL$FHw^*=2oNCfQGuAM^B_QAnLti? z$9&zgZnP#qfB*pkuM3!Bc->A*0!<*VqxjKQcqTxA009DT7w|6hc5*vBqd*tyBHOvH z&Ulg?69EDQ_AX#@Vee49fl351$#kCqRGz z0RjXFJS%WN*|`_{tfTq_2oNAZfB=C{3zP(R_hHKJ(`Uy12@oJafB*pk&kNiQc4eiz zvCms-L4W`O0t5&U_^iOAWGC8v_Pp3T0RjXF5FkL{1%ZdrF8^XX-=lbeR1*RO2oNAZ zfWT)29(~d-1D}uEedeUtD**xo2oNAZ;3a|YlHE%kYD9nl0RjXF5Fqd=0nzSL^7c!B z009C72oTsn;L%6z%3q1H!QOO9fB*pk1PBlyu#rIg1t$+5K4`a*x^4*&AV7cs0Ro!| zJc@R)LlbwKvFn%s0RjX*C{XT8xi$4cf4kmL;8C!P`Mmt!hWpkv0RjXF5O}vhdEa~Y zF71!NI|Uv^ySPz1{E;TE0oTDhPl|mJAV7e?76SDxZ;PJwNnj5GHLX30b~$Ay(Cy(w z83O?V1PCk@7~kxccBDOloePYw^*e!b4NVSar33;b=<#w-b@Pu1PBn=LO`n9LRFtT7bq|L_}fkH zK3*8QT=xQ+CIko&Ah5Q;@V4gre`~|)?+^laV%@Xjmgt@pQ=b3<0t7Y^XsK?a?sZFG z-vYODcCU_BwtH1hI|2j<5Lit>s#}dxM~4JuP9fWRVwKFW>dMLlXvfB*pk z1PBly@EL*n*T{{T&J4q6PJ_J?AV7cs0RjXT3zS5+**7H?4^9UJ2oNAZfB*pkPYJ|# z8cftZMW!+V0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXFTuk84#g5nE5+Fc;009C7PATvw9;ZAq2StDY0RjXF5V(?nRClGb?N|vA zAV7csf%6Jvsxw)4-V^M|2oNAZfB=DO2-HyLChRrNwxc9KfB*pk1kNll)hN9!(et{o%+0t5&UAaHsCsqXZr*Z~qC zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z9~AI!Lwpe5t_ctzK!5-N0xJo;{O`C5gDaf@-4Gx^fB*pk1XdAvJ)OPYa+QJWga82o z1PBlyKw!CmNVnWj4+IDhAV7csfsYIP$;ZcsVE_aO5FkK+009D3;Pubd4Y}^+4x9l3 z1PBlyK!5;&9SGFfy7>9`@;}*b2dBgk2oNAZfB=Cj3%vgMxGC0+r7J@^b^-(l5FkK+ zz)=OpFgF#-w4Db50t5&UAV7e?2L#H!)0ZDpnwyti?odMl1PBlyK!5;&mj$+pbqo4^ z`B*e0K!5-N0t5(LRG>t!Md>TPC~@ymIG4-5Nlzq?w$0DCXj z#kv%#^zkCOW!5CR`Xtu))62;fB*pk1PJUypw8Mws{3xz zE^F;$z(zrU009C72oN}fz>=xDIR0UNu2Do}LBiz774&%cW9ezweUW zi(}A?009C72oNAZpa_)kHN>#jIBpwfc*}lUtZQ?1CDOHB+z)tdt7ifP2oNAZfB=C{ z2-L9FrtHd6TTySsMudw;`x(!?|@`&1+d6vfi*^Olmd4Wz8YYWu7Z7qkUGZ{j{!Pr3V25 z1PBlyK!Cue0yT)$JlDmrTro}I)moYLax@VIYa!RgBweJs8tLLGmt)a`009C72oNAZ z;4K0<#Wp0e++jwvn#VGf<+eJM%zC+Lh;c)O*cxlbr&^9>4*~=T5FkK+0D(6Mlq43h zE}n*XH-xq}&(`I$TFmSgwfl;(GB*#|F1Nj5_;x{n009C72oNAp1?ntaX0(#XGU3&T z7C*<}mUU~Tx;DyLBNuBae%64P)%_qqfB*pk1PBm#n?Q|mk>(3Jk_j+ zl>h+(1PBlyK;ZoX5$4KXGss1`F4gC8LnOA0cy&!%YNO5Ct(&&eGXVkw2oNAZfWSKi zB9irw*!Qqpi!o_e|7){x8Q^j*uWiejyRuLkzH{vMMSuVS0t5&UAkYLNu$3&9xh>LM zSszdN$a03Y*q;B7W>Fq~4lU!UJldw*?gs$^1PBlyK!Cs-1!{cDG*^<@7}kbV7ilg3 zizqh)w-)L$3g-ISFk_uy_r`N)R|E(UAV7csfleUf+OV8cZV}%y!DW1ltk&XO6mx5- zp6hDB%f?Zx4Tiov5gf0RRwT$kA{%CVSPZ)$%~4Z|itfB=DC z2(;h-zo@DT0Rrz6h&a|B5!w23TZ;8rZiUQob>&cuP!~P5CaoLK1PBlya5{ndmT3F;tLti=x>cMz{!76T5FkL{cLKxP!|y7qMS#G& z1TvBhJB#c#K5CH5#abt~MbwL0Q>u$(mv!rpXwdaCcBepq009C72oNB!rNC{F8~2qV ztu94sE01AQE9JVnGFIjPOO;{G*pC7M0t5&UAV7e?_5vBrhTTMY++)8`D-GMm4Y@X2 zjPrKccmCUCMV8@l3&@HRi;W~Z3O}Z2oNAZfB=E51coeDyT4f&_xWZ07}?5}Rx2tE_g^E}c@Q8# zfB*pk1PHuOphmH_zb>QY#9g<3ifMh5sT`&9Xe~SwAV7cs0RjXFyjP%4VzXQ}Wwcm5 zRf}RvZ#U(sQh%HFy~ks31PBlyK!5;&OA6fNwK1^u>*GriEyu+@*0J2Lo=xseRW6C@ zpa~ElK!5-N0`C@xyw*Zmmb-;1nst>Typ0>OMH_N<)S9=Io(T{jK!5-N0tDV6&?UKA zY_Y5hY+bPosVq$cnEwas`Tr3Qu$x>VBZ_Umc zyk+QiLVy4P0t5&UATS7ITx%Jv=CZn!<$l9RR<`uzwon^STgH+C0RjXF5FkK+!1e-N zdYk34ZhcP3weZ%@&gI?M`y0xp?Z<8p1PBlyK!5-N0)s$=w+W+Ph;rNXX#FhW^_8YB zl?V_ZK!5-N0tB`fh~UW(;?e>RZ4+IDhAV7csfvXE- zcpCy(7v4(NE031U>V~P-h}PAa$Gx$J0s#U92oNAZfWR9BBCoY6xgp8by~f%$+m>}^ z3&Y4}8zKirlNSEoFnYTnK!5-N0t5)0LZAh$B?ptiZ0KN!WwA8NYqtwiaEmQd<5sL| z=1W5@PXq`MAV7cs0Ro*sO-yU#rc7+L=iBf$2DY-fD^EeLX1{S*U7ct#u2&#HfB*pk z1PBn=T;M^f>l0qYxGAwksU^0kHIA?^k1G`j5FkK+009C7-XRdVtOc`2<(!h6CAq%E zILfJ`vTFKJ-ndi$$ty;VsJd<6dOEHk{i!!-jEttLK>j0RjXF z5FkL{fxt@1DRNos>f3Uw)Q7q{iB|{MH!f?&>JNr*H30$y2oNAZfWV3Zvn&=1L*Kc+ zUl{lKZHuv%Sl3Y~5+Fc;009C7HW!$JTzny-Jcd2?<@tu`6LZ;O9O2YkZhU+U+jgrB0zuu0RjXFi~=otjVoR&WG<_H zWnRl@7G33rq0hctr{}s2i5#epD z{3yxw>t_ve4sUF(K!5-N0t5&UAn;Cshrz6DXftmav1bAV2oNAZfB=DS1Y#y_ zh2+$SvA$d*TiySc_2aN&OIzs6LS0kwOn?9Z0t5&U_+DTPQ{PwnX=@+YvfTRZH)O&a zdn#L6oUD~}ZpESm+nuG0LzZ=dA)a;epV z-#7cVi2wlt1PBlyK%fdNk9B=ui}ENtg|rgT`YjL2S*JChX7k4W6bKL?K!5-N0t6li ztS}!|v)B;EZu8oh@v>GML|JIXS={Sej};UM5FkK+009C7eiWF})sIylRmi;7`kCdj z+)|r$#m6^bX9+JB9_`Y40t5&UAV7csfk|M6dAjJV4{Uw;>xP!nqSiQ!zDZvmD<}{k zK!5-N0t5)WLm;Erkka~C7Ul8#4v#kE`Z3~VlQ!lq`L$J^2@oJafB*pk1nvq%@LKwq z1+y-feOcdjHD$fB>#Q{lp_KdkuC4yk0cuZx009C72oN~Gz#7TvCdoClKCfkXYa3?C z?Lp(HyT;hYeJT(jK!5-N0tC)2usAwpcpG}D<+{+X@2BK$rsKL)H;aC=3B7Zl0!K%H z009C72oQK(Ad}bPM3?(7xvY(2mgI6_*pk_;RqJczhQ4_#mxwnO6$lU@K!5-N0t6li z43TMts(#i`Bdl29A0bOs(L0sfB*pk z1PBoLPN1ZxDT{qq@uzK><60K$7y9xn)a4!9)}ou-n^lU5yPtM#I{^X&2oNAZfWVOH zR!B~f-bT-E;cKdE)w)WvB-gJmJ+|s&=L!S}5FkK+009Db1y;#TnclMd(p?wKruB98 znEm<0;cbX%efiIzd%v-P>`OSw(NwFsEDrB*Xu>+2h>KhFdR5FkK+0D(&g zWSkl!)ys$6hqwN&>!bDgQMz$&L#^9LxO`aS9ux==AV7cs0Rrb2nC8h|Kh{3IMY;8q z>)X=phE^#*N_Vf)F!wjsQy@Tq009C72oTs*;7fSxGg`}dS*Z=gRxPGdvM1TMR0t5&UAaGA0 z5>?Ao_qP9LU1YJ=M=cLaw;RUJzS}Skr*%2DQXoKp009C72oSg{FlMp4TYtMUBU9+$=j{pGz1PBlyaB+c{4eJBeiyU2g%Z%10+3Nak-mdjO z4{zNF`VFzV_0$@ACP07y0RjXF5V$X}LT>sJ-ddk^L)~wd$03xZR_-fBCT!~?Z*~jQ zY9#^$2oNAZfB=C`peCl}AF3-|W-uGN{6nwtS|Rda#>BhNW{qRR*g$~*0RjXF5FkL{kw6Vi%cE0fu`z)4S*%ZKUHMCc@iuVZSgLz;;;bh? zfB*pk1PIIpN)oI8%~wCWRP)*p>$>okvv4i#&5~R!44<&;r|Qa%V}l0)0t5&UAV7e? za{`g+mZzx9X!k-|-B5=V<+iK7JWF-64QmYTIS#c65FkL{bOPff!s(980TGx9#P=n} zs5RU2%tA)77TCHT=e^GY+ib7hLR6Y|JzJPoD-j?-fB=DC3-s?Rziy-=fx`)u0M%uv z*M}cjtaX&dVWD52X|Gj^g>iRXt*#iGr#fS01p)*J5FkK+0D&(8F`4#d@Z@99W;lZp*Fv zT;F!qUuL%(T7!6Q_4{?o1PBlyK;V}G{oBnio2W+MkOC3v)<|_VmJITsH0?H*~44CANNjjed{DYdrx11PGi=V0@1_ z*>O1>0-q3wEY{-H%lmIZE<0)q(OX~6g|>^bp?zd7>&%u~r5M@bv5lQ65FkK+!0rTQ zZxg#4odFRzl0Z#i%SYT_l_iLk$IxeP7#8|UeVti37h3D(1JeTm0t5)`Szz|gu;+mq z8-YUz#1*x8pm|xg@D{;rxEVVOY+0%9s@8A&?KadOH>W9t{bl!uGDZ#R677vxT#s0mnsv0D;R2#BcfWPxzNraNq>i5r~Uvjj6gC zziNETOSE02xiE}1@?%>+3v7L*S)Hi0&VlNM009C7_9u|P{=0XE{f*Fw2pmWt6Wt2Q zsa}}%!29wnqdna4rB)}n!r;2z6bTR@Kww7#^?kt~-**<4fB*pkXA;O?_~pl$j>)kQ_@qEwQ!DJh>n4h=%SYwB zwK}gfEcGqo{%fnW!WeZy;9vq?{RcZ?hWorg{>mTUGM;a*1pxv#0&84PabXVK&aTm1 z=r{D`)*?S+*9O(Mh)KM*-ZKFL1PGi?puS_A?ywvXfzJq()U--+iVJf%g4s2i3wJj3 z>xVB+)b_L1>x}I)vi3?~u|T_~7I&lr0y`DRccA#Sztiy<7J=glta3f|S7nsjCHklw zd9BsS@@!#5oa&6L6bKL?K;SF_`5xgn{aH?@%U2LWmD_PGl8oKc=2EDj9>A1^S!_?`YWD#$Gm|+X0dWnE$g~8??YN&&J9EFU)HzX z_8ahZOMgKjdjM=w}4-cmC2hp=WleE`c)(L?Byye8UGL#(v@|9Tw^Z zduO5F(ACd;ICiwc*rvXe2pmmdypE1GaN{NLTY>sk;HCasFZBp~FA(=lmtRkLU5*i~ zF4g^hTkfM@Yuz`9E?S-M55rahCln|b!z)MiQlnRPqz!@P0{JWdwO9J`o$G9bsGd@^~5L*N$zUj4s7QsvkJv-g5y zABxcv__#ogVv9muy(HsjJDOZGEYz)ap)b!qhgTPd_I>M;^rmiG_nrw{Mc}np|7)$T zV(K_|Cop?w*xl$1h`^x)hKaTXV~*T)dr`)_%AJf>s}B2`wTXqHMXqn-@%GdtJYQ2_ z{G-zE58p-edn+|}AW+{5UU;SNVC;rKV21*crj}e#!zDR{vC>myw>HDpHV(%0YM< zt|l@ZN6b# zQXp_8f!U?->jRHg(-rjVW-1c+kU+j-y<|V6Z@1?Z7$(_XI=Fg84%cP8o3s^EslCVK zmM*+a`>R{(a+JF*%QENGkrIJ}3G`RRGee(UK+iN(m%t|k@`c|0(*ML5?32KW1mbF1 za7ER(p6O>!(bdbe{cKpZQeEoHb*iqf)ylDDEGrPWlt6jyzw+{rOY2fj4))*z`DWln zd+@Vp_&X7Z_l=j{Ii~RsSLD5?=((DBL= zx!9}Z@Q0hf|NWvr{CRW$`w+;tjhEg#+W6}gdH-ika;0Y3L#vVPhQ*2F+` zZ5h`p5V(TCYp?#-T3x}@G44{JykNa%cX?(E>W~5vr)tc5R5x9oH>{9skA-~q@*WIf~U{!(mjb9$C_Ng-h7Zr#rDf88W*Ouf6!=a=H+bLp{1cykN`Y=!aqa1ok7a z@Pf(K7+78RP*bS%DS~9w>Cq)9s z5{PTzg%Q8j>V+L?LSO}f{FVRGD}9BX>w>_^1Tr$^MfLiD4b6v3^ZwHq>0)zPXv=l4 z*=EdcS*07!EAMMvb43D26}Y_=etR6=A%82S-p2*`bXuB9!xh}->LTBjN8Mh0yYiADo$yRKq$>(6x-hQ@=9rHsFuW%m zZ{S8uV2=V3s7jPt^vSinC?k;7|AuRHNNR2A(R1Xu_Ne9IXPdd(qna@hc#nWT+Pufv zUOp!fuW^5R`JBH!pHCoST_n5LkF15V-#^Fx@)1|_*epwNfyd+Z;b=*K009C72oSic zz`_ufDQx=DVp@G}Oa1mS)WwctLtkkqFHD+OJ(Z68Tmt3NIM)F=8Uk~H`0YPmV~GHP zB?5U(ExW8TutgY)%kw6q<+fZ~OSw5J$?y)7RN$Ogk7tMcQ21hLjnW{5ZJju{bT&j2WfZ& z4kr+QTzdVHL97dBeK2d~hnsIUjGwB@jF)3tGPKtZN=pI+2oTs9`6jQ;x3;^i1$(}sT;O#@JYDNlI9dV(2wX}ae%T-GfR8xlqZu3TB7wN5 z7G7ELD*weJ{!kW=mfNyCtc%sL96xh7bz#wwX-t3s0Rnp#h~M{n9^cood29M=V$IG3 zGG#3pQ@+ZlK-Ly#&o#2;s+Qg|zh%Xe$QhNdf2wX&<{K`Mrk>;D!!NzR3mlBxnbuK*Y z8pwuwsq=K!FVz6oVqSahYh<~8-frQLG$%lS0D(OVMRtnXFN4_FHVZxV<< zC&kNj`R=+Gdo4cr*$26yT%XF%`d@39V_IQk%a2VD1PBlyK%l*6ksz>Rfeca0$2VoM zp)|bw+xpw*NO1F+z4=nqUp^{55FkK+z)l77Px3F0?KAHW!yDO)W7dqoTLe~#Ps3|H zFSJ^&H&NUAo9B#t`7znjqTkjwlywLD6zyBim7NeEK!Cuf1co=OPwn1*3H&4w$tho^ zKUMs3d*93O!Y@zr#5S!TO2gj!SU0qYRX^@i1p)*J5IC&B@qWp-x30sI8~Fcc?@ZL@ zRAB(x_kZa7U9v%N8%O;emt$KEBm_8Y8Ru{NbOI7~+1s(bJ(bB`edx@$S8cus{ee)%bOm*&#WR}wfTeCoW|#5bD02sGrY@}w|&uU8zT zNb!|}L#H7C0SG*pfP7tarz;RdfmYv{NHD zD>rqQHZ?clfhPnY009U*g+M(i?$RMUtnSiU+WAHT9#HM>y83Z1i?RlF#ZZjoF%{rR zI7dXcdrWWu0SG|g$^^PsRZ4CVSMM@x9+ zCZ~HB7=|mJ5P$##AOHb9wCW-Ampt;RBqwE@TYp(6z9F!KfW4?I6Lp6VEvj?fopkel zq?k1-jj)nlUK_Q$VS779c?duN0ucBc0`@6?!#2O6$oD z>4XnAIg#Dx{O)a>Dzp_QmAmT8EqwBX00bZafrk;09e-PwHWvG)vU(g1gl~Lc3xTr< z_;lS{t+)vv>e3T)`Tiz5Sy}n^;Yh+diR!A`aL*G05P$##9zh_V5MOoZjDtasvWeSQ z4aFD&rxJ(>ySGyH<4(+HPE5%5DlV!`#ZA-|n{vaDCj=k>0SG*XKzkc-#V*-lHoRZ4 zrL+kGjX;^P``?Gzv^S?JyZ@Z8fn0pR%0{kmRn_QgJ9%5j1px>^00Pe>aOoZ1PO$#| z%weEcPaz-?UAcC5M`yixu?65BQ-1%QYgesUMH8&JrE`Ahc|rgJ5P-mQ2-MC0l3mhM zD2^qLq)UzwjY3=5g-5o2tWV=2A33(tH7?N zoEVmFH55%tAVB~E5P$##&L+SybT)D7+d<%%xGBYDNgVuDjI7CW3M}p2VT6Hv0lQ;h zDGC7yKmY;|fWW&5l<2C)P&;}qL0S~g0o$S+MY557Bb;1?$P)q(fB*y_009UtT00Izz00bZaf!7kq(bZ-M<|Kl{>{8@# zoAbL@a#^8r6p?4h;e{szAOHafKmY;|fWQQS98pcE*JX*58h&MuDo0#4QWWQ^n^I`S zMX{~{SU~^+5P$##AOL~46VSh&up5HKWfp=h#b`B1%SNO3cC|SgD%LVJ8vz0kfB*y_ z009UBX8pUW4 zCXOP!tf;L@#gkanB~^_OAOHafKmY;|fB*#M2}s;@K;$IBm{%fV$ok!?``7$lF;Su` z&8xckfkOiU2tWV=5P$##5&;S6QVfTO?`p*fJrIFs5ZLe-IE{pXyXQcU4 zMx|}rn?y+nKmY;|fB*y_@FD^hQ0aK;)M}U2tWV=5P*RH zL(i*8(XK0M(eiq}kT2~IP)lkraNZ$8c!wt?n#$Z{b8yo0qLRMYTYH00bZafmah~N5-o$(0K?92^{oSV27bt zL}{8I%P$%A)h0z3?H%*w@UY9IApijgK;X^<;!wGBA80!S{)Rw~s5aLy3f|mPmu~@^ zug0$0oDjLTBg-`t0Rj+!00iDmpdAzM=0NWuFeK1LQA6d*wD>5oSPs}cG;@vmF(Y@G z6WM6+t}cA8YzSr$fB*y_@N@!%bWa~)`nR1x7g6nV6Q#vvmLt(swbm#c@q_>bAOHaf zKmY;|SRkN3-?pG%snUQ=ZS4oJrf2BQnuT7>7`!}&-Nm5IV-wTXl@E^K&000Izz00bZa0SL?zC_z(-sAkPR zD>N8$vpKnYCD$c}C2D;Hbrl5y1Rwwb2tWV=5LhN~%vZ1)m-&0OVT=~9+j9PFP}fJ9 zQe?ULXdwUr2tWV=5P$##3IUC@4hWob_%$bY0h?CrLoh5*+fx*b5(FRs0SG_<0uX?} zDgrsAT2)}mXc(i_Xl$hL(wZM3TW-RvVyas5AOHafKmY;|fB*!XKn}aMLrGq`uq?lx z>lCR#{DlpxT@}zfB*y_009UfCI00Izz00bZa0SMTOx&tDo6xAiM08UX|r%3so z(Kx{z{}fB*y_009WBAkc+ZE9@stmIJmZlB-%>A`0__00bZa0SG7ozQkc7KwySI z4z*@XK4<3`Ez9{;oyoBlvsKpwNz@9HSo07d009U<00Izz00brobWzlVepObE%d$Kh z)v1w3Z~fob$n7ces_HR<00bZa0SG_<0uYeMX?N_TL0Vxcjpibs~pvi6uCsm zJRtx92tWV=5P$##76{~sYQgM-D!k;VPK$)1BvhOVqibVjX38$MCbMh#V3rF&KtjUZQ1Rwwb2tYsya5OLxATUWF zhgy>ct1?G{T$CCqVkwGZ!YJG8d%LjV2>}Q|00Izj0)BqfV+1e|fIuOjK~xK`wlc}F zn7Is3Nz*A(zO`ahKo)DUihQ0BfB*y_009U<00OfFBxsWOYSv(-BFAVdhsRMO9Ih)- z8W#n4LI45~fB*y<0gi{p0to_2pe%|UUTvn*Imro;!)wm3)rvMNvdp`>K*tjT5P$## z8i9JQv@9eDKtMyN5_Z`F*|AJ=EEcl5i-fY4L_ihXYdq0+R%C5H@MBCNn!3 z$+7rGitsFoDOtk3$maxKBoQ^LVk$9bqy=*ED9jTA z5P$##o<|@Z7|-h*J%Yg51iG+mbLBY}>padTL{Y0tRw`CavZ=-h5P$##An+6dY5RXl zm*@usen~)<)b9VkA;)54S%S3kM-|akNn|+^olz+gHasB!0SG|gX$1Uacv`o_Z(xHEPY6H&0#77h2SywKPwe5RJ{f^e zR_GzHia>;QtBegDB?e_dVUAbvl>;Lb^ z;imX#_K?6q3rgICYjx>~EO!x}CUOatiw`Z4e1#292tWV=5ICAZ-E5C`yxL!PN~|vR z9K-(1drrUT$&U!wg4(;VZCbh)NknhVy{AGUT2suFh|+uk+ejcm00Iy=oKu7_F|?9I)jQRW6oQ z77QgJ_j8F*8w4N#ftL`lJ@%)a)jgkG{-8~vI^H_9kJF$bnxdh5mI%HXk6JM4|EPZMD zCdbW9E_1ae5V*{d#0FWosTiRyG{ zR5eSAS{eZY5P$##jwO&b=wltP_m=nn^`)?c00brol(_1U6_uT2x%0lP@DQ&vD#a%n zO%?R6F{e-DFwfvij;RiCun|P@}qDYuO!bqbLL* z009VGlz?pcZ1fi$9GZ1M0!J;Vv@AQ9DSs5Z)rG7jf?X~lMIxUk1Rwwb2t1B}?*DA` zj~iDy^dkZX{d0ABU8)@286~np<+7Tyk;v^IB9a6b1Rwwb2t1X5?*DA`PaR(Rbuxji z|Ni5!nYu1Lb58Dpw=N+iq_EtybY0;Dbq~0zkAOHafK;W_jx;_80t)yWPxC;SUQTy8(Uc^1sOO^8yY$w&}@00bcLFamlOu+cwkRO!wS33TDr)^>DGBoU5AiqNbwBB%?F zJRtx92t1QOcS@}7Vw@yv?XiQvTL^4gP-8g5AT2DidzE7?jucZRs009U<;1LA$kVw1!BRWMVAn+psWhq5SwW|fX zF2h6iIH%D3SjeM9c;Z!EC4m3|2teS81iC}wi5;X*5IB{EM6)}ODUn2rB_~U$ zRn~-Co)CZl1R(G@0^P~*xZcqr2%JnHf~XotZK}UpmUD?Nzk5a4X-cBCAQWA(M1uFG(e9gY-ImlVrJnh0M*MR?^20SG_<0*@om z9TJc09UX$exdcj#b;yz$hGG$-S@7nmuBKdKR#A$d%Y)h=009U<;I9efja~QuoblI{ z;~xSKCSdDnf9y1h(PE9}fGrz!!DLqC0`f*rU+g`21n3$BAOL|E63{ckUn}fCf?f!a zE<<3FfCf59=7+fxr(4XgF1FyQ`j!%R~|0helKR-Ag~BxY(tl6U0%gwS;_kM1mn68gp2tWV=5P$##AOL}$fQ4EfkM*i=QXY$mAM@yiH4%>7 zNRp%c+Ja;xR#BEG1Rwwb2tWV=5P-lE0S&Kq$4;Xl&8r;c*P28V?aEeJmf$aJctQXI z5P$##AOHafED`9Vs3prKoqF*IOyp|o3C&O=*JOG8;x3A3Pm#wH0uX=z1Rwwb2tZ&& zK!dCOu~UxGvaH{<#*f=+@Fp#g5HDM0*^FvbnBv1x+sS|c1Rwwb2tWV=5C{SqQ0)($ z#&KD$Aj=W2&6cnhwIU($ga8B}009U<00I!0CvedJERkchEZ5g_(t?p(M{}0uX=z1Rwwb2q=LPS4kMPn?~m(I}}B@pOZb@bF)-H8n?S?IDh~IAOHafKmY=- zAdo|?%^mKX48k%E%rrPtMULGfWXr{~OjNgdL?{RW2tWV=5P-nD2$YDckD|7AUjsJ( zzSL!PrQRiYD}SmSn(l8=OhtG^bz8@Sau9$31Rwwb2)vBIQ9+$XY{5>WH&4vTT`-xA zIz>r@Q=Slj00bZa0SG_<0`mkss@okq<+v=%)6t$(Csy&UE|Fc`d~}5+ zvnH1iSFau(Iu8K|KmY;|fB*#6637A7+A?FiVJKE(F;P@=mB(?M|BRiRK>z{}fB*y_0D<=qkncD9@M>e0sdag2&B!H6#CJR9fU!m<|9A=0uX=z1Rwwb2+R`j;Ht$`vzChrbrTkzC_ep7 zpev?~R5h)THWf{HoARwWaTswN}p_wYSan83b-|7&1Rwwb2tWV=5LhOlL6ihu5mhalkG1YV9^xck+_^*5)e@FYbq2H7wQ#OC0RuT z2tWV=5P$##AOL|`0`1k>tjPz3g<->cDWvgOjnO1k6AN-@Bt0SG_<0uX?}3;_+PW^^mEEg~D;b696y z+$3B|(!Qj1Q;*=(ER2ZiDhUJ#KmY;|fB*y_ut;DKYc1MNDZTvSL&}AL$~Ea8Rar8d zVNzP!4K7=h5!U0009U< z00Iz@w_|;H^*s|Wzxaqs)JUorRx0VJI?Kf{vUx%P0uX=z1Rwwb2rLn>0BgzOgU%eR zzNRV(9N zT}6Qa0SG_<0uX=z1eOR`NVR0Ktn-j;)5AS`*_3Kk64f;pNDzPk1Rwwb2tZ(gKp#>q z7|y6Rg>$vi`eS`1$16}>R915%gC_(a009U<00Izzz$Ae#h?=xm&h!9n&%?fvE!C93 z&izE4M0G)eCj=k>0SG_<0uWdxU}4m<&60LcIG4+6NH+}XN_weobP#|51Rwwb2tWV= zm4Jp;HTAWSBeTQg+KS?_$_NmE00bZa0SG_<0`mlR26gdv?XZBZYY#!){J^1s00bZa z0SG_<0+~P;L}kTV`PgvIyy;Kal?Id-b-b!uI}q4G00Izz00bcLY62dUZD;ToL7ji= zDt~ukd&4LR0SG_<0uX=z1YSiTUXE?;^q)j^`n4`0-PSRo90VW$0SG_<0xu+B|6bgV zj{i+mCt=-=Mo|<35P$##AOHafyp4bdW!t;`CsCa`-QFfjLI45~fB*y_0D<=rumEc7 zi?RG)LmV96y>BS!F$5q00SG_<0ub0iKw`0-#SaeW+}(~wQ4|6YfB*y_009WRj(~+w z+q?ZY5uJG5-X=;y00Izz00bZaf%g$0s(as<(_;ug00K8Az-Rs&4<1ebYXTb8?Wn|} z!oRrhXcR>u009U<;GqO&zR8)%ekcUG1%Vj?d!xF)`47WNt7h6uHUuC50SLU9fE-#= z-Ji^yG9(WIk0nt52J4<4mZhYj;lZ~(O`u_^qU^lLX90))F0uXpPf$6AjI``$M=>7`{SQxgq<29HQM>Vli*xM+|LjVF0fWYGj z$jLJ9)O7CHjvNR)oPdR1J3DDkbfMMnbUkm=ga0mU=YUWg0uX?}LkY;CGVI#!|M_z0 zkTeADO2DG7eXVZ`s;spL~<_OS!?Fdmt7<_JS8gRf&c^{009Uj0(zQQx*ZaB#3U<32)vZQF>9goQW7O1v#`z- zTkbC%54sHj2tWV=3k38$8R+ed8Dx@#z#9onEs*ayh!-hU-_^MbTWT8RwU>C2x$xxY z>b@TXNtmEQT^5voa%_t`{XYRJQO_YZK z1Rwx`-w}}A-@m-^-QSXXTU4A)xR}bDFe3{B4<}$T)!t5ump*utzXe+^Q<(cK+lMzP zl^4BO#I?6cl!pKWAOL|M6NnAHJWEUDE;)8QY;2l3m?*0?OyrXVfmacb1+xD$jyiEi z=Fok5!q;&O!hJ5O^qo*wee`j=qYY9mOdMfoBsqW`UR& zTWQ(jP_AoH6dKhDT}^m~$`!wyO{B+Z$6)i|sBb34zBF z(1j-7gzmb0m8qAs;ygHW*It#>HLXxPwJJA_4tF(*!VrJ}1R!t$0fb61nZ$u0*J zhQN~v=qlUYL0e_E)O^Xc2u~#a<7+YG$Zv1=#L$atlUTdEM+OHFfB*!3O+fecbgS(t zr+^#;UtRf(_^Ker5O@IrTW5Pas$ODs>XP$?YKku5brp?Ba`V!r7$hu{I|LvA0SMfc zfPM9%o4ee~p07PAcS(HPD|O+8zApT2W!OXDZUpiI+1z$szG6Wb+pzPI|#gufGrRW$L6}esMJEf%G^*=;cF;& z3Q6c6x5~0RsP^HICj=k>0SMfSz~Eh-?D#e7>z-KYuZvLt0`DMj%mUFhD!_(;nJY@R z{4Q5eZ3_Pk=L*ShR$x?XYuge=c3z1UP}OGT7{!2Jl=^4i^QU!66q)8J0Ln!?`PXjfB*y_0D&75@a?|zpzQvBP{={h zM3ZjZMVkH_0&NQYrv7Wysx)>tsd$m4seZ(xF58k4SrSR%DN|U*ZZ&0O2HYV40SG|g zF$8qaw~b%Vj(7)9vL4e%I&v0)Hk+6~!d!Ta*-vDRjap7Pkzyj(5Kj{&C8nnELTV(L zS<{L)E0=gc00Izzz#|CQ31O#$92R;Ic(Obm(MLLQ9)UJ>m_4$Vl!xQD5K9ssh)oWQ z#$LTfoW$BxkLE#ryLpwxdsJ)7S5@J#OGGA52tWV=5O@j!I}Y02&LK-brH}OEECOvF ziF8)2*R4l+bj?#JUy?B|0@UKQ;!qReT}Z1eeyf!x%(M-KnAP?)sb(QS00Izzz?})$ zVK9HcbKhwD$pnVe=;Z1zSe+7C->#W3t9U6sz{}fWSit#6e+uzu)~NuoRpBLx%cJ4AyJQqC-s@W98bWbj5?F#Ez$9{+{t5&yK~8@zRe zxAFv^@nXPp+^K8InMZDi+)?R zLinl)8fx|NmN>Df&e+OlEx9`9X4LYngx;n2LwBT#mC+vWYtlah+3_Xw7dM5i84Du{Ow+7%jJ3yx3ax z6{}%ftX?s$OIb5xA&XhLw7A#pu3V8TL52VXAOL}T6OhwD&I|t~a=Px_H(LK20?QMq zXn)hJU)Ab3#?>!!uvn}W3aB+&D+a!J6{z3jp`rzH9>+zYYSgNB<5m$81R(GN0&Nd? zL1$mqMLR7@r$uPHe?3HAhJ)_zCy*x6z?p0$qJ7n+OR4X%1zTT%XbaL;sYP#=Em)-n zN$E2uLRR>06mlscYAy&s00Izr1_3`TN@x5y@Qjw<^|Kgp40J?Dj0u!bLFP}dkYt@) zz3SO1?ew6F12zM#CI=?wMW{MNc@{%S$-~N6qJ?-RTeHMUWU+Et3q(Or@PGgWAOL|o z6R=HR_xjQe+wS%5w^83Df0RiE1UdqfQ$**Q%`u%_U5N)LY$>G6?<2#g5S z0Hf2?In{(t|J;Oj`1|e+mY#Ug73#~=m#fhX?`l*MG6bq|g;~kk_WbI+3gLn$1Rwwb z2;7>09RSh=Jrn!@h;tx!Z7MJ8ks)9aMY$IgUBuAOD^0zER$eq6kRH#F#n9B;lrq85 zSL--2(TP25V9mhwGON_hoE=WfhO z{6&%KTWxC!0Rj+s1p(b1UeVK6cT$dtdX)HKRMSGn&IXQwSI?4Tqpv3z z%&Z#6G)HTguU@(sO>)|r^jb78y^~XeLQ&P_K8otP1^xuw^Z^18SV6$HiWP>K+?s%l zv+n!S3q1#PUWbGIA<(=(XSJ9MUC+c zOP&ybzzYb-mhggZzP^k4$v;u3M?n>m5)lF&ffX@IokvaRTs$+OogH_rY^md2b(|9g z%}cpU02lm<(nNjf=AveWCh8DfRA{n0W@`_^JR$HJ0tHu#q(asa_<8Q(JweMAdqp7-_(#f_OIzb?c&6HCvbG> zarVPNjuJh$Gbm1jOyh-enH(1BtKgx+2M#)s>a2Rn6q5cbmx=yLR{2vkRTzRazUoRv zzeT)OlHy4p=0gp{ODM`yHQA`-nDwwa(hz{avkCaF^z2U3yYUXMM}yrQPj?J(BD`?Y z=nRmEPA`oM>NHt{qZ$`sjs4wi43qaFdR+V77!*}#C%SB2kE*bsPW-7G%~#{% zEsR8zgj8Ua*>rJ%VUw7wj(`Sm6=xX_8A)*KmAnIe;Wi>Nl+4vFK+R;%2B{7!%l74oJZxrsT6OGsM zqRc}O@tQ_%o-n`Syj)U+W~i(pHwZug0uXpO0pI+~As~`o`RuTqxW_^9a3*xG5%8g( zpA!~3v;qSurj9%Zs%Itx*lh0tLwnlV>k6os2+krQ%P(Y?WZhbEQB)U}undNtJ*Ou&ae&4whJ@`IC@JRi&+qpnaQfT~YhWV+Cz zw^dg%LKdAm(R)p`EMKf{WGgp{s2guWd3b4k$gQhHGq^zj0uX?}^9acHUk;0M4A_Y< zbD!#XK8&XHYkZ@vU-kQ`a9^2X9&-sY8YpkUYR-k!0szl z-Aff}Bj)SSAK%P-v+(cnr*`|;?7X%;x0SG*uKsgT5 zk<$*3BuyhorKSzYy(s|+5%jmufk8Lg%or#}$!a;$JTOB$s{xgTRdV-OYjtnUhsS7@ zULA`xD#fKc7j2Wx*6J<}s;kvazz_lufB*#UOTbQ!Xn#6Kl9;2uu;lqz0y6RvGU(+| zLEl-|iP`d14L@2g`?-VGaLu&T`aeS#x+dyzD=}14eR6{U1Rwx`=MwNUL5~RU zrJfu$Uxc~t&no5$kbegP8X?<@I;s0TV(5y8!nSHhVwwKcvPpVDFxJ9_!o`K zqkJzHb?}4$1Rwx`=Maz&`*BRz$&t>Q$k3;q5`H>82LL@;BG6{Qf>kpTX~D3l+;-XM z_S#V|Ey|L$rmx`UZo1hllAOHafK;T&f zMj@RZ1<^-IGPK|sgWZcEk4^rz5WQkiXrvf(!KmY;|IFW#F+J9Q3?entVw=*L0q+&fM zx|=sg@|reGUCHD21SB9R;~O(zO@C}ge6p;Q>677&_1Z^|p;9+A+ETEQ8A~mmk*`l9 z)fQQlZ27)!rF6;kv64)=#7rMeHjQSB1s4P$009V`OF%d9^QzS9>`c%~E#2KEznvPP zl1#g_9JkvO@Q}`jbyas(&49s2fmM!gXQU*Ct@d>#x)kt5?$ElVoo9RWE3fFoMih|> zM_Nn_swXiLt!9N8PY6H&0uVTlfbZykT%n&Vr53BNRo70GBDr24V$zg)T1Zl|xgJ2k z#x{odV~5JX$87ju>t<^H!Sudr>7+$atq&G=wR9n-&@^Xq;RMk@Ry}Hl6fR{&u1+=K zNi%X~r>N!#5P$##AaE`L+nP_TQ!DI`iIU|BYw6WFbV?|X` zqQo6?U%Fy4*_2wcysysSjoKezjF6;aC5=oa!@RV6Gm<00ba#4guYc&)kN){lE0l8!&o^Dl7Yg;~Y5D@^=Jc9+bJaX8NgFog|CR3M-v4 zigasr-Mqn!rB3gx&^O}$N=FvCKm z?@OQ!_)H(VIaz0g2^v#KISVkRJe1XKwHnXM(i6;ag009W>B`~v@&%4#V`s-5j{yu87!bvM@irmY2QY^exkv&<4%zF~> zAU?);+=*^V>YRvqAoD|tThK8snR2v9OLsn7_PwMax1-gGq{8&HhG z)(n+pJXBdt!jvZjAOHafY$mW_Pu);tbMqFCVmUJ8d?;7v-m-?doe7DX5r{Ee+3YZn zrxw%5ZZKDd{}seT4r3Q` zYRDBDOZh!Ac|L+b9_PM8Y5ZN$&4ZFCv4lrz#Xyx2QuLlQr4^MarOyfd4YT%kMUj2F zDN-}?;4Ki^02Nh1=Qm3jZ;SM9h?OQo00I!W8Ufvew>7GUQrn7uQz{(+eKBo*)keyn zy(y`?6R6`n>_`dNdYw-I%eRD;Ng>6cNb?!?OZ!XV>+~kgUIlS1r*cN{*yO z5&0hIwImV*AOHaf>>!Y~*BxH|w&+|N_1LfzA|K(F{kKiR`^f~lKp@xclOVD@DdtTq z6G(o`JhFUwPS2`REEk-yirVh*bPU^@nmDcz4YJ-1vVxY9lBeWF4*U-wyd5niApijg z98BQWd#aoi<%)yCQhq;}6YefbppCvYu$u&t5S2s`lD4=`?v^LIe2GJ|RO76=sjL)s zv|Y=8anq_iHm=o5`2cRRt7IIwAOHafK;SR}dcGay?aV!T>7Y5PKlr&gfi?-Op)H-H z)`yZ=5}|7OBgsrg*>}v4u554j;MHZITltiFD{%#1lKUF8y(^T200bZafei$993fxT z<_AkVq}xgJl^=}nOrQ?BcA}=T;Bkda6#HEs5?V}mJF?A#1trs#H_4Tb>}aZS*mkeg zS{tkx>Z)m~ga82uKmY<4C9vldS=}W&XlhU=XLn?+_JQHe3D}62yN6#j-3#7J3Fl&# z=p5DC3qPnB-DIUb5?fBLje>}W#e zwO_DSh@aM;EVo=F2tWV=5V#5f-TnW(G37L{in^n{KQaEi5mfL)0wpxi8BlMfEfOQt zbO_o;iyky$>+_{d$+4mm!I@?D^TST=uUdP%-A%yS{S?Ucs_jYfUCl#)00bZafh!TP zz58!lWJj^o)SVWZaqpKaf6MJD-Y3RgvT`hD(@^gvTQ%(_6Q^X#-7hJv9yIN#@DWD0 zdzOC4wY}XzVECF+Wi@T-zQpBIie+;vBMeh72i_{qpuD+-6odc-AOL~C zCE%NXJr@6>wo*qq81&vB<9}M~U-Sf@-xILGmvTPWbSBuXWi?4Y1n36=3*|hZD-WGS zi}e?qa%okIcGp!(`{!aO>Hmk8Yw@FR!E?T4A6kVP0uX=z1kNH5M?k6X(~+^aN$Nl9 zv*%uyl)nK18ET2s{HlWGM|M2hJXF0WEutwo8rzjldq#cs72JTzWD^a-q^fb5QA>6} zJoc#-$^b6Zj0yq}fB*!pKp^)2zidl)8bpQq{L5PLeFXv%eaW>t;LzYf0tow~VVs0) zk=ATWXrN=3W+oX{Re5x??g}VYv_VmQ-SAq#iXVR0v8a`-=msVbfB*y_@FN1-&XKPg z+n)z=?$+xoKN#PSfQM#nz^gPTl)y|wG7IB0pzv;MoK}iiQq0Z!N}C1G(KT z7%6SGEB9-?9HkF`u5SXC5P$##An+3cdItI-In{u2GE8Of&8r8_UPqL_2Z1)=Rgzg3 zmv$l&@+_*7CjprRa2}S$R201`)N&GlXzDd-apla~auKwvYg^luJUX$q5!gWh0uX?} zuL#(oDd%OJnO#f#cg&^G-b$w9s(BwV%(MkwF00OTjFgzCqFziqnWbRE$ zo%QJ2>x}YOCQydDj!kdh$^&h3{T_Y!Avw_9H z+`DWKL8rgesobi%Nj2-E&{ahO0uX=z1g=S-KSxGw)N@o0+L2~UMjSVBsw|yRTl`bz zQUuCy$4Hm?BZHqJi>iz!hpkLDvDH~OoOh8nWx0!~#xJ4KD#T~F2>*9{YNw5|@# zF3CzZMXVg$)(ffOz*GuOWOe>VHIe}V2tWV=7bM`D{Zz~3%q*LIQ7srv6`aZIP6=n0 znE`QXnToqiFgrnp00bZafzt{6bWfHepgE$`ZP!BH>ieM;8+fshbPc3gRiuZe52 z0GSYg00bcL69Q$M{^3V$IV4KAC(epnpRPX{$$M4mL#~b1Sr8c!lniI38rfWt31fdG ztzpZs^X^TZ&CIVb$rX77H1u}6bm`mlqKZyWKbQJxD8;ezRQECtma|k69Rwf%0SKH& zK+ebWYO|W6LOEMz&)l;cMSW)xkl~l1m#ayZmMoPTZqVC>q&gTl31{*w1C*9m zJ>6YU5~W{#e_KZ0SNq*z)$z&dY0%1|B18rr>*8Om}kE$A?8Dyw+Xa z7|hc6P~B`f6cB&_1R(G*0`+hy{qmEwKXM+{U%Dd%Jmk{oN|VE&s!WTplV=M;v`9Z` z%uwSpwXL^g=3+RK7F4YWp{RD%$%BQCz+~dVou_LMfB*y_@CO9yVUiBo?uh+^I&pac z0uffpV3+39c@To-MMEQ3pUqsPFi}Tcsw?DSVxKpzR`k}Q=J&DEH2H++u|20_5P$## zAaF1Nc|S6IWnyP)KI0Fr6n9r4phGQDl{QG9lGR@|X3N=9AksF6yie|{rmB$%R!TxP zPsZ8*16_XlDDBsd?=gYH290uX?} zegcC7M3U*0-S2;&2W{Ox7nB|o&;X&0v=}I9zj+iN zsw~39*x`Wa^^1cF<$?eNAOHaf6awX-XdI?bjn1SQpD1~Zv98A7H+Nk- zFJWaP9*|B@rWTfm@cL8~?zM~L1_sGZ5Ka)lH~%91N(rn+7WgfM0F=DgrC^_*e) zW?b|g0uX?}O9)J!sowW;V#Gn+A0EGEW35@$3h4vaN&@{Tcc~gFNMP1!WReW>BzChb zG3}J*r#cXw+V(B1`Ve|GDI*YcCZ9lp00bZaf!7iE5b~5WH?Dj({~D9EX{i;_FR@&* zLzf7|XtzO+!7mIQqw=iTDoCIv*->0g)Q7x@o4h(jYC(wRG4AFtbUYJ*#C!^Lv1Ixu zT!;{W00bURK+fXDE6xftibG_v$O%eq)yI0g?H}zhZ~_LbB#JNy$b6nic;~um5K|}> z>HN7@c?_dD%gg*b6Kl!XC>KB$N_8*<*64~6f)xZH009U*n}8g&isbc9Geb`OzmMgYeq19lS z=Do_fp~#a2+IUPzlO@Q600bZafoBnr{r^*s1~ztNd@A(U`ZcXEn~(kb>!#kuzs6QN z+T~W`sg7cw9X8&>TF9b1$@RistfeDgpT$ZvYAz*24ucT93LeV@0^7`UxiDG?KmY;| zxH$pc{TKTX2W&O+1EZ#YC46l9RT}y$KpW~!;gr)0h$-j_jR#!*noR>UQAtczF1wkn zB;A2!boYq$BC?A>E*qJ<4Ly2ckyx>rUy@%)gf2q>0ub0kK+m&14o)l^yZu6yW>SyU zIK3B2oTQS5%~!ReXY+;MstITl&w|8;J_TJGz{wbRAg9GVk;6L0X?9{_VO;fNNl}+F z6E&Mx^}%f=fdX5W_us%0wuo8g!MKACJ{)ZjREzN?nAT$dsolTu=|ATee1CLtr_u z6TlMrt?{(O#%kH&fT9q900bcL4FNws>-IkWZ0#1ZKkFr@!CxN+YkCmv8roXhqF+NT z=}!cLYyZ?2JDO!7n2GMIAdg8=@_jDpICu%ui!LI#uu>1E5K-*)CPKc{j@uRj8DlTY zu>9>+>igRY@D2e8KmY-M8M!u&M@Y4&02oPRg8+DWZQwqZwXM z^OL!_>61A%4(z%ZFqtBLLBK~x*mqaK{e_qBOs%5t%3uuv2teRk1paQ1{EL334ZfV6 znu=<4w@>;aUhH_a#zlMUv$nbBAgmyuaad)S1wHsRqqxyoAX7zLwwtBINTjByb4C=d zt5#;}MIxaU`Aue|SEXuhI|*dC!8pccr|XI0Qo}?xSrC8#1a3s29%Hv?bKT{&wcRdU zRh=MqnsJ5hMa#OjOlEc#B&G;R)HQj@sV@qBNQ|Y4>LMn*D@>_}xq7U2O;A^n95^%Y zl9{fs<#`N&gjNQsjK|+xQqSLb#w!FM0D;p8+-oPR8@%#K+psC@B==)owO-&foQoBC zBh5w+5N{r*$s)H279$W$ku?N}(p@ROyW$0b!wbU)J(R=B>%z zD9gCl2>cP7@7y}L*@pyaid81VFxnDD$P)>Pc_sedv1tF^!70*lJ1*d#hnetotjx z$FtXxI*C9T!qL!tU$qS4_oXNS0SG|gQUvTgx>S>98{_A%>#gMrcX9nBRylwH)!|j{>(IX%&i6$rC*J)sC)OE!mIQO)c%fQPu(+|^y zcHT~l5B%t)QU`IHsf6r%5YS<~M^kAf1Rwx`Sps$>&8n}gh|@GZYq+Gxd5h(W$yIt{ z4T&~Kt1i>LXwb!W}0fc2|N4k0vhDrXS+iR&^WdIZ3{YQ(d{w)*%M7%3hI8 z)$i~o^{jQ)yC!u30y>-*Xa`Mz00bbgk3c@H_IWzH^zc}fQ#G#fQNH^4{-bV4D3@H< zhNe8kl>`Fb>{BO#IFnId9Qnbp%r>A@m33*VNh7?D&Lo>7U!Q=DY=U#r~)LD7ELfpte;S_1l*H6w9{CE4^t!2HP(Y7V1!| zHT;ts_uM_!xL9Zgs^1fk@%()&XaNKu0D+wZ;x)rgH)j^t&9^&L#|dfAaFZUUPik{C zH@7D>_@q`ms+xpvO4Okj#fO-#jL6!PT%7r(g+|qiudv{GLjpRYH*7aeh5!U0&=W}K zRj;^sYILr48G6WG$<1OZB3=90429%QcGzK>z{}_?AFDuf8q#Tl;#fP7Bv~aU$_WyBe^TSEQDWw2DAS zPZJ$x3DsIyx9D+gRF_AoxEB9@g+x@h2>SX;8_(;vlNLe%0ucB>Ku@+0HrG?9gEbD= z{&|Ha_l@jYlp5RRllV*^u`@AV%teSLQ(A(r(9XIn25Z89@e@AGr{7x@RUdXd??pgI z^j=M-wGe;+1fD~nJ6tCcSLkWitYL#BPH=;viu59Z4yz{G%d2vaMZHr@q7;e(4xoqRF?I4S}sb zrPY#*l~K>L;FrhRLQ`Bi)98 z4=lrYn-Qa-5P-m=2*f7bPFa6TqZwB?W21#r*h6Q}DGTyu3H0#n7?!XqUlH9ECz?Iu zObUNG$4mKCI#*KV6<(4H#48f0gPBMBiVdYr5P$##o<+cR-L?sfq%TYS5y$k8cjste zG^ZPcP};Lok@!TQgBN)9dr^tt`tVMDNr7pn=4x8!xqVqHkiUeLuu#&APEcN-KpR?_ zLf3CEErb9BAaF8)zu6k)*p^+_H(`5}o~a-`yvT+u?U@B`t&S!y7|wclvm()R#4;aj z=m#^yFa_ulG*QTO8Yyaq7_>_r+1&FP7ap=zvq!oQ0UcWz)yr%l_hCm%Apn8L6Oco0 z@wD7dAYAKtDwWuF?3?m-zXz8r?OE_>jrKM#n=W{Hr7EFoh>H{nJ(a`A2|4I7uaD@Z zWGxnx&GJO0SJfljn1F6qKG zf91xTTOOqbN&Hns&-2^R6>4=d2u1I!WGm8!)yj-nm|ZJ6vS==f%DjZHoT_z?9FPG4 z2tWV=5V$n~KUDwVq?7YH(CDG+39BmSgw;i#IU*pc`*M&HygL4MT9llmZ`n3ETG~q5 zRGqC~3U$iny050U>WYwn00bZa0SMfhKtB8at|MBDy7!}3GXAc*Lp=`&-KgbD*u@yst00bZa0SG*dfS-W#2k(adinH$YZQeCo zj@g05hFZ=jGNPj~!adr42A@xLIKOJv%?in_fE{eJEEzSShH}d}O&*x)0TIzIOq1 zY$!RYoEfByCJrpyDCsQhytG0{5P$##AOL~q5wO!TpPvWxu|JRp?^s5M@BtP6l?$h% z539p-{;I;K`88Y%y~>2gaw{mh=`T`M(+nf>_TVll5Fr2o2tWV=4=3O!=|R2p=+KYg zS*HgFk+b#eRydsu$>iOh-{L^0!hB~nQtK)ADKF}F6OPn8=TDZ;2FMVA00bZafu|C% zL-3g1Nwik{#cPuBmtXP4?BMm?F}44Jmo7qxZ;qvhw~0&t0LoV`h2Ua=4sn;Tw{Bio z+)R3sB3%XULrZrG5)k;FKtH*@FHZ>wKmY>g6419GM^>q)s-4KbBc_Abl(z|rJVNkR z2cVWXUqznWg0D*@PutU}F(x*6O{g9T^x%|4trA@y@ zOK;goi`VLe(YURqM2N`~nG)Ki%S=*+ifTN}Bn^QL1ei-3piu+@5O@}WIDrRGIgf3R zoOtJQRRV14CyY#+D8nGmLO9Xe>=`s>c66iw7X)?_n4Mv}J>viZ5P-m42xNPd?QiJ9zB^Mt@k0<%+WWqHgX009Wxo`9ag zQ@7GHJ8q|s;@fwe4tz~OXM()D)ju{bbn4h^U7sj*GW8z@BwK29t6cd+R#x9r_U_)Z z@i%RC%(0s`pJqb<0ub0wKsLg9`ROca^=!xRt=`q`CxVAL0yZx^rt>+{QZZ@lHJzq> z8i_wCTc(rU2NgUqs`LI1dP?$72~5teKdlkx5P$##u0}wQAKeZ;hKme6g0I$E+VfKa z8sL`+Qs##L(&ogJQH|tiMt&_P8CCJbC{8(~n-NGEh$j%>1Lz5msR9BJxIBTf7wVa- zCsDe2_T}4815YFnft}2gQmxJ%oii57O$TpgAYq zAK0%)bZJ%W_lTa-2?#*oodhIo^HbVS=@Mv$kAu@cNNk z^Hiu|o~5`$pb)T`QzneOceD9pT=HBhnmV~mFjFfcCAlDQK7l-6&##>tApijg{0#wp z$CA!nJ)-}nD!e|CKnvN@)EPu|qUo|EQDEqusP2i=;`)8kIcT3tuHRT%2muH{U>yNH zll66pY;tn>%M;GpbpT&(<wwaf88oJ56(%ChAdpSh9{{sRx6Ms-KRYCv)5co?1 zHF}Hl)+?*|e_1)cpF%*xIt$>eOZxF3=2Z8L@Xo%Cb=6Zi(2v^?kePRz#?nv-KmY>Y z5|BO4j^b}iV*h3W@wQGG#5q|qBV5yI<%v&^H*=)#XA_Xwcy^uC2LT8`;1mM#1sXBk zDX1S@NgR?IyvcNuW7GdgUg^4~MUG4K^%6Z71kNMCd^?XdH9-IZClX+DI}!HdtI{Yf zzpay4P6E1dP*(#wD^u=|r$YxHM1bk~puwao5O@%Qv^R0AK4@Ie>dIi!jH0^w4z3U4 zY9!aPCH&)pz)c7+TW>N@G!p`^BhZdg_Nmtm{_!0yQJOlf(VB&IHJOBo*LTOa2agc= z3j%DGe?b+W5P-lD1pE}%ug#9|hmRK%u%Jx<)bK6d!PSf^BqPmxF*mw?I|A+F@a>vT zgCPKc=MyL&J>?e{1a=XSR~R;tbVi9UpH(%MGr<(aG+kl3s|6H>z!?O1S$76y>VNeQ3FFA80uQAn;rQWsf4Rd+zZ5q-QH9l)d!u zJG1a7Lq(7 zi0b|bEN&qHfkO!JvGWj&IDr5JAOHafKmY#5P$##AOHaf{F;D8b^P$}ug8J2C7|!>S0lh) zab*~zBItzh6A)rAW9})kAElwc-0SK%iU>~jt>(;Qs1_BUR zB4AP7k_9>lKmY;|_+tVZ((x7SA5+FX1RhU-sP6GYOa~zVfg2FeuV8P`PMQb-2wa%} z9}urRIs10 zWrl)=KmY;|fB*#UNPwvBDx;?Vy!=%fLpvY<0SG_<0uZi_~RYrn#KmY;| zfB*z;NkD(D?v^coTBFNIJgrOg2Lcd)00bZaffEVvs_sPCi&YWTE#g550SG_<0uX?} z2LeQO9{`=Dmj5j1th%TN0uX=z1Rwx`=Mf;NyULg{5?2`s+5rIwKmY;|xF-Q(iK~no zBXO0HpdAo^00bZafqN1lmbl8eF%nl93EBYx2tWV=5V$7+Vu`Da8$VTdm64zw5P$## zAOL}T5+JI(%D9!0xJpxK2LvDh0SG_<0{0^zK^?)wCB}`BxWq8f2nav`0uX?}T?r7? zU1sD6uP-wcGz0<=fB*y_a7O|}br%`6^1_sNrWY9tngIa_KmY;|xFrFN>If$;F?M_v zeu-hA5fFd?1Rwx`dlDe1yU@51TwiD~XbJ=%009U<;C2Kgth-&KX)pvJ009U<00Izz zKu3;_s000Izz00bZa0SG_<0uX=z1Rwwb z2tWV=5P$##z9YboZhyxMYY0F90uX=z1R!ut0{oS{YmN)8f&c^{009U<00Q3;AgcS0 z7uFDf00bZa0SG|gk_7md7A`p~GztO`fB*y_009VmNkF4IezxvQYM4U+0uX=z1Rwx` z%MsvZ-Q|Xa20;J<5P$##AOL|41c>T3K%)o*AOHafKmY;|xEukZy2}j-4T1m!AOHaf zKmY<82=Ie-8=z4H0uX=z1Rwwb2waZJus0SG_<0uX=z1Rwwb2tWV=5P$##An+Fi_zw0j zsNxd>5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$## zAOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;| zfB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U< z00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa z0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z z1Rwwb2tWV=5P$##AOHafKmY;|xF3Ok|L)gjS_}aQKmY;|fB*zm5qMRc^N+A@)ug}( z0uX=z1Rwx`dk}b4AlD5^iRz^D#C9DO5)UBo-bMX@!J`WhfB*z`5QzOho;zIKuBe1{ z|NeVp&u=$WG#CO9fB*y_0D%t#EU2-#rrclk+Dcy1NCpC3s;Cbf4go{#J&oq_-aAOL{@fj+Qlaot-^1ERXY zgdll;0zRqv!Gik_B|U%u1R(Gwffm+;R2&qs+`ja5OY`V-eYtVVUeIU=Gy-i-yR`5I zzLi3P00bZafhQ2?-qzJ)KzsK1&@P>SPZ&!20D(dv&FWas@)_+FpVF8B5P$##-cDeA z2DBVuBZt9L4}{j!r}psev-^ep*GVl=T)s3d@9dc9FPsu|83GV^7lFL{4`luBrXB=U zcnF`=*@yIqZa_f8xrsM+9_A6(F-0H%0SLT-Kniijq5vo{-9y7VIq%*u#PsnE1jeg( zm?NLnEbk3G=pzIm0D*TBh@F0T2GsQPqPp}(6?_#e%!nE*r1UScj$DW!G zCE($j9u3KHJ1XQXDDz$InD+@0A_Pt*&{kzg(twaxKBdIT?WQ^iT%Q1|;`(Dm3qKI( zCb6CfsX%{1SWs6A_z&qMLqrHb;2Z+|qAaQStTj?BW>~3nnoKPaxCw!!ucL0#1)2$g zj)0s4DP!VT(2w{M*=4&_1Q7xd_)7w#McF=OjZ_O6QcBmbEo9d7Uyd2RApijg{Dy#> z0$t5h$3ii%6CoW6T_F+>fWTi7=$E8@zRHVM*5=Af7qWOL*IzXkzYw?)0T#lI28*Vy zA~3PN>y|&h`O&e;D@G82z)=L!TAUBaN|2W9R*6To4?hsNF9AN?+;{9~c_NS|vTXlJ z6XMdTP)?8X>W&Kn5IBWEw-^_eUT3#1vEc2Lu2BgDeoJ8T`1@^>s2u{k2*}<);h^L# zoeKVaY%!WBOBMtma3F!S5@W?JtULM0_2s3DT^hXL_Q3w&3If+5FnRu6r+Ksl0^bvm z17Nn)(&->)zuFR)|hJhB-v7%Q3#_S;k7LLD%^pI}6j=F#{p;~u`WtyigDDDu+YlhCyUkG1(BlZ$2Y>N5c_vKt#L<@oB=Pi_N8%Sm3?En!9X7y=((YCNW=bOZuUAWizouX6we0SNpdfgF5& z|EexGEPGld=fcPkcp!nY4j$Mmx&(nQ2*_bDcxU%TX-pvifiDT<_$!L;If=5rWjSiI zzev$iNDz1ofjvvcm=9C#g4iM*UBPV*AZb#$`78q?cZ^Fz4f1OgC%z~u?( ze!sny^1^@%0uWdrkb=5>%Vnx`ytk8Aaq>1US7vg~;&t7^IH7_71R!vK0=uHRU4`$@ zjvhc@4S^JBtug=3Mqb!?EGGq1T_#TCsNHw9U=0BXKmY=FAmBUy)~0Ilt%WHEfmaa7 zk=EaKxYRTe*yZ}=bsjJ5{&p1b4gm;2;AaFjhh_F@0DB0$hkz`R(?9;mt91WPH7fUITOZmcF_ZAl%)LY_ zEBRayfB*y_a1#Qy!++V>I2N>+CcbolIRxHAAeKvc{-o1ZYih+%jCXnRv`Ft)P5lWU zDun<9An+Uly1{?hopvZlK}&t<0&@twhJdV)8aVx;*YYZ^wxF)wXj07xK@{~p-!Ixr zoe+Qk1R$`HfbQf|WoKV2#NIDYDQM{_7vw6jKO`;kIKmY;|IF3MU z#ctY%%?S86$JfdB*`0D)BmEH;}mji}8c zySC3qzU6po$^m&0fWU1%Vq7@E3MzG0*M^eQ%0cpFs)&5P$##eoSCt1FykbC#0Y*f6D)HH>e&0 z5ZFP$*LYpsD_lvDV&;z(1u%gC1Rwx`zb0V2`E)I&Te!E6_tOr@g#ZL@K|td(`&$$m zrmcAkr-u3s?k&1VBOw3*2)uxR#cbsh_qeYM;hd{lR5wxF9nNdUHIf4X2;78#?g8;` z?g1RhQx!n28P=I>W01H4kE$E`hT6>kgow3i$x{+`*=25P-m4 z2xwe3+1Rh5x=9aYLI47fB~X8=PQp7Py2p+)9fJS_ZbZP}wN18I_v!X&+)dM?y{Vfl zPbLH)@L&RID<~py-Ghgku0a3-w;^CV^JH`V)Av$b7yJ5Tc`_jYfd>OYi^Q?upS)MwG4fWZ9;)V;t%y3!+kVaLM1|Jc$42teSL1aw>e z)bhG_&j>T++1h8okPU%H5QzQ2VmW}r0=FfwYX6Y;{1VXFkKC0zTf%Jz zoQ6XH0v9K+YF93Om<#AulxGXS_#B{l5ZFp!#rl^RP9i!B=5#k;OW4Yrau9$31eOTs zX1i*O-5k}~=kujTpo0JeZc0G*g*8o=n9gjAxt6gYZ%tWjAOHafKwvEa+i91-5{VsI zx8bas?P@Y%-EnyF1OW&-Lr00Pe@ppn_iE_(E)QCyAa2|*0Rq>nh*g^mT5P$##AOHafT!TOj=BjXwcF_t5KmY;|fB*y_0D-Rv z)Mze*uS#PK0SG_<0uX=z1R!t$0`h%rM04@HK(lB91Rwwb2tWV=5P-nf1pGgkNYUNb zE+_y22tWV=5P$##AaDf&^3R#%>k4h64G@3;1Rwwb2tWV=UlSO86Z^FX3P1n?5P$## zAOHafT!cV=Tld{RkaCd@&$4BOg z1Rwwb2tWV=5P-l%2zXFu;oBgHEC2AxMOsNSAOHafKmY;|fB*y*3HTSVbK%?Q<=vt) zln{Ub1Rwwb2tWV=KO-P<-CX6fin#*hLjVF0fB*y_009X6h=9JW`%&Fg3jqi~00Izz z00ba#7=ig$b%#}fBM3kM0uX=z1Rwx`-x1*Z*Wa2apDXD z5P$##AOHaf{D=Ti-H*UiEd(F{0SG_<0uVTw0D;}nMDYg!2tWV=5P$##AOHafKmY;| zfB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U< z00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa z0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV= z5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHaf zKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_ z009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz z00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_< z0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb z2tWV=5SStG@867qYzROA0uX=z1Rwx``w$?gyU$qBQV2i*0uX=z1RyX+fcJEBWXOjA z1Rwwb2tWV=HzV-xKl#N40SG_<0uX=z1R!v80t9t8A3&N90SG_<0uX=z1e5?#9TNcp z5P$##AOHaf+@AnnzTSTf=>Y^F009U<00I!;C+e635P$##AOHafKmY;|fB*y_009U< z00I!W3IYDTx~q%??SKFTAOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb z2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$## zAOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1g=6r{wHnzH|?v82JL_V1Rwwb z2tWV=n+cTvo~J~0{3kt|0a6eG5P$##AOHafT!Fwpxp-Z7g`uDg5O_WTz8HA^7}G-t zK;UNtr*}QAK=`92xa3X;S>i7coMCeonffo~CuX*v{({%_y z;BN`Yd%AM{Z6$bz00baV3GmfGMS%bT2teRq0vgm2)*Vb0cMyQUG=Z|&$bQ3~GmVE_ z2tWV=I|%5TI^NaoAV^UNK;UZv8rl)qea(#m5P$##mI&BqW;WL)M(7{_fddKHrc>V4 z6@jhiK(M%i00bbww#poU00hn^An~03=*QU=Qy&B%009U<00Izzz_A3%kA28be(S`H5@bs z0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb z2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$## zAOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;| zfB*y_009U<00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U< z00Izz00bZa0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa z0SG_<0uX=z1Rwwb2tWV=5P$##AOHafKmY;|fB*y_009U<00Izz00bZa0SG_<0uX=z z1Rwwb2tWV=5P$##AOHafKmY;|_`kh-VNVvh*t0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjZ(1pfW^U;4*`009C7 z2oNAZ;M4;D%0sd{^;J|n0RjXF5Fl`OfiBZ^$?onN#!r9%0RjXF5IC#ADAlEv_%t@Y zdJrH$fB*pk1PGi+U>xdFo-2qA`Hm;Yj-*^n2_*d6$aDvbaE0t5&UxT(N2v5nT_x9n1~8*Pg%Iqvy5_NFfx!zMt0 z009C7jwmnm5FkL{Rsv08i*c7sm#5;| z`MBn&NOk$Z*cJ=jqnwlX`9gpI0RjXF5Fqetff~w6L@T}L;MVMTTBCGXbZ8qEGBjQW`r~6V*HEZ{ki>6Tm1PBlyK!CubKoixbJ4>MJCgPgo z<`?sfU4+0ob(an+E7NwZ6Cgl<009C72z*?iiD+|e*V(p+Xw9MXi_t)ig59C{Ddzgh z=DGH5BS3%v0RjXF5cq^Z8_!;~7sqz7tv&5wIki*5U?jo#U##U&*!58MzUt0?0t5&U zAV7csf%O7ICd&!z#fdqmrHJXn{fIfb@<_+V32CK#dEJ{M2oNAZfB*pk1Xc?)!EE(8<-iosnv<6o)6tRRa-NH& z9PMJQ4}7IPUkMN(K!5-N0tDU`Xv5g{Msl!=a8|-v+gP(4Ij-coh;)6bi%scKzHaZ^ z83YIrAV7cs0RoLco4%UOs}{Rh7Eck|nx>vC=3~p@BHb!x2N57ZfB*pk1Xc(P`Rnaj zvpVNirs0MLUoEBT(y2KUt|-(Y1PBlyK!5-N0?PtT@>)J<%bqUcHSNwXmOz*G#oS%$ zpqy8qw)E&&0t5&UAV7csfl=amkE4rY)01;j8#TYMQa-$mY*&8KZlS$t`_>5%AV7cs z0RjXXfgx%&8$Y)=H2-`l&(-B1__@BdM1TMR0t5&UxQ{@SwZ1jz@>dkk|CFNt5H{*5 zpTc%e->OQx1PBlyK!5;&D+!cPR}$A3#+5%zEvc@FkBf_u?aBwY>8br?yDyZcNdg22 z5FkK+z_kR*@3QrOtnj_TMPQ4p_WBVu#Ifa(o@4zGWVh9i*K!5-N0=E{(5v`kvdo^*_ z#lO}|!fQ1w6Cgl<009C7_7#Y1wl31eQRPEed2Ziprgs7a2oNAZfWWLkWVQVNRp~AV zyExv1009C72oNAZ;CKQN(<0h+q3uP$ix^lAJ>E!EM1TMR0t5&UAW#Ily!JZTr2{<( z5FkK+009C7jwLXSXfYf2BG|=@-So6$4N5fx2oNAZfB=Ep3CzW_m#Hoe2&obPAI#?3 zd^pGk0t5&UAV7csfv*arOcwv-$J1%MIH(*N@h+C)A<`8GUkMN(K!5-N0!I+&L)!CP zSF&F>b5|0b4`+{X{nS8!009C72oRVGn&009C72pmTsK5KpY z7*|c%`mQ3?Np|bK97%ux0RjXF5csk{ie}~S zCf0_ulI6N{zFeH<2@oJafB*pk1imJaruO=|J=1kxW7aSM0t5&UAVA>j0%fAE`?_|H z@9S0RfB*pkj{@G1g5br z#kur|k7482SIXkyidGN-0(TY2H>kS~-na=6An;Tm?vTTyOwtYOIoU=_)65PXLowiHaPOv-HWm64-`wB>P_r3N;PJqA*fg#G}zmphNyQT6m zY;Hufdtqre0RrC_sJEu?_oN2`1PGi>ppS96@ba5LZqY7`y0Z2LS?K6v+3XFSf5~0t5)0QJ~Lg zuZxcmSN>m4$~iA>h|gg?2oNCfQ-Qb}c@Q8#fIus-Hr18;XN0;sUza0Z1iG@NWIMOn z7S}QX0^bvGxA~r}mI)9zsleJ)mxh<`p%LM_To)rw%XvfI8*P=1@zsL>0RjXF5FkL{ zcLH6i+tOjlZjt9os_Q~t*^nEGBm5k_#niC`2)rTSHuDCWQwR{atU#CP$`so>qs$2} z&)$`6R})^k*}C7p1L_JYFYhdfbT{M`( zT%M(MiT1x39lz$JVFCmQ zd`KW}f#p`4zm_j$!w~L1)R$%m5V)B@ovJI(UmSdQ)5<-h<^CtrzRUK2exn5f1PEMP zpk%!CHUCrQ@7xZrea(%Iz}E!EsqQgreY)cabg9jF%J;4O<jH-1dc6Gvs=z~v6BAZJsrDn)e#_Y zNP!{PH9s-#QmJUS3%gDU5ZGIwyZPocSC+@Oz zzm%U;W7&tYRoXKF0yhvyH@%trUcMLJVDyGafWRjN`ZQHS)s`m9&E{i2L*_eLzNf`f z{r{GN97})zffEbl`(IOk{K|2<7v@`S?DHT%fWUKs5}r!5EAwN|k00&r?lz-se_bi} zuZWnb^^)%X+NARd5Fl_Gfi}Lya=YFQVrJ86hNn;h1imYf6J7rJGY6_Iot5CV<%}oC z=KEAFA+1EHiw@#B-`L#9p6J;{fWY+x;zpQnhSwXK5fLEpErCc*^|7sw@7-=nO;Jr$ z7Ek%+wyiuz6Cgm~yaL^iwA}#WK3E_5rdU@z6CglfA`rpdRM} zse}N59R&KDpj5YmzAg!zLLg6rmASBYZWIv+zd6pX@wl1g8`@Vp`{qEjO@IJ_KM2IV zFW>*Ze9!$uiB2Uz;2;8#nPR%`Amxn9=x$`WzPO(qw9IkQ)(8+FK!5-N0y_xgnXvBX zz#Y0@*=4G-n^;_Vg2M<9AV7cs0Rnducy|IU&+&ctBiQy*H`<4Gy(*EE6|6Yeqn9@k?HbdI5U=pJhir=j~y2krS5Y*c`2&t7CzRAh6oTK za0r3!W_O5M6hVN%u>^)_wyCai+M6eD>S@ivIl`4t7oX2YzKehIW6!v`rgp~=AV6S? zfKazZ%drG*Bk-3<7U!n)lplX-=R?@3gc9Z=$K^DazvNVxLtZ}ML!D`c009EK3FO<_ zZoTW60D%h%M07gZBT6d&lz>;lUA+Mg`R-_StA_vq0_z3hUbg;dM-m`F;FUn+rTjZ= zd)`~-`tCwqH*eR(x-QezX!mM>_7fmL;E)3OCU(fm6h(l*Sp~{{Wv8DP=hEC9WGb@z z)w*u#u8VYTigQ}F5g>310XMKyTqZ>lIF&%11WQG)%~%iP%O}2lcFk)K&5k#8$u9qj zUH(#&-S{wT1PBl~hk#Ufj_agK0%sDa+34@Hb#J#2d2K_a%m)u;$5IF0FP!NDsFeVL zn+h~HubT=OHUR=37Z~zUnKVmZYf9SCSH3;Hld8J8!qvT&KBmbo|8ig%NiF(~LDW+{ z6Cgm~+XCg@_w8P^Pk_L^1nMWS!%vNy<4{Db;jxXcJ8#=b<>*njqY7frJ1sir;{qv! zyA&T+)!;P*@{g##Kdx~xje@`t1j_xS&2{BHc=MdwkmB`he+dnMz##>iI202rk%zWsqNa(Br$!8n$2&6Vq_*Sf@;gmB z=W_xzu@Befb8Tyh!1)EZSS)m ze(gLp5sPiG%g1z^`r|G9P@rC%^8Ch2>xZ@KiU0uu1PEL~pndO6%v{xl&dHuZ64K6M{w27ihcdM{iStP7vmy8fB*pk-x6pixVk>JB)jnhS@#zH zty*W>E!7S+*BWAAb@FcZL>s>@P$OM>{(4_JAV7cs0RjYS@@d|Ax4i`q;i-QUU#q&U zqgAa&lYJe-!m4u}^m&1L2|nMl76}j_K!5;&2Z8#=n*&kWyDe+=XSWLvef(}iKS4Jv zl*)crf}RF}^kNGBVS^^Tik7;=7!rePfee9g3rpTx{R+K5laTn6Y z*uxqD0t5&UAaHttl6zA8d1oYDj%%MbHS<=di#_DlQZ4yUC%TEpF4^S@+Y@6$yKb2P z0RjXF5Fl`RfgF5d6q{mBo)r7T@3C#_Y`t-ml_%-)DcxeOb(G_B%Im+ZZ{Cpv2oNAZ zfB=C*3zYe-%_a7+s9o3=4mbC?>V$`RxLRO;cHPiD_uDNHAV7cs0RjZhEb#us*(4pM z)#EsfN}0yDN#Vz-S|tPs5FkK+0D(OOCgCVn_bB6apWUah!{^MU^5!$-Xd_QrzHZDB z1PBlyK!5;&%LzQhx&x0e|C(K2U#vY;UpE}#bL75K3j_!dAV7csf$s~{7&JV8zt1;& zh!8hDH74g49)jHz%Q^u91PBlyaD0J>w6nV8$5gcX)Ey3djCE1OLafW1WxE|NlP(Dm zAV7csfjtCrtQ&&S<`Uiyl$*O+I^oHLT}gIJC)!Sc009C72oN}!!2BH6iXw9+8_#vE zIIB720HH2d69VILjMkcpEfOF=fB*pk1gNo20sab$xXGMXmbqtB+m-1PBly zK;VM{-2_&8>Xz2Donlg+7h7}e&yOiX>66^U!p{rR;k-b(GFx7E^X=G5fB*pk1PBZQ z8$X<^L1}2<^-}j1{`$a=91*=OeI6UTJa!f+FNgef)6Ww-m#upO1PBlyaD0JHNvF+A zuZI>9YIqNSef+16h+nm9D;;X+vc#u4(#{(K&DD70Y^M+)K!5-N0!sq%q2-nttl>R* zsl{gdaByB~_I!1*OvvS7O)99XU+rGw&jjivi05a=*++l?0RjXFY!%q});hc?zv^ga zw(Qj@pWPpUHMba*G?Rwi5c1xQqyKDyH*IbGOX#LRhE0F~0RjZx7TA_-`uF4)zw6!~ zH(Gdc(%WNrc4Ev4jf!Yj%8AG-mrK&Y7k->(Ux^?G_+N}kYjk&pQf7ui1E;3&|F1qNK)i)I!|j*7{$9M=-jd~k~Wk+DkV%Ey-VZKy*9lk;+~(PCG}aNuOAo;P1+-RqeE z0RjXF5Fl_#fk`rIS7S0Pk2!73%iZeKq1#yw&CxINS6-MN`gFbTd-XHh!fWx-!?X6wRY>{@^IYCrN@(PAwYlt z0RjXFTvH%Tel2CAG~mhJ$^2J|a7!)=Q+rE?M`!(G>7Xt&_Q$PQSZd040t5&UAV7e? z^#o?aQ5|O4Su$7M_UgGyU#||E?jP!y?rGPDqt-38=UOH}fB*pk1PEMOU^X80BX0KA zZO^Ca%28{MsqNM0uB*Db^xRamW^t(*+X)aLK!5-N0+$nL!cqTO=xC7TPf)v$RoBkN zy%X%x$Gk62i`}`LIIt=F$>L}zRtOLvK!5-N0@oE7C!(B{9tK;EiOrFwy505p;piW2 z7#F_0_M>uiLx2DQ0t5&U*j=E8wkEQTYf1;CxL5wk6KZ=Wx+rfs$4&Q)2V;!@0RjXF z5Fl_}f%tqiVp})D`rHgSGF=XKU1SVfkCS$hqF!3$IQNjZUY@pmK;PDULH+J1?sa*~{n$f*009C72pnEu zMHD&w81^V|HrK5vq|I4%dBtf9heQi`)-Pwa+TOzRLK`*{AV7cs0Rkrzn3<`GM3B?T z$%b;2a;NEORbA7QVtv(#^9RMraelszb8QdX<{Pk;009C72oN}%z&JZZ78ruS*~W5| zdWXc6quGjdHacTid4E7dpF?X4OYe8$OacT55FkL{FajySMT%=5-CKY6`&ebdr`><@ z<;iHjGnzI&t?Z#aWwgBV{PAJ!C`)VI^&BFtx~=`@3fcyz%gfE!Lx2DQ0t5)0M29yH34fP#AKc_t#(#h8bI@I)+E>bIhIep8y(bMYAhSAL~ zZRxk$=(wia9Q;(vG(-u8q|v zYl~;i?pWw~(q^|h+k%Y*2oNAZfWS!wQVfV#*F8;Q-KHt0?*ep*^Shnw(Rw7T5qq9* zYhu{8qN1_s8Iul%wxH@56>0t5&UAVA>g0yPKB#<~-!?X&~)Uu z2y}l;buTsE&WkTwb^rka1PBlya14RRP`6^D=@_MdyNV%teYvNZQ1|J+o6G#=!DyZU z0RjXF5ZFzidBg7}bY6dcxLdKm>o`xL{jR%j&(#f|!tQ!?Kb=;8d4cprfB*pk1dcB7 z@Y$a?-h9b|;nx)3{FwBcZLfZf*B={JpWr|O1PBlyKwyi&@P1#Gww!z2W0OVseYYPD zv6(jge6RH~f4=3_E!Gm^dG$#SBtU=w0RjY83$*XG-fsuC$XLVLZd1C~I;&m%!SW=*l~>op#vc@-3jzcP5Fl_nf%=AfyMdo>!1YS~e*SF>)lg+#N~tn( zX-{%M0djNr&jSf)CVhOdzcwOaJR(IsEy)ONH z8ga2^I|vXUK!Cs{1X8ps@3NN|&BX`N<)M|M++{kfMz-|a{A*QmDG~Cz7u#@Def8~9 z>`F+75gqR1hqrSLZXh_y|4!(q)*sxLC%FUr&h0RjXF5V*2{H`5DV z-QQo-Hl(HH8Pl{a4qBYCn?Gx&A)5#gAV7cs0Rs0Cn2S|k9eo70^2qaUP5;eeR1k@; z9=h=S)j~B+fB*pk1PBly@I>GtpiPb)K9$X>POzK!SS3J!009C72+RshCdg)w`RK+- zb!nEa33qMtd2?)tBl2Wk**iL+IX4#LNDl%82oNAZfWW;4exHX*4jX;AnlC}ga3!#H zd(-xObiG6+z?DPhzt$r?6Cgl<009C72z*%}$FWhUi>bD5F0P%z8wI*iQS*te+d4YZ z3IPHH2oNAZ;3fjQ%+)2^aWD()@s_6%EvEHm56>HKa^(z@009C72oNB!uRuv&<50Gc z>C!hNwYtQQ#&KxDYAtpXQ-ChC& z2oNAZfB=Cv1tN!y5?D;g4JmAhY28vgTQ}QfX>i=+cr8!s&7Nx`0RjXF5FkK+z?%Xy zADpI^9>UzP;Z;95)kXFz3&V-irB@BvPk;ac0t5&UIH|z+7u9|0lLkJKcK!5-N0t8+P%zgm7oa)ArZMOB%ArH+@Q(azf{s?2XNgD|eAV7cs zfr|;$yilJnHoP5%GncWVjJfS~+r~1x)A}a+h1yg$g##k%rqe>K6Qqs|CEs3pqww85Ut~kfAI-F09p(Mr}8EexI&oPtuss6M>fB*pk z1PB~apk|I7H;!0fuBnEU6ixD@Z0yRNrj_aX_ea$g)fG31ow2pd(WOFSDgTp?{aj^T ztI=TYz6*MNMNvca>p_430RjXFTv?!hv+oyHg4A?MEaG1GPk(-lV0v7?^HU35%51g1-sh)k*A4*!1PBly@SZ@Q zg!+Z|+WFd9GXZ53Rwf<)ei(VKEYjOdSgV`*s$xULy5BrnsJZffQ-xj#5FkK+009D> zz&M;VYY~xlR>~2rWV(e~#uY~O3kQCFBn?&9Z+^=2hoA3Fiv$P|AV7csfoB3GF-`JG zznaf%=Dx-e>RG!V+85=OA|4v7+nbv5(ark9IiKFpL*+QvuYI~3?GYeAfB*pk1l9?3 zA6)jSq*=&+8St~&uf=jBs?Eo>QhRga@8;@qP0#G2s$|&|XORE_0t5&UAn;9rCdDl* z=18?iJb9Ukej4HyF2VxZuz4wxF0^Me0RjXF5FkL{ZGoIXQg%!KTX?+P^xsZ=9VK5M z@wWCG;@t{OhY%n@fB*pke-J2fuEdUU7O86sAAtU$&%d79rMVoHYO<@( ze{Fm7`IYI_^X7(~K!5-N0t5&U*eZ}e%Y2$jwzl}A3AQ(X5`&w z=bl{RJRui~`Pb-1DX-W*IoB=%1PBlyK!Cu91R{!b*`s?tZW1|Sq$`&pMY%o(Kg7Cz zx-Q9n=&EUk009C72oNAJBQQ#Hb!Fx_n^p^y^j0mqFjrPrx8Xnn1PBlyK!CtTfgyY} zOa0W-#>T#U__-##8qa?5ps-)QZki`RfB*pk1b!k=5=Z?cHm~)c8vdk!4V`=})^*cq z8@hhy&_2xd3sT)Xj?N)KfB*pk1l9@6{3=*FF>=qxLe#oKetJ|ITON3cvtR1Ern#=K zw0hXU{3QX+5+Fc;009C&6&T{pJwit$y8P&#B5i%=QDR)zdg(L1MrUon`&Reg8I)ED z5FkK+0D&V5hRn=bqj#7tc_5g%||~3U8<;!Q4h;YCvDh1X>;z(7-$SPJtjx@ zt8=H>Mt}eT0t5&UIDtTyaz0vVWTZ)hX}wQQa|@Hh-&!5oU5=?yM{2w)=dq^9eQ$N{ zBmx8o5FkK+z^(%QEwcdoJCLncFW6jQ)#m^Pd^t__cX(>4vM#W`XZ$%3ZAwYlt0RjXF>@Scq z&1Z`kLekLgL#liH==0-s481>FdRa&LIBS3%v0RjXF>?;r{X*$8 zYMKPkq0GLlX}#775FkK+009D3;1>a__BA}0UZ>M*!~PE})g+X%QEIJZrkw5Sj=X8w zQM0ow{&tQmYRdnQ2s#OQvE73J0RjXF5Fjuwuv1Rxy8UWSNsUMQIUB{`OI|8lyIs?m z)a+~)f066P*I`&|%IFt=QP2FV#a03Y2oNAZ;J^aYVDp1g`x&|}r#$I0r?MgAJUQ}V zS82T8+%;08QA~(E3_W_Ad+Zsb=4xu{dC#U-u|R+T0RjXFTt;BWRM1DLCzz4E-Yl_; zXQRebQ?a@G8VjRGcgoDu=&;|fbQKSU#l&L`rqfaUzC1k=AV7cs0Rp=Vn-=r31GnGIMOLto`DYta`00t5&UAV8oI=+aal zOQz|nJ2WEUJTL!Qfr4fV_|O z1PBlyK!Cu(1%|})t3peULqk(eayHtzz(h71!C!QTdN2+CqQ;0RjXF z+(cj;aK1d~p|hBX>mNC=e7Wns`Jsk>(@;uEbloqjwZUmPaOb5#Ef>-Q)`e!WZZyo% z%FbiZJplp)2oNCfJ%O5IzSl!-x%QN@Q_fE{jil#v$d1{g6w=ht6_mH{Sy+|po^$Bz z6retdk9En|2%l0t5&UAaH7d91FfRf*jdKjSm?l;z*uNib*6B zNh75fE4|hvzCB&d)-M{in*ad<1PBlyuplt{46r|@guR^U<`3wPwD4TuX^xxhOf982 z*eAm04ckkA009C72%J>lOW|t1**;s;gi)VQinm|c5sdpsEu-Hsvmn$}CC>y15FkK+ zz%~JSZJXD|qnlJWIdXwp5ao6}1xo+WC?dl&;NOvo* ztHTHoAV7csf%6NLoVIctlTf$m+?8EyJ8ZU~eq+Qw4*~=T5FkK+z)=N0npDbXnJeeq z`nWV+*b%C?7+2J+tsL5pW6(7L0t5(Tf&P}xgTPG$BCqT;)Fvv87I!LV+U=;OW<{)< zN?9jBfB*pk1P&lj(#k%CG)ZZ^`0H|JV{O{F@N0IzE>C|12oNB!Nub`<>+`0Q9ZcY~ z0(*wKg+EM4B^`=0(p@U3{X2@XB{t`+hbmVw1PBly&F{1 z2P+#05FoItK>nFKev@X`Ds)cZhXV0p-|+?C#iCS0Dk4^Pt!9OLcav!1+^|??@K!Y9 z5CQ}U5cq*Wy<;zQwd0%LLPa(c_@ltiFX}$b?Oewu#UaN{mP)M4LpjrUHVxjv1PBl~ zjX-ygeyq3LqTQ$;Wo#kv7lD`=kLmGv?jHR@-SGT*1-e4qNfMeO6Q*OLhB6robLP0!7JBgeY<((XTrr7{T+AaFT>dVd}d zEPenVZsPsouxWhw=hkw^xxerC^|`9GL|}tJd1;^Q1>U8$RCQN)y>rBK+%8Two(kI z%5e%;2>}8Gt|d@@uI_He{Zk&}BwNL5{^u6}eI>DQq_?kM3|=1uRtX&FJ0pLerrSe) zJpTNbGM!kr>Y6%;009Dj6o{yn^IEwh*RSa=To>axI;r>N`uxX^pPt_K-7OCVJU!D+ z0=E(P#kb-*%&wAruPC>ZxPPQ`hx16kLiqX-ZnKwz^#cLR|-i^y`RlL7KtCFT1{`qnK|b_Xd?83YIrxV%8U z`;N2IBIw1KDzg{-&dwb0=o+2Ko{S(rHbxp*OKNsuZb>yBhMXR8vz0Y2z**# z9G-?GH7rH6O1c4Iy_vtaucTot1PBly@E}lf zTzuTxW&K?&YMq~qlYYMb4{%s>{zooaG`PR{U-Z9=P*hvHk z5V(p!-0$O2l3czWAMTzU1=TuBwUe(`xfsSl;EBNSs(*6O+^*ro^o{3FJ(dZp8IoT%Qj%l6XgI-=EsmgO#cr0v{JhKiJeC!M3$M`ldPPH}|#?Ihp_g z0tB83M6P?bf8Twh($ZU0pY2jv{X5paCF-5P4+P@XzO|eFJEShe_srHt98Z7%0RpEI zh^TbrWH-T#TH~!L|G&IlO^&ci;9>%Ag|V9D+UJY87!Cmf1PD9|obu=QTy*z_^*AJ3 z2;5$vjdSht?O^~AAV7e?z5+|Zv%Fc&PBku_vhP6jPT(DZ?XTuG$F=#4iQT$G0x=&F}nMr_LsD zaDhI^O%@Jbw(80ukua+t$25eLtJuYb${(3)EMC|D1pNS@>4DGK8@aAV7e? zc?6a-UBtcaah~C*l)xth>MOtdu_vw0{_^Q3x;l9qa_-45pz;Y2xSYVkeR+6eO9#Z; zng@X!2$UCkef9VM8lW_C-vZOipF{6-qjdrV2oTs!V0jWEe&McrbpLw0-HOyPf!_+$ zSAP4$j8Hed21KSJ)(H?Gu&Y42Ex))k=WG{qbuW+Hbs#z?@JWH1>b&X~RpT@17dMZ^ zbL}8NfB=F01mfOZ|39fB-`3sRCn{D?FA%X#XnA%SvyX56XGHc9AVA=-0_pah-{__V zdiR@(Sigcmyskx-r&p5DQyx1B5Fl_|f%5(~_coW`{o)PKTi|gopUSoh)3Y&SO}*XFt#su(hX z+X>|Rz}(#Z?IaAC0D&6_#4T?w{+xN}&&Jcnx>!E*IMq&o009C72oRVPxKhAb9!vVA zy2)eC!Zrf86j=VoIX}mh$9Dd!V*~^Ud{*F2lU5PzM%nJOlv*QjdV%XDpzDq3^e-|4 zAVA<-0_lc#uX|qn6>KwO_bpfL5;&be{=SGC!sTuWmmAROURw$#K;Rbw`CfOi8{W&| zlmq%;_X}rz5IDX-_brhMP2VCfzm1MR9u*QGK;WJN_q>5Wi*@%Dx#z3jsH;Ftb@^GY zt1O-g5FkL{_yYaMu(PFJ@H42{aoR|r2=w0%k?CU7oqpTai+}(D0@o6_<=j+$_nLq2 z%Ci;oyRLQNjfOxcFvL0}1PBlyaB6{DhPrgcmUCMd>$+)+Q(s)g6IdmX?gHgyzv^fQ z5g$S`jq*DVm)d`$s&f@@w^qar|nz|{p}rf%^)Y?!R`D|T0ZAsAmL zu=w3ThyVcs1PB~k;6++%W8JX_qB;Tu2oNAZfB=E#0x@?{|Ns0*dkGLAK!5-N0tAjP zu=vST+OfFr_`^~m0RjXF5FkK+KoRgagI);)2oNAZfB=Cj2n@e`cZJay0|5dA2oNAZ z;I;xotc#`FG8i}k0t5&UAVA>k0^?XG*q!})s-FM>0t5&UxUIl6)|s=r?MuPH2@oJa zfB=D03(TduyzSJZQak|y1PBlyK;V7?i@DCU-Tht+MofSJ0RjXFoLk^&u=6jqJNLy^ zJplp)2oNA}H-T5t?rt8&OMn0Y0t5&UIITeXZ_6$}{AVamdtDVyfB*pk1PI(wAb;Sx znC+5?f34jeUlztpfB*pk1PGi`U@_Fijx?Wl%0Vfb009C72oNA}UxCGVXUgurFA5_k zK!5-N0tC(}5TD2{JbV~?&P%Fl0t5&UAVA=@0t>0mN3pkkMHn~%0t5&UAaGWJ{Ht{N zcj_Jzo*BEdUQ~4xAV7cs0Rs0GNPj9Z^MUMrJ&c?H0RjXF5Fl`Jfys>B$w#An0t5&U zAV7e?jRo3&W$}#}44nW00t5&UAaHJh_)WX|aqPKAqIv=Z2oNAZfB=Cc;4fjl380#eAV7cs z0Rs0HFj;r+>u>Y~2oNAZfB*pk1PBlyK!5-N0tXQ=QFo9Fap5wtu4UGT+0tAjE z;4Sw^SL2ekr2mx3CC6n@1PBlyK;TdU@rGO8a{Glt)u))#3v~Z^y3>!t007(GUSQW5kdY7|K!5;&Lko-(U71}ubis-{kAOgT zo@=F20t5&UxQ@Ui++Am2MnZr90RjXF5V)DZIM>~5@PPW z=QG$lUVdXHK!5-N0tBui@Xx2PSGknNL4W`O0t5&U80PCt*m*S&AV7cs0RjY0EYQTd zG>_q9EYk25FkK+009Db7kJEd=IrkNnlOF>1PBlyK;V=D zV%;e(o1zI2AV7cs0Rj&Ka@_-o4Fm`fAV7csfins;|B{m~;hk|5Y9>H{009C72oOjD z;~6_71PBlyK!5-N0;d!xegkd zhlo)*uDy&?<=BsK<-WQkH}~|BPBcP*009C72oSiDK$q!qw0b`5IP&=sZ|qI|&du4a zDCdpNoI-#A0RjXF5V*8JJ6ZPWfu_tBO^)N>Xf1!_+Lkb0{&YdwBS3%v0RjXFTvlK@ zTedjRE}|{&AMF^2vz*;V`yW=OCk*QkhuT1Z009C72oNAJD=;Lex|9wZO{v9c4;$v& zN(at7W{(|joW{$hm1uK(ur&e%2oNAZfB=E1z*3x=9#_{>+?tPgO%8ilOlOo}_B@_F zoHyD~EAUK!009C72oNB!Bru9kb!G10x-XuG{gL!uKUU57J!>X)*mOE{Z;1c_0t5&U zAV8oOn2A&U1Y6oyJ_emRXmQiy8S69IVxuY533mN8``JPp;eXbtjtCGSK!5;&HwE&i zq~kbMS{iR#v({D+IV>LCY+k$T$#OkwuD6owgu5qvpV}43pg*Ol9RdUh5Fqe#fhI|% zzMHjGi)D&#uIM;@Zu^sMOFgEjv9+luz1TG?P%angS)9d2jalXS`xYEAy4*xX$qqQ@+BhQ33=A5Fqe-fjnoEgIrnaE7?^WS>?>e(kK@vGz4_`U)$f1N7uGTiqv=$!xo0(TVH zX|Co5FkK+z;=NgfVQ7@+%twmSC--rI*wbd%C07mUu<4+SG%mnLx2E*(+FHE z_DoY%Bj$rJD}w+50t5&UAn;XzF4L9y zlJXmaF;{2y?q%7Az;twiByT6-ifdByl1PBly z@Iir<6K`#*>*AeY_rc4cDFOrt5FkK+z@G$GX1X*rH~SFm{-p0@0t5&UAV7e?uLa^G z*SUvS_v(u8c|u5FkK+009D91lr%ci-afGZP9Zq0RjXF5FkL{C<5bD*R36; zICT&pK!5-N0t5)G6v%%^F%#`pp6)OL1PBlyK!5;&eFf^T(9I;eylLO+^iF^P0RjXF z5FoHkAf>yM;>Q0mift`8ng9U;1PBlyK;Q@hF*TR!$TM`^mm`#=1_A^K5FkK+0D-p! zBH-1}X5Vhai3A7`AV7cs0Rl%B$RE@mxj?lMAV7cs0RjYWEUV^&J&u5QRsagmSAV7cs0RjY`3Jf`JcIoN4b`l^!fB*pk1PB~KApV6Xvstd)c!WaL zK!5-N0t5&UAn-z<{=4j6B|M+VzJRow009C72oNB!r$C;S>kDY-=%&jN>-?%+Pi27s z0RjXF5Fl_+fs)wb>om``>!$1udij(^fB*pk1PI(+V1D{7|I1C+{pc1yc#CqRGz0RjXF5IB#3P1IX zav(r}009C72oN~CK>nBHo_!GNCqRGz0RjXF++HC6r|5650Du4i0t5&UAaHsCzgTzr zOK1QD2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZ zfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&U zAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C7 z2oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N z0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+ z009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+z|95z-F*CpPk;ac0t5&UxP*XEcZthr5CjMi zAV7e?y#++NdtZN}CqRGz0RjZBB_P{f>v|du0RjXF5Fl_zfqx?19WT2v6Cgl<009CQ z6R44{K3{BjhC_e=0RjXF5FkK+009C72oNAZ;5-5*>CSVlR7!vV0RjXF5LgoU7muZ# zwi6&gfB*pk1PGi)K&Cs*rBWyX0t5&UAV6SV;NO2SQ76{T>)1+w009C72oN}nK%}~} z)T&Mb1PBlyK!5;&mjbfgOCkplAV7cs0RjY$Eg;Yx`}(Mk009C72oNAZfB*pk1PBly zK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF z5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk z1PBlyK!5-N0t5&UAV7cs0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5&UAV7cs z0RjXF5FkK+009C72oNAZfB*pk1PBlyK!5-N0t5~q@Gm_MP=*o+5FkK+009C7{vZ&U zEU;tO2oNAZfB=DC3rs$M9pat8hW+)W&>sN;1PBly zK;Sb1L!#@KM7z(>YJ~s+0t5&UAn;Rx{Kpf0r0W)bT7k|85FkK+009C7J|K|)9(MX` zc9HHr(6%NB5FkK+009C7b`h9P+KG0%Tn3#IAV7cs0Rja6F7OcSB)h+(YJmU&0t5&U zAnts+YR$~Y3cFEeoOv$rSxkS2oNAZfB*pk1P&n3#kZKW zoBY>f7m{86?~%pP9s~#wAV7cs0Rl%8h>TWqTK;Q__M_QJv3Xa2^kk=10t5&UAV7cs zf#V1~1iN8su4KC7l&TT}1PBlyK!5;&7Xs~kT@7 transform_tolerance: 0.01 - min_height: 0.0 - max_height: 1.0 + min_height: 1 + max_height: 5.0 angle_min: -3.14159 # -M_PI/2 angle_max: 3.14159 # M_PI/2 diff --git a/src/FAST_LIO_LOCALIZATION/launch/align_pcd_map.launch b/src/FAST_LIO_LOCALIZATION/launch/align_pcd_map.launch old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/launch/gdb_debug_example.launch b/src/FAST_LIO_LOCALIZATION/launch/gdb_debug_example.launch old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/launch/localization_MID360.launch b/src/FAST_LIO_LOCALIZATION/launch/localization_MID360.launch old mode 100644 new mode 100755 index f198b97..bfcad41 --- a/src/FAST_LIO_LOCALIZATION/launch/localization_MID360.launch +++ b/src/FAST_LIO_LOCALIZATION/launch/localization_MID360.launch @@ -1,22 +1,21 @@ - - - - - + + + + - - + + - + @@ -38,11 +37,9 @@ - + - - diff --git a/src/FAST_LIO_LOCALIZATION/launch/localization_avia.launch b/src/FAST_LIO_LOCALIZATION/launch/localization_avia.launch old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/launch/localization_horizon.launch b/src/FAST_LIO_LOCALIZATION/launch/localization_horizon.launch old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/launch/localization_ouster64.launch b/src/FAST_LIO_LOCALIZATION/launch/localization_ouster64.launch old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/launch/localization_velodyne.launch b/src/FAST_LIO_LOCALIZATION/launch/localization_velodyne.launch old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/launch/move.launch b/src/FAST_LIO_LOCALIZATION/launch/move.launch deleted file mode 100644 index 91a7c0b..0000000 --- a/src/FAST_LIO_LOCALIZATION/launch/move.launch +++ /dev/null @@ -1,5 +0,0 @@ - - - - - \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/launch/nav.launch b/src/FAST_LIO_LOCALIZATION/launch/nav.launch old mode 100644 new mode 100755 index 826953a..8d13c1d --- a/src/FAST_LIO_LOCALIZATION/launch/nav.launch +++ b/src/FAST_LIO_LOCALIZATION/launch/nav.launch @@ -1,5 +1,7 @@ - - - + + + + \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/launch/r_serial.launch b/src/FAST_LIO_LOCALIZATION/launch/r_serial.launch new file mode 100755 index 0000000..7ace517 --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/launch/r_serial.launch @@ -0,0 +1,5 @@ + + + + \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/launch/sentry_build_map.launch b/src/FAST_LIO_LOCALIZATION/launch/sentry_build_map.launch old mode 100644 new mode 100755 index 3194a4b..a5acf79 --- a/src/FAST_LIO_LOCALIZATION/launch/sentry_build_map.launch +++ b/src/FAST_LIO_LOCALIZATION/launch/sentry_build_map.launch @@ -3,7 +3,7 @@ - + diff --git a/src/FAST_LIO_LOCALIZATION/launch/sentry_localize.launch b/src/FAST_LIO_LOCALIZATION/launch/sentry_localize.launch old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/launch/sentry_localize_odom.launch b/src/FAST_LIO_LOCALIZATION/launch/sentry_localize_odom.launch old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/msg/DataAI.msg b/src/FAST_LIO_LOCALIZATION/msg/DataAI.msg new file mode 100755 index 0000000..03020c0 --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/msg/DataAI.msg @@ -0,0 +1,11 @@ +float32 yaw +float32 pit +float32 rol +float32 vx +float32 vy +float32 wz +float32 pos +float32 ang +bool reach +bool achieve +uint8 notice diff --git a/src/FAST_LIO_LOCALIZATION/msg/DataMCU.msg b/src/FAST_LIO_LOCALIZATION/msg/DataMCU.msg new file mode 100755 index 0000000..d3351fd --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/msg/DataMCU.msg @@ -0,0 +1,8 @@ +float32 q0 +float32 q1 +float32 q2 +float32 q3 +float32 yaw +float32 pit +float32 rol +uint8 notice \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/msg/DataNav.msg b/src/FAST_LIO_LOCALIZATION/msg/DataNav.msg new file mode 100755 index 0000000..f7c39af --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/msg/DataNav.msg @@ -0,0 +1,5 @@ +bool reached + +float32 x +float32 y +float32 yaw \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/msg/DataRef.msg b/src/FAST_LIO_LOCALIZATION/msg/DataRef.msg new file mode 100755 index 0000000..181dd7f --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/msg/DataRef.msg @@ -0,0 +1,3 @@ +uint16 remain_hp +uint8 game_progress +uint16 stage_remain_time \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/msg/GoalPose.msg b/src/FAST_LIO_LOCALIZATION/msg/GoalPose.msg new file mode 100755 index 0000000..1a6618e --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/msg/GoalPose.msg @@ -0,0 +1,8 @@ +float32 x +float32 y +float32 angle + +float32 max_speed +float32 tolerance +float32 circle +bool rotor diff --git a/src/FAST_LIO_LOCALIZATION/msg/Pose6D.msg b/src/FAST_LIO_LOCALIZATION/msg/Pose6D.msg old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/msg/Ps2Data.msg b/src/FAST_LIO_LOCALIZATION/msg/Ps2Data.msg new file mode 100755 index 0000000..2b52c1c --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/msg/Ps2Data.msg @@ -0,0 +1,20 @@ +# control input message +float32 lx +float32 ly +float32 rx +float32 ry + +float32 up_down +float32 left_right + +bool l1 +bool l2 +bool r1 +bool r2 + +# 四种模式 +uint8 mode # 0:手柄控制 1:键盘控制 2:自瞄 3:手动瞄准 + +bool select +bool start + diff --git a/src/FAST_LIO_LOCALIZATION/msg/position.msg b/src/FAST_LIO_LOCALIZATION/msg/position.msg new file mode 100755 index 0000000..aaaf333 --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/msg/position.msg @@ -0,0 +1,3 @@ +int8 passball +float32 x +float32 y \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/msg/serial.msg b/src/FAST_LIO_LOCALIZATION/msg/serial.msg new file mode 100755 index 0000000..c6baf4f --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/msg/serial.msg @@ -0,0 +1 @@ +uint8[] data # 定义二进制数据字段 \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/msg/underpan.msg b/src/FAST_LIO_LOCALIZATION/msg/underpan.msg new file mode 100755 index 0000000..8341a54 --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/msg/underpan.msg @@ -0,0 +1,2 @@ +int8 dian +int8 passball \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/package.xml b/src/FAST_LIO_LOCALIZATION/package.xml old mode 100644 new mode 100755 index e780a3b..5d22a1a --- a/src/FAST_LIO_LOCALIZATION/package.xml +++ b/src/FAST_LIO_LOCALIZATION/package.xml @@ -26,6 +26,7 @@ tf pcl_ros livox_ros_driver2 + serial message_generation geometry_msgs @@ -37,11 +38,12 @@ tf pcl_ros livox_ros_driver2 + serial message_runtime rostest rosbag - + diff --git a/src/FAST_LIO_LOCALIZATION/rviz_cfg/.gitignore b/src/FAST_LIO_LOCALIZATION/rviz_cfg/.gitignore old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/rviz_cfg/loam_livox.rviz b/src/FAST_LIO_LOCALIZATION/rviz_cfg/loam_livox.rviz old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/rviz_cfg/localization.rviz b/src/FAST_LIO_LOCALIZATION/rviz_cfg/localization.rviz old mode 100644 new mode 100755 index e2f6a61..2c0c4c0 --- a/src/FAST_LIO_LOCALIZATION/rviz_cfg/localization.rviz +++ b/src/FAST_LIO_LOCALIZATION/rviz_cfg/localization.rviz @@ -17,7 +17,7 @@ Panels: - /Path1 - /MarkerArray1/Namespaces1 Splitter Ratio: 0.6382352709770203 - Tree Height: 417 + Tree Height: 897 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -444,17 +444,19 @@ Visualization Manager: Frame Timeout: 15 Frames: All Enabled: true + bash: + Value: true body: Value: true - body_2d: - Value: true - body_foot: - Value: true camera_init: Value: true + car: + Value: true + goal_pose: + Value: true map: Value: true - robot_foot_init: + odom: Value: true Marker Alpha: 1 Marker Scale: 1 @@ -464,14 +466,15 @@ Visualization Manager: Show Names: true Tree: map: - body_2d: - {} + bash: + goal_pose: + {} camera_init: body: - body_foot: + car: {} - robot_foot_init: - {} + odom: + {} Update Interval: 0 Value: true - Alpha: 1 @@ -549,10 +552,10 @@ Visualization Manager: Window Geometry: Displays: collapsed: false - Height: 656 + Height: 1136 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 000000ff00000000fd000000040000000000000156000001defc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001de000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000001defc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000001de000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b800000052fc0100000002fb0000000800540069006d00650100000000000004b8000003bc00fffffffb0000000800540069006d006501000000000000045000000000000000000000035c000001de00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd000000040000000000000156000003befc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003be000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000001defc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000001de000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073800000052fc0100000002fb0000000800540069006d0065010000000000000738000003bc00fffffffb0000000800540069006d00650100000000000004500000000000000000000005dc000003be00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: @@ -561,6 +564,6 @@ Window Geometry: collapsed: false Views: collapsed: false - Width: 1208 + Width: 1848 X: 72 Y: 27 diff --git a/src/FAST_LIO_LOCALIZATION/rviz_cfg/sentry_build_map.rviz b/src/FAST_LIO_LOCALIZATION/rviz_cfg/sentry_build_map.rviz old mode 100644 new mode 100755 index 5c472a2..8a277a9 --- a/src/FAST_LIO_LOCALIZATION/rviz_cfg/sentry_build_map.rviz +++ b/src/FAST_LIO_LOCALIZATION/rviz_cfg/sentry_build_map.rviz @@ -18,7 +18,6 @@ Panels: - /Localization1/localization1 - /Localization1/localization1/Shape1 - /MarkerArray1/Namespaces1 - - /Axes3/Status1 Splitter Ratio: 0.6382352709770203 Tree Height: 467 - Class: rviz/Selection @@ -481,7 +480,7 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 27.20014190673828 + Distance: 36.58704376220703 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 @@ -497,9 +496,9 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 1.279795527458191 + Pitch: 0.8997958898544312 Target Frame: body - Yaw: 0.9917507767677307 + Yaw: 6.254936218261719 Saved: ~ Window Geometry: Displays: @@ -518,4 +517,4 @@ Window Geometry: collapsed: true Width: 1102 X: 191 - Y: 33 + Y: 27 diff --git a/src/FAST_LIO_LOCALIZATION/rviz_cfg/sentry_localize.rviz b/src/FAST_LIO_LOCALIZATION/rviz_cfg/sentry_localize.rviz old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/scripts/global_localization.py b/src/FAST_LIO_LOCALIZATION/scripts/global_localization.py index 322e6b8..42f1092 100755 --- a/src/FAST_LIO_LOCALIZATION/scripts/global_localization.py +++ b/src/FAST_LIO_LOCALIZATION/scripts/global_localization.py @@ -2,22 +2,26 @@ # coding=utf8 from __future__ import print_function, division, absolute_import +import numpy as np import copy import _thread import time import open3d as o3d import rospy -import ros_numpy from geometry_msgs.msg import PoseWithCovarianceStamped, Pose, Point, Quaternion from nav_msgs.msg import Odometry +from std_msgs.msg import Bool from sensor_msgs.msg import PointCloud2 -import numpy as np +from fast_lio_localization.msg import underpan import tf import tf.transformations +from sensor_msgs.point_cloud2 import read_points, create_cloud_xyz32 global_map = None -initialized = False +initialized = True +dian = False +th_ok_msg = False T_map_to_odom = np.eye(4) cur_odom = None cur_scan = None @@ -31,18 +35,16 @@ def pose_to_mat(pose_msg): def msg_to_array(pc_msg): - pc_array = ros_numpy.numpify(pc_msg) - pc = np.zeros([len(pc_array), 3]) - pc[:, 0] = pc_array['x'] - pc[:, 1] = pc_array['y'] - pc[:, 2] = pc_array['z'] - return pc + points_list = [] + for point in read_points(pc_msg, field_names=("x", "y", "z"), skip_nans=True): + points_list.append(point) + return np.array(points_list) def registration_at_scale(pc_scan, pc_map, initial, scale): result_icp = o3d.pipelines.registration.registration_icp( voxel_down_sample(pc_scan, SCAN_VOXEL_SIZE * scale), voxel_down_sample(pc_map, MAP_VOXEL_SIZE * scale), - 1.0 * scale, initial, + 3.0 * scale, initial, o3d.pipelines.registration.TransformationEstimationPointToPoint(), o3d.pipelines.registration.ICPConvergenceCriteria(max_iteration=20) ) @@ -60,19 +62,8 @@ def inverse_se3(trans): def publish_point_cloud(publisher, header, pc): - data = np.zeros(len(pc), dtype=[ - ('x', np.float32), - ('y', np.float32), - ('z', np.float32), - ('intensity', np.float32), - ]) - data['x'] = pc[:, 0] - data['y'] = pc[:, 1] - data['z'] = pc[:, 2] - if pc.shape[1] == 4: - data['intensity'] = pc[:, 3] - msg = ros_numpy.msgify(PointCloud2, data) - msg.header = header + # 创建 PointCloud2 消息 + msg = create_cloud_xyz32(header, pc) publisher.publish(msg) @@ -107,7 +98,7 @@ def crop_global_map_in_FOV(global_map, pose_estimation, cur_odom): # 发布fov内点云 header = cur_odom.header - header.frame_id = 'map' + header.frame_id = 'camera_init' publish_point_cloud(pub_submap, header, np.array(global_map_in_FOV.points)[::10]) return global_map_in_FOV @@ -123,15 +114,30 @@ def global_localization(pose_estimation): scan_tobe_mapped = copy.copy(cur_scan) tic = time.time() + if cur_odom is None: + cur_odom = Odometry() + cur_odom.header.stamp = rospy.Time.now() + cur_odom.header.frame_id = "map" + cur_odom.pose.pose.position.x = 0.0 + cur_odom.pose.pose.position.y = 0.0 + cur_odom.pose.pose.position.z = 0.0 + cur_odom.pose.pose.orientation.x = 0.0 + cur_odom.pose.pose.orientation.y = 0.0 + cur_odom.pose.pose.orientation.z = 0.0 + cur_odom.pose.pose.orientation.w = 0.0 + global_map_in_FOV = crop_global_map_in_FOV(global_map, pose_estimation, cur_odom) + rospy.logwarn("cur_odom is None. Using default pose for global localization.") + else: + global_map_in_FOV = crop_global_map_in_FOV(global_map, pose_estimation, cur_odom) - global_map_in_FOV = crop_global_map_in_FOV(global_map, pose_estimation, cur_odom) + # global_map_in_FOV = crop_global_map_in_FOV(global_map, pose_estimation, cur_odom) # 粗配准 - transformation, _ = registration_at_scale(scan_tobe_mapped, global_map_in_FOV, initial=pose_estimation, scale=5) + transformation, _ = registration_at_scale(scan_tobe_mapped, global_map_in_FOV, initial=pose_estimation, scale=3.0) # 精配准 transformation, fitness = registration_at_scale(scan_tobe_mapped, global_map_in_FOV, initial=transformation, - scale=1) + scale=0.6) toc = time.time() rospy.loginfo('Time: {}'.format(toc - tic)) rospy.loginfo('') @@ -149,11 +155,16 @@ def global_localization(pose_estimation): map_to_odom.header.stamp = cur_odom.header.stamp map_to_odom.header.frame_id = 'map' pub_map_to_odom.publish(map_to_odom) + th_ok_msg.data = True + th_ok.publish(th_ok_msg) + return True else: rospy.logwarn('Not match!!!!') rospy.logwarn('{}'.format(transformation)) rospy.logwarn('fitness score:{}'.format(fitness)) + th_ok_msg.data = False + th_ok.publish(th_ok_msg) return False @@ -188,23 +199,31 @@ def cb_save_cur_scan(pc_msg): pub_pc_in_map.publish(pc_msg) # 转换为pcd - # fastlio给的field有问题 处理一下 - pc_msg.fields = [pc_msg.fields[0], pc_msg.fields[1], pc_msg.fields[2], - pc_msg.fields[4], pc_msg.fields[5], pc_msg.fields[6], - pc_msg.fields[3], pc_msg.fields[7]] pc = msg_to_array(pc_msg) cur_scan = o3d.geometry.PointCloud() cur_scan.points = o3d.utility.Vector3dVector(pc[:, :3]) +def dounderpan(msg): + global dian + dian = (msg.dian == 1) + + # 处理underpan消息 + + def thread_localization(): global T_map_to_odom while True: # 每隔一段时间进行全局定位 - rospy.sleep(1 / FREQ_LOCALIZATION) # TODO 由于这里Fast lio发布的scan是已经转换到odom系下了 所以每次全局定位的初始解就是上一次的map2odom 不需要再拿odom了 - global_localization(T_map_to_odom) + if dian: + global_localization(T_map_to_odom) + rospy.loginfo('Global localization success') + rospy.sleep(1 / FREQ_LOCALIZATION) + else: + + continue if __name__ == '__main__': @@ -212,17 +231,17 @@ if __name__ == '__main__': SCAN_VOXEL_SIZE = 0.1 # Global localization frequency (HZ) - FREQ_LOCALIZATION = 0.5 + FREQ_LOCALIZATION = 10 # The threshold of global localization, # only those scan2map-matching with higher fitness than LOCALIZATION_TH will be taken - LOCALIZATION_TH = 0.8 + LOCALIZATION_TH = 0.6 # FOV(rad), modify this according to your LiDAR type FOV = 6.28 # The farthest distance(meters) within FOV - FOV_FAR = 30 + FOV_FAR = 40 rospy.init_node('fast_lio_localization') rospy.loginfo('Localization Node Inited...') @@ -231,14 +250,16 @@ if __name__ == '__main__': pub_pc_in_map = rospy.Publisher('/cur_scan_in_map', PointCloud2, queue_size=1) pub_submap = rospy.Publisher('/submap', PointCloud2, queue_size=1) pub_map_to_odom = rospy.Publisher('/map_to_odom', Odometry, queue_size=1) + th_ok = rospy.Publisher('/global_localization_th_ok', Bool, queue_size=1) rospy.Subscriber('/cloud_registered', PointCloud2, cb_save_cur_scan, queue_size=1) rospy.Subscriber('/Odometry', Odometry, cb_save_cur_odom, queue_size=1) + rospy.Subscriber('/underpan', underpan, dounderpan, queue_size=1) # 初始化全局地图 rospy.logwarn('Waiting for global map......') initialize_global_map(rospy.wait_for_message('/map', PointCloud2)) - + th_ok_msg = Bool() # 初始化 while not initialized: rospy.logwarn('Waiting for initial pose....') @@ -255,6 +276,12 @@ if __name__ == '__main__': rospy.loginfo('Initialize successfully!!!!!!') rospy.loginfo('') # 开始定期全局定位 + # pose_msg = rospy.wait_for_message('/initialpose', PoseWithCovarianceStamped) + # initial_pose = pose_to_mat(pose_msg) + # th_ok_msg.data = global_localization(initial_pose) + # th_ok.publish(th_ok_msg) + + _thread.start_new_thread(thread_localization, ()) - rospy.spin() + rospy.spin() \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/scripts/publish_initial_pose.py b/src/FAST_LIO_LOCALIZATION/scripts/publish_initial_pose.py index 4f17fac..ee021e4 100755 --- a/src/FAST_LIO_LOCALIZATION/scripts/publish_initial_pose.py +++ b/src/FAST_LIO_LOCALIZATION/scripts/publish_initial_pose.py @@ -1,4 +1,4 @@ -#!/usr/bin/python3 +#!/usr/bin/python3cmd_pid_publishe # coding=utf8 from __future__ import print_function, division, absolute_import diff --git a/src/FAST_LIO_LOCALIZATION/src/.vscode/c_cpp_properties.json b/src/FAST_LIO_LOCALIZATION/src/.vscode/c_cpp_properties.json new file mode 100755 index 0000000..fd7508e --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/.vscode/c_cpp_properties.json @@ -0,0 +1,23 @@ +{ + "configurations": [ + { + "browse": { + "databaseFilename": "${default}", + "limitSymbolsToIncludedHeaders": false + }, + "includePath": [ + "/home/r1/1/devel/include/**", + "/opt/ros/noetic/include/**", + "/home/r1/1/src/FAST_LIO/include/**", + "/home/r1/1/src/FAST_LIO_LOCALIZATION/include/**", + "/usr/include/**" + ], + "name": "ROS", + "intelliSenseMode": "gcc-x64", + "compilerPath": "/usr/bin/gcc", + "cStandard": "gnu11", + "cppStandard": "c++14" + } + ], + "version": 4 +} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/.vscode/settings.json b/src/FAST_LIO_LOCALIZATION/src/.vscode/settings.json new file mode 100755 index 0000000..5aafb1d --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/.vscode/settings.json @@ -0,0 +1,10 @@ +{ + "python.autoComplete.extraPaths": [ + "/home/r1/1/devel/lib/python3/dist-packages", + "/opt/ros/noetic/lib/python3/dist-packages" + ], + "python.analysis.extraPaths": [ + "/home/r1/1/devel/lib/python3/dist-packages", + "/opt/ros/noetic/lib/python3/dist-packages" + ] +} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/IMU_Processing.cpp b/src/FAST_LIO_LOCALIZATION/src/IMU_Processing.cpp new file mode 100755 index 0000000..0f51d2e --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/IMU_Processing.cpp @@ -0,0 +1,136 @@ +#include "IMU_Processing.h" + +const bool time_list(PointType &x, PointType &y) {return (x.curvature < y.curvature);}; + +void ImuProcess::set_gyr_cov(const V3D &scaler) +{ + cov_gyr_scale = scaler; +} + +void ImuProcess::set_acc_cov(const V3D &scaler) +{ + cov_vel_scale = scaler; +} + +ImuProcess::ImuProcess() + : b_first_frame_(true), imu_need_init_(true) +{ + imu_en = true; + init_iter_num = 1; + mean_acc = V3D(0, 0, 0.0); + mean_gyr = V3D(0, 0, 0); + after_imu_init_ = false; + state_cov.setIdentity(); +} + +ImuProcess::~ImuProcess() {} + +void ImuProcess::Reset() +{ + ROS_WARN("Reset ImuProcess"); + mean_acc = V3D(0, 0, 0.0); + mean_gyr = V3D(0, 0, 0); + imu_need_init_ = true; + init_iter_num = 1; + after_imu_init_ = false; + + time_last_scan = 0.0; +} + +void ImuProcess::Set_init(Eigen::Vector3d &tmp_gravity, Eigen::Matrix3d &rot) +{ + /** 1. initializing the gravity, gyro bias, acc and gyro covariance + ** 2. normalize the acceleration measurenments to unit gravity **/ + // V3D tmp_gravity = - mean_acc / mean_acc.norm() * G_m_s2; // state_gravity; + M3D hat_grav; + hat_grav << 0.0, gravity_(2), -gravity_(1), + -gravity_(2), 0.0, gravity_(0), + gravity_(1), -gravity_(0), 0.0; + double align_norm = (hat_grav * tmp_gravity).norm() / gravity_.norm() / tmp_gravity.norm(); + double align_cos = gravity_.transpose() * tmp_gravity; + align_cos = align_cos / gravity_.norm() / tmp_gravity.norm(); + if (align_norm < 1e-6) + { + if (align_cos > 1e-6) + { + rot = Eye3d; + } + else + { + rot = -Eye3d; + } + } + else + { + V3D align_angle = hat_grav * tmp_gravity / (hat_grav * tmp_gravity).norm() * acos(align_cos); + rot = Exp(align_angle(0), align_angle(1), align_angle(2)); + } +} + +void ImuProcess::IMU_init(const MeasureGroup &meas, int &N) +{ + /** 1. initializing the gravity, gyro bias, acc and gyro covariance + ** 2. normalize the acceleration measurenments to unit gravity **/ + ROS_INFO("IMU Initializing: %.1f %%", double(N) / MAX_INI_COUNT * 100); + V3D cur_acc, cur_gyr; + + if (b_first_frame_) + { + Reset(); + N = 1; + b_first_frame_ = false; + const auto &imu_acc = meas.imu.front()->linear_acceleration; + const auto &gyr_acc = meas.imu.front()->angular_velocity; + mean_acc << imu_acc.x, imu_acc.y, imu_acc.z; + mean_gyr << gyr_acc.x, gyr_acc.y, gyr_acc.z; + } + + for (const auto &imu : meas.imu) + { + const auto &imu_acc = imu->linear_acceleration; + const auto &gyr_acc = imu->angular_velocity; + cur_acc << imu_acc.x, imu_acc.y, imu_acc.z; + cur_gyr << gyr_acc.x, gyr_acc.y, gyr_acc.z; + + mean_acc += (cur_acc - mean_acc) / N; + mean_gyr += (cur_gyr - mean_gyr) / N; + + N ++; + } +} + +void ImuProcess::Process(const MeasureGroup &meas, PointCloudXYZI::Ptr cur_pcl_un_) +{ + if (imu_en) + { + if(meas.imu.empty()) return; + + if (imu_need_init_) + { + + { + /// The very first lidar frame + IMU_init(meas, init_iter_num); + + imu_need_init_ = true; + + if (init_iter_num > MAX_INI_COUNT) + { + ROS_INFO("IMU Initializing: %.1f %%", 100.0); + imu_need_init_ = false; + *cur_pcl_un_ = *(meas.lidar); + } + // *cur_pcl_un_ = *(meas.lidar); + } + return; + } + if (!after_imu_init_) after_imu_init_ = true; + *cur_pcl_un_ = *(meas.lidar); + return; + } + else + { + *cur_pcl_un_ = *(meas.lidar); + return; + } +} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/IMU_Processing.h b/src/FAST_LIO_LOCALIZATION/src/IMU_Processing.h new file mode 100755 index 0000000..a7f888e --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/IMU_Processing.h @@ -0,0 +1,59 @@ +#pragma once +#include +#include +// #include +// #include +// #include +#include +#include +// #include +#include +// #include "Estimator.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/// *************Preconfiguration + +#define MAX_INI_COUNT (100) +const bool time_list(PointType &x, PointType &y); // {return (x.curvature < y.curvature);}; + +/// *************IMU Process and undistortion +class ImuProcess +{ + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + ImuProcess(); + ~ImuProcess(); + + void Reset(); + void Process(const MeasureGroup &meas, PointCloudXYZI::Ptr pcl_un_); + void set_gyr_cov(const V3D &scaler); + void set_acc_cov(const V3D &scaler); + void Set_init(Eigen::Vector3d &tmp_gravity, Eigen::Matrix3d &rot); + + MD(12, 12) state_cov = MD(12, 12)::Identity(); + int lidar_type; + V3D gravity_; + bool imu_en; + V3D mean_acc; + bool imu_need_init_ = true; + bool after_imu_init_ = false; + bool b_first_frame_ = true; + double time_last_scan = 0.0; + V3D cov_gyr_scale = V3D(0.0001, 0.0001, 0.0001); + V3D cov_vel_scale = V3D(0.0001, 0.0001, 0.0001); + + private: + void IMU_init(const MeasureGroup &meas, int &N); + V3D mean_gyr; + int init_iter_num = 1; +}; diff --git a/src/FAST_LIO_LOCALIZATION/src/IMU_Processing.hpp b/src/FAST_LIO_LOCALIZATION/src/IMU_Processing.hpp old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/src/all_move.cpp b/src/FAST_LIO_LOCALIZATION/src/all_move.cpp new file mode 100755 index 0000000..e1b9d0b --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/all_move.cpp @@ -0,0 +1,274 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace rm_simpal_move { + +struct AHRS_Eulr_t { + float yaw; + float rol; + float pit; +}; + +struct Goal_t { + float x; + float y; + float angle; + float range; + float max_speed; + float tolerance; + bool rotor; +}; + +class RMSimpleMove { +public: + RMSimpleMove(ros::NodeHandle nh); + ~RMSimpleMove(); + +private: + void timer_callback(const ros::TimerEvent&); + void goal_pose_callback(const fast_lio_localization::GoalPoseConstPtr& msg); + void reach_location_callback(const std_msgs::Bool::ConstPtr& msg); + int8_t AHRS_GetEulr(AHRS_Eulr_t *eulr, const geometry_msgs::Quaternion &quat); + float calc_linear_velocity(float distance, float max_speed); + float calc_angular_velocity(float yaw, float target_yaw); + bool is_goal_reached(float x, float y, float tolerance); + fast_lio_localization::DataAI data_ai_msg; + + ros::NodeHandle nh_; + ros::NodeHandle private_nh_; + std::shared_ptr tf_buffer_; + std::shared_ptr tf_listener_; + std::shared_ptr tf_broadcaster_; + ros::Timer timer_; + ros::Subscriber goal_pose_sub_; + ros::Subscriber reach_location_sub_; + ros::Publisher data_ai_pub_; + ros::Publisher data_nav_pub_; + std::atomic running_; + std::atomic goal_reached_; + AHRS_Eulr_t current_eulr_; + Goal_t goal_pose_; + float distant; + float angle; +}; + +RMSimpleMove::RMSimpleMove(ros::NodeHandle nh) + : nh_(nh), private_nh_("~"), running_(true), goal_reached_(false) +{ + tf_buffer_.reset(new tf2_ros::Buffer()); + tf_listener_.reset(new tf2_ros::TransformListener(*tf_buffer_)); + tf_broadcaster_.reset(new tf2_ros::TransformBroadcaster()); + + timer_ = nh_.createTimer(ros::Duration(0.01), &RMSimpleMove::timer_callback, this); + goal_pose_sub_ = nh_.subscribe("/goal_pose", 10, &RMSimpleMove::goal_pose_callback, this); + reach_location_sub_ = nh_.subscribe("/localization_ok", 10, &RMSimpleMove::reach_location_callback,this); + data_ai_pub_ = nh_.advertise("/chassis/data_ai", 10); + data_nav_pub_ = nh_.advertise("/chassis/data_nav", 10); + + ROS_INFO("RMSimpleMove 启动!!!"); +} + +RMSimpleMove::~RMSimpleMove() +{ + running_.store(false); +} +void RMSimpleMove::timer_callback(const ros::TimerEvent&) +{ + try + { + geometry_msgs::TransformStamped trans; + trans = tf_buffer_->lookupTransform("bash", "car", ros::Time(0), ros::Duration(0.01)); + geometry_msgs::TransformStamped maps; + maps = tf_buffer_->lookupTransform("map", "car", ros::Time(0), ros::Duration(0.01)); + AHRS_GetEulr(¤t_eulr_, trans.transform.rotation); + + //ROS_INFO("pitch=%f, roll=%f, yaw=%f", current_eulr_.pit, current_eulr_.rol, current_eulr_.yaw); + + // geometry_msgs::TransformStamped goal_transform; + // goal_transform.header.stamp = ros::Time::now(); + // goal_transform.header.frame_id = "map"; + // goal_transform.child_frame_id = "goal_pose"; + // goal_transform.transform.translation.x = goal_pose_.x; + // goal_transform.transform.translation.y = goal_pose_.y; + // goal_transform.transform.translation.z = 0.0; + // goal_transform.transform.rotation.x = 0.0; + // goal_transform.transform.rotation.y = 0.0; + // goal_transform.transform.rotation.z = 0.0; + // goal_transform.transform.rotation.w = 1.0; + + // tf_broadcaster_->sendTransform(goal_transform); + + geometry_msgs::TransformStamped goal_in_car; + goal_in_car = tf_buffer_->lookupTransform("car", "goal_pose", ros::Time(0), ros::Duration(0.01)); + + float goal_x_in_car = goal_in_car.transform.translation.x; + float goal_y_in_car = goal_in_car.transform.translation.y; + float map_x_in_car = maps.transform.translation.x; + float map_y_in_car = maps.transform.translation.y; + + fast_lio_localization::DataNav data_nav_msg; + if (is_goal_reached(goal_x_in_car, goal_y_in_car, goal_pose_.tolerance)) + { + if (!goal_reached_) + { + data_nav_msg.reached = true; + goal_reached_ = true; + } + } + else + { + data_nav_msg.reached = false; + goal_reached_ = false; + } + data_nav_msg.x = trans.transform.translation.x; + data_nav_msg.y = trans.transform.translation.y; + data_nav_msg.yaw = current_eulr_.yaw; + + data_nav_pub_.publish(data_nav_msg); + distant=sqrt(pow(goal_x_in_car,2)+pow(goal_y_in_car,2)); + angle=atan2(goal_y_in_car,goal_x_in_car); + + if(goal_pose_.range>0.0){ + data_ai_msg.yaw = calc_angular_velocity(0.0,angle); + if(abs(angle)<0.4) + data_ai_msg.vx = calc_linear_velocity(goal_x_in_car, goal_pose_.max_speed); + else + data_ai_msg.vx = 0; + } + else{ + if(goal_pose_.range==0){ + data_ai_msg.vx = calc_linear_velocity(goal_x_in_car, goal_pose_.max_speed); + data_ai_msg.vy = calc_linear_velocity(goal_y_in_car, goal_pose_.max_speed); + data_ai_msg.yaw = calc_angular_velocity(current_eulr_.yaw, goal_pose_.angle); + }else{ + data_ai_msg.yaw = calc_angular_velocity(0.0,angle); + } + } + data_ai_msg.pos = distant; + data_ai_msg.ang = 2; + data_ai_msg.achieve = false; + if(abs(angle)<0.1) + data_ai_msg.achieve = true; + if (goal_pose_.rotor) + data_ai_msg.notice = 0b11000000; + else + data_ai_msg.notice = 0b00000000; + data_ai_pub_.publish(data_ai_msg); + ROS_INFO("DataAI: vx=%f, vy=%f, yaw=%f,mapx=%f,mapy=%f", data_ai_msg.vx, data_ai_msg.vy, data_ai_msg.yaw,map_x_in_car,map_y_in_car); + + ROS_INFO("Goal pose relative to car: x=%f, y=%f,yaw=%f,distant=%f,circle=%f,angle=%f,pose=%f,reach=%d", + trans.transform.translation.x,trans.transform.translation.y,current_eulr_.yaw,distant + ,goal_pose_.range,angle,data_ai_msg.pos,bool(data_ai_msg.reach)); + + } + catch (const tf2::TransformException &ex) + { + + ROS_WARN("Could not transform car to map: %s", ex.what()); + } +} + +void RMSimpleMove::goal_pose_callback(const fast_lio_localization::GoalPoseConstPtr& msg) +{ + goal_pose_.x = msg->x; + goal_pose_.y = msg->y; + goal_pose_.angle = msg->angle; + goal_pose_.max_speed = msg->max_speed; + goal_pose_.tolerance = msg->tolerance; + goal_pose_.rotor = msg->rotor; + goal_pose_.range = msg->circle; + //ROS_INFO("Received goal pose: x=%f, y=%f, angle=%f", msg->x, msg->y, msg->angle); +} + +int8_t RMSimpleMove::AHRS_GetEulr(AHRS_Eulr_t *eulr, const geometry_msgs::Quaternion &quat) +{ + if (!eulr) + return -1; + + const float sinr_cosp = 2.0f * (quat.w * quat.x + quat.y * quat.z); + const float cosr_cosp = 1.0f - 2.0f * (quat.x * quat.x + quat.y * quat.y); + eulr->pit = atan2f(sinr_cosp, cosr_cosp); + + const float sinp = 2.0f * (quat.w * quat.y - quat.z * quat.x); + eulr->rol = fabsf(sinp) >= 1.0f ? copysignf(M_PI / 2.0f, sinp) : asinf(sinp); + + const float siny_cosp = 2.0f * (quat.w * quat.z + quat.x * quat.y); + const float cosy_cosp = 1.0f - 2.0f * (quat.y * quat.y + quat.z * quat.z); + eulr->yaw = atan2f(siny_cosp, cosy_cosp); + + return 0; +} + +float RMSimpleMove::calc_linear_velocity(float distance, float max_speed) + +{ + float k_linear = 3.3f; + float k_linear_sm = 9.0f; + float velocity; + if(abs(distance)>0.3){ + velocity = k_linear * (distance-goal_pose_.range); + if (abs(velocity) > max_speed) + { + velocity = copysign(max_speed, velocity); + } +}else{ + velocity = k_linear_sm * (distance-goal_pose_.range); + if (abs(velocity) > max_speed - 2) + { + velocity = copysign(max_speed, velocity); + } + +} + return velocity; +} + +float RMSimpleMove::calc_angular_velocity(float yaw, float target_yaw) +{ + float angle_diff = target_yaw - yaw; + if (angle_diff > M_PI) + { + angle_diff -= 2 * M_PI; + } + else if (angle_diff < -M_PI) + { + angle_diff += 2 * M_PI; + } + // float k_angular = 2.4f; + // float k_angular_sm = 5.4f; + // if(abs(angle_diff)>0.1) + // return k_angular * angle_diff; + // else + // return k_angular_sm * angle_diff; + return angle_diff; +} + +bool RMSimpleMove::is_goal_reached(float x, float y, float tolerance) +{ + return sqrt(x * x + y * y) < tolerance; +} + +void RMSimpleMove::reach_location_callback(const std_msgs::Bool::ConstPtr& msg) +{ + data_ai_msg.reach = msg->data; +} // namespace rm_simpal_move +}; +int main(int argc, char** argv) +{ + ros::init(argc, argv, "global_position_listener"); + ros::NodeHandle nh; + rm_simpal_move::RMSimpleMove simple_move(nh); + ros::spin(); + return 0; +} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/chong.cpp b/src/FAST_LIO_LOCALIZATION/src/chong.cpp new file mode 100755 index 0000000..fd269d1 --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/chong.cpp @@ -0,0 +1,226 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // 核心矩阵运算 +#include // 几何变换相关 +#include "mbot_linux_serial.h" +struct Pose2D { + double x; + double y; + double yaw; +}; +class obtain_tf { +public: + obtain_tf(std::string fa, std::string ch) : tf_listener_(tf_buffer_), father_frame_(fa), child_frame_(ch) { + fetchTransform(); // 在构造函数中调用 fetchTransform 方法 + } + double x, y, yaw; + double ob_x() { + return x; + } + double ob_y() { + return y; + } + double ob_yaw() { + return yaw; + } + bool fetchTransform() { + //ROS_INFO("等待变换: %s -> %s", father_frame_.c_str(), child_frame_.c_str()); + try { + transform_ = tf_buffer_.lookupTransform( + father_frame_, + child_frame_, + ros::Time(0), + ros::Duration(10.0) + ); + //ROS_INFO("变换获取成功"); + x = transform_.transform.translation.x; + y = transform_.transform.translation.y; + yaw = suanyaw(); + return true; + } catch (tf2::TransformException &ex) { + // ROS_ERROR("变换获取失败: %s", ex.what()); + return false; + } + } + + +private: + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + std::string father_frame_; + std::string child_frame_; + geometry_msgs::TransformStamped transform_; + + + double suanyaw() { + tf2::Quaternion q( + transform_.transform.rotation.x, + transform_.transform.rotation.y, + transform_.transform.rotation.z, + transform_.transform.rotation.w + ); + double roll, pitch, yaw; + tf2::Matrix3x3(q).getRPY(roll, pitch, yaw); + return yaw; + } +}; + + + +class map_to_odom { +public: + map_to_odom(ros::NodeHandle nh,Pose2D pose,ros::Publisher send_odom) :nh_(nh),map_car("map","car"),map_odom("map","camera_init"), + pose_(pose),send_odom_(send_odom){ + + updatePose(); // 在构造函数中调用 updatePose 方法 + } + void send_fix() { + nav_msgs::Odometry fix; + fix.child_frame_id = "camera_init"; + fix.header.frame_id = "map"; + fix.header.stamp = ros::Time::now(); + fix.pose.pose.position.x = send_x; + fix.pose.pose.position.y = send_y; + fix.pose.pose.position.z = 0; + fix.pose.pose.orientation = q; + send_odom_.publish(fix); + ROS_INFO("fix:x=%.6f,y=%.6f,yaw=%.6f", fix.pose.pose.position.x, fix.pose.pose.position.y,yaw_); + } + void run() { + ros::Rate rate(10);// 10 Hz + int i=0; + while (ros::ok()) { + i++; + updatePose(); + send_fix(); + if(i>4) + break; + + } + } + +double suan_dx(){ + return pose2_.x - map_car.ob_x(); +} +double suan_dy(){ + return pose2_.y - map_car.ob_y(); +} +double suan_dyaw(){ + return pose2_.yaw - map_car.ob_yaw(); +} +private: + ros::NodeHandle nh_; + ros::Publisher send_odom_; + obtain_tf map_car,map_odom; + double send_x, send_y, send_yaw, dis , x_, y_, yaw_,targe_x,targe_y,targe_yaw; + geometry_msgs::Quaternion q; + Eigen::Vector3f translation; // 平移分量 + Eigen::Matrix4f T_translation; + Eigen::Matrix3f R; + Eigen::Matrix3f rot_matrix; + Pose2D pose_,pose2_; + +Pose2D transformPose(const Pose2D& sys2_in_sys1) { + // 从输入中获取sys2在sys1下的位姿 + double x = sys2_in_sys1.x; + double y = sys2_in_sys1.y; + double yaw = sys2_in_sys1.yaw; + + // 计算sys1在sys2下的位姿 + Pose2D sys1_in_sys2; + + // 通过旋转和平移的逆变换计算新坐标 + sys1_in_sys2.x = -x * cos(yaw) - y * sin(yaw); + sys1_in_sys2.y = x * sin(yaw) - y * cos(yaw); + + // 偏航角取反(角度标准化到 [-π, π]) + sys1_in_sys2.yaw = -yaw; + + // 标准化角度 + while (sys1_in_sys2.yaw > M_PI) sys1_in_sys2.yaw -= 2 * M_PI; + while (sys1_in_sys2.yaw < -M_PI) sys1_in_sys2.yaw += 2 * M_PI; + + return sys1_in_sys2; +} + + void updatePose() { + pose2_ = transformPose(pose_); + pose2_.y -= 0.376; // 偏移量 + pose2_.x += 0.06; // 偏移量 + x_ = suan_dx() + map_odom.ob_x() ; + y_ = suan_dy() + map_odom.ob_y(); + yaw_ = suan_dyaw() + map_odom.ob_yaw(); + translation = {x_,y_,0}; + T_translation = Eigen::Matrix4f::Identity(); + T_translation.block<3,1>(0,3) = translation; + R = Eigen::AngleAxisf(yaw_, Eigen::Vector3f::UnitZ()); + Eigen::Matrix4f T_rotation = Eigen::Matrix4f::Identity(); + T_rotation.block<3,3>(0,0) = R; + Eigen::Matrix4f T_map_to_odom = T_translation * T_rotation; // 先旋转后平移 + send_x = T_map_to_odom(0, 3); + send_y = T_map_to_odom(1, 3); + rot_matrix = T_map_to_odom.block<3, 3>(0, 0); + Eigen::Quaternionf quat(rot_matrix); + q.w = quat.w(); + q.x = quat.x(); + q.y = quat.y(); + q.z = quat.z(); + + } + + + + geometry_msgs::Quaternion getQuaternionFromYaw(double yaw) { + tf2::Quaternion tf_quat; + tf_quat.setRPY(0, 0, yaw); + geometry_msgs::Quaternion msg_quat; + tf2::convert(tf_quat, msg_quat); + return msg_quat; + } +}; + +int main(int argc, char **argv) { + ros::init(argc, argv, "fix"); + ros::NodeHandle nh; + // serialInit(); + ros::Publisher send_odom = nh.advertise("/map_to_odom",1000); + double sick1,sick2,sick3; + bool dian,passball; + bool sign = true; + Pose2D pose; + pose.x = 6.67; + pose.y = 1.66; + pose.yaw = 0.032; + // dian=0; + // x=0; + // y=0; + ros::Rate r(100); + + while(ros::ok()){ + // read5float(dian,passball); + dian =1; + if(dian==1 || sign){ + { + map_to_odom map(nh,pose,send_odom); + map.run(); + if(abs(map.suan_dx())>0.006 || abs(map.suan_dy())>0.006 || abs(map.suan_dyaw() )>0.01) + sign = true; + else + sign = false; + ROS_INFO("dian=%.1f,sick1=%.2f,sick2=%.2f,sick3=%.2f",dian,sick1,sick2,sick3); + } + }else{ + ROS_INFO("dian=%.1f,sick1=%.2f,sick2=%.2f,sick3=%.2f",dian,sick1,sick2,sick3); + } + + r.sleep(); +} +} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/chong0.cpp b/src/FAST_LIO_LOCALIZATION/src/chong0.cpp new file mode 100755 index 0000000..5ae8a2a --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/chong0.cpp @@ -0,0 +1,230 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // 核心矩阵运算 +#include // 几何变换相关 +#include "mbot_linux_serial.h" + +struct Pose2D { + double x; + double y; + double yaw; +}; + +class obtain_tf { +public: + obtain_tf(std::string fa, std::string ch) : tf_listener_(tf_buffer_), father_frame_(fa), child_frame_(ch) { + fetchTransform(); // 在构造函数中调用 fetchTransform 方法 + } + double x, y, yaw; + double ob_x() { + return x; + } + double ob_y() { + return y; + } + double ob_yaw() { + return yaw; + } + bool fetchTransform() { + if (!tf_buffer_.canTransform(father_frame_, child_frame_, ros::Time(0), ros::Duration(1.0))) { + ROS_WARN("等待变换: %s -> %s 不可用", father_frame_.c_str(), child_frame_.c_str()); + return false; + } + try { + transform_ = tf_buffer_.lookupTransform( + father_frame_, + child_frame_, + ros::Time(0) + ); + x = transform_.transform.translation.x; + y = transform_.transform.translation.y; + yaw = suanyaw(); + return true; + } catch (tf2::TransformException &ex) { + ROS_ERROR("变换获取失败: %s", ex.what()); + return false; + } +} + +private: + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + std::string father_frame_; + std::string child_frame_; + geometry_msgs::TransformStamped transform_; + + + double suanyaw() { + tf2::Quaternion q( + transform_.transform.rotation.x, + transform_.transform.rotation.y, + transform_.transform.rotation.z, + transform_.transform.rotation.w + ); + double roll, pitch, yaw; + tf2::Matrix3x3(q).getRPY(roll, pitch, yaw); + return yaw; + } +}; + + + +class map_to_odom { +public: + map_to_odom(ros::NodeHandle nh,Pose2D pose,ros::Publisher send_odom) :nh_(nh),map_car("map","car"), + map_odom("map","camera_init"),send_odom_(send_odom),pose_(pose) { + + updatePose(); // 在构造函数中调用 updatePose 方法 + } + void send_fix() { + nav_msgs::Odometry fix; + fix.child_frame_id = "camera_init"; + fix.header.frame_id = "map"; + fix.header.stamp = ros::Time::now(); + fix.pose.pose.position.x = send_x; + fix.pose.pose.position.y = send_y; + fix.pose.pose.position.z = 0; + fix.pose.pose.orientation = q; + send_odom_.publish(fix); + ROS_INFO("fix:x=%.6f,y=%.6f,yaw=%.6f", fix.pose.pose.position.x, fix.pose.pose.position.y,yaw_); + } + void run() { + int i=0; + while (ros::ok()) { + i++; + updatePose(); + send_fix(); + if(i==10) + break; + + } + } + +double suan_dx(){ + return pose2_.x - map_car.ob_x(); +} +double suan_dy(){ + return pose2_.y - map_car.ob_y(); +} +double suan_dyaw(){ + return pose2_.yaw - map_car.ob_yaw(); +} +private: + ros::NodeHandle nh_; + ros::Publisher send_odom_; + obtain_tf map_car,map_odom; + double send_x, send_y, send_yaw, dis , x_, y_, yaw_; + geometry_msgs::Quaternion q; + Eigen::Vector3f translation; // 平移分量 + Eigen::Matrix4f T_translation; + Eigen::Matrix3f R; + Eigen::Matrix3f rot_matrix; + Pose2D pose_,pose2_; + + Pose2D transformPose(const Pose2D& sys2_in_sys1) { + // 从输入中获取sys2在sys1下的位姿 + double x = sys2_in_sys1.x; + double y = sys2_in_sys1.y; + double yaw = sys2_in_sys1.yaw; + + // 计算sys1在sys2下的位姿 + Pose2D sys1_in_sys2; + + // 通过旋转和平移的逆变换计算新坐标 + sys1_in_sys2.x = -x * cos(yaw) - y * sin(yaw); + sys1_in_sys2.y = x * sin(yaw) - y * cos(yaw); + + // 偏航角取反(角度标准化到 [-π, π]) + sys1_in_sys2.yaw = -yaw; + + // 标准化角度 + while (sys1_in_sys2.yaw > M_PI) sys1_in_sys2.yaw -= 2 * M_PI; + while (sys1_in_sys2.yaw < -M_PI) sys1_in_sys2.yaw += 2 * M_PI; + + return sys1_in_sys2; +} + + + void updatePose() { + pose2_ = transformPose(pose_); + pose2_.y -= 0.376; // 偏移量 + pose2_.x += 0.06; // 偏移量 + x_ = suan_dx() + map_odom.ob_x() ; + y_ = suan_dy() + map_odom.ob_y(); + yaw_ = suan_dyaw() + map_odom.ob_yaw(); + translation = {x_,y_,0}; + T_translation = Eigen::Matrix4f::Identity(); + T_translation.block<3,1>(0,3) = translation; + R = Eigen::AngleAxisf(yaw_, Eigen::Vector3f::UnitZ()); + Eigen::Matrix4f T_rotation = Eigen::Matrix4f::Identity(); + T_rotation.block<3,3>(0,0) = R; + Eigen::Matrix4f T_map_to_odom = T_translation * T_rotation; // 先旋转后平移 + send_x = T_map_to_odom(0, 3); + send_y = T_map_to_odom(1, 3); + rot_matrix = T_map_to_odom.block<3, 3>(0, 0); + Eigen::Quaternionf quat(rot_matrix); + q.w = quat.w(); + q.x = quat.x(); + q.y = quat.y(); + q.z = quat.z(); + + } + + + + geometry_msgs::Quaternion getQuaternionFromYaw(double yaw) { + tf2::Quaternion tf_quat; + tf_quat.setRPY(0, 0, yaw); + geometry_msgs::Quaternion msg_quat; + tf2::convert(tf_quat, msg_quat); + return msg_quat; + } +}; + +int main(int argc, char **argv) { + ros::init(argc, argv, "fix"); + ros::NodeHandle nh; + //serialInit(); + double sick1,sick2,sick3,dian; + bool passball; + Pose2D pose; + bool sign = false; + // x=-6; + // y=1.5; + // pose.x=0; + // pose.y=0; + pose.x=6.0; + pose.y=2.0; + pose.yaw=0.00; + ros::Publisher send_odom = nh.advertise("/map_to_odom", 10); + ros::Rate rate(20); + //clearSerialBuffer(); + dian = 1; + while(ros::ok()){ + //read4float(dian); + + if(dian==1){ + { + map_to_odom map(nh,pose,send_odom); + map.run(); + if(abs(map.suan_dx())>0.006 || abs(map.suan_dy())>0.006 || abs(map.suan_dyaw() )>0.01) + sign = true; + else + sign = false; + ROS_INFO("dian=%.1f,sick1=%.2f,sick2=%.2f,sick3=%.2f",dian,sick1,sick2,sick3); + } + }else{ + ROS_INFO("dian=%.1f,sick1=%.2f,sick2=%.2f,sick3=%.2f",dian,sick1,sick2,sick3); + } + rate.sleep(); +} +} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/commands.cpp b/src/FAST_LIO_LOCALIZATION/src/commands.cpp new file mode 100755 index 0000000..b93d02c --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/commands.cpp @@ -0,0 +1,225 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // 核心矩阵运算 +#include // 几何变换相关 +#include +#include +#include +#include +#include +#include +#include +#include +struct Pose2D { + double x; + double y; + double yaw; +}; + +class obtain_tf { +public: + obtain_tf(std::string fa, std::string ch) : tf_listener_(tf_buffer_), father_frame_(fa), child_frame_(ch) { + fetchTransform(); // 在构造函数中调用 fetchTransform 方法 + } + double x, y, yaw; + double ob_x() { + return x; + } + double ob_y() { + return y; + } + double ob_yaw() { + return yaw; + } + bool fetchTransform() { + if (!tf_buffer_.canTransform(father_frame_, child_frame_, ros::Time(0), ros::Duration(1.0))) { + ROS_WARN("等待变换: %s -> %s 不可用", father_frame_.c_str(), child_frame_.c_str()); + return false; + } + try { + transform_ = tf_buffer_.lookupTransform( + father_frame_, + child_frame_, + ros::Time(0) + ); + x = transform_.transform.translation.x; + y = transform_.transform.translation.y; + yaw = suanyaw(); + return true; + } catch (tf2::TransformException &ex) { + ROS_ERROR("变换获取失败: %s", ex.what()); + return false; + } +} + +private: + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + std::string father_frame_; + std::string child_frame_; + geometry_msgs::TransformStamped transform_; + + + double suanyaw() { + tf2::Quaternion q( + transform_.transform.rotation.x, + transform_.transform.rotation.y, + transform_.transform.rotation.z, + transform_.transform.rotation.w + ); + double roll, pitch, yaw; + tf2::Matrix3x3(q).getRPY(roll, pitch, yaw); + return yaw; + } +}; + + + + +class send_goal { +public: + std::vector pose_list; + + send_goal(ros::NodeHandle nh) : nh_(nh) { + pose_list.resize(3); + initializeGoalPoses(); + } + void get_r1(float x , float y) { + pose_list[1].x = x; + pose_list[1].y = y; + pose_list[1].angle = 0.0; + pose_list[1].max_speed = 6.0; + pose_list[1].tolerance = 0.00; + pose_list[1].rotor = 0.0; + pose_list[1].circle = -1; + } + void sendGoalPose(const fast_lio_localization::GoalPose& goal_pose) { + goal_pub_.publish(goal_pose); + geometry_msgs::TransformStamped transform; + transform.header.stamp = ros::Time::now(); + transform.header.frame_id = "map"; + transform.child_frame_id = "goal_pose"; + + transform.transform.translation.x = goal_pose.x; + transform.transform.translation.y = goal_pose.y; + transform.transform.translation.z = 0.0; + + tf::Quaternion q = tf::createQuaternionFromYaw(goal_pose.angle); + transform.transform.rotation.x = q.x(); + transform.transform.rotation.y = q.y(); + transform.transform.rotation.z = q.z(); + transform.transform.rotation.w = q.w(); + + // 广播变换 + tf_broadcaster.sendTransform(transform); + } +private: + ros::NodeHandle nh_; + ros::Publisher goal_pub_; + tf::TransformBroadcaster tf_broadcaster; + + void initializeGoalPoses() { + pose_list[2]; + goal_pub_ = nh_.advertise("goal_pose", 1000); + // 初始化目标点 + pose_list[0].x = 0.490; + pose_list[0].y = -3.228; + pose_list[0].angle = 0.0; + pose_list[0].max_speed = 6.0; + pose_list[0].tolerance = 0.00; + pose_list[0].rotor = 0.0; + pose_list[0].circle = -1; + } +}; + +fast_lio_localization::underpan underpan; +fast_lio_localization::position sub_position; +bool th_ok = false; +void sub_underpan_callback(const fast_lio_localization::underpan::ConstPtr& msg) { + underpan.dian = msg->dian; +} +void sub_position_callback(const fast_lio_localization::position::ConstPtr& msg) { + sub_position.passball = msg->passball; + sub_position.x = msg->x; + sub_position.y = msg->y; +} +void sub_hz_ok_callback(const std_msgs::Bool::ConstPtr& msg) { + th_ok = msg->data; +} + +int main(int argc, char **argv) { + ros::init(argc, argv, "commands"); + ros::NodeHandle nh; + setlocale(LC_ALL,""); + double sick1,sick2,sick3; + float r1_x,r1_y,carx, cary,before_x, before_y,dx, dy; + before_x = 0.0; + before_y = 0.0; + obtain_tf map_car("map", "car"); + bool dian = false, passball = false; + std_msgs::Bool msg; + int i=0; + ros::Subscriber sub_underpan = nh.subscribe("/underpan", 10, sub_underpan_callback); + ros::Subscriber sub_r1 = nh.subscribe("/position", 10, sub_position_callback); + ros::Subscriber sub_hz_ok = nh.subscribe("/global_localization_th_ok",10, sub_hz_ok_callback); + ros::Publisher pub_sign = nh.advertise("/localization_ok", 10); + send_goal goal(nh); + fast_lio_localization::GoalPose goal_pose; + ros::Rate rate(100); + // clearBothSerialBuffers(); + goal_pose = goal.pose_list[0]; + goal.sendGoalPose(goal_pose); + while (ros::ok()) { + ros::spinOnce(); + dian = underpan.dian; + passball = sub_position.passball; + if(dian==1 && th_ok) { + map_car.fetchTransform(); + carx = map_car.ob_x(); + cary = map_car.ob_y(); + dx = abs(carx - before_x); + dy = abs(cary - before_y); + ROS_INFO("dx=%.2f, dy=%.2f", dx, dy); + if(dx < 0.02 && dy < 0.02) { + i++; + if(i > 200) { + msg.data = true; + pub_sign.publish(msg); + } + }else{ + i = 0; + } + before_x = carx; + before_y = cary; + }else{ + i=0; + } + if(passball) { + ROS_INFO("传球模式"); + // write1float(true,map_car.ob_x(),map_car.ob_y()); + //read1float(r1_x,r1_y); + r1_x = sub_position.x; + r1_y = sub_position.y; + goal.get_r1(r1_x,r1_y); + goal_pose = goal.pose_list[1]; + goal.sendGoalPose(goal_pose); + ROS_INFO("发送目标点: x=%.2f, y=%.2f, angle=%.2f", goal_pose.x, goal_pose.y, goal_pose.angle); + }else { + // write1float(false,0,0); + goal_pose = goal.pose_list[0]; + goal.sendGoalPose(goal_pose); + ROS_INFO("瞄框"); + } +ROS_INFO("dian=%d,passball=%d",dian,passball); + rate.sleep(); +} +} diff --git a/src/FAST_LIO_LOCALIZATION/src/controlpid.cpp b/src/FAST_LIO_LOCALIZATION/src/controlpid.cpp deleted file mode 100644 index 15a4649..0000000 --- a/src/FAST_LIO_LOCALIZATION/src/controlpid.cpp +++ /dev/null @@ -1,198 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "mbot_linux_serial.h" -class PIDController { -public: - PIDController(double kp, double ki, double kd) - : kp_(kp), ki_(ki), kd_(kd), integral_(0.0), prev_error_(0.0) {} - - - double control(double setpoint, double pv) { - double error = setpoint - pv; - integral_ += error; - double derivative = error - prev_error_; - prev_error_ = error; - return kp_ * error + ki_ * integral_ + kd_ * derivative; - }//pid - -private: - double kp_, ki_, kd_, integral_, prev_error_; -}; - -struct TargetPose { - double x, y, yaw; -}; - -class PoseController { -public: - PoseController() - : nh_("~"), - x_controller_(0.12, 0.0, 0.0), - y_controller_(0.15, 0.0, 0.0), - yaw_controller_(0.12, 0.0, 0.0), - robot_mode_(0) { - target_poses_ = { - {1.582, 0.00, 0.0}, - {0.000, 1.60, -M_PI/2}, - {0.705, 1.60, -M_PI/2}, - {1.482, 1.60, -M_PI/2}, - {2.234, 1.60, -M_PI/2}, - {2.981, 1.60, -M_PI/2}, - }; - target_ = target_poses_[0]; - //laser_sub = nh_.subscribe("/scan", 10, &PoseController::laser_callback, this); - pose_subscriber_ = nh_.subscribe("filtered_pose", 10, &PoseController::pose_callback, this); - cmd_pid_publisher_ = nh_.advertise("cmd_vel_pid", 10); - //position_id_subscriber_ = nh_.subscribe("/position_id", 10, &PoseController::position_id_callback, this); - pid_status_publisher_ = nh_.advertise("/pid_status", 10); - //robot_mode_subscriber_ = nh_.subscribe("robot_mode", 10, &PoseController::robot_mode_callback, this); - goal_subscriber_ = nh_.subscribe("/move_base_simple/goal", 10, &PoseController::goal_callback, this); - serial_write3float_=nh_.subscribe("cmd_vel_pid", 10, &PoseController::serial_write3double_callback, this); - //scan_sub_=nh_.subscribe("/scan",10,&PoseController::distant,this); - } - -private: - // void robot_mode_callback(const std_msgs::Int64::ConstPtr& msg) { - // robot_mode_ = msg->data; - // if (msg->data == 1) { - // target_ = target_poses_[0]; - // } - // } - - // void position_id_callback(const std_msgs::Int64::ConstPtr& msg) { - // size_t id = static_cast(msg->data); - // if (id < target_poses_.size()) { - // target_ = target_poses_[id]; - // } else { - // ROS_WARN("Invalid position id: %ld", id); - // } - // } - - void pose_callback(const geometry_msgs::PoseStamped::ConstPtr& msg) { - double x = msg->pose.position.x; - double y = msg->pose.position.y; - tf2::Quaternion quat; - tf2::fromMsg(msg->pose.orientation, quat); - tf2::Matrix3x3 m(quat); - double roll, pitch, yaw; - m.getRPY(roll, pitch, yaw); - TargetPose target_local = transformTargetPose(x, y, yaw);//算位姿 - calculateControl(target_local);//检验 - } - void goal_callback(const geometry_msgs::PoseStamped::ConstPtr& msg) { - double x = msg->pose.position.x; - double y = msg->pose.position.y; - tf2::Quaternion quat; - tf2::fromMsg(msg->pose.orientation, quat); - tf2::Matrix3x3 m(quat); - double roll, pitch, yaw; - m.getRPY(roll, pitch, yaw); - target_={x,y,yaw}; - }//目标位置位姿 - - TargetPose transformTargetPose(double x, double y, double yaw) { - TargetPose target_local; - target_local.x = cos(yaw) * (target_.x - x) + sin(yaw) * (target_.y - y); - target_local.y = -sin(yaw) * (target_.x - x) + cos(yaw) * (target_.y - y); - target_local.yaw = target_.yaw - yaw; - if (target_local.yaw > M_PI) - target_local.yaw -= 2 * M_PI; - else if (target_local.yaw < -M_PI) - target_local.yaw += 2 * M_PI; - return target_local; - }//算位姿 - - void calculateControl(const TargetPose &target_local) { - double error_threshold = 0.05; - double control_x = 0.0, control_y = 0.0, control_yaw = 0.0; - if (std::abs(target_local.x) > error_threshold || std::abs(target_local.y) > error_threshold || std::abs(target_local.yaw) > error_threshold) { - //校零 - control_x = x_controller_.control(0.0, target_local.x); - control_y = y_controller_.control(0.0, target_local.y); - control_yaw = yaw_controller_.control(0.0, target_local.yaw); - control_x = std::min(control_x, 0.2); - control_y = std::min(control_y, 0.2);//限速 - } else { - std_msgs::String msg; - msg.data = (robot_mode_ == 6) ? "OKK" : "OK"; - pid_status_publisher_.publish(msg); - } - - geometry_msgs::Twist cmd; - cmd.linear.x = control_x; - cmd.linear.y = -control_y; - cmd.angular.z = control_yaw; - cmd_pid_publisher_.publish(cmd);//发送pid - } - //发送 - void serial_write3double_callback(const geometry_msgs::Twist::ConstPtr& msg) { - //write3float(msg->linear.x, msg->linear.y, msg->angular.z); - write3float2(msg->linear.x, msg->linear.y, 0//msg->angular.z);//lzcdxc - ROS_INFO("linear.x: %f, linear.y: %f, angular.z: %f", msg->linear.x, msg->linear.y, msg->angular.z); - } - - //避障 -// void laser_callback(const sensor_msgs::LaserScan::ConstPtr& msg) { -// static const float min_distance = 0.45; // 最小安全距离,单位:米 -// bool obstacle_detected = false; - -// for (size_t i = 0; i < msg->ranges.size(); i=i+30) { -// float distance = msg->ranges[i]; -// if (distance < min_distance && !std::isnan(distance)) { -// obstacle_detected = true; -// break; -// } -// } - -// if (obstacle_detected) { -// // 处理避障逻辑 -// ROS_WARN("stop!!!"); -// stopRobot(); -// } else { -// // 继续正常运动 -// continueMoving(); -// } -// } -void stopRobot() { - geometry_msgs::Twist stop_cmd; - stop_cmd.linear.x = 0; - stop_cmd.angular.z = 0; - cmd_pid_publisher_.publish(stop_cmd); -} - -void continueMoving() { - // 继续向目标移动的逻辑 -} - ros::NodeHandle nh_; - ros::Subscriber pose_subscriber_; - ros::Subscriber goal_subscriber_; - ros::Publisher cmd_pid_publisher_; - ros::Publisher pid_status_publisher_; - ros::Subscriber robot_mode_subscriber_; - ros::Subscriber position_id_subscriber_; - ros::Subscriber serial_write3float_; - ros::Subscriber scan_sub_; - std::vector target_poses_; - PIDController x_controller_, y_controller_, yaw_controller_; - TargetPose target_; - ros::Subscriber laser_sub; - int robot_mode_; - float min_distance = 0.5; // 最小安全距离,单位:米 -}; - -int main(int argc, char **argv) { - ros::init(argc, argv, "pose_controller"); - serialInit(); - PoseController node; - - ros::spin(); - return 0; - -} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/flag.cpp b/src/FAST_LIO_LOCALIZATION/src/flag.cpp old mode 100644 new mode 100755 index 5cbf182..eb79241 --- a/src/FAST_LIO_LOCALIZATION/src/flag.cpp +++ b/src/FAST_LIO_LOCALIZATION/src/flag.cpp @@ -1,52 +1,85 @@ #include -#include -#include -// tf chage https://zhuanlan.zhihu.com/p/340016739 +#include +#include +#include +int main(int argc, char** argv) +{ + // 初始化ROS节点 + ros::init(argc, argv, "static_tf_broadcaster"); + ros::NodeHandle node; -int main(int argc, char** argv){ - ros::init(argc, argv, "flag"); - ros::NodeHandle nh; - ros::Publisher pose_publisher = nh.advertise("/pose_controller/filtered_pose", 10); - ros::NodeHandle node; - geometry_msgs::PoseStamped pose; - tf::TransformListener listener; - tf::TransformBroadcaster broadcaster; - tf::Transform transform_broadcaster; - ros::Duration(1.0).sleep(); + // 创建静态坐标变换广播器 + static tf2_ros::StaticTransformBroadcaster static_broadcaster; - ros::Rate rate(1000); - while (node.ok()){ - tf::StampedTransform transform_listener; - - try{ - listener.lookupTransform("map", "body", - ros::Time(0), transform_listener); - } - catch (tf::TransformException ex){ - ROS_ERROR("%s",ex.what()); - ros::Duration(1.0).sleep(); - } - float robot_pose_x=transform_listener.getOrigin().x(); - float robot_pose_y=transform_listener.getOrigin().y(); - float robot_pose_z=transform_listener.getOrigin().z(); - float robot_oriation_x=transform_listener.getRotation().getX(); - float robot_oriation_y=transform_listener.getRotation().getY(); - float robot_oriation_z=transform_listener.getRotation().getZ(); - float robot_oriation_w=transform_listener.getRotation().getW(); - pose.header.stamp = ros::Time::now(); - pose.header.frame_id = "now"; - pose.pose.position.x = robot_pose_x; - pose.pose.position.y = robot_pose_y; - pose.pose.position.z = robot_pose_z; - pose.pose.orientation.x = robot_oriation_x; - pose.pose.orientation.y = robot_oriation_y; - pose.pose.orientation.z = robot_oriation_z; - pose.pose.orientation.w = robot_oriation_w; - pose_publisher.publish(pose); - + // 创建TransformStamped消息 + geometry_msgs::TransformStamped transform; + geometry_msgs::TransformStamped transform2; + geometry_msgs::TransformStamped transform3; - rate.sleep(); - } - return 0; -}; \ No newline at end of file + // 设置时间戳和坐标系关系 + transform.header.stamp = ros::Time::now(); + transform.header.frame_id = "body"; // 父坐标系 + transform.child_frame_id = "car"; // 子坐标系 + + // 设置平移参数(Y轴正方向偏移0.6米) + transform.transform.translation.x =- 0.0; + transform.transform.translation.y = 0.330; + transform.transform.translation.z = 0.0; + + // 创建四元数(绕Z轴顺时针旋转90度) + tf2::Quaternion q; + q.setRPY(0, 0, 0); // Roll, Pitch, Yaw (Z轴旋转-90度) + transform.transform.rotation.x = q.x(); + transform.transform.rotation.y = q.y(); + transform.transform.rotation.z = q.z(); + transform.transform.rotation.w = q.w(); + + // 设置 body 到 map 的变换 + transform2.header.stamp = ros::Time::now(); + transform2.header.frame_id = "map"; // 父坐标系 + transform2.child_frame_id = "bash"; // 子坐标系 + + // 设置平移参数(假设 body 在 map 中的位置) + transform2.transform.translation.x = 0.0; + transform2.transform.translation.y = 0.330; + transform2.transform.translation.z = 0.0; + + // 创建四元数(假设 body 在 map 中没有旋转) + tf2::Quaternion q2; + q2.setRPY(0, 0, 0); // Roll, Pitch, Yaw (Z轴旋转-90度) + transform2.transform.rotation.x = q2.x(); + transform2.transform.rotation.y = q2.y(); + transform2.transform.rotation.z = q2.z(); + transform2.transform.rotation.w = q2.w(); + + // // 设置 map 到 odom 的变换 + // transform3.header.stamp = ros::Time::now(); + // transform3.header.frame_id = "map"; // 父坐标系 + // transform3.child_frame_id = "coordinate"; // 子坐标系 + + // // 设置平移参数(假设 odom 在 map 中的位置) + // transform3.transform.translation.x = 0.0; + // transform3.transform.translation.y = 0.0; + // transform3.transform.translation.z = 0.0; + + // // 创建四元数(假设 odom 在 map 中没有旋转) + // tf2::Quaternion q3; + // q3.setRPY(0, 0, -M_PI/2); // Roll, Pitch, Yaw (无旋转) + // transform3.transform.rotation.x = q3.x(); + // transform3.transform.rotation.y = q3.y(); + // transform3.t ransform.rotation.z = q3.z(); + // transform3.transform.rotation.w = q3.w(); + + // 发送变换 + static_broadcaster.sendTransform(transform); + static_broadcaster.sendTransform(transform2); + // static_broadcaster.sendTransform(transform3); + + ROS_INFO("Static transforms published"); + + // 保持节点活跃 + ros::spin(); + + return 0; +} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/laserMapping.cpp b/src/FAST_LIO_LOCALIZATION/src/laserMapping.cpp old mode 100644 new mode 100755 diff --git a/src/FAST_LIO_LOCALIZATION/src/mbot_linux_serial.cpp b/src/FAST_LIO_LOCALIZATION/src/mbot_linux_serial.cpp old mode 100644 new mode 100755 index 2bad270..5edac0e --- a/src/FAST_LIO_LOCALIZATION/src/mbot_linux_serial.cpp +++ b/src/FAST_LIO_LOCALIZATION/src/mbot_linux_serial.cpp @@ -2,48 +2,31 @@ #include #include -/*=================================================================== -程序功能:串口通信测试程序 -程序编写:公众号:小白学移动机器人 -其他 :如果对代码有任何疑问,可以私信小编,一定会回复的。 -===================================================================== -------------------关注公众号,获得更多有趣的分享--------------------- -===================================================================*/ + using namespace std; using namespace boost::asio; //串口相关对象 -boost::system::error_code err; -boost::asio::io_service iosev; -boost::asio::serial_port sp(iosev); -uint8_t usart_start = 0xFF; - uint8_t usart_id = 0x06; - uint8_t usart_end = 0xFE; +boost::system::error_code err,err2; +boost::asio::io_service iosev,iosev2; +boost::asio::serial_port sp(iosev),sp2(iosev2); +uint8_t usart_idf = 0x01; +const unsigned char ender_read = 0xFD; +const unsigned char header_read = 0xFC; -/******************************************************** - 串口发送接收相关常量、变量、共用体对象 -********************************************************/ -const unsigned char ender[2] = {0x0d, 0x0a}; -const unsigned char header[2] = {0x55, 0xaa}; -//发送左右轮速控制速度共用体 -union sendData +union receiveData2 { - short d; - unsigned char data[2]; -}leftVelSet,rightVelSet; -union sendDatelf + float d; + unsigned char data[4]; +}; +receiveData2 sick_1,sick_2,sick_3,r1_x,r1_y,r2_x,r2_y; +union receivesign { - float d; - unsigned char data[4]; -}X,Y,YAW; -//接收数据(左轮速、右轮速、角度)共用体(-32767 - +32768) -union receiveData -{ - short d; - unsigned char data[2]; -}leftVelNow,rightVelNow,angleNow; - + bool d; + unsigned char data[1]; +} dian_,passball_; // 用于接收sign的值 +// alignas(4) unsigned char dian_[4],sick_1[4],sick_2[4],sick_3[4]; /******************************************************** 函数功能:串口参数初始化 入口参数:无 @@ -51,7 +34,7 @@ union receiveData ********************************************************/ void serialInit() { - sp.open("/dev/ttyUSB0", err); + sp.open("/dev/underpan", err); if(err){ std::cout << "Error: " << err << std::endl; std::cout << "请检查您的串口/dev/ttyUSB0 是否已经准备好:\n 1.读写权限是否打开(默认不打开) \n 2.串口名称是否正确" << std::endl; @@ -65,151 +48,63 @@ void serialInit() iosev.run(); } - -/******************************************************** -函数功能:将对机器人的左右轮子控制速度,打包发送给下位机 -入口参数:机器人线速度、角速度 -出口参数: -********************************************************/ -void writeSpeed(double Left_v, double Right_v,unsigned char ctrlFlag) +void passballserialInit() { - unsigned char buf[18] = {0};// - int i, length = 0; - - leftVelSet.d = Left_v;//mm/s - rightVelSet.d = Right_v; - - // 设置消息头 - for(i = 0; i < 2; i++) - buf[i] = header[i]; //buf[0] buf[1] - - // 设置机器人左右轮速度 - length = 5; - buf[2] = length; //buf[2] - for(i = 0; i < 2; i++) - { - buf[i + 3] = leftVelSet.data[i]; //buf[3] buf[4] - buf[i + 5] = rightVelSet.data[i]; //buf[5] buf[6] + sp2.open("/dev/tor2", err2); + if(err2){ + std::cout << "Error: " << err2 << std::endl; + std::cout << "请检查您的串口/dev/ttyUSB0 是否已经准备好:\n 1.读写权限是否打开(默认不打开) \n 2.串口名称是否正确" << std::endl; + return ; } - // 预留控制指令 - buf[3 + length - 1] = ctrlFlag; //buf[7] + sp2.set_option(serial_port::baud_rate(115200)); + sp2.set_option(serial_port::flow_control(serial_port::flow_control::none)); + sp2.set_option(serial_port::parity(serial_port::parity::none)); + sp2.set_option(serial_port::stop_bits(serial_port::stop_bits::one)); + sp2.set_option(serial_port::character_size(8)); - // 设置校验值、消息尾 - buf[3 + length] = getCrc8(buf, 3 + length);//buf[8] - buf[3 + length + 1] = ender[0]; //buf[9] - buf[3 + length + 2] = ender[1]; //buf[10] - - // 通过串口下发数据 - boost::asio::write(sp, boost::asio::buffer(buf)); - - - + iosev2.run(); +} +double get_dian(){ + return (bool)dian_.d; +} +double get_sick1(){ + return (double)sick_1.d; +} +double get_sick2(){ + return (double)sick_2.d; +} +double get_sick3(){ + return (double)sick_3.d; } -void write3float(float x,float y,float yaw) +bool read5float(bool &dian,bool &passball) + + { - unsigned char buf[18] = {0};// - int i, length = 0; - - X.d = x;//mm/s - Y.d = y; - YAW.d = yaw; - - // 设置消息头 - for(i = 0; i < 2; i++) - buf[i] = header[i]; //buf[0] buf[1] - - // 设置机器人左右轮速度 - length = 12; - buf[2] = length; //buf[2] - for(i = 0; i < 4; i++) - { - buf[i + 3] = X.data[i]; //3456 - buf[i + 7] = Y.data[i]; //78910 - buf[i + 11] = YAW.data[i];//11121314 - } - - - // 设置校验值、消息尾 - buf[3 + length] = getCrc8(buf, 3 + length);//buf[8] - buf[3 + length + 1] = ender[0]; //buf[9] - buf[3 + length + 2] = ender[1]; //buf[10] - - // 通过串口下发数据 - boost::asio::write(sp, boost::asio::buffer(buf)); - -} -void write3float2(float x,float y,float yaw) -{ X.d = x;//mm/s - Y.d = y; - YAW.d = yaw; - - unsigned char buf[16] = {0};// - buf[0]=0xFF; - buf[1]=0x09; - buf[2]=0x01; - buf[15]=0xFE; - for(int i=0;i<4;i++){ - buf[i+3]=X.data[i]; - buf[i+7]=Y.data[i]; - buf[i+11]=YAW.data[i]; - } - boost::asio::write(sp, boost::asio::buffer(buf)); - -} -std::string string2hex(const std::string& input) -{ - static const char* const lut = "0123456789ABCDEF"; - size_t len = input.length(); - - std::string output; - output.reserve(2 * len); - for (size_t i = 0; i < len; ++i) - { - const unsigned char c = input[i]; - output.push_back(lut[c >> 4]); - output.push_back(lut[c & 15]); - } - return output; -} - -/******************************************************** -函数功能:从下位机读取数据 -入口参数:机器人左轮轮速、右轮轮速、角度,预留控制位 -出口参数:bool -********************************************************/ -bool readSpeed(double &Left_v,double &Right_v,double &Angle,unsigned char &ctrlFlag) -{ - char length = 0; unsigned char checkSum; - unsigned char buf[15]={0}; - bool succeedReadFlag = false; + unsigned char buf[11]={0}; //========================================================= // 此段代码可以读数据的结尾,进而来进行读取数据的头部 try { boost::asio::streambuf response; - boost::asio::read_until(sp, response, "\r\n", err); // 第一次分割数据 根据数据尾"\r\n" + boost::asio::read_until(sp, response,(char)ender_read, err); std::string str; std::istream is(&response); while(response.size() != 0) { - std::getline(is, str, (char)header[0]); // 第二次分割数据 根据数据头 这个会丢 0x55 - // std::cout <<"筛选前:"<<" {"<< string2hex(str) << "} " <>1)^0x8C; - else - crc >>= 1; - } - } - return crc; -} +void clearBothSerialBuffers() { + boost::system::error_code ec; + char buffer[256]; + // 清空 sp 的缓冲区 + for (int i = 0; i < 10; ++i) { // 最多尝试10次,防止死循环 + size_t len = sp.read_some(boost::asio::buffer(buffer, sizeof(buffer)), ec); + if (ec || len == 0) break; + } + + // 清空 sp2 的缓冲区 + ec.clear(); + for (int i = 0; i < 10; ++i) { + size_t len = sp2.read_some(boost::asio::buffer(buffer, sizeof(buffer)), ec); + if (ec || len == 0) break; + } +} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/mbot_linux_serial.h b/src/FAST_LIO_LOCALIZATION/src/mbot_linux_serial.h old mode 100644 new mode 100755 index 7f835be..1a2d5dc --- a/src/FAST_LIO_LOCALIZATION/src/mbot_linux_serial.h +++ b/src/FAST_LIO_LOCALIZATION/src/mbot_linux_serial.h @@ -8,11 +8,14 @@ #include #include #include -extern void write3float2(float x,float y,float yaw); extern void serialInit(); -extern void writeSpeed(double Left_v, double Right_v,unsigned char ctrlFlag); -extern void write3float(float x, float y, float yaw); -extern bool readSpeed(double &Left_v,double &Right_v,double &Angle,unsigned char &ctrlFlag); -unsigned char getCrc8(unsigned char *ptr, unsigned short len); - +extern void passballserialInit(); +extern void clearBothSerialBuffers(); +extern bool read5float(bool &dian,bool &passball); +extern bool read1float(float &x, float &y); +extern void write1float(bool passball,double x, double y); +extern double get_dian(); +extern double get_sick1(); +extern double get_sick2(); +extern double get_sick3(); #endif diff --git a/src/FAST_LIO_LOCALIZATION/src/position.cpp b/src/FAST_LIO_LOCALIZATION/src/position.cpp new file mode 100755 index 0000000..c98fa56 --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/position.cpp @@ -0,0 +1,130 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +static serial::Serial ser; +static std::mutex serial_mutex; + +class obtain_tf { +public: + obtain_tf(std::string fa, std::string ch) : tf_listener_(tf_buffer_), father_frame_(fa), child_frame_(ch) { + fetchTransform(); // 在构造函数中调用 fetchTransform 方法 + } + double x, y, yaw; + double ob_x() { + return x; + } + double ob_y() { + return y; + } + double ob_yaw() { + return yaw; + } + bool fetchTransform() { + if (!tf_buffer_.canTransform(father_frame_, child_frame_, ros::Time(0), ros::Duration(1.0))) { + ROS_WARN("等待变换: %s -> %s 不可用", father_frame_.c_str(), child_frame_.c_str()); + return false; + } + try { + transform_ = tf_buffer_.lookupTransform( + father_frame_, + child_frame_, + ros::Time(0) + ); + x = transform_.transform.translation.x; + y = transform_.transform.translation.y; + yaw = suanyaw(); + return true; + } catch (tf2::TransformException &ex) { + ROS_ERROR("变换获取失败: %s", ex.what()); + return false; + } +} + +private: + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + std::string father_frame_; + std::string child_frame_; + geometry_msgs::TransformStamped transform_; + + + double suanyaw() { + tf2::Quaternion q( + transform_.transform.rotation.x, + transform_.transform.rotation.y, + transform_.transform.rotation.z, + transform_.transform.rotation.w + ); + double roll, pitch, yaw; + tf2::Matrix3x3(q).getRPY(roll, pitch, yaw); + return yaw; + } +}; + + + +// 串口参数 +void serialInit() { + std::lock_guard lock(serial_mutex); + if (ser.isOpen()) ser.close(); + serial::Timeout to = serial::Timeout::simpleTimeout(100); + ser.setPort("/dev/tor1"); + ser.setBaudrate(115200); + ser.setTimeout(to); + ser.open(); + if (ser.isOpen()) { + ser.flushInput(); + ser.flushOutput(); + ROS_INFO("Serial port initialized and buffers cleared."); + } else { + ROS_ERROR("Failed to open serial port!tor1_position"); + } +} + + +bool write1float(double x,double y){ + std::lock_guard lock(serial_mutex); + if (!ser.isOpen()) return false; + try { + // 一帧总长度=帧头1+标志1+数据8+帧尾1=11字节 + std::string buf(11, 0); + buf[0] = 0xFC; // 帧头 + buf[1] = 0x01; // 标志 + float x_f = static_cast(x); + float y_f = static_cast(y); + memcpy(&buf[2], &x_f, 4); + memcpy(&buf[6], &y_f, 4); + buf[10] = 0xFD; // 帧尾 + ser.write(buf); + return true; + } catch (...) { + ROS_ERROR("Failed to write data to serial port."); + } +} +int main(int argc, char** argv) +{ + ros::init(argc, argv, "ros_serial_node"); + ros::NodeHandle nh; + serialInit(); + + ros::Rate rate(1000); + double x, y; + bool o; + obtain_tf tf_ob("map", "car"); + while (ros::ok()) { + tf_ob.fetchTransform(); // 获取变换 + x = tf_ob.ob_x(); + y = tf_ob.ob_y(); + o = write1float(x,y); + ROS_INFO("x: %f, y: %f,o=%d", x, y,int(o)); + rate.sleep(); + } +} diff --git a/src/FAST_LIO_LOCALIZATION/src/preprocess.cpp b/src/FAST_LIO_LOCALIZATION/src/preprocess.cpp old mode 100644 new mode 100755 index d809508..bd86e99 --- a/src/FAST_LIO_LOCALIZATION/src/preprocess.cpp +++ b/src/FAST_LIO_LOCALIZATION/src/preprocess.cpp @@ -3,11 +3,16 @@ #define RETURN0 0x00 #define RETURN0AND1 0x10 +const bool time_list_cut_frame(PointType &x, PointType &y) { + return (x.curvature < y.curvature); +} + Preprocess::Preprocess() - :feature_enabled(0), lidar_type(AVIA), blind(0.01), point_filter_num(1) + :lidar_type(AVIA), blind(0.01), point_filter_num(1), det_range(1000) { inf_bound = 10; N_SCANS = 6; + SCAN_RATE = 10; group_size = 8; disA = 0.01; disA = 0.1; // B? @@ -34,7 +39,6 @@ Preprocess::~Preprocess() {} void Preprocess::set(bool feat_en, int lid_type, double bld, int pfilt_num) { - feature_enabled = feat_en; lidar_type = lid_type; blind = bld; point_filter_num = pfilt_num; @@ -48,6 +52,25 @@ void Preprocess::process(const livox_ros_driver2::CustomMsg::ConstPtr &msg, Poin void Preprocess::process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out) { + switch (time_unit) + { + case SEC: + time_unit_scale = 1.e3f; + break; + case MS: + time_unit_scale = 1.f; + break; + case US: + time_unit_scale = 1.e-3f; + break; + case NS: + time_unit_scale = 1.e-6f; + break; + default: + time_unit_scale = 1.f; + break; + } + switch (lidar_type) { case OUST64: @@ -58,6 +81,10 @@ void Preprocess::process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointClo velodyne_handler(msg); break; + case HESAIxt32: + hesai_handler(msg); + break; + default: printf("Error LiDAR Type"); break; @@ -65,6 +92,227 @@ void Preprocess::process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointClo *pcl_out = pl_surf; } +void Preprocess::process_cut_frame_livox(const livox_ros_driver2::CustomMsg::ConstPtr &msg, + deque &pcl_out, deque &time_lidar, + const int required_frame_num, int scan_count) { + int plsize = msg->point_num; + pl_surf.clear(); + pl_surf.reserve(plsize); + pl_full.clear(); + pl_full.resize(plsize); + int valid_point_num = 0; + + for (uint i = 1; i < plsize; i++) { + if ((msg->points[i].line < N_SCANS) && + ((msg->points[i].tag & 0x30) == 0x10 || (msg->points[i].tag & 0x30) == 0x00)) + { + valid_point_num++; + if (valid_point_num % point_filter_num == 0) { + pl_full[i].x = msg->points[i].x; + pl_full[i].y = msg->points[i].y; + pl_full[i].z = msg->points[i].z; + pl_full[i].intensity = msg->points[i].reflectivity; + //use curvature as time of each laser points,unit: ms + pl_full[i].curvature = msg->points[i].offset_time / float(1000000); + + double dist = pl_full[i].x * pl_full[i].x + pl_full[i].y * pl_full[i].y + pl_full[i].z * pl_full[i].z; + if (dist < blind * blind || dist > det_range * det_range) continue; + + if ((abs(pl_full[i].x - pl_full[i - 1].x) > 1e-7) + || (abs(pl_full[i].y - pl_full[i - 1].y) > 1e-7) + || (abs(pl_full[i].z - pl_full[i - 1].z) > 1e-7)) { + pl_surf.push_back(pl_full[i]); + } + } + } + } + sort(pl_surf.points.begin(), pl_surf.points.end(), time_list_cut_frame); + //end time of last frame,单位ms + double last_frame_end_time = msg->header.stamp.toSec() * 1000; + uint valid_num = 0; + uint cut_num = 0; + uint valid_pcl_size = pl_surf.points.size(); + + int required_cut_num = required_frame_num; + if (scan_count < 5) + required_cut_num = 1; + + PointCloudXYZI pcl_cut; + for (uint i = 1; i < valid_pcl_size; i++) { + valid_num++; + //Compute new opffset time of each point:ms + pl_surf[i].curvature += msg->header.stamp.toSec() * 1000 - last_frame_end_time; + pcl_cut.push_back(pl_surf[i]); + if (valid_num == (int((cut_num + 1) * valid_pcl_size / required_cut_num) - 1)) { + cut_num++; + time_lidar.push_back(last_frame_end_time); + PointCloudXYZI::Ptr pcl_temp(new PointCloudXYZI()); //Initialize shared_ptr + *pcl_temp = pcl_cut; + pcl_out.push_back(pcl_temp); + //Update frame head + last_frame_end_time += pl_surf[i].curvature; + pcl_cut.clear(); + pcl_cut.reserve(valid_pcl_size * 2 / required_frame_num); + } + } +} +#define MAX_LINE_NUM 128 +void +Preprocess::process_cut_frame_pcl2(const sensor_msgs::PointCloud2::ConstPtr &msg, deque &pcl_out, + deque &time_lidar, const int required_frame_num, int scan_count) { + pl_surf.clear(); + pl_corn.clear(); + pl_full.clear(); + if (lidar_type == VELO16) { + pcl::PointCloud pl_orig; + pcl::fromROSMsg(*msg, pl_orig); + int plsize = pl_orig.points.size(); + pl_surf.reserve(plsize); + + bool is_first[MAX_LINE_NUM]; + double yaw_fp[MAX_LINE_NUM] = {0}; // yaw of first scan point + double omega_l = 3.61; // scan angular velocity (deg/ms) + float yaw_last[MAX_LINE_NUM] = {0.0}; // yaw of last scan point + float time_last[MAX_LINE_NUM] = {0.0}; // last offset time + + if (pl_orig.points[plsize - 1].time > 0) { + given_offset_time = true; + } else { + cout << "Compute offset time using constant rotation model." << endl; + given_offset_time = false; + memset(is_first, true, sizeof(is_first)); + } + + for (int i = 0; i < plsize; i++) { + PointType added_pt; + added_pt.normal_x = 0; + added_pt.normal_y = 0; + added_pt.normal_z = 0; + added_pt.x = pl_orig.points[i].x; + added_pt.y = pl_orig.points[i].y; + added_pt.z = pl_orig.points[i].z; + added_pt.intensity = pl_orig.points[i].intensity; + added_pt.curvature = pl_orig.points[i].time * 1000.0; //ms + + double dist = added_pt.x * added_pt.x + added_pt.y * added_pt.y + added_pt.z * added_pt.z; + if ( dist < blind * blind || dist > det_range * det_range || isnan(added_pt.x) || isnan(added_pt.y) || isnan(added_pt.z)) + continue; + + if (!given_offset_time) { + int layer = pl_orig.points[i].ring; + double yaw_angle = atan2(added_pt.y, added_pt.x) * 57.2957; + + if (is_first[layer]) { + yaw_fp[layer] = yaw_angle; + is_first[layer] = false; + added_pt.curvature = 0.0; + yaw_last[layer] = yaw_angle; + time_last[layer] = added_pt.curvature; + continue; + } + // compute offset time + if (yaw_angle <= yaw_fp[layer]) { + added_pt.curvature = (yaw_fp[layer] - yaw_angle) / omega_l; + } else { + added_pt.curvature = (yaw_fp[layer] - yaw_angle + 360.0) / omega_l; + } + if (added_pt.curvature < time_last[layer]) added_pt.curvature += 360.0 / omega_l; + + yaw_last[layer] = yaw_angle; + time_last[layer] = added_pt.curvature; + } + + + if (i % point_filter_num == 0 && pl_orig.points[i].ring < N_SCANS) { + pl_surf.points.push_back(added_pt); + } + } + } else if (lidar_type == OUST64) { + pcl::PointCloud pl_orig; + pcl::fromROSMsg(*msg, pl_orig); + int plsize = pl_orig.points.size(); + pl_surf.reserve(plsize); + for (int i = 0; i < plsize; i++) { + PointType added_pt; + added_pt.normal_x = 0; + added_pt.normal_y = 0; + added_pt.normal_z = 0; + added_pt.x = pl_orig.points[i].x; + added_pt.y = pl_orig.points[i].y; + added_pt.z = pl_orig.points[i].z; + added_pt.intensity = pl_orig.points[i].intensity; + added_pt.curvature = pl_orig.points[i].t / 1e6; //ns to ms + + double dist = added_pt.x * added_pt.x + added_pt.y * added_pt.y + added_pt.z * added_pt.z; + if ( dist < blind * blind || dist > det_range * det_range || isnan(added_pt.x) || isnan(added_pt.y) || isnan(added_pt.z)) + continue; + + if (i % point_filter_num == 0 && pl_orig.points[i].ring < N_SCANS) { + pl_surf.points.push_back(added_pt); + } + } + } else if(lidar_type == HESAIxt32) { + pcl::PointCloud pl_orig; + pcl::fromROSMsg(*msg, pl_orig); + int plsize = pl_orig.points.size(); + pl_surf.reserve(plsize); + for (int i = 0; i < plsize; i++) { + PointType added_pt; + added_pt.normal_x = 0; + added_pt.normal_y = 0; + added_pt.normal_z = 0; + added_pt.x = pl_orig.points[i].x; + added_pt.y = pl_orig.points[i].y; + added_pt.z = pl_orig.points[i].z; + added_pt.intensity = pl_orig.points[i].intensity; + added_pt.curvature = (pl_orig.points[i].timestamp - msg->header.stamp.toSec()) * 1000; //s to ms + + double dist = added_pt.x * added_pt.x + added_pt.y * added_pt.y + added_pt.z * added_pt.z; + if ( dist < blind * blind || dist > det_range * det_range || isnan(added_pt.x) || isnan(added_pt.y) || isnan(added_pt.z)) + continue; + + if (i % point_filter_num == 0 && pl_orig.points[i].ring < N_SCANS) { + pl_surf.points.push_back(added_pt); + } + } + }else{ + cout << "Wrong LiDAR Type!!!" << endl; + return; + } + + sort(pl_surf.points.begin(), pl_surf.points.end(), time_list_cut_frame); + + //ms + double last_frame_end_time = msg->header.stamp.toSec() * 1000; + uint valid_num = 0; + uint cut_num = 0; + uint valid_pcl_size = pl_surf.points.size(); + + int required_cut_num = required_frame_num; + + if (scan_count < 20) + required_cut_num = 1; + + + PointCloudXYZI pcl_cut; + for (uint i = 1; i < valid_pcl_size; i++) { + valid_num++; + pl_surf[i].curvature += msg->header.stamp.toSec() * 1000 - last_frame_end_time; + pcl_cut.push_back(pl_surf[i]); + + if (valid_num == (int((cut_num + 1) * valid_pcl_size / required_cut_num) - 1)) { + cut_num++; + time_lidar.push_back(last_frame_end_time); + PointCloudXYZI::Ptr pcl_temp(new PointCloudXYZI()); + *pcl_temp = pcl_cut; + pcl_out.push_back(pcl_temp); + last_frame_end_time += pl_surf[i].curvature; + pcl_cut.clear(); + pcl_cut.reserve(valid_pcl_size * 2 / required_frame_num); + } + } +} + void Preprocess::avia_handler(const livox_ros_driver2::CustomMsg::ConstPtr &msg) { pl_surf.clear(); @@ -72,7 +320,6 @@ void Preprocess::avia_handler(const livox_ros_driver2::CustomMsg::ConstPtr &msg) pl_full.clear(); double t1 = omp_get_wtime(); int plsize = msg->point_num; - // cout<<"plsie: "<points[i].line < N_SCANS) && ((msg->points[i].tag & 0x30) == 0x10 || (msg->points[i].tag & 0x30) == 0x00)) { - if((msg->points[i].line < N_SCANS) && ((msg->points[i].tag & 0x30) == 0x10 || (msg->points[i].tag & 0x30) == 0x00)) + valid_num ++; + if (valid_num % point_filter_num == 0) { pl_full[i].x = msg->points[i].x; pl_full[i].y = msg->points[i].y; pl_full[i].z = msg->points[i].z; - pl_full[i].intensity = msg->points[i].reflectivity; - pl_full[i].curvature = msg->points[i].offset_time / float(1000000); //use curvature as time of each laser points - - bool is_new = false; - if((abs(pl_full[i].x - pl_full[i-1].x) > 1e-7) + pl_full[i].intensity = msg->points[i].reflectivity; // z; // + pl_full[i].curvature = msg->points[i].offset_time / float(1000000); // use curvature as time of each laser points, curvature unit: ms + double dist = pl_full[i].x * pl_full[i].x + pl_full[i].y * pl_full[i].y + pl_full[i].z * pl_full[i].z; + if (dist < blind * blind || dist > det_range * det_range) continue; + if(((abs(pl_full[i].x - pl_full[i-1].x) > 1e-7) || (abs(pl_full[i].y - pl_full[i-1].y) > 1e-7) - || (abs(pl_full[i].z - pl_full[i-1].z) > 1e-7)) + || (abs(pl_full[i].z - pl_full[i-1].z) > 1e-7))) { - pl_buff[msg->points[i].line].push_back(pl_full[i]); + pl_surf.push_back(pl_full[i]); } } } - static int count = 0; - static double time = 0.0; - count ++; - double t0 = omp_get_wtime(); - for(int j=0; j &pl = pl_buff[j]; - plsize = pl.size(); - vector &types = typess[j]; - types.clear(); - types.resize(plsize); - plsize--; - for(uint i=0; ipoints[i].line < N_SCANS) && ((msg->points[i].tag & 0x30) == 0x10 || (msg->points[i].tag & 0x30) == 0x00)) - { - valid_num ++; - if (valid_num % point_filter_num == 0) - { - pl_full[i].x = msg->points[i].x; - pl_full[i].y = msg->points[i].y; - pl_full[i].z = msg->points[i].z; - pl_full[i].intensity = msg->points[i].reflectivity; - pl_full[i].curvature = msg->points[i].offset_time / float(1000000); //use curvature as time of each laser points - if((abs(pl_full[i].x - pl_full[i-1].x) > 1e-7) - || (abs(pl_full[i].y - pl_full[i-1].y) > 1e-7) - || (abs(pl_full[i].z - pl_full[i-1].z) > 1e-7) - && (pl_full[i].x * pl_full[i].x + pl_full[i].y * pl_full[i].y > blind)) - { - if(pl_full[i].x * pl_full[i].x + pl_full[i].y * pl_full[i].y < max_scan_range * max_scan_range){ - pl_surf.push_back(pl_full[i]); - } -// pl_surf.push_back(pl_full[i]); - } - } - } - } - } } void Preprocess::oust64_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) @@ -175,93 +369,33 @@ void Preprocess::oust64_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) int plsize = pl_orig.size(); pl_corn.reserve(plsize); pl_surf.reserve(plsize); - if (feature_enabled) + + + double time_stamp = msg->header.stamp.toSec(); + // cout << "===================================" << endl; + // printf("Pt size = %d, N_SCANS = %d\r\n", plsize, N_SCANS); + for (int i = 0; i < pl_orig.points.size(); i++) { - for (int i = 0; i < N_SCANS; i++) - { - pl_buff[i].clear(); - pl_buff[i].reserve(plsize); - } + if (i % point_filter_num != 0) continue; - for (uint i = 0; i < plsize; i++) - { - double range = pl_orig.points[i].x * pl_orig.points[i].x + pl_orig.points[i].y * pl_orig.points[i].y + pl_orig.points[i].z * pl_orig.points[i].z; - if (range < blind) continue; - Eigen::Vector3d pt_vec; - PointType added_pt; - added_pt.x = pl_orig.points[i].x; - added_pt.y = pl_orig.points[i].y; - added_pt.z = pl_orig.points[i].z; - added_pt.intensity = pl_orig.points[i].intensity; - added_pt.normal_x = 0; - added_pt.normal_y = 0; - added_pt.normal_z = 0; - double yaw_angle = atan2(added_pt.y, added_pt.x) * 57.3; - if (yaw_angle >= 180.0) - yaw_angle -= 360.0; - if (yaw_angle <= -180.0) - yaw_angle += 360.0; + double range = pl_orig.points[i].x * pl_orig.points[i].x + pl_orig.points[i].y * pl_orig.points[i].y + pl_orig.points[i].z * pl_orig.points[i].z; + + if (range < (blind * blind) || range > det_range * det_range || isnan(pl_orig.points[i].x) || isnan(pl_orig.points[i].y) || isnan(pl_orig.points[i].z)) continue; + + Eigen::Vector3d pt_vec; + PointType added_pt; + added_pt.x = pl_orig.points[i].x; + added_pt.y = pl_orig.points[i].y; + added_pt.z = pl_orig.points[i].z; + added_pt.intensity = pl_orig.points[i].intensity; + added_pt.normal_x = 0; + added_pt.normal_y = 0; + added_pt.normal_z = 0; + added_pt.curvature = pl_orig.points[i].t * time_unit_scale; // curvature unit: ms - added_pt.curvature = pl_orig.points[i].t / 1e6; - if(pl_orig.points[i].ring < N_SCANS) - { - pl_buff[pl_orig.points[i].ring].push_back(added_pt); - } - } - - for (int j = 0; j < N_SCANS; j++) - { - PointCloudXYZI &pl = pl_buff[j]; - int linesize = pl.size(); - vector &types = typess[j]; - types.clear(); - types.resize(linesize); - linesize--; - for (uint i = 0; i < linesize; i++) - { - types[i].range = sqrt(pl[i].x * pl[i].x + pl[i].y * pl[i].y); - vx = pl[i].x - pl[i + 1].x; - vy = pl[i].y - pl[i + 1].y; - vz = pl[i].z - pl[i + 1].z; - types[i].dista = vx * vx + vy * vy + vz * vz; - } - types[linesize].range = sqrt(pl[linesize].x * pl[linesize].x + pl[linesize].y * pl[linesize].y); - give_feature(pl, types); - } - } - else - { - double time_stamp = msg->header.stamp.toSec(); - // cout << "===================================" << endl; - // printf("Pt size = %d, N_SCANS = %d\r\n", plsize, N_SCANS); - for (int i = 0; i < pl_orig.points.size(); i++) - { - if (i % point_filter_num != 0) continue; - - double range = pl_orig.points[i].x * pl_orig.points[i].x + pl_orig.points[i].y * pl_orig.points[i].y + pl_orig.points[i].z * pl_orig.points[i].z; - - if (range < blind) continue; - - Eigen::Vector3d pt_vec; - PointType added_pt; - added_pt.x = pl_orig.points[i].x; - added_pt.y = pl_orig.points[i].y; - added_pt.z = pl_orig.points[i].z; - added_pt.intensity = pl_orig.points[i].intensity; - added_pt.normal_x = 0; - added_pt.normal_y = 0; - added_pt.normal_z = 0; - double yaw_angle = atan2(added_pt.y, added_pt.x) * 57.3; - if (yaw_angle >= 180.0) - yaw_angle -= 360.0; - if (yaw_angle <= -180.0) - yaw_angle += 360.0; - - added_pt.curvature = pl_orig.points[i].t / 1e6; - - pl_surf.points.push_back(added_pt); - } + pl_surf.points.push_back(added_pt); } + // pub_func(pl_surf, pub_full, msg->header.stamp); // pub_func(pl_surf, pub_corn, msg->header.stamp); } @@ -275,10 +409,11 @@ void Preprocess::velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) pcl::PointCloud pl_orig; pcl::fromROSMsg(*msg, pl_orig); int plsize = pl_orig.points.size(); + if (plsize == 0) return; pl_surf.reserve(plsize); - + /*** These variables only works when no point timestamps given ***/ - double omega_l=3.61; // scan angular velocity + double omega_l = 0.361 * SCAN_RATE; // scan angular velocity std::vector is_first(N_SCANS,true); std::vector yaw_fp(N_SCANS, 0.0); // yaw of first scan point std::vector yaw_last(N_SCANS, 0.0); // yaw of last scan point @@ -290,6 +425,111 @@ void Preprocess::velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) given_offset_time = true; } else + { + given_offset_time = false; + // double yaw_first = atan2(pl_orig.points[0].y, pl_orig.points[0].x) * 57.29578; + // double yaw_end = yaw_first; + // int layer_first = pl_orig.points[0].ring; + // for (uint i = plsize - 1; i > 0; i--) + // { + // if (pl_orig.points[i].ring == layer_first) + // { + // yaw_end = atan2(pl_orig.points[i].y, pl_orig.points[i].x) * 57.29578; + // break; + // } + // } + } + + for (int i = 0; i < plsize; i++) + { + PointType added_pt; + // cout<<"!!!!!!"< (blind * blind) + && dist < (det_range * det_range)) + { + pl_surf.points.push_back(added_pt); + } + } + } + +} + +void Preprocess::hesai_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) +{ + pl_surf.clear(); + pl_corn.clear(); + pl_full.clear(); + + pcl::PointCloud pl_orig; + pcl::fromROSMsg(*msg, pl_orig); + int plsize = pl_orig.points.size(); + if (plsize == 0) return; + pl_surf.reserve(plsize); + + /*** These variables only works when no point timestamps given ***/ + double omega_l = 0.361 * SCAN_RATE; // scan angular velocity + std::vector is_first(N_SCANS,true); + std::vector yaw_fp(N_SCANS, 0.0); // yaw of first scan point + std::vector yaw_last(N_SCANS, 0.0); // yaw of last scan point + std::vector time_last(N_SCANS, 0.0); // last offset time + /*****************************************************************/ + + if (pl_orig.points[plsize - 1].timestamp > 0) + { + given_offset_time = true; + } + else { given_offset_time = false; double yaw_first = atan2(pl_orig.points[0].y, pl_orig.points[0].x) * 57.29578; @@ -305,138 +545,63 @@ void Preprocess::velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) } } - if(feature_enabled) + double time_head = pl_orig.points[0].timestamp; + + for (int i = 0; i < plsize; i++) { - for (int i = 0; i < N_SCANS; i++) - { - pl_buff[i].clear(); - pl_buff[i].reserve(plsize); - } + PointType added_pt; + // cout<<"!!!!!!"<= N_SCANS) continue; - added_pt.x = pl_orig.points[i].x; - added_pt.y = pl_orig.points[i].y; - added_pt.z = pl_orig.points[i].z; - added_pt.intensity = pl_orig.points[i].intensity; - added_pt.curvature = pl_orig.points[i].time / 1000.0; // units: ms + int layer = pl_orig.points[i].ring; + double yaw_angle = atan2(added_pt.y, added_pt.x) * 57.2957; - if (!given_offset_time) + if (is_first[layer]) { - double yaw_angle = atan2(added_pt.y, added_pt.x) * 57.2957; - if (is_first[layer]) - { - // printf("layer: %d; is first: %d", layer, is_first[layer]); - yaw_fp[layer]=yaw_angle; - is_first[layer]=false; - added_pt.curvature = 0.0; - yaw_last[layer]=yaw_angle; - time_last[layer]=added_pt.curvature; - continue; - } - - if (yaw_angle <= yaw_fp[layer]) - { - added_pt.curvature = (yaw_fp[layer]-yaw_angle) / omega_l; - } - else - { - added_pt.curvature = (yaw_fp[layer]-yaw_angle+360.0) / omega_l; - } - - if (added_pt.curvature < time_last[layer]) added_pt.curvature+=360.0/omega_l; - - yaw_last[layer] = yaw_angle; - time_last[layer]=added_pt.curvature; + // printf("layer: %d; is first: %d", layer, is_first[layer]); + yaw_fp[layer]=yaw_angle; + is_first[layer]=false; + added_pt.curvature = 0.0; + yaw_last[layer]=yaw_angle; + time_last[layer]=added_pt.curvature; + continue; } - pl_buff[layer].points.push_back(added_pt); + // compute offset time + if (yaw_angle <= yaw_fp[layer]) + { + added_pt.curvature = (yaw_fp[layer]-yaw_angle) / omega_l; + } + else + { + added_pt.curvature = (yaw_fp[layer]-yaw_angle+360.0) / omega_l; + } + + if (added_pt.curvature < time_last[layer]) added_pt.curvature+=360.0/omega_l; + + yaw_last[layer] = yaw_angle; + time_last[layer]=added_pt.curvature; } - for (int j = 0; j < N_SCANS; j++) + if (i % point_filter_num == 0 && !std::isnan(added_pt.x) && !std::isnan(added_pt.y) && !std::isnan(added_pt.z)) { - PointCloudXYZI &pl = pl_buff[j]; - int linesize = pl.size(); - if (linesize < 2) continue; - vector &types = typess[j]; - types.clear(); - types.resize(linesize); - linesize--; - for (uint i = 0; i < linesize; i++) + if(added_pt.x*added_pt.x+added_pt.y*added_pt.y+added_pt.z*added_pt.z > (blind * blind) + &&added_pt.x*added_pt.x+added_pt.y*added_pt.y+added_pt.z*added_pt.z < (det_range * det_range)) { - types[i].range = sqrt(pl[i].x * pl[i].x + pl[i].y * pl[i].y); - vx = pl[i].x - pl[i + 1].x; - vy = pl[i].y - pl[i + 1].y; - vz = pl[i].z - pl[i + 1].z; - types[i].dista = vx * vx + vy * vy + vz * vz; - } - types[linesize].range = sqrt(pl[linesize].x * pl[linesize].x + pl[linesize].y * pl[linesize].y); - give_feature(pl, types); - } - } - else - { - for (int i = 0; i < plsize; i++) - { - PointType added_pt; - // cout<<"!!!!!!"< blind) - { - pl_surf.points.push_back(added_pt); - } + pl_surf.points.push_back(added_pt); } } } + } void Preprocess::give_feature(pcl::PointCloud &pl, vector &types) @@ -513,52 +678,6 @@ void Preprocess::give_feature(pcl::PointCloud &pl, vector &t i = i_nex; last_state = 0; } - // else if(plane_type == 0) - // { - // if(last_state == 1) - // { - // uint i_nex_tem; - // uint j; - // for(j=last_i+1; j<=last_i_nex; j++) - // { - // uint i_nex_tem2 = i_nex_tem; - // Eigen::Vector3d curr_direct2; - - // uint ttem = plane_judge(pl, types, j, i_nex_tem, curr_direct2); - - // if(ttem != 1) - // { - // i_nex_tem = i_nex_tem2; - // break; - // } - // curr_direct = curr_direct2; - // } - - // if(j == last_i+1) - // { - // last_state = 0; - // } - // else - // { - // for(uint k=last_i_nex; k<=i_nex_tem; k++) - // { - // if(k != i_nex_tem) - // { - // types[k].ftype = Real_Plane; - // } - // else - // { - // types[k].ftype = Poss_Plane; - // } - // } - // i = i_nex_tem-1; - // i_nex = i_nex_tem; - // i2 = j-1; - // last_state = 1; - // } - - // } - // } last_i = i2; last_i_nex = i_nex; diff --git a/src/FAST_LIO_LOCALIZATION/src/preprocess.h b/src/FAST_LIO_LOCALIZATION/src/preprocess.h old mode 100644 new mode 100755 index 5f0da48..a5e2e18 --- a/src/FAST_LIO_LOCALIZATION/src/preprocess.h +++ b/src/FAST_LIO_LOCALIZATION/src/preprocess.h @@ -10,11 +10,14 @@ using namespace std; typedef pcl::PointXYZINormal PointType; typedef pcl::PointCloud PointCloudXYZI; -enum LID_TYPE{AVIA = 1, VELO16, OUST64}; //{1, 2, 3} +enum LID_TYPE{AVIA = 1, VELO16, OUST64, HESAIxt32}; //{1, 2, 3, 4} +enum TIME_UNIT{SEC = 0, MS = 1, US = 2, NS = 3}; enum Feature{Nor, Poss_Plane, Real_Plane, Edge_Jump, Edge_Plane, Wire, ZeroPoint}; enum Surround{Prev, Next}; enum E_jump{Nr_nor, Nr_zero, Nr_180, Nr_inf, Nr_blind}; +const bool time_list_cut_frame(PointType &x, PointType &y); + struct orgtype { double range; @@ -48,7 +51,25 @@ POINT_CLOUD_REGISTER_POINT_STRUCT(velodyne_ros::Point, (float, z, z) (float, intensity, intensity) (float, time, time) - (uint16_t, ring, ring) + (std::uint16_t, ring, ring) +) + +namespace hesai_ros { + struct EIGEN_ALIGN16 Point { + PCL_ADD_POINT4D; + float intensity; + double timestamp; + uint16_t ring; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; +} // namespace velodyne_ros +POINT_CLOUD_REGISTER_POINT_STRUCT(hesai_ros::Point, + (float, x, x) + (float, y, y) + (float, z, z) + (float, intensity, intensity) + (double, timestamp, timestamp) + (std::uint16_t, ring, ring) ) namespace ouster_ros { @@ -86,6 +107,10 @@ class Preprocess Preprocess(); ~Preprocess(); + void process_cut_frame_livox(const livox_ros_driver2::CustomMsg::ConstPtr &msg, deque &pcl_out, deque &time_lidar, const int required_frame_num, int scan_count); + + void process_cut_frame_pcl2(const sensor_msgs::PointCloud2::ConstPtr &msg, deque &pcl_out, deque &time_lidar, const int required_frame_num, int scan_count); + void process(const livox_ros_driver2::CustomMsg::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out); void process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out); void set(bool feat_en, int lid_type, double bld, int pfilt_num); @@ -94,10 +119,10 @@ class Preprocess PointCloudXYZI pl_full, pl_corn, pl_surf; PointCloudXYZI pl_buff[128]; //maximum 128 line lidar vector typess[128]; //maximum 128 line lidar - int lidar_type, point_filter_num, N_SCANS;; - double blind; - double max_scan_range; - bool feature_enabled, given_offset_time; + float time_unit_scale; + int lidar_type, point_filter_num, N_SCANS, SCAN_RATE, time_unit; + double blind, det_range; + bool given_offset_time; ros::Publisher pub_full, pub_surf, pub_corn; @@ -105,6 +130,7 @@ class Preprocess void avia_handler(const livox_ros_driver2::CustomMsg::ConstPtr &msg); void oust64_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); void velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); + void hesai_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); void give_feature(PointCloudXYZI &pl, vector &types); void pub_func(PointCloudXYZI &pl, const ros::Time &ct); int plane_judge(const PointCloudXYZI &pl, vector &types, uint i, uint &i_nex, Eigen::Vector3d &curr_direct); diff --git a/src/FAST_LIO_LOCALIZATION/src/send.cpp b/src/FAST_LIO_LOCALIZATION/src/send.cpp new file mode 100755 index 0000000..cac00fd --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/send.cpp @@ -0,0 +1,195 @@ +#include +#include +#include +#include +#include + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "send_pose"); + ros::NodeHandle nh; + + // 创建预定义目标点列表 + std::vector pose_list(100); + + // 初始化默认坐标点 + // 点1:原点 + + // 点2:前进1米 + + pose_list[0].x =-3.9140;//-4.657,-4.660 4.662,4.644,4.657 + pose_list[0].y =-5.9587;//-5.948,-5.957,-5.968,-5.965,-5.957 + pose_list[0].angle =-1.741; + pose_list[0].max_speed = 5.0; + pose_list[0].tolerance = 0.00; + pose_list[0].rotor = 0.0; + pose_list[0].circle = -1; + + pose_list[1].x =-3.9140;//-4.657,-4.660 4.662,4.644,4.657 + pose_list[1].y =-5.9587;//-5.948,-5.957,-5.968,-5.965,-5.957 + pose_list[1].angle =-1.741; + pose_list[1].max_speed = 5.0; + pose_list[1].tolerance = 0.00; + pose_list[1].rotor = 0.0; + pose_list[1].circle = 0; + // 点3:侧向移动1米,旋转90度 + + pose_list[2].y =-1.0; + pose_list[2].angle =0 ; + pose_list[2].max_speed = 8.0; + pose_list[2].tolerance = 0.00; + pose_list[2].rotor = 0.0; + pose_list[2].circle = 0.0; + + + + pose_list[3].x=-3.914; + pose_list[3].y=-5.9587; + pose_list[3].angle =0 ; + pose_list[3].max_speed = 4.0; + pose_list[3].tolerance = 0.00; + pose_list[3].rotor = 0.0; + pose_list[3].circle = 3.5; + + pose_list[4].x=-3.914; + pose_list[4].y=-5.9587; + pose_list[4].angle =0; + pose_list[4].max_speed = 4.0; + pose_list[4].tolerance = 0.00; + pose_list[4].rotor = 0.0; + pose_list[4].circle = 3.8; + + pose_list[5].x=-3.914; + pose_list[5].y=-5.9587; + pose_list[5].angle =0; + pose_list[5].max_speed = 4.0; + pose_list[5].tolerance = 0.00; + pose_list[5].rotor = 0.0; + pose_list[5].circle = 4; + + pose_list[6].x=-3.914; + pose_list[6].y=-5.9587; + pose_list[6].angle =0; + pose_list[6].max_speed = 4.0; + pose_list[6].tolerance = 0.0; + pose_list[6].rotor = 0.0; + pose_list[6].circle = 4.5; + + pose_list[7].x=-3.914; + pose_list[7].y=-5.9587; + pose_list[7].angle =0; + pose_list[7].max_speed = 4.0; + pose_list[7].tolerance = 0.0; + pose_list[7].rotor = 0.0; + pose_list[7].circle = 5; + + pose_list[8].x=-3.914; + pose_list[8].y=-5.9587; + pose_list[8].angle =0; + pose_list[8].max_speed = 4.0; + pose_list[8].tolerance = 0.0; + pose_list[8].rotor = 0.0; + pose_list[8].circle = 5.5; + + pose_list[9].x=-3.914; + pose_list[9].y=-5.9587; + pose_list[9].angle =-1.57 ; + pose_list[9].max_speed = 4.0; + pose_list[9].tolerance = 0.0; + pose_list[9].rotor = 0.0; + pose_list[9].circle = 6.0; + + pose_list[10].x=-3.914; + pose_list[10].y=-5.9587; + pose_list[10].angle =0; + pose_list[10].max_speed = 4.0; + pose_list[10].tolerance = 0.0; + pose_list[10].rotor = 0.0; + pose_list[10].circle = 4.2; + + pose_list[11].x=-3.914; + pose_list[11].y=-5.9587; + pose_list[11].angle =0; + pose_list[11].max_speed = 4.0; + pose_list[11].tolerance = 0.0; + pose_list[11].rotor = 0.0; + pose_list[11].circle = 4.7; + + pose_list[12].x=-3.914; + pose_list[12].y=-5.9587; + pose_list[12].angle =0; + pose_list[12].max_speed = 4.0; + pose_list[12].tolerance = 0.0; + pose_list[12].rotor = 0.0; + pose_list[12].circle = 5.2; + + pose_list[13].x=-3.914; + pose_list[13].y=-5.9587; + pose_list[13].angle =0; + pose_list[13].max_speed = 4.0; + pose_list[13].tolerance = 0.0; + pose_list[13].rotor = 0.0; + pose_list[13].circle = 5.7; + + pose_list[14].x=-3.914; + pose_list[14].y=-5.9587; + pose_list[14].angle =0; + pose_list[14].max_speed = 4.0; + pose_list[14].tolerance = 0.0; + pose_list[14].rotor = 0.0; + pose_list[14].circle = -1; + + // 参数处理 + int selected_index = 0; // 默认选择第一个点 + if(argc >= 2) + { + try { + selected_index = std::stoi(argv[1]); + if(selected_index < 0 || selected_index >= pose_list.size()) + { + ROS_WARN("Invalid index %d, using default pose 0", selected_index); + selected_index = 0; + } + } + catch(...) { + ROS_ERROR("Failed to parse index argument"); + return 1; + } + } + + ROS_INFO("Selected pose index: %d", selected_index); + + ros::Publisher pose_publisher = nh.advertise("/goal_pose", 10); + tf::TransformBroadcaster tf_broadcaster; + ros::Rate rate(10); + + const auto& goal_pose = pose_list[selected_index]; // 获取选中的目标点 + + while(ros::ok()) + { + // 发布目标位姿消息 + pose_publisher.publish(goal_pose); + + // 创建并填充坐标系变换 + geometry_msgs::TransformStamped transform; + transform.header.stamp = ros::Time::now(); + transform.header.frame_id = "map"; + transform.child_frame_id = "goal_pose"; + + transform.transform.translation.x = goal_pose.x; + transform.transform.translation.y = goal_pose.y; + transform.transform.translation.z = 0.0; + + tf::Quaternion q = tf::createQuaternionFromYaw(goal_pose.angle); + transform.transform.rotation.x = q.x(); + transform.transform.rotation.y = q.y(); + transform.transform.rotation.z = q.z(); + transform.transform.rotation.w = q.w(); + + // 广播变换 + tf_broadcaster.sendTransform(transform); + rate.sleep(); + } + + return 0; +} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/test_goal.cpp b/src/FAST_LIO_LOCALIZATION/src/test_goal.cpp new file mode 100755 index 0000000..05ce58c --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/test_goal.cpp @@ -0,0 +1,84 @@ +#include +#include +#include +#include // 关键:添加四元数转换工具 +#include +#include +#include +#include +#include + +int main(int argc, char** argv) { + ros::init(argc, argv, "fixed_goal_pose_publisher"); + ros::NodeHandle nh("~"); + + // 参数配置 + std::string car_frame = "car"; + std::string map_frame = "bash"; + nh.param("car", car_frame, "car"); + nh.param("bash", map_frame, "bash"); + + // 初始化TF监听器 + tf2_ros::Buffer tf_buffer; + tf2_ros::TransformListener tf_listener(tf_buffer); + + // 等待并获取初始位姿 + ROS_INFO("等待 %s 到 %s 的变换...", map_frame.c_str(), car_frame.c_str()); + geometry_msgs::TransformStamped transform; + try { + transform = tf_buffer.lookupTransform( + map_frame, // target frame + car_frame, // source frame + ros::Time(0), // 获取最新可用时间 + ros::Duration(10.0) // 超时时间 + ); + ROS_INFO("成功获取初始位姿!"); + } catch (tf2::TransformException &ex) { + ROS_ERROR("变换获取失败: %s", ex.what()); + return -1; + } + + // 创建静态坐标系发布器 + static tf2_ros::StaticTransformBroadcaster static_broadcaster; + geometry_msgs::TransformStamped static_transform; + static_transform.header.stamp = ros::Time::now(); + static_transform.header.frame_id = map_frame; + static_transform.child_frame_id = "/goal_pose"; + static_transform.transform = transform.transform; + static_broadcaster.sendTransform(static_transform); + + // 关键:四元数转欧拉角计算yaw + tf2::Quaternion q( + transform.transform.rotation.x, + transform.transform.rotation.y, + transform.transform.rotation.z, + transform.transform.rotation.w + ); + + double roll, pitch, yaw; + tf2::Matrix3x3(q).getRPY(roll, pitch, yaw); + + // 初始化话题发布器 + ros::Publisher pose_pub = nh.advertise("/goal_pose", 10); + + // 构建PoseStamped消息 + fast_lio_localization::GoalPose pose_msg; + pose_msg.x = transform.transform.translation.x; + pose_msg.y = transform.transform.translation.y; + pose_msg.angle = yaw; // 使用正确计算的yaw值 + pose_msg.max_speed = 4.0; + pose_msg.circle = 0.0; + pose_msg.tolerance = 0.0; + + ROS_INFO("发布目标位姿: x=%.2f, y=%.2f, yaw=%.2f rad (%.1f°)", + pose_msg.x, pose_msg.y, yaw, yaw * 180/M_PI); + + // 持续发布话题消息 + ros::Rate rate(10); // 10Hz + while (ros::ok()) { + pose_pub.publish(pose_msg); + rate.sleep(); + } + + return 0; +} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/tor1_serial.cpp b/src/FAST_LIO_LOCALIZATION/src/tor1_serial.cpp new file mode 100755 index 0000000..70afc21 --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/tor1_serial.cpp @@ -0,0 +1,87 @@ +#include +#include +#include +#include +#include +#include + +static serial::Serial ser; +static std::mutex serial_mutex; + +// 串口参数 +void serialInit() { + std::lock_guard lock(serial_mutex); + if (ser.isOpen()) ser.close(); + serial::Timeout to = serial::Timeout::simpleTimeout(100); + ser.setPort("/dev/tor1"); + ser.setBaudrate(115200); + ser.setTimeout(to); + ser.open(); + if (ser.isOpen()) { + ser.flushInput(); + ser.flushOutput(); + ROS_INFO("Serial port initialized and buffers cleared."); + } else { + ROS_ERROR("Failed to open serial port!tor1"); + } +} + + +bool read2float(bool &passball, double &x, double &y) { + std::lock_guard lock(serial_mutex); + try { + // 一帧总长度=帧头1+标志1+数据8+帧尾1=11字节 + std::string buf = ser.read(12); + std::cout << "buf(hex): "; +for (size_t i = 0; i < buf.size(); ++i) { + printf("%02X ", static_cast(buf[i])); +} +std::cout << std::endl; + if (buf.size() != 12) return false; + if ((uint8_t)buf[0] != 0xFC || (uint8_t)buf[1] != 0x01 || (uint8_t)buf[11] != 0xFD) + return false; + for (size_t i = 0; i < buf.size(); ++i) { + printf("%02X ", static_cast(buf[i])); +} +std::cout << std::endl; + bool passball_f; + float x_f, y_f; + memcpy(&passball_f, &buf[2], 1); + memcpy(&x_f, &buf[3], 4); + memcpy(&y_f, &buf[7], 4); + passball = bool(passball_f); + x=double(x_f); + y=double(y_f); + return true; + } catch (...) { + return false; + } +} + +fast_lio_localization::position sub_position; + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "tor1_serial_node"); + ros::NodeHandle nh; + serialInit(); + double x, y; + bool passball; + ros::Publisher pub_pos = nh.advertise("/position", 1000); + while (ros::ok()) { + + if (read2float(passball ,x , y)) { + sub_position.passball = passball; + sub_position.x = x; + sub_position.y = y; + pub_pos.publish(sub_position); + ROS_INFO("pass: %d,Dian: %f, Passball: %f",int(passball),x, y); + } else { + sub_position.passball = false; + sub_position.x = 0.0; + sub_position.y = 0.0; + pub_pos.publish(sub_position); + ROS_INFO("Failed to read data from serial_2 port."); + } +} +} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/uart.cpp b/src/FAST_LIO_LOCALIZATION/src/uart.cpp new file mode 100755 index 0000000..01e9887 --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/uart.cpp @@ -0,0 +1,180 @@ +#include +#include +#include +#include +#include +#include +#include // 文件控制定义 +#include // UNIX标准函数定义 +#include // POSIX终端控制定义 +#include // 字符串操作函数 +#include +#include +#include +#include +#include +class SerialNode +{ +public: + SerialNode() + { + ros::NodeHandle nh; + offsets_sub_ = nh.subscribe("/chassis/data_ai", 1000, &SerialNode::xyyawCallback, this); + + // 打开串口 + serial_fd_ = openSerialPort("/dev/r2self", B115200); + if (serial_fd_ == -1) { + ROS_ERROR("Failed to open serial port!"); + } + } + + ~SerialNode() + { + if (serial_fd_ != -1) { + close(serial_fd_); + } + } + +private: + int openSerialPort(const char* port, int baudRate) + { + // 打开串口设备 + int fd = open(port, O_RDWR | O_NOCTTY | O_NDELAY); + if (fd == -1) { + ROS_ERROR_STREAM("Unable to open serial port: " << port); + return -1; + } + + // 配置串口参数 + struct termios tty; + memset(&tty, 0, sizeof(tty)); + + // 获取当前串口配置 + if (tcgetattr(fd, &tty) != 0) { + ROS_ERROR_STREAM("Failed to get serial port attributes"); + close(fd); + return -1; + } + + // 设置波特率 + cfsetospeed(&tty, baudRate); + cfsetispeed(&tty, baudRate); + + // 设置数据位为8位 + tty.c_cflag &= ~CSIZE; + tty.c_cflag |= CS8; + + // 关闭奇偶校验 + tty.c_cflag &= ~PARENB; + + // 设置停止位为1位 + tty.c_cflag &= ~CSTOPB; + + // 禁用硬件流控制 + tty.c_cflag &= ~CRTSCTS; + + // 启用接收和本地模式 + tty.c_cflag |= CREAD | CLOCAL; + + // 禁用规范输入处理 + tty.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); + + // 禁用软件流控制 + tty.c_iflag &= ~(IXON | IXOFF | IXANY); + + // 禁用输出处理 + tty.c_oflag &= ~OPOST; + + // 设置最小字符数和超时时间 + tty.c_cc[VMIN] = 1; // 至少读取1个字符 + tty.c_cc[VTIME] = 10; // 超时时间为1秒 + + // 应用配置 + if (tcsetattr(fd, TCSANOW, &tty) != 0) { + ROS_ERROR_STREAM("Failed to set serial port attributes"); + close(fd); + return -1; + } + + return fd; + } + + void xyyawCallback(const fast_lio_localization::DataAI::ConstPtr& msg) + { + // 提取第一个目标的偏移量 + float sent_x = static_cast(msg->vx); + float sent_y = static_cast(msg->vy); + float sent_yaw = static_cast(msg->yaw); + float pos = static_cast(msg->pos); + float ang = static_cast(msg->ang); + bool reach = static_cast(msg->reach); + + // 立即发送数据包 + sendDataPacket(-sent_x, -sent_y, sent_yaw, pos, ang, reach); + + } + + void sendDataPacket(float sent_x, float sent_y,float sent_yaw,float pos, float ang , bool reach) + { + ROS_INFO("Sending data packet..."); + if (serial_fd_ == -1) { + ROS_ERROR("Serial port not open!"); + return; + } + + const uint8_t start_flag = 0xFF; + const uint8_t control_frame = 0x09; + const uint8_t camera_frame = 0x01; + const uint8_t end_flag = 0xFE; + + // 转换为字节数组 + uint8_t sent_x_bytes[4]; + uint8_t sent_y_bytes[4]; + uint8_t sent_yaw_bytes[4]; + uint8_t pos_bytes[4]; + uint8_t ang_bytes[4]; + uint8_t reach_bytes[1]; + std::memcpy(sent_x_bytes, &sent_x, sizeof(sent_x)); + std::memcpy(sent_y_bytes, &sent_y, sizeof(sent_y)); + std::memcpy(sent_yaw_bytes, &sent_yaw, sizeof(sent_yaw)); + std::memcpy(pos_bytes, &pos, sizeof(pos)); + std::memcpy(ang_bytes, &ang, sizeof(ang)); + std::memcpy(reach_bytes, &reach, sizeof(reach)); + + + // 构建数据包 + std::vector data_packet; + data_packet.reserve(25); // 预分配空间优化性能 + data_packet.push_back(start_flag); + data_packet.push_back(control_frame); + data_packet.push_back(camera_frame); + data_packet.insert(data_packet.end(), sent_x_bytes, sent_x_bytes + 4); + data_packet.insert(data_packet.end(), sent_y_bytes, sent_y_bytes + 4); + data_packet.insert(data_packet.end(), sent_yaw_bytes, sent_yaw_bytes + 4); + data_packet.insert(data_packet.end(), pos_bytes, pos_bytes + 4); + data_packet.insert(data_packet.end(), ang_bytes, ang_bytes + 4); + data_packet.insert(data_packet.end(), reach_bytes, reach_bytes + 1); + data_packet.push_back(end_flag); + + // 发送数据 + write(serial_fd_, data_packet.data(), data_packet.size()); + + //ROS_INFO("Received offsets: x=%.5f, y=%.5f, yaw=%.5f", sent_x, sent_y, sent_yaw, pos, ang, reach); + // 调试输出 + //ROS_DEBUG("Sent packet: "); + for (auto byte : data_packet) { + ROS_DEBUG("%02X ", byte); + } + } + + ros::Subscriber offsets_sub_; + int serial_fd_; // 串口文件描述符 +}; + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "serial_node"); + SerialNode node; + ros::spin(); + return 0; +} \ No newline at end of file diff --git a/src/FAST_LIO_LOCALIZATION/src/underpan_serial.cpp b/src/FAST_LIO_LOCALIZATION/src/underpan_serial.cpp new file mode 100755 index 0000000..09e59be --- /dev/null +++ b/src/FAST_LIO_LOCALIZATION/src/underpan_serial.cpp @@ -0,0 +1,74 @@ +#include +#include +#include +#include +#include +#include + +static serial::Serial ser; +static std::mutex serial_mutex; + +// 串口参数 +void serialInit() { + std::lock_guard lock(serial_mutex); + if (ser.isOpen()) ser.close(); + serial::Timeout to = serial::Timeout::simpleTimeout(100); + ser.setPort("/dev/r2self"); + ser.setBaudrate(115200); + ser.setTimeout(to); + ser.open(); + if (ser.isOpen()) { + ser.flushInput(); + ser.flushOutput(); + ROS_INFO("Serial port initialized and buffers cleared."); + } else { + ROS_ERROR("Failed to open serial port! underpan"); + } +} + + +bool read5float(bool &dian) { + std::lock_guard lock(serial_mutex); + if (!ser.isOpen()) return false; + try { + // 一帧总长度=帧头1+标志1+数据8+帧尾1=11字节 + std::string buf = ser.read(7); +// std::cout << "buf(hex): "; +// for (size_t i = 0; i < buf.size(); ++i) { +// printf("%02X ", static_cast(buf[i])); +// } +// std::cout << std::endl; + if (buf.size() != 7) return false; + if ((uint8_t)buf[0] != 0xFF || (uint8_t)buf[1] != 0x01 || (uint8_t)buf[6] != 0xFE) + return false; + float dian_f; + memcpy(&dian_f, &buf[2], 4); + dian =bool(dian_f); + return true; + } catch (...) { + return false; + } +} + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "underpan_serial_node"); + ros::NodeHandle nh; + serialInit(); + ros::Publisher pub_underpan = nh.advertise("/underpan", 1000); + fast_lio_localization::underpan underpan_msg; + ros::Rate loop_rate(100); // + bool dian = false, passball = false; + while (ros::ok()) { + if (read5float(dian)) { + std_msgs::Bool dian_msg, passball_msg; + underpan_msg.dian = dian; + underpan_msg.passball = passball; + pub_underpan.publish(underpan_msg); + ROS_INFO("Dian: %d, Passball: %d", dian, passball); + } else { + // ROS_INFO("Failed to read data from serial port."); +} +loop_rate.sleep(); +} +} \ No newline at end of file diff --git a/src/Livox-SDK2 b/src/Livox-SDK2 new file mode 160000 index 0000000..6a94015 --- /dev/null +++ b/src/Livox-SDK2 @@ -0,0 +1 @@ +Subproject commit 6a940156dd7151c3ab6a52442d86bc83613bd11b diff --git a/src/Point-LIO b/src/Point-LIO new file mode 160000 index 0000000..97b0042 --- /dev/null +++ b/src/Point-LIO @@ -0,0 +1 @@ +Subproject commit 97b0042e397ec71c327966abebff9b4b7e2c154a diff --git a/src/livox_ros_driver2/config/MID360_config.json b/src/livox_ros_driver2/config/MID360_config.json index 2d659c8..b3d2f0f 100644 --- a/src/livox_ros_driver2/config/MID360_config.json +++ b/src/livox_ros_driver2/config/MID360_config.json @@ -24,7 +24,7 @@ } }, "lidar_configs" : [ - { + { "ip" : "192.168.1.176", "pcl_data_type" : 1, "pattern_mode" : 0, @@ -34,7 +34,7 @@ "yaw": 0.0, "x": 0, "y": 0, - "z": 0 + "z": 0.0 } } ] diff --git a/src/livox_ros_driver2/launch_ROS1/msg_MID360.launch b/src/livox_ros_driver2/launch_ROS1/msg_MID360.launch index 1e08745..4fd04e3 100644 --- a/src/livox_ros_driver2/launch_ROS1/msg_MID360.launch +++ b/src/livox_ros_driver2/launch_ROS1/msg_MID360.launch @@ -1,5 +1,4 @@ - @@ -30,11 +29,12 @@ + args="$(arg cmdline_arg)" + output="screen"/> - + - + \ No newline at end of file diff --git a/src/pcd2pgm/launch/run.launch b/src/pcd2pgm/launch/run.launch index 6371265..d841534 100755 --- a/src/pcd2pgm/launch/run.launch +++ b/src/pcd2pgm/launch/run.launch @@ -2,11 +2,11 @@ - +i - + - + diff --git a/src/pcd2pgm/src/pcd2pgm.cpp b/src/pcd2pgm/src/pcd2pgm.cpp index 3ebb0eb..db2c5c1 100644 --- a/src/pcd2pgm/src/pcd2pgm.cpp +++ b/src/pcd2pgm/src/pcd2pgm.cpp @@ -24,8 +24,8 @@ const std::string pcd_format = ".pcd"; nav_msgs::OccupancyGrid map_topic_msg; //最小和最大高度 -double thre_z_min = 0.3; -double thre_z_max = 2.0; +double thre_z_min = 0.05; +double thre_z_max = 0.1; int flag_pass_through = 0; double map_resolution = 0.05; double thre_radius = 0.1; @@ -64,8 +64,8 @@ int main(int argc, char **argv) { pcd_file = file_directory + file_name + pcd_format; - private_nh.param("thre_z_min", thre_z_min, 0.2); - private_nh.param("thre_z_max", thre_z_max, 2.0); + private_nh.param("thre_z_min", thre_z_min, 0.05); + private_nh.param("thre_z_max", thre_z_max, 0.1); private_nh.param("flag_pass_through", flag_pass_through, 0); private_nh.param("thre_radius", thre_radius, 0.5); private_nh.param("map_resolution", map_resolution, 0.05);