From 607108f7a13df4731e771121584350857b0604af Mon Sep 17 00:00:00 2001 From: rostest Date: Wed, 1 Mar 2023 12:04:48 +0100 Subject: [PATCH] v5.5.2: Support for message type 7, improved source id and documentation * Support for message type 7 * Configuration and support for message specific source ID * Improved transform messages * Improved documentation * Renaming and cleanup --- .gitignore | 2 + CMakeLists.txt | 18 +- README.md | 48 ++- doc/cpp_api.md | 27 +- doc/{sim_messages.md => lls_messages.md} | 69 ++-- .../rviz_pointcloud_converter_screenshot2.png | Bin 0 -> 146985 bytes doc/sequenceDiagramROSUDPMessages.png | Bin 0 -> 67947 bytes doc/sequenceDiagramROSUDPMessages.txt | 20 + doc/sequenceDiagramResultTelegrams.txt | 13 + doc/sequenceDiagramSourceIdExample1.png | Bin 0 -> 41405 bytes doc/sequenceDiagramSourceIdExample1.txt | 15 + doc/sequenceDiagramSourceIdExample2.png | Bin 0 -> 15411 bytes doc/sequenceDiagramSourceIdExample2.txt | 7 + doc/sequenceDiagramSourceIdExample3.png | Bin 0 -> 15382 bytes doc/sequenceDiagramSourceIdExample3.txt | 7 + doc/sequenceDiagramSourceIdExample4.png | Bin 0 -> 15217 bytes doc/sequenceDiagramSourceIdExample4.txt | 7 + doc/sick_localization_services.md | 40 +- doc/source_id.md | 91 +++++ doc/source_id_01.png | Bin 0 -> 47584 bytes doc/source_id_02.png | Bin 0 -> 71207 bytes include/sick_lidar_localization/fifo_buffer.h | 2 +- ...pointcloud_converter.h => lls_transform.h} | 37 +- .../sick_lidar_localization.h | 32 +- .../sick_ros_wrapper.h | 8 +- .../sick_lidar_localization/sick_services.h | 10 +- .../udp_message_parser.h | 49 ++- .../udp_message_publisher.h | 6 + .../udp_receiver_thread.h | 16 +- include/sick_lidar_localization/udp_sender.h | 64 ++-- launch/lls_transform.launch | 13 + launch/pointcloud_converter.launch | 10 - launch/sick_lidar_localization.launch | 55 +-- msg/CodeMeasurementMessage0303.msg | 1 + msg/CodeMeasurementMessage0304.msg | 1 + msg/CodeMeasurementMessage0701.msg | 9 + msg/EncoderMeasurementMessage0202.msg | 1 + msg/LineMeasurementMessage0403.msg | 1 + msg/LineMeasurementMessage0404.msg | 1 + ...ocalizationControllerResultMessage0502.msg | 1 + msg/OdometryMessage0101.msg | 7 - msg/OdometryMessage0104.msg | 1 + msg/OdometryMessage0105.msg | 1 + src/gen_service_call.cpp | 8 +- ...tcloud_converter.cpp => lls_transform.cpp} | 44 ++- src/lls_transform_thread.cpp | 354 ++++++++++++++++++ src/pointcloud_converter_thread.cpp | 292 --------------- src/sick_lidar_localization.cpp | 90 +++-- src/sick_lidar_localization_main.cpp | 27 +- src/sick_services.cpp | 18 +- src/udp_message_parser.cpp | 148 ++++---- src/udp_receiver_thread.cpp | 45 +-- src/udp_sender.cpp | 165 ++++---- ...StartLocalizingSrv.srv => LocStartSrv.srv} | 6 +- ...2_sick_lidar_localization_pointcloud.rviz2 | 64 ++-- ...64_sick_lidar_localization_pointcloud.rviz | 64 ++-- ...iz_sick_lidar_localization_pointcloud.rviz | 72 ++-- .../linux_unittest_gen_sick_caller.txt | 2 +- .../win64_unittest_gen_sick_caller.txt | 2 +- test/rest_server/python/README.md | 61 +++ ..._pcapng_player.py => lls_pcapng_player.py} | 2 +- ...im_udp_receiver.py => lls_udp_receiver.py} | 28 +- .../{sim_udp_sender.py => lls_udp_sender.py} | 24 +- .../python/scripts_LLS1-OdometryUDPSender.py | 182 --------- .../python/scripts_LLS2-OdometryUDPSender.py | 122 ------ .../python/send_odometry_message_0101.py | 66 ---- .../python/send_odometry_message_0105.py | 2 +- test/rest_server/python/sick_rest_server.py | 2 +- test/scripts/make_ros2.cmd | 1 - test/scripts/run_linux_ros1_simu.bash | 49 +-- test/scripts/run_linux_ros2_simu.bash | 42 ++- test/scripts/run_linux_simu.bash | 6 +- .../run_linux_unittest_gen_sick_caller.bash | 2 +- .../run_linux_unittest_gen_sick_caller_2.bash | 2 +- .../run_linux_unittest_gen_sick_caller_3.bash | 2 +- .../scripts/run_linux_unittest_time_sync.bash | 4 +- .../run_linux_unittest_udp_receiver.bash | 12 +- test/scripts/run_win64_ros2_simu.cmd | 25 +- test/scripts/run_win64_simu.cmd | 12 +- .../run_win64_unittest_gen_sick_caller.cmd | 4 +- test/scripts/run_win64_unittest_time_sync.cmd | 4 +- .../run_win64_unittest_udp_receiver.cmd | 10 +- ...layer.cmd => simu_run_lls_pcap_player.cmd} | 2 +- ...erver.cmd => simu_run_lls_rest_server.cmd} | 0 ...=> simu_run_lls_rest_server_time_sync.cmd} | 0 ...sender.cmd => simu_run_lls_udp_sender.cmd} | 2 +- ...ages.cmd => verify_lls_input_messages.cmd} | 4 +- test/tools/python/ros_service_prep.py | 4 +- 88 files changed, 1445 insertions(+), 1322 deletions(-) rename doc/{sim_messages.md => lls_messages.md} (77%) create mode 100644 doc/screenshots/rviz_pointcloud_converter_screenshot2.png create mode 100644 doc/sequenceDiagramROSUDPMessages.png create mode 100644 doc/sequenceDiagramROSUDPMessages.txt create mode 100644 doc/sequenceDiagramResultTelegrams.txt create mode 100644 doc/sequenceDiagramSourceIdExample1.png create mode 100644 doc/sequenceDiagramSourceIdExample1.txt create mode 100644 doc/sequenceDiagramSourceIdExample2.png create mode 100644 doc/sequenceDiagramSourceIdExample2.txt create mode 100644 doc/sequenceDiagramSourceIdExample3.png create mode 100644 doc/sequenceDiagramSourceIdExample3.txt create mode 100644 doc/sequenceDiagramSourceIdExample4.png create mode 100644 doc/sequenceDiagramSourceIdExample4.txt create mode 100644 doc/source_id.md create mode 100644 doc/source_id_01.png create mode 100644 doc/source_id_02.png rename include/sick_lidar_localization/{pointcloud_converter.h => lls_transform.h} (79%) create mode 100644 launch/lls_transform.launch delete mode 100644 launch/pointcloud_converter.launch create mode 100644 msg/CodeMeasurementMessage0701.msg delete mode 100644 msg/OdometryMessage0101.msg rename src/{pointcloud_converter.cpp => lls_transform.cpp} (75%) create mode 100644 src/lls_transform_thread.cpp delete mode 100644 src/pointcloud_converter_thread.cpp rename srv/{LocStartLocalizingSrv.srv => LocStartSrv.srv} (64%) create mode 100644 test/rest_server/python/README.md rename test/rest_server/python/{sim_pcapng_player.py => lls_pcapng_player.py} (99%) rename test/rest_server/python/{sim_udp_receiver.py => lls_udp_receiver.py} (85%) rename test/rest_server/python/{sim_udp_sender.py => lls_udp_sender.py} (93%) delete mode 100644 test/rest_server/python/scripts_LLS1-OdometryUDPSender.py delete mode 100644 test/rest_server/python/scripts_LLS2-OdometryUDPSender.py delete mode 100644 test/rest_server/python/send_odometry_message_0101.py rename test/scripts/{simu_run_sim_pcap_player.cmd => simu_run_lls_pcap_player.cmd} (89%) rename test/scripts/{simu_run_sim_rest_server.cmd => simu_run_lls_rest_server.cmd} (100%) rename test/scripts/{simu_run_sim_rest_server_time_sync.cmd => simu_run_lls_rest_server_time_sync.cmd} (100%) rename test/scripts/{simu_run_sim_udp_sender.cmd => simu_run_lls_udp_sender.cmd} (90%) rename test/scripts/{verify_sim_input_messages.cmd => verify_lls_input_messages.cmd} (68%) diff --git a/.gitignore b/.gitignore index f705d6a..e313ad9 100644 --- a/.gitignore +++ b/.gitignore @@ -52,6 +52,8 @@ doc/20210726_rest_api_test.pptx doc/*_lidar_localization2.pptx test/scripts/wireshark.cmd +test/rest_server/python/scripts_LLS1-OdometryUDPSender.py +test/rest_server/python/scripts_LLS2-OdometryUDPSender.py test/data/wireshark/20210727_*.* test/data/wireshark/20210921-*.* diff --git a/CMakeLists.txt b/CMakeLists.txt index e4019a8..6cb969f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -116,24 +116,24 @@ add_executable(gen_service_call src/gen_service_call.cpp) target_link_libraries(gen_service_call sick_localization_lib ${CURL_LIBRARIES} jsoncpp_lib ${catkin_LIBRARIES}) if(ROS_VERSION GREATER 0) - add_executable(pointcloud_converter src/pointcloud_converter.cpp src/pointcloud_converter_thread.cpp) - target_link_libraries(pointcloud_converter sick_localization_lib ${CURL_LIBRARIES} jsoncpp_lib ${catkin_LIBRARIES}) + add_executable(lls_transform src/lls_transform.cpp src/lls_transform_thread.cpp) + target_link_libraries(lls_transform sick_localization_lib ${CURL_LIBRARIES} jsoncpp_lib ${catkin_LIBRARIES}) endif() if(ROS_VERSION EQUAL 1) add_dependencies(sick_localization_lib ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) add_dependencies(sick_lidar_localization_main sick_localization_lib ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) - add_dependencies(pointcloud_converter sick_localization_lib ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + add_dependencies(lls_transform sick_localization_lib ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) elseif(ROS_VERSION EQUAL 2) ament_target_dependencies(sick_localization_lib rclcpp geometry_msgs nav_msgs sensor_msgs std_msgs tf2_ros visualization_msgs) - ament_target_dependencies(pointcloud_converter rclcpp geometry_msgs nav_msgs sensor_msgs std_msgs tf2_ros visualization_msgs) + ament_target_dependencies(lls_transform rclcpp geometry_msgs nav_msgs sensor_msgs std_msgs tf2_ros visualization_msgs) if(ROS2_HUMBLE) # rosidl_typesupport for ROS2 humble or later rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp") target_link_libraries(sick_localization_lib "${cpp_typesupport_target}") - target_link_libraries(pointcloud_converter "${cpp_typesupport_target}") + target_link_libraries(lls_transform "${cpp_typesupport_target}") else() rosidl_target_interfaces(sick_localization_lib ${PROJECT_NAME} "rosidl_typesupport_cpp") - rosidl_target_interfaces(pointcloud_converter ${PROJECT_NAME} "rosidl_typesupport_cpp") + rosidl_target_interfaces(lls_transform ${PROJECT_NAME} "rosidl_typesupport_cpp") endif() else() add_dependencies(sick_lidar_localization_main sick_localization_lib) @@ -144,7 +144,7 @@ endif() ############# if(ROS_VERSION EQUAL 1) - install(TARGETS sick_localization_lib sick_lidar_localization_main gen_service_call pointcloud_converter ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(TARGETS sick_localization_lib sick_lidar_localization_main gen_service_call lls_transform ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} FILES_MATCHING PATTERN "*.h*") install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) elseif(ROS_VERSION EQUAL 2) @@ -152,8 +152,8 @@ elseif(ROS_VERSION EQUAL 2) ament_export_include_directories(include/${PROJECT_NAME}/) ament_export_libraries(sick_localization_lib sick_lidar_localization_main) ament_package() - # install(TARGETS sick_localization_lib sick_lidar_localization_main gen_service_call pointcloud_converter DESTINATION lib) - install(TARGETS sick_localization_lib sick_lidar_localization_main gen_service_call pointcloud_converter DESTINATION lib/${PROJECT_NAME}) + # install(TARGETS sick_localization_lib sick_lidar_localization_main gen_service_call lls_transform DESTINATION lib) + install(TARGETS sick_localization_lib sick_lidar_localization_main gen_service_call lls_transform DESTINATION lib/${PROJECT_NAME}) install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) else() install(DIRECTORY launch DESTINATION ${CMAKE_BINARY_DIR}) diff --git a/README.md b/README.md index 4a5699e..8d351e3 100644 --- a/README.md +++ b/README.md @@ -15,7 +15,7 @@ The drivers support the following ROS versions in the same source: ## Specification The customer requirements and the REST API specification for the implementation of the project: --[specification](doc/specifications/README.md) +[specification](doc/specifications/README.md) ## Build on native Linux @@ -210,8 +210,8 @@ Common parameters are: |--------------------|-------------------|--------------------|-------------|-----------------| | hostname | 192.168.0.1 | string | hostname:=192.168.0.1 | IP address of the SIM localization controller | | verbose | 0 | int | verbose:=1 | Print informational messages (verbose>0, otherwise error messages only) | -| udp_ip_sim_output | "" | string | udp_ip_sim_output:=192.168.0.100 | IP address of your local machine (i.e. the receiver of UDP stream messages) | -| udp_ip_sim_input | 192.168.0.1 | string | udp_ip_sim_input:=192.168.0.1 | IP address of host to send input UDP messages to, should be identical to hostname (except for unittests) | +| udp_ip_lls_output | "" | string | udp_ip_lls_output:=192.168.0.100 | IP address of your local machine (i.e. the receiver of UDP stream messages) | +| udp_ip_lls_input | 192.168.0.1 | string | udp_ip_lls_input:=192.168.0.1 | IP address of host to send input UDP messages to, should be identical to hostname (except for unittests) | ## REST API services @@ -234,32 +234,36 @@ UDP stream output messages are: * [Localization result messages type 5 version 2](msg/LocalizationControllerResultMessage0502.msg) UDP stream input messages are: -* [Odometry messages type 1 version 1](msg/OdometryMessage0101.msg) * [Odometry messages type 1 version 4](msg/OdometryMessage0104.msg) * [Odometry messages type 1 version 5](msg/OdometryMessage0105.msg) * [Encoder measurement messages type 2 version 2](msg/EncoderMeasurementMessage0202.msg) * [Code measurement messages type 3 version 3](msg/CodeMeasurementMessage0303.msg) +* [Code measurement messages type 7 version 1](msg/CodeMeasurementMessage0701.msg) * [Line measurement messages type 4 version 3](msg/LineMeasurementMessage0403.msg) * [Line measurement messages type 4 version 4](msg/LineMeasurementMessage0404.msg) -See [UDP stream messages](doc/sim_messages.md) for details and examples. +See [UDP stream messages](doc/lls_messages.md) for details and examples. ## Timestamps and time synchronization The localization timestamps in UDP output messages are converted to system time using a Software-PLL. See [Time synchronization](doc/timing.md) and [Software-PLL](doc/software_pll.md) for details. +## System setup and source Ids + +See [System setup and source Ids](doc/source_id.md) for further information about source Ids and their configuration. + ## Tools and unittests ### Visualization of localization results -Localization results (i.e. the sensor position and orientation) can be visualized on ROS using pointcloud_convert. The tool converts Localization result messages and publishes the sensor pose and transform. Run pointcloud_converter and rviz, then add topic `/cloud/PointCloud2` and display type `TF`. +Localization results (i.e. the sensor position and orientation) can be visualized on ROS using lls_transform. The tool converts localization result messages and publishes the sensor pose and transform. Run lls_transform and rviz, then add display type `TF`. ROS-1 usage example: ``` source ./install/setup.bash roslaunch sick_lidar_localization sick_lidar_localization.launch & -sleep 3 ; roslaunch sick_lidar_localization pointcloud_converter.launch & +sleep 3 ; roslaunch sick_lidar_localization lls_transform.launch & sleep 3 ; rosrun rviz rviz -d ./src/sick_lidar_localization/test/config/rviz_sick_lidar_localization_pointcloud.rviz ``` @@ -268,13 +272,29 @@ ROS-2 usage example: ``` source ./install/setup.bash ros2 run sick_lidar_localization sick_lidar_localization ./src/sick_lidar_localization/launch/sick_lidar_localization.launch & -sleep 3 ; ros2 run sick_lidar_localization pointcloud_converter ./src/sick_lidar_localization/launch/pointcloud_converter.launch & +sleep 3 ; ros2 run sick_lidar_localization lls_transform ./src/sick_lidar_localization/launch/lls_transform.launch & sleep 3 ; rviz2 -d ./src/sick_lidar_localization//test/config/rviz2_sick_lidar_localization_pointcloud.rviz2 ``` -The following screenshot shows an example of the sensor pose with the sensor transform and 4 points in "cloud" coordinates: +The following screenshot shows an example of the sensor pose: + +![rviz_pointcloud_converter_screenshot](doc/screenshots/rviz_pointcloud_converter_screenshot2.png) + +Poses are published by ROS-transform-messages (TF) of tType geometry_msgs::TransformStamped. Each TF message has a parent and a child coordinate system identified by tf_parent_frame_id resp. tf_child_frame_id. These frame ids are configured in the launchfile, by default: +* tf_parent_frame_id: "map" +* tf_child_frame_id: "lls" + +The default frame ids for transformations should only be used as an example. In a real application, the reference to the robot is usually specified here, as it is, for example, in the ROS Nagivation stack. Here one would then use the reference +* tf_parent_frame_id: "base_link" +* tf_child_frame_id: "lls" -![rviz_pointcloud_converter_screenshot](doc/screenshots/rviz_pointcloud_converter_screenshot1.png) +Frame ids are normally customized according to the application resp. setup +* tf_parent_frame_id: "map" is used by rviz by default +* tf_parent_frame_id: "base_link" is often used in examples + +Other frame ids can be e.g. "robot", "vehicle" or "lidar". Choose parameter tf_parent_frame_id and tf_child_frame_id to match the target setup! + +See https://roboticsknowledgebase.com/wiki/state-estimation/ros-navigation/ for further examples. ### Unittests @@ -319,6 +339,12 @@ Open sick_lidar_localization.sln in build folder and rebuild (debug version) See [Quickstart-Setup-SOPASair.md](doc/Quickstart-Setup-SOPASair.md) for a quickstart. Find detailed information in the operation manuals published on https://supportportal.sick.com/products/localization/lidar-localization/lidar-loc/ . +### Source Ids + +:question: What are source Ids and how should I configure them? + +:white_check_mark: See [System setup and source Ids](doc/source_id.md) for further information about source Ids and their configuration. + ### Test and diagnosis :question: How can I activate informational messages for tests and diagnosis? @@ -335,7 +361,7 @@ Find detailed information in the operation manuals published on https://supportp :white_check_mark: sick_rest_server.py requires python3 and flask. Install flask with `pip install flask` (on Linux, use `pip3 install flask`) -:question: `ModuleNotFoundError: No module named pcapng` when running sim_pcapng_player.py +:question: `ModuleNotFoundError: No module named pcapng` when running lls_pcapng_player.py :white_check_mark: sick_rest_server.py requires python3 with modules scapy, pypcapfile and python-pcapng. Install with `pip` (resp `pip3` on Linux): ``` diff --git a/doc/cpp_api.md b/doc/cpp_api.md index d5b6c0c..6673ba4 100644 --- a/doc/cpp_api.md +++ b/doc/cpp_api.md @@ -32,41 +32,56 @@ int main(int argc, char** argv) sick_lidar_localization::UDPMessage::OdometryPayload0105 odometry0105; sick_lidar_localization::UDPMessage::EncoderMeasurementPayload0202 encoder_measurement0202; sick_lidar_localization::UDPMessage::CodeMeasurementPayload0303 code_measurement0303; + sick_lidar_localization::UDPMessage::CodeMeasurementPayload0701 code_measurement0701; sick_lidar_localization::UDPMessage::LineMeasurementPayload0403 line_measurement0403; sick_lidar_localization::UDPMessage::LineMeasurementPayload0404 line_measurement0404; odometry0104.telegram_count = 1000001; odometry0104.timestamp = 123456789; + odometry0104.source_id = 0; odometry0104.x_velocity = -1234; odometry0104.y_velocity = -1234; odometry0104.angular_velocity = 1234; odometry0105.telegram_count = 1000002; odometry0105.timestamp = 123456780; + odometry0105.source_id = 0; odometry0105.x_position = -1234; odometry0105.y_position = -1234; odometry0105.heading = 1234; encoder_measurement0202.telegram_count = 1000003; encoder_measurement0202.timestamp = 123456781; + encoder_measurement0202.source_id = 0; encoder_measurement0202.encoder_value = 123456789; code_measurement0303.telegram_count = 1000004; code_measurement0303.timestamp = 123456782; + code_measurement0303.source_id = 0; code_measurement0303.code = 1234; + code_measurement0701.telegram_count = 1000004; + code_measurement0701.timestamp = 123456782; + code_measurement0701.source_id = 0; + code_measurement0701.code = "1234"; + code_measurement0701.x_position = -1234; + code_measurement0701.y_position = -1234; + code_measurement0701.heading = 1234; line_measurement0403.telegram_count = 1000005; line_measurement0403.timestamp = 123456783; + line_measurement0403.source_id = 0; line_measurement0403.num_lanes = 1; line_measurement0403.lanes.push_back(1234); line_measurement0404.telegram_count = 1000006; line_measurement0404.timestamp = 123456784; + line_measurement0404.source_id = 0; line_measurement0404.lcp1 = 12; line_measurement0404.lcp2 = 34; line_measurement0404.lcp3 = 56; line_measurement0404.cnt_lpc = 78; line_measurement0404.reserved = 0; - if (!lidar_loc_api.sendUDPMessage(odometry0104, false, false, 1) - || !lidar_loc_api.sendUDPMessage(odometry0105, false, false, 1) - || !lidar_loc_api.sendUDPMessage(encoder_measurement0202, false, false, 1) - || !lidar_loc_api.sendUDPMessage(code_measurement0303, false, false, 1) - || !lidar_loc_api.sendUDPMessage(line_measurement0403, false, false, 1) - || !lidar_loc_api.sendUDPMessage(line_measurement0404, false, false, 1)) + if (!lidar_loc_api.sendUDPMessage(odometry0104, false, false) + || !lidar_loc_api.sendUDPMessage(odometry0105, false, false) + || !lidar_loc_api.sendUDPMessage(encoder_measurement0202, false, false) + || !lidar_loc_api.sendUDPMessage(code_measurement0303, false, false) + || !lidar_loc_api.sendUDPMessage(code_measurement0701, false, false) + || !lidar_loc_api.sendUDPMessage(line_measurement0403, false, false) + || !lidar_loc_api.sendUDPMessage(line_measurement0404, false, false)) { ROS_ERROR_STREAM("## ERROR sick_lidar_localization: UDPSender::sendUDPPayload() failed"); } diff --git a/doc/sim_messages.md b/doc/lls_messages.md similarity index 77% rename from doc/sim_messages.md rename to doc/lls_messages.md index 75b8499..bd96316 100644 --- a/doc/sim_messages.md +++ b/doc/lls_messages.md @@ -1,8 +1,8 @@ # UDP stream messages -LiDAR-LOC receives and sends messages from resp. to the localization controller using UDP. [UDP output messages](#sim_output_messages) are UDP messages sent from localization server to the local PC. [UDP input messages](#sim_input_messages) are UDP messages sent from the local PC to the localization server. On ROS-1 and ROS-2, these UDP-messages are converted from resp. to ROS messages. On native Linux and Windows systems, these UDP-messages can be processed using the [C++ API](../README.md#cpp_api). +LiDAR-LOC receives and sends messages from resp. to the localization controller using UDP. [UDP output messages](#lls_output_messages) are UDP messages sent from localization server to the local PC. [UDP input messages](#lls_input_messages) are UDP messages sent from the local PC to the localization server. On ROS-1 and ROS-2, these UDP-messages are converted from resp. to ROS messages. On native Linux and Windows systems, these UDP-messages can be processed using the [C++ API](../README.md#cpp_api). -## UDP output messages +## UDP output messages UDP output messages are: @@ -128,19 +128,19 @@ Parameters can be configured in the launch file [sick_lidar_localization.launch] | **parameter name** | **default value** | **parameter type** | **description** | |--------------------|-------------------|--------------------|-----------------| -| udp_ip_sim_output | "" | string | IP address of your local machine (i.e. the receiver of UDP stream messages) | -| udp_port_sim_output | 5010 | int | UDP port of output messages | -| udp_sim_output_logfile | "" | string | Optional logfile for human readable UDP output messages, or "" to disable logfile | +| udp_ip_lls_output | "" | string | IP address of your local machine (i.e. the receiver of UDP stream messages) | +| udp_port_lls_output | 5010 | int | UDP port of output messages | +| udp_lls_output_logfile | "" | string | Optional logfile for human readable UDP output messages, or "" to disable logfile | -## UDP input messages +## UDP input messages UDP input messages are: -* [Odometry messages type 1 version 1](../msg/OdometryMessage0101.msg) * [Odometry messages type 1 version 4](../msg/OdometryMessage0104.msg) * [Odometry messages type 1 version 5](../msg/OdometryMessage0105.msg) * [Encoder measurement messages type 2 version 2](../msg/EncoderMeasurementMessage0202.msg) * [Code measurement messages type 3 version 3](../msg/CodeMeasurementMessage0303.msg) +* [Code measurement messages type 7 version 1](../msg/CodeMeasurementMessage0701.msg) * [Line measurement messages type 4 version 3](../msg/LineMeasurementMessage0403.msg) * [Line measurement messages type 4 version 4](../msg/LineMeasurementMessage0404.msg) * [ROS odometry messages](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) @@ -152,12 +152,13 @@ ROS-1 examples to send UDP input messages (odometry, encoder measurement, code m ``` source ./install/setup.bash roslaunch sick_lidar_localization sick_lidar_localization.launch verbose:=1 & -rostopic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 '{telegram_count: 1000001, timestamp: 123456789, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' -rostopic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 '{telegram_count: 1000002, timestamp: 123456780, x_position: -1234, y_position: -1234, heading: 1234}' -rostopic pub --once /localizationcontroller/in/encoder_measurement_message_0202 sick_lidar_localization/EncoderMeasurementMessage0202 '{telegram_count: 1000003, timestamp: 123456781, encoder_value: 123456789}' -rostopic pub --once /localizationcontroller/in/code_measurement_message_0303 sick_lidar_localization/CodeMeasurementMessage0303 '{telegram_count: 1000004, timestamp: 123456782, code: 1234}' -rostopic pub --once /localizationcontroller/in/line_measurement_message_0403 sick_lidar_localization/LineMeasurementMessage0403 '{telegram_count: 1000005, timestamp: 123456783, num_lanes: 1, lanes: [1234]}' -rostopic pub --once /localizationcontroller/in/line_measurement_message_0404 sick_lidar_localization/LineMeasurementMessage0404 '{telegram_count: 1000006, timestamp: 123456784, lcp1: 12, lcp2: 34, lcp3: 56, cnt_lpc: 78}' +rostopic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 '{telegram_count: 1000001, timestamp: 123456789, source_id: 0, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' +rostopic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 '{telegram_count: 1000002, timestamp: 123456780, source_id: 0, x_position: -1234, y_position: -1234, heading: 1234}' +rostopic pub --once /localizationcontroller/in/encoder_measurement_message_0202 sick_lidar_localization/EncoderMeasurementMessage0202 '{telegram_count: 1000003, timestamp: 123456781, source_id: 0, encoder_value: 123456789}' +rostopic pub --once /localizationcontroller/in/code_measurement_message_0303 sick_lidar_localization/CodeMeasurementMessage0303 '{telegram_count: 1000004, timestamp: 123456782, source_id: 0, code: 1234}' +rostopic pub --once /localizationcontroller/in/code_measurement_message_0701 sick_lidar_localization/CodeMeasurementMessage0701 '{telegram_count: 1000004, timestamp: 123456782, source_id: 0, code: "1234", x_position: -1234, y_position: -2345, heading: -3456}' +rostopic pub --once /localizationcontroller/in/line_measurement_message_0403 sick_lidar_localization/LineMeasurementMessage0403 '{telegram_count: 1000005, timestamp: 123456783, source_id: 0, num_lanes: 1, lanes: [1234]}' +rostopic pub --once /localizationcontroller/in/line_measurement_message_0404 sick_lidar_localization/LineMeasurementMessage0404 '{telegram_count: 1000006, timestamp: 123456784, source_id: 0, lcp1: 12, lcp2: 34, lcp3: 56, cnt_lpc: 78}' ``` Example output from `sick_lidar_localization`: @@ -174,12 +175,13 @@ Example output from `sick_lidar_localization`: Use `ros2 topic pub` on ROS-2. Examples to to send UDP input messages (odometry, encoder measurement, code measurement and line measurement message): ``` -ros2 topic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 '{telegram_count: 1000001, timestamp: 123456789, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' -ros2 topic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 '{telegram_count: 1000002, timestamp: 123456780, x_position: -1234, y_position: -1234, heading: 1234}' -ros2 topic pub --once /localizationcontroller/in/encoder_measurement_message_0202 sick_lidar_localization/EncoderMeasurementMessage0202 '{telegram_count: 1000003, timestamp: 123456781, encoder_value: 123456789}' -ros2 topic pub --once /localizationcontroller/in/code_measurement_message_0303 sick_lidar_localization/CodeMeasurementMessage0303 '{telegram_count: 1000004, timestamp: 123456782, code: 1234}' -ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0403 sick_lidar_localization/LineMeasurementMessage0403 '{telegram_count: 1000005, timestamp: 123456783, num_lanes: 1, lanes: [1234]}' -ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0404 sick_lidar_localization/LineMeasurementMessage0404 '{telegram_count: 1000006, timestamp: 123456784, lcp1: 12, lcp2: 34, lcp3: 56, cnt_lpc: 78}' +ros2 topic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 '{telegram_count: 1000001, timestamp: 123456789, source_id: 0, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' +ros2 topic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 '{telegram_count: 1000002, timestamp: 123456780, source_id: 0, x_position: -1234, y_position: -1234, heading: 1234}' +ros2 topic pub --once /localizationcontroller/in/encoder_measurement_message_0202 sick_lidar_localization/EncoderMeasurementMessage0202 '{telegram_count: 1000003, timestamp: 123456781, source_id: 0, encoder_value: 123456789}' +ros2 topic pub --once /localizationcontroller/in/code_measurement_message_0303 sick_lidar_localization/CodeMeasurementMessage0303 '{telegram_count: 1000004, timestamp: 123456782, source_id: 0, code: 1234}' +ros2 topic pub --once /localizationcontroller/in/code_measurement_message_0701 sick_lidar_localization/CodeMeasurementMessage0701 '{telegram_count: 1000004, timestamp: 123456782, source_id: 0, code: "1234", x_position: -1234, y_position: -2345, heading: -3456}' +ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0403 sick_lidar_localization/LineMeasurementMessage0403 '{telegram_count: 1000005, timestamp: 123456783, source_id: 0, num_lanes: 1, lanes: [1234]}' +ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0404 sick_lidar_localization/LineMeasurementMessage0404 '{telegram_count: 1000006, timestamp: 123456784, source_id: 0, lcp1: 12, lcp2: 34, lcp3: 56, cnt_lpc: 78}' ``` ### Configuration of UDP input messages @@ -188,16 +190,27 @@ Parameters can be configured in the launch file [sick_lidar_localization.launch] | **parameter name** | **default value** | **parameter type** | **description** | |--------------------|-------------------|--------------------|-----------------| -| udp_ip_sim_input | "192.168.0.1" | string | IP address for input UDP messages, i.e. IP adress of the localization controller or "" for UDP broadcasts | -| udp_port_sim_input | 5009 | int | UDP port of input messages | +| udp_ip_lls_input | "192.168.0.1" | string | IP address for input UDP messages, i.e. IP address of the localization controller or "" for UDP broadcasts | +| udp_port_lls_input | 5009 | int | UDP port of input messages | | odom_topic | "/odom" | string | Topic of ros odom messages or "" to deactivate | -| udp_sim_input_source_id | 21 | int | Source_id of UDP input messages, see notes below | -| ros_odom_to_udp_msg | 3 | int | Convert ros odom message to upd, see notes below | - -Parameter `udp_sim_input_source_id` is an identifier of the odometry sender. This ID has to match the ID in the SIM configuration file. You can get SIM configuration file using Sopas Air: Log in as user service, download the configuration file and get parameter odometer/external/interface/sourceId. Use this sourceId for the parameter `udp_sim_input_source_id`. - -Parameter `ros_odom_to_udp_msg` converts ros odom message to upd: -* ros_odom_to_udp_msg = 0: map velocity to OdometryPayload0101 (Type 1, Version 1, LidarLoc 1), +| udp_lls_input_source_id | 21 | int | Source_id of UDP input messages, see notes below | +| ros_odom_to_udp_msg | 3 | int | Convert ros odom message to udp, see notes below | + +Parameter `udp_lls_input_source_id` is a default identifier of all UDP input messages if source_id is not otherwise specified in the sender. This ID has to match the ID in the LLS configuration file (lidarloc_config.yml). You can get configuration file using SOPASair: Log in as user service, download the configuration file and get parameter odometer/external/interface/sourceId. Use this sourceId for the parameter `udp_lls_input_source_id`. +Note: In sick_lidar_localization version 5.5 or newer, the ID can be set in 3 different ways: +* The ID can be specified in each UDP input message by its parameter `source_id`. If the source_id in the message is greater 0, it will be send to the localizer server. We recommend this setting. +* If the source_id in the message is equal 0, a default ID from configuration file (launch-file) is used. +* This default source_id can be configured for different message types and message versions in [sick_lidar_localization.launch](../launch/sick_lidar_localization.launch) by + ``` + + ``` + e.g. + ``` + + ``` +* If the parameter `udp_lls_input_source_id__` is not configured, the default source id is given by parameter `udp_lls_input_source_id`. + +Parameter `ros_odom_to_udp_msg` converts ros odom message to udp: * ros_odom_to_udp_msg = 1: map velocity to OdometryPayload0104 (Type 1, Version 4, LidarLoc 2), * ros_odom_to_udp_msg = 2: map position to OdometryPayload0105 (Type 1, Version 5, LidarLoc 2), * ros_odom_to_udp_msg = 3: map velocity to OdometryPayload0104 and position to OdometryPayload0105 diff --git a/doc/screenshots/rviz_pointcloud_converter_screenshot2.png b/doc/screenshots/rviz_pointcloud_converter_screenshot2.png new file mode 100644 index 0000000000000000000000000000000000000000..8441ef3756acfc5e5f9572e5df134f51d12c474a GIT binary patch literal 146985 zcmZ5{1yEaU(Cz_>mf})eiUe;dE=7t{+`YI%ahKvwad$}}xI3j3x8hE4m*NgLeE=LjUY>B~ITNt6C;@3P5mooh!)0@KJT*dK^`ou1m-I;x77A*R{4SZ8;l|{Q6AG71@ce!Ce_;ZBHL+Ke`j_2DW>X0NXc$7S_u+mgyHoPbbmFkQp@Qp8vAhO4-)^IgUUoIc?RDN#C zPBc_AX336174)~0;5C2|+HF;Dv>NtgY?1COs{aE^6a`yci8Tco5m5>6GV%E-NoK25 z4I-b#SEO8$y=;OlijtS|>oLk$LLy|@jy_0W1fH}vW!IpB1C5!LwLz2F?`kY*$D>?b zcCt>n+Toqat6(grq550d|Ah7qr_A}Sa*%aaQ^wAWK(gaLQq7)fS4!K#uNX5 zo{*GOqzHP76*q6ztr)kMvbsD^<%LP$qOu3xpArS2Oc*#`Zf&%?v>M-|3BpRpNt+PH z28F|g=lREnseMZ^~)eEo{yA=$_n{n-M^+0dCwkbX(B69*PGw)D5TBMk7XD3j3+ za)aFK*Jp~=6S(RCLx{Poyri9sD(A@xU*bEAFZ}s_VfmoYZjnij?)L#S-)Zm}rQj3zuE zg`-?%QNzB4SVkN&~e@^)jks{Yvhd&9>3UI0k%DM9R4l_3tx3@dJu> zpDc)zqKe+TiYcrP4~^a01#0T9U)l-jXos|A`i4N``#Dlz>|B6pKr6ezgID1k_JKVuDt}dE0386N^8d8XT29+aH8M8fIGv@* zIVD%D5b2tJYvyll%q)F=0;#RcbCS5y6QH(PC&8Uuv)Q+{7!B+P;SfoR75SCx+rP2U zJbqHK;GlO}X|1uGJpQwU6UR1d+`q`$=%?!#u((FUUgU5NE!0`vwgSTuq2DaOPt%uM!gnC1y)jy@FFUeX6ET zSHzLeqmoe&3ZY3smDCtp?%4S~w~a5gJ-*mXySAUH<94=`vA?b$k#PAhVh zwJ9Wf3TUp?$epXT$Z=0Ez7|nB5)hKdjK~1?Tew*sluL<6lMAN%-1F}n=0VcUMO)nz zM<^FZnUR#c3-|dYSse0YS)2Sj1YJw9SQYIyTAXl)k1*wtcs1_4?>(_O=EQyCNI;~9 z&55t}`Gc7lY|&4w!~oCLlTkG&0xkR6#p&GD;ndO1<=WNh+QseVICFM7XMd~8n6%~~ zO&nqNHhIInD1^0{Fhw`_oCORg8n#&#w@QFOukaRcx2?l@w2X{!f*R;-ojrw9OpdRE{mM~xUarOt8zD@ zgSvu)U;kV<309)jP@}_knpBDI8O*2tXwa-%G)T21_a@7zadDn8I-@y9x0+8$seFVV z&hrBkZL=o%RGwGtuyrllvee-ev!=)z#;4s=6sr90E<{9kzfaQV60(wx#MXZyB$EG< z0%$@5-+!?zeh^o{eX$P9D&QMEZEP_^#s~p9fkX%ZL6xRrQ6YpZTLxdxhObZvrTcF@4Agu2P)qa0~HkC;v4$+w1eUXPz7(be+CB+y9r zIs{>jF3NJ|n(sm4L0GK_n#uW~^x`c?-rkrO>rpXU>r$=Ihz)8G>l($mwY zyp7x>Zq~27#$+ZWCf;9P|9#%py;ik&ROCe`n~!S}GFs4KV_MCN`1=ekYb7^c3B&rs zX~pw+As>4%DRBpHsg?Ej_l)h3RtTfu$d_idz4MiSjCOcMQzWWo(}$qh+`g%Q4e?(J zG}?GOj1uy3_*oJlQ^feRe73IAYwEQkN!nXmbdmLl$)d!Cagi3droQ^dq0*CTH>rqGg% ztJ!>74@9A;SG2+RI}%0^!+Evm7O0f?s!mpTD`W)T`*UgN4a62BuWm8w`~&yrT{jtH zNjEn)1%)yC%y&s#AQ-?3`a5X|Cyez>T zM%vNI>HPZonI7Q-hqwx*%q#26XIAj!o--c|k49$qL!{yhA08eI5)NRi!14^Z|6b7A z+M1FwD?}vqs)|>b)=T2tGYKW&D_4dK-!kk6OpJ7N67hvX#d9zOOLc)l09d3yb>>{u zXxnP240j+M-~aT|I8M9cI)BXs-tnjiNV(fXu1<4&ZIcOZ&Gz^*5vut`97DTAL#TLh ztunI*vDs{Wd+UxJsX`unUX2->&rX?SCmj0{>%qbZzl5|37rmJsY^SoueB09XEGh`s zYlQe*#w(iYmE0<6@dY0#QyP4Ek0Dvxeb0AXN18mQYZV6y>RES-jkE zt?Zb7<%i~3H)aZ-eaExA;1jRf(ZfHBjmI?j^F${y(^jE3e}V1Hpp8%!u32SwqJRvp zpHn-JaW!WZ*U*jf-MPj2bpO&z2yzV&z?aroMbu!47~1!uTmNz8co& zaULLgeGO-QF@~oMata>(cF)V*@dD-{cz;lY?LwX9-`p;Wu_Xt-Bgcqx{V-Wk328Nh z3O(COwNT{|u4>P!`vqenUwu|irnlsu3_uZS*SCCQpCV`d7S`65azNNXE&~=j>+oBl zJt;acazc0QURm=;lA8f{qnPCpZ4Zg zTNDg7l+94T4?+clKYSpc9Fc+D@%r$SgLVQop(&SMlIHV}c6?LkH?E;|%#sIj2J#e& z3gv4oX|ryU6Hg*!?@H4B{9M)I7M#xtsr&+}xLpd1sQ4 z?~Rh+R{3YAUVLbKrjC?YXg~7R`hKxeqq^GfUoR+8^jR&ogr>-{#cU)!J3E_@O~1`~ zFFqwjquy$o{GPN>yK4fkdhS(rQKXHtQA7P-Y9--_atwThp*hKk=&vnqbThlq=FbQB zN(D4?HVyZ32n_0Qqk&A@hXdu+hkgBII_fiwb3*2OzHo2Be`fdDT`zl&;vjT~CAnJL-Bg^BKqj4?DW`+;t;)5oS<4ipe`gM-1X9}_>5#%0TEq4} zU51kJH?R@w8((YG#;$NqQtOoL=`hV!-kW*4X=vko-^OE%zZ@cT@>r~A>u5r`OU?BK zb5J?D`od?+%V278@J5QMcTkX&jFKs+0^W_>y>=g=?FkJb>&!*pphZ7pLj%Zp%>WE^AG$qd6c-55UzxK@(v-SDCx@}|Uhh~^_ z9(_$&Xr+R}sPodGbfuL9*Z{cT>QQ^aw%KF#51H4rXT7j<1m0f`1VAxf!(@Yl5nmP+ zW34MhtjM;JHeb=&J@i9uKOFFNkf91IT3!xYGz^3Ve1n(6?Hc_Fk=Jf^+6y8l(kaHs zZWzCD&f)(rKFaP$t4((nBjtP*9y(*fT$&!t)S@*Cm#a%13Fm4}$tYHf?z=$QUOMo* zP`Y>Pe0%D9`uFOR5w+U0Hid~lVcp1!tVKeqY6?d)+;D^O%+-vWQpY}XOaVsrFb2iD+01!W7)F4~O zdw#YSskP#ZFFHh0Q3PIm9%F-laRs~37&rh1BAy=at?L(_H#`*r+w5p(x$3=3Siyz<7u1tCVt3z$KcEpogJj1QX=J(te;`|cHv z*3`F7bSi3YzoVqz_~2W0%J6N}FMGu2m3 zi!c}~9!6=+9^`a5p^u%1Vp7CJMsD2F+seG)i^pq40E?Ww!|&PGzyL}pn8t1>FmV!H z!nsXKJS%#c4|dF%wt_J~6%`e1p464p((y*d#s~-qTFE|x1nk=7uD^p&~9~oY-0@a1P zX`^bE+hhNBj_*MA9E=bu*>|D%$@}TKHg%9>#`o~jjjJjTZNt@W5n{nzclyZqZEd@{ ze;I6_ZYvKD$Xs99M_cSZ&+;o$zg!PSs~ob&NYitVYE@B9%74I<3X;N6gDj?w^kuut#&`e=#VqfD7} z{F9omJh*vYi}zL?OtT<+R#RK!h-QO{RuaAnVjUhC9^}$Oq#Vs}J3JJa>{gp8YHSd4 zK45=0H*(vorNxWriYn$MZRe^ka{4IPLkli{&&JQh1itASrWse#O-)HkQqv5$k9omO zyUk3kQSS_I&fc{8a@sdMb;V6Gb?7JSI?W@inftvb@MK9_EG zafi|7^6$RkY^_?0gSqC`^DpY3>qkEdQRs|(jeK|r6i3FBt`RD^>89I~YVcK|YZxnw#61%h`M3Gkb+l3!EkmRt^D(G?yTI-tarXv3&^2m(Mm@=I?IgpmwcrUnASyN9wnBFAq}OoTcYH znV*lEq2;LyA6(CWx6ejKSCg1A3r!kL#Iqc1yRR(0H{Uv~k=arLz7EOpI1SDCoR!wg z_6c89$f`cxLOPy*#{FB?7&_MerP$n4XwPN4*tYFrdXbNRFE&o#_7qXk^N;hOGiPGa zZ}MXNfE6!s{DoJix{zU9JaPy9e$U(|g)Tb;ScD{0CuRw6Rj5FPbUVkuonIC`ikmAB zcVqil>CG+F{alfPHruG_KGHv{|1J`kU6T!&Df$|Tdy7A9*Fe!wkQq>v1Uq)Ysq?azipj$eb+ni zZRMure6;HgpG$NeNgo?UiAikpj?cD40@ZSmBL+>jAR{5BRBk?MPyRDr`JM#-xox3d z|7j@g%j?tnKel?+d)hH92X-Aw>SC|r)>J=jF{z`VRJ=DiYeqQA$IvCm8Lug$i+r(S z4f%P*m;g!(CN6RzbI)dEt7}@pCxV->1005 z2)mf&Ap9ziMn5CE?;SF|dVm zwZ0{$A_C!m*_$IqJ3GGhHsQ96ZXi#$Hn2Lh%He&-%C#tV9?0G@Eu%p*<Bi|u?$l=xSG7>;;2 zin_6kc88AC(cR^KXp&O_scZOOW?Shd?^9Rp?Ia&2Hv^X$d+mB=`v18%a`Qdn=#^6z z7W;X+RP-9HO;+djq&iM@xjVyD*w_oPo`*S4BN287eZwRPd`>I(_XLA@A$%L#3ic`; z`+q!Yixr;D=KRU(mZk2w(HytP(LbNcL`$r~HWgRGX+`uI4$x^HN^NBI=C40NWywiU z=$siO@$a7|rX2%-cPbWB=m-E_fochnX!8vD#a933*mk?$x4fv!GH%P>DXyd;)*Y!2 z?9mb|#>bru^`b}s-Vl>V@^$$K8?Fo}sj15YB?I9jNn4D9i3Bpy_1I9&{mYnf` zu$iScoN_Qf=GS5Ak&p9Q!K2-iYF!fmr8e3`EgEU!QqQznrJ8_LGLE%FTy+1XcF*H? zM4h;SL2H*H4Y=x^Li4xf)RiBan%^d}gFX;QXG%aeU+Gj2plJt&&<2$Bi!sy@^S%ap zGwTErqSf{VmX`6Bpz|hY&qnpyECi7d2otuAcn?>w1e$&-_fmsy+^qdrm} z=}%%-vTa>8T0Nw-HCgt)?PM{<+WW%v#0szS`r5%mx)o^GjHl`8?L|UDs$rJRuAquj zhh)7s6g4p^RM%<1WdDzU(VjOYbusA#vLZ{2cXr`TR+m57RHJ?_|_G zkrhsa)$eVpvITl4Novx8-X>=IsMk%BpF2(c=vG&F`aQjJ+04Jiem=}jNjp6*kh_w5Xd&pvzf{*ptn4<*Z8T069v%k(n*uGZ0fC$gaL|ZjZ&k&0fxR0G5 zT2-lwJdFQ~^*iVYeJKP*=oMPn8emH)zC2wc8F5 zdx5uOU&YL1GNss?5s}FdR<8b#S>d}an2ig-&CtlM+*)Zi{P*m0k^o~4c^rOEPO8Kg zhQ`Xqt7>X$Dl4B!t%A~&jgGY$RVz#s{{k_EOoVpD8G-@UGbI;=@D$^zco`O$80Cd2 zD!`AdZ>Nr;F$>(x`JSt|9fW!R^ljol(v;;Vg8`}S@?D7AIj657_VnQ6;`1vJm^A+i zsk?R_pB(DUnXhAJPgB<=a?&)JoX8qA>=H|Hm8Os<(Lp;qp!(e4bMg|xR21Q^}utmS4AX{?2A990c;_2Bb zOpTE-;!`}@Z7-E;s3Ea(WAa7ao)yT)j-|%uH}TrL-CcNEs7_UIiL77d5Xj$e=N8Vs zt&Qfqmrvs@48C)KMyh`E>Gh9s!m%O~tZVn+?c2&a2ea{t5={lq(_-7pWt`gKA`2*}Wye6n}!l^sEKTGJ5qq5U}bHbi=8&1=nm59H|dX^R8Q>F_?*DCo9g!e;~1xMpQC)qwx)jy;`U^B%GA_>k40xk;Jc|Lq0P#G&`Ha9MJ8=?!xrY~q4GR=Mnq zW@XF_pDb4iyj~v(goIoltkhqx1~0PB0si?6>BX|f{0#QbZaG&6D@E6<;jOG@0D$+W z^3h1Ol2xyzO>k@X=r_H$dJvX$d_Tp*T3gv0gRy8=)d&=2xFKQR!}XJ^8RBZIzN_{G zZAEJhn_8ZT>tTx9wTH*;&`O-iS)WTaX4G<$pLmwUf4m?BWyT9~%k?adJzjbD8kMq) zgDaQQVM>wtWtawAUv8fux3lw%F7R8_a^KHK2N6ls^vsTy8l2`AMTE*VJ!)@CxI|ux zRDXvcFe?h#%DlbCIEvzTuV~Cff(`fI&DYTpdO2j5`SWv zD7One&Pqr2vIu*{9!z~=v>9Z{6f_w9TQIASAeOB0BIO5HyC?TKPyJ=66OrP#t({9R zd-a34+5>Cs4(FBPz3!dkA^Z7qbG6gqIl~-XW>;-?R!OpU&COT9PPvm3edSgFr^_|w zVoe+Io83taquH2SXFXKmr#(}OFWOYW?K6*;d{*lqTUkxU$GPOsd-@wYausS_DkX~d zuQV!FH{v}_PXC2Noj4a=EZ3W@NBhU9?GZpkK&}>2Q1|OzIeo7p*Zb^f0TnY0ic^(% z6{*%LyAAAFBr-2oyKV4&2ByNNkZ;@f9$v4lzhphw@fPi3q5i8d6d~Vp*r|XM724H9gAh}3D|OqkQ+`Nl*iZeE9Mz0M z45n=er55R{KG`P6P5(jx9h0O(p#~tRsOQ|v&E7{6x}tD8wMssf>^>;?FaDBEn5co& z4>aZD!gRSlKY>lCWiO$z0b4sGXEtkd zz28)*IY|fSHDoRNCjNCsqruPfwL58hjZo6*D_e(nKwf0(W_F+RrveJ%m6w$|#piK(L=qRecF7l=mX}+Xlq1viod&D7-naEwZ{cp*9G8EDKLrKB{$%N( zjL+gUkqQk66Ret`dm!d5qBZ??=ZODE;VJZ|<|Op!OTzVzkANc5pZeY2DLF5?I*LEl z9Pbjs8(MX!**M8AH&Ry&foLbYwr0zn`s5K5bCkWmCr7RwW0d-AO$|;xPrn;eeDzco zPOv~R`NDcdlCAqbov9yhqpr^0IGn{szm-|G?(Nmb)Jr04wcVmRU)}m_t?5@Iizlff z?BRC2;<)^yD5vnK)rFz?J^)iM(ay)*_VE6%8ZV*W!&B3H=Pmx}^F}@~n9VCb>9uk# zzxO^ZEX?9Inz;A*IMeurLR9?4Kwc}leutHzI8;xnY=#0H(edaXmKulpnD!-|>ngI^ zuIx4%Mo<*dKg-4hkQQui863|-V3oE7IbN-R0V4vqUz$G*s4GG=$3pon7O znneKb>xZ30|1Rhv86dp3b~rm@-1S_h$hHw ztU+L|Y4bY6s@02_wC8lsLviG2HVu_mT>X0Ri5&n2`=AMJwe%Z~B*|!8Dhx+Lqx1U#EGr#U+d-nai@H5J7r{Y9E znD6Wn=9*Y6P9KLO(xE=68kk1{#7=$e4bOv_t%SzP1gvw4E=ETbT-lZvr`+%K&m$M> zZ_Z5($SteNlE%7GmAnqSvijJ-JfHSEX%4Q6hKLNN4wW+?`^r`3Zb) zk5cFl{1&G+EcdfufSl^0hOxECids5f^)54ew~qf19Xm7x{sPS7FCX~)!!W>`-}o-n`20G}tOmAY`^v)+p^Qmw!}M2~?_pE`BXc!B#a?>; zDH^7F5e1L?5|W}b!@ep!zPjMA$;s(>*V~CB9AIFtioZv)GznEPU&@)Y6tVcJX2V4L zga2;TeAaLKdWP>K{Avk3V>$J#ykqFX!-(_E64lz%{x=)<6(op8(tO`m1GoxXMBWi* zZU=Z53>WEgVwz8NyraV&wv@!|*$kROOBxsRY_aQC_+Bw%ywDI0jq!G~fR3`jd&6tj z+a4N)^Lw!@LX6zM_Wa{=88YqB8>;4it-M}AZ-RPVX=HVo)_fV-^A1Y309JAGgZ@gk z&1jOg1Q%?mJtZLwY1l31r*qy)#E)m@;J7`?Uj;&%S`fBv^cw$lcb#1C{hb(LQicP>z~~EmYclu=#l?eGJVhyhX;POOcV2WKvSDlJhM-0O^cdbNd;e!lt0QMm*tyyib)wI2H&fMw7-4)uE#&Soh zYDeQ@B`U`PCakRJJ0trPl*-C9FviUHcwS3x2OcB1? zzPfIM=lF4l4m3+(d;cc5-BWA=(NeYCP0|^~9|HTo9)?HpLl8;;EDxg*tRag9MFda^ zfa3Ble3M9S)R2Hso!<3JLdKAgo0~I)^b;MfnxSyCg~ALsk~f+9v(YwWoSTaePxpRr ztpFhR@+t4lBOGAUvKgFF5fp-W=9}K=HS>6P-ZjwrfQGaF2oppJd!zZE)uiOEdyUQl zL?BlW{x>la03?FeckJ8Ah>0n$Q!o$Jolb`v?QJgyI>{(5wpV8ZRmXM>&|X0BQ_=sI z6LE5%uJ_DMc}M;kTz(X#rY$onRPNtmOc=xo( zL5L$N=(M}{Lk=v4l2kf1m#n#e9>zP-Z%;&?F-q9;V!1$L=9^2{x67jw;|A{r3O zNJRxiAdEI`+`OU$!d<@4z$Vq^zOLK$6Vqy;G!Ge5)bOmQY3Ua+XM1AjBH5Bvy*4v} zhQ{m!#r?$|EyGIba6T~5X@NlgKp%YdGfmW z`p~U$fY4f!+sA~&$y~{5xI8nrw0=nq52beqEUzoeqU@z%x4``SGDqXS4W>^2o6y~- zwp{j&Th-&zeF=+-nzE|*^Lfc+rQa$m);X zORd5Z5sP|l3Tf_SBdwY4?!e-lJGj8#)~^X{EB_u9$glZ<=f6B{RT7?*E?GO@zh8zn z?QaErfA@0j3;h;fig=lVx-I&?LX~3|sPpKQj8S3arPV zayF&QiW56a9Wrg^Bn1P%l{1!`V;iWl>s9G2>KQ8eTa4urr#CutXev1D!MPD4rGB%? z(|;@*(`A`)AkO2D4bnUgsjnl+WCBHE96r4$xIQTX@FbCREQHl*e8sQQIFX$#@CL_X zAzJ_a+Q_Q8FQM#y9Hv)H3;MC0RgAKG-9G<%H~D4KZ~>TBjD_qu!Skq>;kmROx#xEf zr@`ogFICZ;{H(jvpQt!J!A(VHr?IJ$*KEaUdXR=^=h2%M{ka9q|F9R*Yan*{b}NmE zp`Y2Iyu*E~4U5)6Cf9Ks+K%UPY` zwfkZv{gT?pplj<^cYTstweh=0qDaqB zIKaQ%iQB`<^^?=idPMiVjbR+%sr8G^r%t&TYS7Vbk0ri^|4H27Gf7KT z^b6{GT&uEEE9VlP``Y&Dw9Hb3RQNPap))*4f`Z#tlYzu8N~hy$iXXvK-B-j?aHIY< z$GgVz*)-O5GUHYM>oK}TEljsJuK{fhw&-)4kohN^Cn%5$*>SKq@5L-uv zijqj!@M@(@A}BpiCc$glc*xuv-(z_MO3%hh$S4i3$UO8n2=KS&^&`}Z8G*~a`sbpy zz)WW>;piIvsDF_yr$Oe*P^Z$@dxxB+60!Ajy)L13cBNWx(dYZ!19(HQv;}V|JpFcH z)(u1GSG9ISnoQn{||3%S$_z{a{OsCi9_N>w&N`yTYGvhK&cD7L87-bPXb z38Z6jjn`y$-*8PM1)a!uf&m^55TyaIP~oUisev$IrJ(%Hiepd0&f|?_^wLucrMk^3 z8FEeu-}d&(=V*o#bUugG&3>+SyJI~MN*4F~0a~?k`n%2#eKz!@-E+gYR}=8|S)q{L zRjAi~fG_^g;iNmWD2n(8VvQW)kycJr-74CgA%#YHN{hw3m{`p|?0eSdXfz zjSIa0?t4O_$gEeu9~@&U1_xN}6Vs;7<5cny2l|t~QKX)`#Wf0~uuL(nu4+=l_ew^? zW#U4KtW_>sna#u^=`OoL57O~e!RK@7S=@~MuOsQelOQTbz||=0U#VWJ8!1=SXy5A< zinPBoDRBa&_50^$%j~hEAfUg~$@%iSPYg4Vh1U#f`Waej-IR2G2(A8o$oq~3jKE6T zHsL+TP1W+O9Vz}|K<&(L0TdLJ-IexMb%;-e8+H88GmH`g{x6qbok&p=ldL3EuV#Rv zO0`Pjq?~U@>NUGs1=iQ{E&+nVLH?yK5X2TB&V&`8dS7+?BPI5yCeI^9gOf0V5y74^ z9XI8O@CKP>zAo~8mdBnUD`NoG>q%1;O>~+d* zPjAYjhJP1*Yx1?0GTrF&0p}T=5c>N1vU##sf*{jY)tb6`dIlF_`r`jjNKaf`g_X%s zap}Y)BtD&V*1uS%A4yrA@QZ$nDj*`fwEw~4udjFo6HBH1*{&t zJak;0UVib;REYVmIJui-BQp}xKl96UVboyRxG!=o!rl?o;oFG zbyz>tew20{HplHd2^*nBr{$yQbiVJ$_mFPHsg30I4}|)j-EOB!=J)bTYD8sp&`qDM znh$zDZm#^?{nO{_!#djJvNouT;D+&ZzA^`?W9mO6^YkMoE!UUcvj@rPI&! ztV@))+*WE3BElq^W>x#*8`$k8O3(~**HYTBawH=m=78M%3aSHUT zZKfNCh|T&epENn@xy2{{B)XUkMI3bGoy4+L3O2e}ZcgWCqJQ`o9V}ZMs=FxQe!-S- zWpBNM*2zqAEv|hYXf0WTxm~I3mMR@dS)k*He@VxQbW;O}?HbTzaw=u7p z4e;OnXf{tGD!s6V3C*tETH4h@A{weLiev4mVm@yrCWxf0oINVYa%vIsU=PBINZ=j0 z?#OPCvf?-ic-0A zu_kZ`sqA1Uj)paV=+~HpE0@4(hu1Rnx=4-x!DCN&0)RtCYhIETz1smj5zow^)8QQx zl-Kw|yvuOgnKcU5I|bm4B)UGlYDi>E*zF&0s&ib#mf$YF)%>+$XmooN=3`Myp8Ef^4>=Zj=< z1pp%1l;U-oa7EJB0HsW@f3G2vKZy!ZE27Iu z3oD7?h$%}fp2Pa;@>Ia`PTRw%XlTTI&KC1acrarY-DRr=eq`!>NfGI(*kqRJ^g7$! z1LEEG`WrY~&!O4;0>f;%E{iR#T;)rOT55ftIffpHXE6(CL+6c{-aK2V_bSEw&OBsx z$sV^c&XWJBSetKiS~`}z>lK{SoNT1Qkq=zR>>tm6rdN*CB6=-WrE?6; z;wdv@vPMoh`*auJ1K|$ZQg?x1ski4}pN|U4XYzcYqcekT^!WI=NYWy`ciQT|Fsq3U zxO?7S?T+g~eDpafie4GtB}EdBWea+J;uQE{r&1xoX>q-)!5rX1sH@ ziJ#8>bC`hEV5~5s!D_7t-bMH)ru1^V<@r3d3|`T5T)Z86R6km<+@u_FQZPYj$4^V=&B1HzQ}KP1f&$+qcD14U6c5Q5o#Tap=! zE2I2tTS0e5d2AePrSXmVZE{2rtXCp=iY6u|-$>2twbdBa?yrs@8kKg9i{-Ff(TatU zkvgcUO zIRg`0(ojAoZRTy$I>Kv7KXMh{joxOebaST^um&-4OH)%J7@YB?cmkQ*ls%0SrPGzN z5HvV6BnzHQy4-v^pplMXWL)OpO*Hhge()BBcfCY)z4REL{0}5}q6$>9nAw^ADIzoz0CySiX=1&M1m->an^W-c ziSGpb6lanzbC!t#w{6~y$(l1i&OhAP4JQ|5B$o+!-w(ViB-gp#)5v&cSM)h^O$ri7 z0oWdgLr_0z&=3mU$NiV14^Dj4FKysq&N8LNcXL!j`A(M)y!2F*KQK&)G6 zmpLjfCsvn<79_wo@SCc-isf(Lyr`hC6IbO%ED!Wz#wOd8=M|7i<3~p1j>>1JP>LYgxcl;nD8-S0?ej(^SbHQpjkh zRfel=pq?fGl4|q5sM{)!dw#BZiQl5nNPfgTFy&V-7*{RVzTE4p;k8Y82ktHYQ{m%w znIj%8&V3z2a=WLtZcr2uI*I4Q8ErjRg)=l@LV9mqU0eRg0y#}yPrFpKnp9G@0Vg5u zn@n^70zetRY}LRg7NU_vo@bGq@W=%}cfxvOaT7wKSS#_P+kLULWQk+xayR*nS)M}% zR@#?5rSm#iha`+$uTUBy0{WXA-6vy>5@J|PJ>|>Q$KwHxp}%-k`IJ~8#+JZ<9hVj< zdZi-6Rw4)mrwUV!|McI)hsh3Z4^@m)bu)_PW~-yoz1N-lnrdV3(fg{4$nb2&bQB`Vt?IX z-z`hy-f^ogeB>S>ZG94L5U#UF&$x0JTR1$?QJ1ycX&`NRyo=u*<8OlFVNuVOib$`0 zuJitq)1DsI6=`0d*O|dAmRCGTTGh2-`Z`~|-c zdn0EaDYMb(_#eIJxz#@Uk_uUm*cNQ+)Nhmp7qAn&$?_g{nU85Ugw-pk4yMX1&&fuF zpnT1d84>mPJ!2Fz=Ie>3*l{`iJn2U6(doMLut7nEQ3ZlgyIm%~g%jlef`Y+@LXN|x z$0r5`%Yk@W1_lN{*O+O;dHmLUWk+V5xTbA1?{l<9kTu^JtHO0q9lIp__fsRq13&wcpfl2PRk2p*jZ{MC5?(uI4r_ z_p6qAYl(JjbgNGCf}O`I%g3OZrNLV$9iKlH#^=k1+D^S%$E&Ju+&X9Ng-b^C07}E} ziz(8`qRr6eoIVfd*;xEFkQ%D!VtM8BAlCqp$LENJIs3)3&LJjHLM*XD$h^m?Q< zzM82DyOQOS%tEJnjoNzmvnSU<8S~N27-=h$Y6f=&iO%Z>6s(P;w{TGN}ylAZ5Cpa*tMPiniXBg7&13v}T$Ky{Gi9;@PdntZjO# z!#g|QDemu4H1XMe#|M9u3mq>Dob;(duOD_N^K5w{%r5n}+S+{J0GS%rBPbSrhT*6T z1M{l_1XZAHut*otfDM)*81d-$P5{E=Wl`otL>x~M^kn6v-4Fa`+Yf0ie>ThDNh#L;Uh9ghYM;`zA-fVv)Km_aQCZKx_ z<@IZlPu@+9jn_GPx*v15SLp)n3ZZX19D=lAlLBkXvcG-*w-*36*+aQLdI6H(mF>GB zzwqcq*kcc^;qPK*hvjhWxvxSg9nS7id7Cp6UWMWU{sOyglC|g~%IotZwRB}XgflI& zV1oK(ygD%&YU~I@iVp4_f(f4+u(jVDPhNf1>g1R_ovb6#W$ts-<4(_pxlOZ9qfhKr zbSberwRF*Uc9%|r4;#JSf7trUfGVS=+e0IWgdiP~($d}1B`96e-Q9?Uba!`m z$D!fS9nwg5cisoz@4ff?arw)s{p>w^X4b4((@M&H^Gxi1gZrU(1`c#PJnZyCcRml9 z?l<^mg-!2-9#2D$G3twG7~gddP8goFOel)9FYqr>QBk-(!uo2@0uKS@DvuA*U+H$9 z;JVYA0{^29 zPtvKF?{T_{@Zqv?-GW&` zwmn^-vPyuOc;fbc5-N>H;*g8R6a^K#tHk!9SYT|v`9g67UG@veLi_v~ML^plJ4a$x zm4QDR-=O<0+1dm^*hv|q`T_ul;9+CQmA@eNKn9VK34=`-@957iCX zc0;bn+g?nDlUHZb@R!_l)mw-|j;OH<3@=PK1v!!g#@MrjpUJ=9**t~b1#ZT1v&Vb` z?CA~OOShX{XRH7FKn3zYCe^|PP4<+I=un?wGoVvyg>!lZB2KtB3)o~2{2EXm1HCC< z1FEcOagg9fUlma!e%SS`-}P8%bj-s;&JIzj3v{fBznDe}O6)82yZ1 z?nN}(ffKV4^EUOH;GUo{5ZYQz8W|g!hdKqd$VXN@Obr-Wis`ABr=bn9(jLIMF!g`Vk~x#JnqrHaJx{&bH6+tB+VUXRwL zG-_y^7)mCt?!JV3gj=qQHzC}7Od=!aY=1LUWdo_Aj@YUVANlQ!+{+TCAv z+kdFB)6hs2eLr_;g`V|Jkjev=3-kvl7S$GZztZ|wX#FEOvtJP3Loob;UTZ$zZA2ZF z*;I4hKcw8qv0||oQ8~GApzvcD$Rh-TKnbBC`F9Nr6y@su>kptAMi*~c z)>e(s(-fLAku zwU#6x=5yQJ-rfd^dZXe?EzXRjq`oA--w|?u5f_(FVK4K1xF+Or+C0;~uxS|}aHVwZ zcD#bA3(IoZl6D_{=FLqy+!{tl{OPm#2fMxzBX?QKoNl;4nfGC^d$`J+@$pXfKuUYs zTt47GuoAnq41x7>GZsER{)Z3S>+9$F?5?h^=;-KYXJ?qAXLlYUy~jWmMPXFTwvZsq(& zl!T!K-RzFHONv=}5>h33kO$;-8BupWMZoji$;DSppuf2E!LTHm`;+H%rtx4oddf8{20gE)4w!v`+utR4~NXL z!tk_ul*&q5PqMW;Gv+RLCpu12#yke!ys;0zp3|2^pSbVQw9ijcC<>d?yI{6R{V2}o z{IIclyiKv0$bv%mmG~|aUlNS~@>IJsdIBMa?igq>jhL!~(TIP4DzW{d?D-GE!K&d1 z=j5go%iwj*RxC1Lo;P3oUZiN);RE$>bF$jz*#fv;UpVCGm>2-VqmLOFjHiFN+sTMw zL`6?_+%}*^U*92kEfz=*FWatuZEN<%Uwivjt-@>1GHnyIlxMHz!N2$AGiv%~x&%dF zXyKz4h234>t|PU@Pb60FN=}e3iH!37iS!wL@%=F;v5FG4wfaCo?#4fpfOcVDzfFFk zWKWUJ`udibpO>6`Q~f_tZ!*avrL&56Y2GNx}I;o2n36fY`1*V z3>eJT1%X)i_Gci`5&3^^d3{OW_!ygh1e&bLhj7Dc<1k@q{XnrkkGBc8TyhM!%Wcsq zF`28VRN3qH;&m0@Cxu?)SVTTi;8LS3BddQplS+49?|Bm?G2Ljp;mhj}c03rJ$k~gE zva+(O!xihdjZ8!g3KB&>D+s!}to;;+5d@pe1_Sz}Lli4jsMDUialiIA>K9<@Upv9J z#m#CpMjrexgw7}PFyawiQDg>sdMG}4{sj1L;lrcx2F5U;RIZE1;uL(p0O14%G(03L zD+)}!*XP2I1)THMcsA`O=%Iw}biN-|n37)$eQMSJv=P=@BY;d+2*g5t+B~JX|J}=; zwa>axr#)W~k$>^IYlDxEP_7O{>HzA)Ov$el{Kh7st9}3X8<0^8cA(Y0Nz#@%ntQ;KbKeeJrWe>4%eG z1YRB|d(XE%vSQv}cFN>^MTCX^DR_FHF;jYX88SY;gH6ouM<)IQ5?(M*4$^FbM!^%D zE3dS`{S+sPL;G)OeB>aIvAcK)pF7E?-MrE&Yn|UgKNE2XR%s-+hPwUU*xWH27<81X zkznwF+l*1a7oM8MzjktcyjIaE7~|u0csgGp0+* zqQORx;>5G0&;t#+LPA2;?!gTlkN32pI8eH}@*FzWtM5>WyN;JRE&l@^9FL^vW4zDO zYS~$2+@A|vZs}ZnpdYidgATBjm3H6w>p}owVpJI<14;P)AcVVYEJ!Gn&z!w^(N~Ly zY$z2eZuN$+c5iK~wJwpHDTS*)_0D4TE)YGWu-G_xz|vRxU@tRx;aL7A1n|FoUgS=bH|T4zgM7>HJ1r> zjszUKT+0oW_OvZs_kyYN=03N*#NF3BeAJ2O-{`PsgCE0ei;}Aj7#=xm6+{`c#J;UL zsFVBZcmt%MAJYIjU-qHd@z+qoi?<`x>s|w9KxwB65_1W zI@6H(w<_i1GbQ%SxWu4)uXm{RqB1jux%`;j!nhhq{Mr0>VPMZ(%i>cM?u{S_ys>-( zyV4hC)F8jC4VEx&71xMrJ>S1BdO>3cE%%sZ0w2h>ze&j(r!1dFSQBw!3?_It^Ro#! z_i+FH_c$7~V>mIU@`KU|<*UJJH7PVo6|tDa#2Ird6;qw(Tlu&whjnHHP=d8aXE<9` z;A)1qm2bt7*Yehxl}a8|%HGZT)z(Yq`$*+^nJ~hD92Gx^pb2exw4IPLF0CH@+ECqV zJW-Dxmi$v&Jq9+oO4_ZZ<}+{RLAJABZ3L}ZCUXRK2WE*PSE{c46~SSKbvj`~^`{jc|yd4)^OdNx4It@*Qb|jA$tqW zTf!U}UWXgU(@p8;0(@0op0^vQyK|_ZA7ey`e1K^%_zC{|IeV_I)VfC7Q$QO@GLRk7 z;c(jgxH(>4wRlpb7}Rs{1vP_l~Y^JE4|F6qXuI&d|I`TYK!!Na;EvJua0eEhUZa{DFp*NiezS;@;gKCI4cL_5nUC3$Cc*^>Y3g8-V~S zouzEG+q(NSU8)Axti+J;cpjp$+6-$S?_w@Mycv8BRWs znVH$z%G<>RErSLURFJzI^VMRWWKUeY4g#~9|}aL9r`c$^?OFg0Nr*V zF$!p;;1Fp?|IN&1x7(bWDM?Cd1ivcV3BMq|0m-7McbUO~3U!EM2cuCCvFM`^g+(&F zj{X?D-ku-7e7*d_7PvZEJhhnnPk#$f)Cg3n8azm_h;Fw&@kQTp*x^M)vUqbs zqmP;3{fbv~!Sn_jO8Fz3<#6QK11iqh$T~}eQWI0us;myyO+sRP z#M!R&$5j3@*y(J23;%4M5(N6p7vAh}_@@dPdvsNPkPUxEQgV+H9;B*eq^Owx4k$ag zpY-L0Bv?@zY(c3`ykk@ic_@YjQY)F0X3t+qtX2aIN1Y7wNw6`$iWDMdEHuKjCAG~X~qigC(Jr^&)ZX7W8{K!lj*^yIyN19EC(eg=W(j{=>#7~A>~SacY})85}{yjSV|Ns&W(`>SEp1e3|rqlfTU zNJy*X%js#lrc1<1{ffD>jOkw&ufYi=>6@+46^|bdT3nzG6>$E|F|W76mxI-XZ?M!( zcI*W@$)8P_+ozWD3_bV{0n36w8yfxhWJR7rpSM4vJ`~+~w5gY^ROZlskRvs`&B+uhQJP#I4Wa6i= zu{2Lz`TbPO97HJQ3efQY7YV+;;954~7gE0`Hd_c2y zH@Eq58sX-M%oN%i$|G+(pwTd2_Vz|$ZOBEVfF2_u47w5OSXl&zdAur<)P3!CbeKij zWkA(o_OJgtu9P%NIK9pgCPX-L;|3UN(8bT0Z&+7-MDu^T)9&Y957|pY-w4yImD7B# z{)!Pd#qK*jp*2Y|Dk8l$qopz~b$(avtF z6)S{;cQVo=nhc;uN^tQR&zcp_H)eQi-@C>z^De*(V$gNl$WL*nM^@v?zC{2D^NUU@ zBU7K^J`Ei^erqucAI1N?U2v;%(|lU2!l>`zu&pWfj5W1quhQhB-brrw*Y8UBK_#n# z?)k3q4Zp`-&JgFnv_A{lT{mpQTY}(VuHxkQnBhan>SO@P?-fV4XWO$e2g?N&*+A|$ zs|w!Y7qIuto9dD4R38yP#4Iv9UPTbC?ZSPY?gglTu!H5(beJC!;ev z`=gKg+{!kWszr;5D-ZX9sCY?S`SKJ^M+-l%+EaHTG&rVF4!OZhl}dlI;pg1F&W>a% zWJB&%cAg4G7Eho!IL6I7^{Dqa|3&7VYkUHDcLL<$*6MS&NQ~GOy0Y!Dh&`6H;Fd{F z;}Lh8=L$k}ykv?kL$~M8hAvnXOjdvPMDce7I5ph6N|RXH@wuI^q9+1BEihPKs-gL0 zLJF;|MsD{Wl2pvElIu-mQciYIGVU&lC5>GKKk=|tkg}2!|Eb)y3-^z{4Nu{33h$~E zxG$fPe`%FA^~W{mh*NJPwYz$xce1%IVtr^JeqeJ#=s$l)V{S`|#TGz^5|ZxdvI7pE zDQS6HOt?xPH(OnPRoD~Wh3mPno7Y7DKKdNNIcrtG<%@ZmVXe1q(vn8z;z0ypQp;xg z)ITG|`Cporji^2mMUX;)R2Phlsek&Af_wm3SR>Wo7rlqMAErDb&^jI7Plcq?HLwwM zt?1(a#gST4K9H`@GoBJXFNdHHRVyecNaaOCHf-VCu@s9~d3kx6nH6c`J~+AnM||9U z>#3YZB+}#O+Kf5x^My3I&aD{}@p_(yM7rSZqc~=SJk}ZqrOx5HqkxzB!Ydu|gx$MmJI@E5v_UzlbVfLow6wHTR0!|?ajD`m*Heq@ zd0QL3M}iH9RG#Z!4q=cJt%#QDZ-ghkSJNyc!QhjQ0f&PrYc<)fv!_7f68=^sf9Rhb zb8~Y$aHLTtfKnX%ug=xgmtH@Nf4}t>OJm&xeEBe(m19iY>aa7rwc$LWm!Jcw$EA zc#oJ@t{Bw+hE9G~27jsQ+e3ZYeFYyn1bSERUEq}|{z99+iAh4$HzV0M_$xX32lZe| z0@qvwkj7{lR!qR<;cS!0TqnL9708GCzN6>oGLO^#^vl5(D(khLi#!3O=sQi$1R_W* z$98Wr@9E*DLa8Kv<6qap*EclfJyD9Rrc=Wnrrk@c*S!WT42o}{el*nN?K@=D*__?x z`(D+w3sgX{Uu!Do|(L;)hI|D`oh- z-Szoh&c4>4MuwGw4PWA&nd-Epc0J;5lZMe0*PgGIoyn{1$XMlR;M;J8cK5q%``Nw{ zuNTYNT{*94Qg0P;x+PA7 zskd5vfZV3F&+I>6rA9e^@;xn6ZSbnwU*q_(_!kaUk!x%DSA?G@oLGW~%MwR-MR*H9I3HNrJvg1Qkv(W*2@FRscfpOJm!-X*Q#50@A)H}oWB3cYZ zSRrWRU~uirX&9!6TY%Vz*~pqO8V0Ii-GWjv_gS(vFT*F58n+RWZ2c!>$h!UHNounL z?Nqnn5o%Q^B?HS0TAY+pnO4%n)9@%6R^assxqIED%U=KyAo-1iMMI}novYR2l)_>C z4h5x5AxA9A`JY(ScTjI5m)P1w?Tz1z275*NpUp$Y)iS;WI?QvNmN0lwG~@O+f)TY+ zBViJ!zfho43I^!PKZqI1VMBSE%S~I~?WU}{_hXp}=9`%ocBfj^?yxgtZP;^?R4jLw zes-Q+?37Czk{?5N-(9WBYI&123LQ|gNlC*IbVH-T+JufkgZv^PNsjO!5^DYkayp}$ z83u-_OrT?zaN#PY(R8So-Am3AyY>E_k z;unHFm}th5jOCiK^{+~n3!DS3=*@>**zqrF$;1=h4%u`-fgnsyC8C=uRbs#G)vK#4 zz_UjStfk-EqBB^^MwwvQaT^`xV||w1^T< zmr!w_v(jvH)rJ7OYKF4+ESs`M>Mcn(^!Y7_)pFqy5M6s+O6)T{C^?@{=O42_4s+d= zS+Umjjrp`eUcTX;Ec?$8ahoI(Y$B5yMVZ)^h_0X?p}2cySxa+T!cdj-Z%||G=z}|| zh0;gEQ^JZ_QE0C&Y(AQN6KftESd^!6N#|k~Q%WAp|Fm`C@PK4KATxySdf)QqBjbgn zh26XEn0`-aXwN0i92zbCo6EBg3iYYAGNbcDQ%WW?hK9I^)&lZSKC%gCocuGxNSJxP zzgklrlY-t*b14h&;%knsf(t)zC653#6S|lIB0e{RDpd(UM{}~bx7UJw(SjYc#u;v? zModg>ZG9qqz~+s3F*Pc#79SQI4ESPRq6(j)rtdT;sHhR4p|MhVqJ%`Rj#itxz6Tu~ zHE+S5BxBb^03sj@e~BPLgrpw`{|X`l{ioXV^xkD*^}#>8F!~+TzYyap_@ZA3aLT|3 zKy{--ZX}+QnC=Ktinzkb5COm&0KYMiQ2u#B^7rE0e`lL8t1WW&^K6`EZP{f!JX&jN zE<((4-}nOMB34=RI`xtnJPZs)U!i~g`@KqOP!2T*7X#Oj*zZm4yhqQV7;ifMkH{rD zszGFyQqlvlx9|gg#0CQ*;TwL!y8cL5+N~y4s^vQE+Bsq(?U+F_qgI z#Ee-#7OO-sLcAW1<~Ar9?|D!;XN`0vs@9foK1i&e=_JQ93T%(z`(L)+blqL-@Hp-} zJX~7_eeq@Mc+F(LR|g+$CSHa~WB1;^{o{Dr-`37PN-)s}=Yw&ocg;x1^jLzvIx27` zv0-8|)(mzU_3Qi!Js95bZwKb?F+0WAeR-aXVoWIzE_J6_4$MyHVzLr&VP zAkcWks6{%f-gqWs`?3q~wkNH0x9w7wKQa)U>(m&@*34^8{(U{?yWdnagUF~)skcOo z1%hOif_USUXyDF4H~~35!8BLq$e^zf_h0=sm@78gWBINx@mnF_>iXGt8_X|iW&HvqG(2|wjV00f$xhjiQ7PqbnI ziw%i^>x~yN}&ky^&gY*^#x~VBebOQNX2=g3&HU&y)g5$nWi+f_SQ`Kk4Woy4CA#^`w|h@1N~ zBj`hfw9CAdeo>|;ru=g-ofH~evh#)VM{?xb@c~& z_1MVBN}y(j$7c3QO#N@g=+h{7IP^*KhWFC>&53j~ElWEwhu6(7&8SF-EdX0u+4;XW zWwGbNP4XkHY=s7}t!7_>>3Pa_cE=}uYXWW$rgE`|pEJw$qXhHBX-7+it|L1UqivN3 ze|l2_y>OXbPE)m1vd4({T*UzfExp!?d}3_u_CEF(=*@h?MOWw$ZYnOO0!@g*hTHVD zQvJQ{73NNhIlSY^-A1|jte!iz^%`fB!Tsgl=;$aRw?m`D-efHGHyhK}TCm^B``$QC zJN7j7yapQvsF?>(zRK^~mr1+dqejU*Wc8MD=mExi&y@iB}jj zt2gaT(_vy%#9nBz4w34TU1j`zW-(r0ZU0h;Vr9v1zNp`kxH5C(ev=CA zbNODt+Kb?{dtG7Tz&Kq-UrL2xV|#PO>Ca`;#m-n7oBr37L630iWrMX~di3`xiGb9+ ztMoS+#*HHn509>{Eq>N*^|4gtI|8bf2^9!{=TyJKT<_F-XiW-NMM`qsWDv-t#kZaP*W>Q}{* zrCz$L?Wjj{{kB=8&NV}=^npArM5?VUl`nlkzkX@zYj|^5 zZs`m`Pz5e$LfZ&mig(SiVc({p&315^J%`HT6@ACbDN$_+OK42g?&Cqh`7Btb++exL z{sJo;oQ>oX&HVcOzoLIkry>(gPOzEXbf06;YR@QYkk}jyC|gvz{>#_wK&Pder&gwz z%l33w#B+{EPwS5SbCl2fbZz8IPPI|UwJZ%H2$bk&4j~%P6EIhe&q(lCH;A>~sK>&} zE|4FU=C@@Y%<)PwTalMn(w#n|8e6tUJsXu_o;8{1l85e_E+kV?lI3o=HeiuE60qY? zqPi|dTWE6xF<$Ma=P=ES1*zPzXO;b0zO(+_W|H(j-s*S-JhX9!=$rXz5b#!dRjPC! z#PLgJ_K%N=aBx&jz}sU!-V1l1{$D1E^_lJeM@#^YUN#3y$_QnQBtt@bB6XWDxg^lL z@d(u~?DN086@|_(_^tOrUjTB<^3ki8@{l%n7oy<^ul?F7n6BI-r@pM@uIMDKDL1;#M0q4=cDdCd4f}h0a(fNs-}^1j zY_*bwfW&VIV@n*89{3Gb8q2G9Bkcx%ANC3|IKz?Oy{n(M=$&VLUE=r)Z9Teph+GBs z-FLHvY~7gIvRld_|C_NkJKK2dS;4PK?at|{4^GSx6S9|7~bKt>x;*J z+`7E1Ofs$kHU9A@gO}BEh5`|tJh@JG9W^oX@|{dnJt_F!EjCOKa8+-~P=dyroIiN8 zxXoWrP23P09I&9$W$>DI&YE*r@k!07USO!m;cz=%rQ;{O8^z;txC;{BV{-4JdUjcb z&1~VTv96#%&;zaQZ@aEm2;A-V9a}@j_%X0Ani%x_rwDMcF_XF z*nkqSo2x6hsO{ek`?ZQ1NNF$exn136QtA14u2Y_e%Eg;LfP%A{inY3D%e61&f-Bx8 zIHk!!J^BAuLZ}HSTe#lI&`5|VYxSN#4_u+gf55j|oe()s6UU3$K3lf%X_=rlObJl- z@)9O-H+|79c3SnKUqrFQcR4%Z;|6t=j%M;9jH$O<-L+oFX?;_inYkZbs6D%p`y6fSSo8>iijLJjr2CnmFEYw z$R>i%A+F#9SFG-md%&f)-E9N*-fXue1xT0z#0X500$@|ogipR(kcHz~uF4CIE%_4F9qy+ciIRC@ZZ!(B2tdI=QkHNzO6xKV%!wGN&yjpAQtK|M^ej6Vw#@B)zJ_82D26a>lM$#c8S)(e)J$``!WlDOaN{8_AVuh*C zaA@5+4iG6VYX8DZpdkIg801uZuSPibSU{Qa#}jg>C93O!iC=;Zn_w@s>bx88PxbeG z>c-hSf+0@1*l)K3GPpse${?T1Tu%CfecVEem0IE9iBc^8@7Q8D@cBL|B9-ZoQFgM4ijyL6iz<|7$1t{Hmk>j5ZJ z42&tPXD01RHG_yBZ=NU8jHjNYxVV}cPk-u$Y+3sI`}4V7nyhvFyz36b6va9vH+)SI zvPgwTMqli%4>{`ZPY~r2h`evEkKCE6+_c9t2Wsx;u7Ck3<(-ZPO6QbnC1Uc*h2Ppk zBfMksl~5uov|H0K#`XG32cE!iAkw4~#MT2pCsWngA*HTLE5iGmlC`r#8Dp*eWfzSY zelV@8Bmp)i(Xm+EY=NF=(w`!|H26*=D3JL$4)5Sxg_fKU=v4Dp@-$s0Q)n)lCn`{apaNBN)1BFZy>N{dy4~qS)OtS<@9aN;KbL6Mx zaaP%>T2(qZdHIILBR6pRM&tPSxMH4^X`MP)yJBi@+Keq@44CV{SgQ>bvF}Bro|jkM z2_S|>M$Ju4U{&X*BR}E4LGP)6*a=9kqWWH0a$xJRl=mJd`+M*zY`*+75{AHT>ciIXCKimFe%L&7s3z3JX&J@n!()Ct-h|nJfVzW4g zfO6myfYLY}@t1WI?mDykT1P6`-tjml)1%S>?^Icu|N8;}N}_zYpJWRZZuWO9I=5gf z-k&|6afjxXJyd==YWcQTdYcH5yLuKy>0Lsg;;>qHA{pA;#9hiC8y{u!T($kB^m2NQ zlCVJG_?h)$ttX>|j3JrxT}RndVr6>Wqx2_?e@93KOJ}`5SM$Me)Z!V&b>nxH9Wqb-gP&2h5xxLnNz zdzor!cp1^idQH_1)IUYza5Bt(+@}A`domy;L2MK3&qbRW&6sQkOMhM=g0#-lO5_`DhY~^y<8=y? zq}wV@7nZKx7){PM3_R9Nf%WC-k}lj8(>r&+JKi%&FWeykK`b<=)|TqSuo`+s+JafUU2t`tO7a507Mp|E5Y{Uz;636t}_mVNHsqhY2s``7;2L%h6Xlh6pPO}{< zdqDlm*Ha{JJQ{L(06rZn!$*jhd@`NrlPUXq_N&%RXE-8si8D)s4dRnkY6j`daIL^y zG@fN#)UPfBnuO=DWnKoBY?k8NNjVtsbtcqyHNZpB0uAC88uOv8RaT3J_|)4`f~T;c zVmC%6bckl zzHHsUJ@hy@$nXyN%FCUwXnLNBl#s)iw~tc^NuO`C8w%1)4wYrU$8`j0Ls!)VHe{5f z;QJ_$XN^^;yHMoLJ#TEpjYis?nSIwZ+AgQaxta+?id-y7kr`u=x|KB0O0MxrSJ zMT2N!?RKRf#v5g^DQ~BA28O&LJB)uS@aoOE9jos8=&|}8B#VwG1tWpJ%&dA*!WR@R z{*#St|2pk^l*#>{nozZFs3HzEkY?~Lh3jQfRlbw3+3;PvvKI$s;De=D!XRgPU-!)K+y@s-&ph-ZSCWaVDug7+pQUsd9ez+sie4Aj15j?JLDFJ zu>lcSHb8+umJLyc2LW#H<&_^X)NGBMKcd1CZNUe;{Q1~nMFy)^v;-4P@06T%RN)}S z<<7Rx-m1{>7qWAOlydWJ3m3~jb=g86peOkZ583B4{B_jeZFfF>cGZtqG>zX-4PQIE z0}+Tc&K&XSDy&LfWZq0ACAa%D*y&N;9Cqa1%H z2&T6+s5L|BRx~0>xw>1g844JLad!iB95PjkE=(9p(zZgaXeQH z)sVnqY`b>SgqMX!P%>ZWw>~=O3R&)Ru%VJH`f6Nde@seMCDBvB*%FoyE6h~Z=6DsK zr&Tik!Eonf(XpvsUQ{JyaP#Q6=+oeh2*^h*&1FNZ^bce%-OcobP2^5U%2vTC2#to0 z0D^wE(@y3$4k`JAA>Pt4!sB-$4ITM2tAw3ni-!lw$GzxBI~DofqFG;q%8q3+vjOs$ zK|-AsF|6P%9D;i@XIIXW2MoB!qhj*NE74JZdSSJ~@zL?D;=*|N$?<&G((kj)X{oCr z9@hgbe2M`hg?g&2{XK?=!sqhN#}cV=vO+sWBE-Uu8Y-Yk7%mM(`Nyg4awAu1c_YjeQb~q zmCG|&LNT=$Q?l)A&)5qby6_1__y%V5xI?cz%%71E6O%JhXqrqZ89laRPmqw56qS;)v7<6LGD1&A zw*2GsdOoh-xH$Z4`PU5}(!(l*#=yXEe2f%LjuOyX%Nj>!IIJ_VD}iR3EGH+25kj%D zvXY+u#mtQP9UrM5KP7Pw4Z+Zir2u1CqX|PUBrkon&0+cZaPDQ?!~A92lImm;sff{U z93e~>$Co5EE${jHXL`Ceyok1$nVplAeavpl79aO@mD2bP$@TA+4z;{}n(cbRc zWn_z}Ivj0nwkvVV_zf8$4+&aW;jITda?7%=B0h*&dY#pDL)E}=h&-t~cUM=uu)f^f zFL5*p`FnHup^T)GlV)|>n+C=PxiREeXlNucO;fB#iHBl{S*R*!6ychWe|48d#Ob&a zGpPEGwI}l|3ub^s8U&OYZ~|QOh>(CIGXy1ic8j_7J5E1?fyL<$I=0pd?5Op==HP0M|sb1!^9opZ33WF)VZMZ&R<_GfFS@1MvlY=BYgH5TOP6@B`{y`mTD;qs4GOJu&TG6JXE9 zSxb0%EqwD$P_;81&T5uYNj>4ivnw|dENS}JL)h8&?RU7m?g>bOFQ@&Nx?pac$Oz$+ac-kY0(H_bTNm=qQ%_n5Cmc8}mw}82V#L22Z@QQzkpwdw?*7ay zjr9$u5YCR-xy?5=d28T)9Khgb6Q&wTWUCC;oxgO&uCXAwI^neFE7nnYTN-(>(WMk| zC3{``SRN=n)_wPa+pmz3ZOp(XMFmdn}8QJ$w%VsVTm?y-f<&tvz(wp9i*fpX7i zo>*yOSsx6OiK3=*Llpi^WAY+2I+hhApWag@)y;l&&;pIqL;4VBd2xKt_Ix+ynAMpb zS_65fBl*rrpp83eNNTJp#es^YfQdR@rEn@&a+!wFDcQqphu*!(unw!uVTXCBZP}K& z&JLm&{woX0M_-kS(GZ+}g*R|O9kdx<^WqgbgD99=s$QX%cE85wa8pImz!ECU`|;|! zNME7o{!1A*m6E=JkUA@s2wLpdFF&KQaEI~GX(+>Gr+A6RAP~rml2OB=qN1Vw4GXS>^7#suqe!MVBHn!d zJl6ZlTsKs+W?5mb97dsOv5NW9Ct_Q6)*0W?=|E_p+L0=v=q(>iq_o@kX?*AOTIBK` zoU70p`LKWyvmv^AO8PdWV!U08nh836Z$p;a`_s0m8=}2}OC-2xX?Yi%mYc|;4I3yM z*k1d`?K|Vi#zyL%)B%&cpP)Xg8Yo1GbO}0i-|fp};{4-ruV+I>3dSo3?#^maUWu>M zW8#QFGzYPz8v^*t{=!*bUDV5FLql29Y3)%=q#uR=v&1!0k`0G@*=?vT9%K4C@&KKG$fa6v*L99o1Ng z5SRQMXUmf*gkT7Ipkb$XrC9_4<#9jcc&WE`Bw=(u*ehljxt&M2P@#a5-@PPeJqH~@2diBeb0p6XB^4& zL^zwG8S8Hb`UxFKAd(NrGW&EbI%83M&+6za7s(OkikePWSxDm4p^r;J`lcaq#qYUo zJC6=FDCNp(jIY+`!ChVi6ILlaqAr&YR?n4`T`xoR776c;V89aZR}3O_2WpHY_(-5@?#+7 z%WTmFbrieu#`Kbw;xr5l!I0ke@2^q)0!HeTF)d94oZ(YuY}{$_8=TQ}=dnx~Ib>;a z=Ikk(cK!_w5t`*dAk&~;_F{$o4ruW~U3Ya;tW82Hk&_;`ITp$@VD$Q|@x4e=U07{F z-sBtP3&ddGf;7qbtBt9(3O5Bq*a`aP(ICu^Y2YP_9}a0@)bZ^ZMYZdz3;g=SBD@l_ z*I}*lXq8VLDOlFu<8rhs9!DFG8GWa=r8#|jHg*!FM8!8s$v1T0veUOR73}$iIwc?= zZI91c3@&PfC0B||2OH#W1*p#pW?ec_9Nzc%Sp<1k79%z%tKj%p&D4rr; z5o7|@x()0tmu;R{X*y`j5`-X7hJ$>9HmJH4d?##&fv^a8MlNB_t&kioU~(thi&~1K7}RO!fVM^+DVlu;y!fqPU3z^X-o>ero2x5FJ3Bxh1q%soYcNh)M&^5oQsWNZ$IG_6 z-1p*C8Od5L2@Yt8S=oPa`T$lw5Iey_?d_Rzr;Qrb0Lo#d$-!2jN81lkH>2FRl%JUpKeeSZVrQKueK zC=8^cPh=+#R8f?Bat`&CUS;RL(HY;|IP~w2E}YMc*{s*e81}xR-IH?}c>z~cgL7t0 zO-<*I*Y`IpVj=kh)w}jA)pf%)lc8dc%J~bYqcDou zH)Y9SyNbVTDIe%;IYu?zQy)f;-WplT8HFF$)nVg`+;7=qW6WH(q$_+)awbclTPCo+ zmq%47=v#3|E2zR$ltJ{w;|$lw34m<4y1DuL#Zn+LQ&TfhQ%@+Y^Kfu*aB<;+9-m-< zHVdGvRo^&f49tNy#C3LdwXyjf67oGyF)x?goOPcg4ho1X4VZz+z+2nfi2lNP%>6Sn zVY-Ry5dc(i4uEAYS2w3tIbMVHJZ)1aNo+P9zRLm5%M?G#;A6HN=XJ$;P+8d1hrD(& zJA1J<+yl!-+?FHW22t&dXu5G!j0b3`Em$?woSq;smn!h=c&+SQR0Ld}2)K1>#nn|p zi|mrcXD|a5m4^p};4kYvJ$|{lF26b>+nJIe8&z}|#r?iY zQnwYE#n-EqjS1wNrp!p$^7;f)v0L$bkWod%!_7T;obJrDih?qOxtetK4YEgOFz~wv zii0Kkn>=lf^1%bHkCFM{fGcYTGFQw*d5c8u$7GeJ`tEMG=~1x#ZbMmM4Bg}hzQ9XU zyy%S9DyNc}zEjX}P=eR0+nSJFxz^f5^;~3|tcZ&+Q;M7ZJcka^>D4~7nOk7+Qg52~ zmvk`1_4|>4hY7t-6xY@4HDOBy-=N(at7)1)4r7?S1~wYbYeZ@H8($U2Gl`TKt?q4K zwBr7h*kxpi;K4VckxMGPc+G&%2CBG1o*4wZx*KHoD9FS;+ME0GagS^!@v}GvfLl82 zG*(IrU}!iw#dl^RkVr&(7&0tGeMuhK_VeR(b`}*B^cgT192_*jNhS|5`>XHe2TWK7 zauMJeGcd&KCVD%d)swYeUa|t5)n)$=d!htcv(-+4Q z!Rr_Pyq}3Q8xA`}nicCN7o-o`3D_^{)APQ`%i`fW(P=5N_m5;MBps3qfhZiPwQ_W) zl2?qC{TYKo;m|NJS6M3cmIGvq{auV#7VeIwbuK*2=TKRnxXC;&W>OO#@?b%GJM|2U zc0%e|$;9^7a(^14P-XPcBkb%LwVLE=#Oi*56Q@erQ`*UzEq+lR?*-<|JW~h#ER{x= z<{-d=k3&{)Q*fQY_tN&JMF6pid+FG(d9hPq4m}RCTFv%T+m6-Z(njN;UA!DoaSA~T zu7_<5$X&r-mmd*pdJEpDS7DDCJU6IW`|&G>D~LhjH#<5=vc4w9#Q`&X4LfPfYD1ewTnr6F0Qw^nD*dZm$BVD@-DNpP z<Pw%pqG5~YvkR6#&x4kJ(Zr8T3k*Q(?6ejhL}VFThHogD%|4WL zvH_iVo2v|)jUHq9-Mhl`xZxInuhYVqe=skM$_s;KK@Avt`tYv9) zpL4FV_rCUJ_4LtnSdRCqui-Erp@{D1-EQYK?sw7eYRdys^toqv&aCt!>A4TUreICb z=)HJ8q^9~80^xhf9Q_Dwg_Y8=tQjr+_}svC#f!W`Uk!C@yWg?QUbcOEtC}sH_IT(x zZ?+4a%ySH%e6MoE8TnU{H~8K?>WJqGxYs{r>xv^;X%w);+8>m&s=W2>S(@HOxjfB& zr+T?^Hn{F979nxk{C!j|KkN_Psr_L9XPT--fKjJ0@7Ma*rb0F|47YfmjDw!J>j82U zeM=rsv)4pxENVB~g!xN3^=N)RFG?9(*E6Wr{yJ3eidfqtA8Ua0d!V2J`Lv3H6a;)G z^&bqYfWyLb0`d2z^L>54VOp2b58>J40s?b2K1KGjB0Z2;DqQ#)Iy%nqxV4#d{YZBj z9TYrC3OaN-3gNO&v4BBRqbnPR)|WoKV~-*DT)4O}{o~@*#Cs6Nv^h&=_s83#?JGUD z7r$IOD(K+LJ^B#Hd(I(TixhTJs~%|4ONeZ^bLlr8ZN9Fn)WXW4v#{TmcOM+o-lUr}eR=V?-2XEaA^;N@M)q+)dX_w8 zTT7oqAlmot|KbZOGwOU{+(=G+`iLOX8XS(X&XjHi7Xj>}I`LjkH_M5gLxgn$|0ku?x9o0jRo)@94b}N*h>N+3SJxgP-`Joi`b?`Uw@n4;cJ^65 zpj~)}O|4ysi4%p#rL9xnWj$PR8h7c8P-uNy=J1!cAm^rSJ=?vcSyA8k`EG;fSY>B6YkWrR5Q4&KS5G{_h zuAhg=q32a0?pAk*wqyw)cmg>XJCzgX=eXh6Mg9*I#K@&@T?)jVFEIQr9xbvIK7HAo zH@{;GLeB4$Uas)-zRLDn2=Np4TypOUsc;)KFALrfsRWkNPfR8p?jAmcL1euKOoI-( z%5ERlnw3eNeCBY!jj`VEa{t!%dxQXS|EmB=zk&u8O=65viQu3hs{DX7T1i-9^XMGt zY#zL&V_`|Ni)Z~Ba?iTlh)hxEz@KukE?9c-i1gj4s0;C#jaaNTIG4Vt?P3CCIR&D{=SkO}p{7zGBuzgPdZ2i<_EoDUhqBv;?g z=+uO?d*=Z6PecQs^isrr*u~YL-rAb=8W6eD)SEV&bgcec>WqUW15=)V=~riLH7h>( z_NaJBfFzFM$F`4w!T&}|2R!GGjr+1)d!cO6$hlp((lT>$oZWW1nu)>mdA)}g1+F!M zWB7-ii5iFAf&cvS!H?}{RWClp#0>PwnaNxqUTmNJtqJHIW%TTu!*|TV+l^B0+OFi` zH(_`vn;5ck7WQsZnORVl6P@QdZNOqd-xKjLc#6(0Ko)5n&xo_;bC zxh^*A=WzuWdqTipG`&Gz35dHYyCL3q&0X$027xKG`+!Cyi@maWQax;3C8?IFoC7bTk2xATvg?a8*>YNL+n(n&JnPq6RwL@-7R=TaXFl)IUqefL-RURH zWqh9i*FN9+mxt)hX-l^orfqu3gSXs`1_^-Qjo!XbS`UD(2lBH-Qy`F=9-_8&{sMH)O)IX#{q-N55WAa#a9$CT62mI) z1bLlzi~E2~ujlP9I{5cgG(dt%nca2Nj^0o3jER@|jwXi%AN*7_?i5O~Gf8DfAm`e) zj+s`g%~J{4<{O>#w6w_SPlVHwwW*t|`(u+BM0BZ}#@9OSA}Fw}#Pe!oSygmGO)|jh zZC-U1&L_u{nq@+CBzK~E)k<~wXt8=MwnY_+LDL{avg_T3EB8yZMv7){z>C0Ilu?yE z^(3&`v>N33N7AOo#^3o9nMPSd@bf*y(Y6L;FN}>L0tS}9y;{e!HVvzu2@2M5J%Rkx z7k#trUp385LtM{`kKL1LBpw8Nf^wbPYJ zc!L5<3kx@DrQhp)T(pb89V%Hr(>K8^eU`w_TTcp3g{kK_%L!o*7=7Lruhv}fUdWqJ zl#PtTKkgLWCsQt-$Qpb&wfzi+O2J9C?jxc40d=#n>6l%ab6>LP5h!#*uo8rZ3A|N_ zmiOk%OlP;|oBsXpuu;6t9*rMA`VU7vy<^U2#7c1(*jdcAb`)Te(Nlc!haggbQtID5eXsl291Y@J zb@6?W9$Ib96?l1hX-MDuFp@d2Q+kSlg&@0Rxj<4<4+6lO~Yya0qFS+7E6AokUUFI=~MBXsHR#~xfp z#ah2p8&E32LSpYhevR0tt)GLKPJsKo$g0WIb~Z35q3a1R??P~+mMGcn!J1acN$Aij zo1m3VSDLiva+%h4!TPiBZ{01uMhcWnU^I42XMtv)LS|PjJ3m^Cf}yA}7g&+~O(@3T ztRVDAOLHHQxqE-WLB!&=da?F=9L6Fhj0d5+ysS0~U83zksayRSPwYC*eubV}^Z;H* zc}X?E8Wk_f`@vi7cZM87Lr0_#@vl_Et3*xs*hL-CF@`N0z1EWx{71c)Jh2>9fcVZicJqEfaKTG zslekup%={}*XXdNHY|}T*896<>LvV=m-EARSeAjG4_s^~Wmv9^;BoP*ag0G5l$-)p zCHzunzcU!Cl<>%m(|uioPFo|@s%0)d8JJ6hbaR+7cyoHJDcrU7x`k<~+a-mKMr!qW zfw=aw{ElVBe&@SS=Lq#a;eD%03D0k{_TpIK;?0{w>n(5*==$UdzEa)c(U?2xI%<$9 zOyPSH7UaAA=|mh0gWHTDOUUnwms3uPECFjQS{=FM$1MI=6FlaSsn~*`);+P~U!`P) zt^pU1A9dK5RzK@HUp%|sXx9DNa{At{X8-W}4V}}x%-+QpwEOLDgT#MpjQ6gqKVD~> zT45Y&uC=4JJL9qD7`w2E6BP#qNJ#n}5prY#IU~((FKSGyXLfxV_o=5H>G0%!feNC; zQ-|7jZ@#FKI~FTv-yfBqRi##>=z@x&cAog5O&fxmzK9`9*&AX$^9h#P*Pgve(RZwR3Ey7Q4Y01 z9l%wwv|#=^lc(#t8Wm@zHGe+q@-ifHFTNqI<@P4eDCB6%@8$JKQbBOzZG=p)n6sD6 zc^~H?=RyEFMp~jqv*YTRxXEK>JZ+twv1sr0hmMuR?XWOZ%YnJ=C$`~3zQB`&6P~mm zO&FW*I|dp!kjP$bc1kvadW%}Sr}w)Hh+^a;WFbx6CT93_Pbq=!*cpcUzWyo+uO+DO z5m8B1rMQ^b(%B`5XIu)jiFXure%eYtodi3rTK7sod0$;PUccXbp2t$-zkHFjVdYsVSbUvRLPj& zVVrIL%Z1udpD}Ywv7=JU;E-h+%=Xc_q$UY4hbRLr8HKFD*YR=u+x^r1kbRzgv%9${ zK`#O2+`v7jK@!SXGQX4JA0Y<|KZv_K{=BDJ3>xse)kCc}h7czXKos?*n6-?IxapG) zf?xUjE7uuo8w(W#x|(u{AW1(-zkjFO7=t671}g;}quFn7apD+x;heYZP6be&SZj9G2U^Yz zL!h@Aun~j^96vJwX<{euGyv2)vvrjIN7BMDa2qd;DXYckjNhZMf z?C{9?X{S`iMvH<@B5 zz1Kj$$D}={0LibVN5gFeQvy`sH4Bdf(f0Y(nX!XvuA4V6x-Rgazuml7b$LC#6xZQvE_~<-M{Nef$`&Voo zej6%*lKIBGd*0%&T6xD_Aqnl7?39$d^tt1USB}mDgD#Dm4XX_aBR@VsgEAthD5USM zyd$|UllNyisSRD;=^{e5Kv^T~eW2}ysBg~(dPO(~P({blWndvfpv<&ytP+csc^;Ju>AA}k_QVRTNY^NI1uwI!3qRHN9iE8ju#)BRB>< zA3p4dj=a~!fFckSQWTPTFU9gT2LYfB1Q7b)+G?z4G#CPxMadwe^*$NZemJr+KD(iBQKk?0zqWUzAlaS;6w>!h z-RY{>;DE^9%Ym5)VnNy_S41t!G$l?tA}r0rPM-DpG3D#xu3J0gHG7XpjEem=lDYbx z{v{v|F7+qP22JR|w6+arq`6o_O9zekjhPZMFY0Kq5Qm4A51Mygu5IrQo|XQ{KWt9_ zZkGJ6A`!MwA`b~4vb#B+yA<;O&O@?zc{JiO*2VfeYkTbpFAX*Ifpp2e{ zG21ykRh;R6%F#HB+SChcI6M{&h*2MP=Ev>H8x?=B}FV^*^>`PdN)h zRxHPMc+0Q1$t?1Z_q#H_(-_?T@>KrdWdo6IGIe4{Gy2G;@@6!p$FT_YP{>!SaFB^Q zoAVbziHk#a+2T%4tEHV`t~;|~(lHRfwcW4va)h92tZV0IaxQ&tZT%L*%b63Ki0(78LFfp8=Rs!} z%IPc07?Dux^=TFIveMtkEqqAs1)BW8+R|V zBn~`-DcZ3dZCoR^Se#0nVyz!Q!h@xasxx%r3QhQtmuUFAngEkN__{DM2>B6+}O)7wwFfS>vh z>16usU(iGuzXjgbiLP#&U@y%dV)_Z0c4 ziS(KjcDvLb-WGEu)bmQ@jrs#|3FqJ!r8`BlH-_urfbwD=F@l!rloSP>2m_@YFO3jP zn=foaYi^~1O?${$!;FM*dj`| z11t0=efsyw|6bpCwXzfR?cKe?w82qJ9=P(hUS7r1sXsUEg3VJdGVMU^JprXk9(+-4 z)oKQ&%3g6i2aSIti@GRy*}*BF9M~=e??5$m+Bw~ByWG*1Et-rd0IsugW4(V{nxwizSrZ^ z0h(Z8w|#4rd!M))T) zJ{{_YSye?H8l#OAb|*S82|R~+spaloTeB_Ux2OM(Mo|Y?oUVG&5}j8__MLy2%9bc^ z)fHtVjC;81Ws>nImarZ35^k%g)A;X>S%?H3FHONUhCJ-xjA*OmbpV;f+2k2hp7Y!m z`1cxc?jW&xxW2KF#CkBUp99?)1^uqR7#9nW4ofa>?CvHiWy0T(h|ni(e%$wlCP+0Km%yco=#A~DI1H0!K|1q+gXFxHM6dU;yyMqD_?$lm+-8w*j407oG=iv2M+zS&{7r_Dk6Qn$;r zK4P#DZzXJB*cwkMkG3~N2(QL5Zod^{p$rU_^<5SCOeNmmW7%Cki9*3jIO-*Eb zhh7rN000!zuMfN>e*w3u!c5LVm*S-o+k@AOM8yClVq$mfu;8XH_GEO2(o2pxA(SW* zOS}jo!ztiNNf*IgD(o}>3Fi1x7AW;Qv|ENoolA`;C(l(l05$&th*nr5N}Ui~YDE;w zUaj2eUSLZae(S47w0G68hp0TtyHr;(gwK;v*}Mw;3UfX`c1mkHJUh1s=bvU`0V35H z)k>sHu+)8fy-#c5j}@<|s6!_G_t$eWu@xV_2k#p$3-xL`*A9DXZux=qK58+@Cor7Tx<4=NH$_H8ZO4sNRtu9oA_p}Uz{&vV>o3280bmoRU|_OfCIUNBIX z9ADzRRiWGQKo9KOuNROjn#+bg+As8q|^#o*QGZ53(0=4^=k>t$S68~|*h!HByAwc_lx zx^j)44mAfS7>_~E&2bJZ{47WPKP|xF*RKLwgnQ58oByz7h6SJepykN0{JUCP(6X@Ui!Z6}{`W>M zdiL+^G%Y4@&V5XJ<7(;2!-F*8tK-Axx8D7CjBeGh4%|b2^9rA-_D`A!w z-R%!pZf;sMldsm=ZqL8KWTaM*X`zQDmy|4@E;AB;a6cK580@V7=uaHQ{&0)Ku|gi)9>q33N9^$9L1L}O3KR0B+myui%S@jxYoA4#i`=ogE68^ z&@2%`!mW)f^vlsMo8AayfA;s!RYWzk{hAwI0l-ZPVqc-}3iXG4M~7~H^&u)6I-39b zl>mkc3AvVBEZ65Qmk-w2X#vj>`O%+ny2Js#&g01!FIxweJc5r)SWf&UYcGXSP}St_ zu%Y@-Oq4}0Ww1PQIDbqtB~L=azpZr#-!=y|qfdTj6xY9J!}`AFf!B8+%jG#AuY5`> zVza5Dbr_A)zQ>hGlzTbr(6V0Aeg5T9*pC=WPF#A#6VET%%E8xN4Bh4Vw-ILr_i`^S zOpH5DWCy-#mVtPn{kmehGW+{`-eKGc6J3&L-%bNVmOQdpUytNif*`-?twRkuq4j83 z8MjYv5ykF-zqU(`VU;39`}=!x6m2yyP0hc-`cG%=5Nm(`W)*X}`C?!vPwIsfGKi_%Pm@F7|HZIJIK$`q3Ti-g`WT!0X+#x_+ZG`X90hKW~-1gB_vH-$^}q zAXT9R39s2+*u&xPx>|PfW=pl4D#Chp4+3ed7O^;)-5r*`iE$yn9%Dj>$`He>upxyt zSP&=)4ubb91d_+9LM4l{)%+**NalPXtqppwK_a9`L3I4K)$)V*Y1a$)^P2$jYY?Ot zg8jX_V#Qw=cRT_F)uwl>JXBGqt)?V)3=*!HD6`cDESv#B#igL0nl)@^XYxgWmnIRk z&2jxYRntD^FT9s*=$J1<|Nd!sVs|a5MtRK{*64!r^+!MaP^g z#q0FGrE>K4H1t_owt`rRP_VwN`*MHN z3XMV~F8`gG;TjVW=M*MI?m%H_$n2t`N7SppuLU^4D-HzU%26lAEG;o<=xbIjTn38oJ)>qx0UF?URbS8@#bTu8mdnEjGWd3B<#|ikLH-li_r~t)-&);A5WhKa zDmF59ZT>&jOCoykq|$(!~T*UQJEtg z$AphWmUCD)q=`a$^c6EQVSRfi0U*B;!sHAEb9m_f>{(`Vfr>=6*r~0$O0z0r;LkU2 zGKxM}j_}FxaiR1>p>u-&ztYzsc3bF+_@YrF=8q(FZmMLD|0)x`EDA$GN5Fb-=O%3A zmjYfQy#dS(AdM(+iI(YO;nuaajylQ$$%8p6?4-}Z!~?K4Af50>_(9$aVKXaCTp ziGHvSfgF(!C^_7+5?DFIr!F0+_fe%>_sk%<*jhgLgjV-td{H$Gh2!>q7KNn#GGd1Y>x(b)ft>JBwIGl}j9HP`T?&9<0!&H~xYg{_l$-9h(~cFl z2Q`_x37@O5g9-LZaMRQpd3L~>$l8-hN${e;Y>Gu~iOtG=wcJfYG?K7*f==!;VAm>P z*_Pe(2}MDj(g-ABBtUT)2S?Rq3M(SFJrjuDqc9e=wffwRrq#3eMp%`3o$GKRU+Nvr z-gkKn9B%OH{)4 z&z`x~ebA9#q83~$h!KuMt6f!b3f!7XwW5?k0ba^@E4p&SDmSi7xd?r*%1y&KW3{dh z?B5V;uUU2!FJ}GoR>d3iLHgVoY6Is#@4TC#Ai=|lV1+NA1TvB4a0~@(uZLS_jo4?h zdk(_gB4j;)S@Et~|hvdAr1tdaByn-Yh2{Z@v-{nq0pdz>QVEjjgKT~vy>7Ov> ztPm^lCsLjh~Duf>wj~tC}AptfkULi92!jIC@fBR;gQmGu>ckA zUhG!EGu^3`CBPB@g`|;D0;@_!wGsC{{ilbqZCHbZ1WTVke?o0)l(k>qSk+}^vd6Rj z>1;g9VM1Xof?8DPT@6E88r28~`Kb?MxTQN&&Pa|ILEQ>4G7?Li||m*MxXcVB}v@Q#dC$ zr`=2Q5qTpA2dF+-h$ceAEJ3etSOvhE#1>xBnjxHm^1m%8ozZ!jC>S zYnTN$Dy|&3JwwAF{Q{`@b$b!6U+SsCvGMOwQnA)=l9GNn8#I3Ii?N(IHEEWXmbRx0 zkODef6xA|w z9Zg~Uq%fEHXZ+~c{qAie&JUtz<#JRrQ>?Mph1=n_$--VOB7e*mVQxEaYUd;>`$*P)TFqm6A%ZBr9 z%i9a4eSc*wEiKTuXU6a@92d?@fK9rnH)G0#@W+IdWq$X(8botl1+qwi6a!0I3~E-FiD}fLLY3MOehZjHb#pUCQkIVLEuI|f^cB{ z!LgE^$r>oxv6&d^(+OCC4=;M2JTGY5KhIf=iDptt!G(h=M~*`D=37(!pU=sB7X=06 zdH%XBFZ8@U3jNOS3Q@v2ATut(^mKBR?pGS{mJ;bd$zfN^k21{;|MZjBzGxX$<81MN zuHBQ#KI90cA&LFZgqeZiuA=9UdtE3iI=FS=>Zy$(mxhWu9}q5yEo2nf=I#(}xxNYexmfGe^kq?_ci(NhLn$phdLQTPpP$1~U6L#F zK0{cLog1Pe7khM(L+CbIM%1cJ!ur+KC_}f$?W+KoP~@;y+ZJN@hoal>uO%WO=U+I5 zo@kxD%{0Hvwr$JfBlq9*TNJ;QX*o(gdrxleIcu^_fL*ZgN%DNfuRCD7yO}l@qa1RG z7$(Ci5XycqWJ>9oDki(yx-2fLC~xf8sWlSJ}EPG|9%yeY5 z%y~^Rh+?kHm=yt7_D};gdbJL+P!$b$k8X;VHn^V)eq_|&a z`DybOj+-2E8e5P^f1Ai4eGTLV#C)AsSIZf*5z^g5VjH0z(*{N%H%A5dkolnf&a|{N zmdlwz?RRd{M)m$w5tRF2z9QjTEUzY5IvKlySVv5q0vArzWZGoL2WW9%Io$A8NJHfEm`{4(={jtAJ?l{ zj^_nq?(_y)C}_xbbxXe2x5s`90qcP0_xrmPH?~Yk8vYq;@2rU;eH{Q^WW z9hH@#VLhAPhE)at;8$RP0E4jSY;ChE4YL|mkH)0tW%dh8%&QDkQ;nNl@2LJ1b`KRS z7%N)BB)Va$>^%P)SuV$&fEfS=fmlK4ASzsbFY91AcbT{ud9<#UiX56nKda}r-*cQ^TBkpxnoVZj?SUwzutSKT zg1PLLtxuincPxG9Y4@%sdi5F{raWmx=mnOw$9CFEz0*S^ui-m`@?HFdF32McmdNV%SGRpm*?|~h+04!_F z;ra$p1VGTc&QSY8Fe>m(P-mAvqe0IKK+Fl_{l12KwSw?2j=`YOnL`>0#T!TGsYCCP zo7vz0YZxk#mP>Tma*-R$W=_sT-jD0A15ZOjadiJuI**aVQ!2?ZKg|L+?>1fP0fDV_gah8S&$0ypiXbd2R?ZO-^lh0yPy?^$P;~T8 z!@=Aob3$&{QX-2qLV&HvAk-VdlpGc&`PI0I{lYE)VsW2_#0QoN@sM+r zl}(`#6B|Ee{p`U&JsT!-?)CRGOXyYDLNn&Hum7yk8?eOp?$q5W{4*JHCZl8QgTZ<^ z*G=7(QQLSG!qax0#b_KjdP(L-Ur%Dr$MhoK_2zW2TlzAQ77U&{H@&%29tjj}MwTHb z_Z@OQClqO`ExSW+Xg|)3$(bV`-sPYsl6U+k?v28^%yJavx1u9s`(VhE%I@uV_9)G~ zzhB}%ll%-53IGy-Dl~DxBbSTXE0VQvO~OsshyQ=z`Nqb_;nmH377uar$ng);+$VwN z=x0FIUT*Bbx6!ue)e5v~sg2Xl(`I~N^v9a6t;WZv^!EXP=hj3G(I<*V>*WzTQ2J6X znc@0!+$|q1NGdy9G|0?Alf|5jA0-F36@%wsJ~9#~YU0W3qJklX73K&`&9Z0~n$Lk) zg_B4*;4e#eNWEuY%b3J*57)(Tkk;*N++HhZP~R;h<;{=Xmh02MW6U9a+*iteS1VG= z!OfX{fLQJ~3|)#KT`#!rw}l|%n*(!Ef&KB{kX7&u6b;F=YRCPQ^N1heABbb95Q5Rc4$Qd^mKr5VRkG&;039X2gA6 zGVvO|`6|5lYUn>*bdp!Aan*FMjmj4%9!#}{l zm9_+%y0mGBi2#;tx}Ye81A@T7t?9bD=U3`54ZXAzaLmM~s~-nSf#;LqA!s{!x0M^A zzO!00qHp}}>m5}_r#2@O>x1t~c{1>F=^(PJuW~HuYZ8I+Z>%-^Pmi4X!-1h(5izM9JBjz2Jk-cVYuDu&?{`CgH&JlLo+T3JQ^@^R$EiNYor0M*p zx5eeaQB^WRzQ>|ggeFnW@yB)(n5@%zHOCqqYmFOKhxtzuAJPBxx$_2pC(z7;NOwB6wVkf+Y6phBY<<2w^>WW ztsToE5n&By2EAbEMW88=&08&a3XEa#O2wNasyy@$uwmn{w;Q`uun5&IxA?`muc zbj$oY!&gZypWb3@84htlj4vNN)u5A)S{BV;r$u98yt4+E;}weeGRw5T7PZa(Pr<%{XnU`2V=5xv39D|AF6J)Rp?&|4XfQk3hvqM`BI)!_k9x z7_r79PSWooM}aH%dVmtBz3Yt2rz@>06I$~$lKyajrOf@&cZym=E`Madp)c5KsD3xR z>LJQVbVrKWuX9u_^^?c+x352CS?Q9L3=DXvyz!+!oLXv7ZHYsA$RK2p*k#hxcjB#5zpFMr%q7Rf-0?5nZ=BmF|AgUFP37bqv@_Z2 zfeTn=#u1X^Z8}2nigdVEfV(x^R+{A=0q%phT*E&k{zEc)VTzPesaN?k)lULpz+%p@ zrw~~=V3WT*;|QgXSE!%m9jx2sHOT*V_YE#~dC8^dRulB-6_|gAd=Hk6!+UZOeBF!SU=l%od#)VeAsJQ+nu9u|zXVe&mhb2X3(IzS1Om!@cCU03UfAPmO= z(_T0b*UFB-+a5|dlS0XaY~HTLiQl_|m9xvd(en=jbsMr8RPv5(n3vr$;NH#E90Y{a zpeNIY9j;!D1o#>OuAA_SR{^GYZ#6H;Oz0y{-aav8}6HAJZJl|C9kgr0SfCvt&Kimo1z(<2nfC@qgxdTBzcp+>nt}iNmo3oFR z^!h9q#}{zW(h}^p&W6ua|KDiSa2^?=s?K@35_4P5^$qCW<6>jkRkwP~1QP?Wo=JdT zPtq@%_fn2xT>l@okFj?pYD(f<0%%+_)c&xTHk;yt_SiC@!sbUK}x5=C@o&b6L&|wEDTCU6BT{{@PfyH^|TFtgqR$3WqN=y|BQpO9A z=vC-fPS+!wY!lA(Y2@B6e{zJ13kVqVW#+)TsQw*_5Dp4T4iScUK)iEcY^tAFrYra& zJ#w?M3Y|di-CLD1ttxfK6F#xI70ZA1y9vGLkRPy?`)aiH_U4it5ZBI4ZCr*Xyo@M| zFDmT6k8~1>ivzJCkTxuUb=RV`dqk*tC(= zBFI1pR*G_YZnVDnp&f+wqw|D;z7=+fRjRzCPjcpz>ZQfjJu2*z)9ICl!>Q2Wz$LV) z3xY#YCp2t)(;Mhhr=~&{eCU1xoxdBDe!}rXdwZEacc*pIY1Kd3lM@2Sw!vtByl4Kp zpzBRFh6)gdxIn|;Dhw$6$<3D}>SW~mu1%&)GbclRzYVfDw5b>M%YXI=-02_h=)Hcv z!yD-lyi+&mpWprWcj8&9brcmCL_zTrkZhzs>2BN39D8&0_F38WegNlpm*w5j)hf&D zt;te#u#Q&>Gd}Tqq}N+y-$Rt1O!>u=$7$Is0XGKL(o+^Mbl$lN17R&W2?-p&N3B>f z@~HHyDdQmcf8!n^oq$r2I8v74Gf5LRQF_L(q5cBfL;^!flWkx zoPi0+SnK~9?w6tNCk}wZfTiZqe|ay)N0vWbo54nGW4*+lciTGDF#s$F(NwMU zkt%nl`mR>o$B#3#DN5d&gaUc20+Fn&^D_Dmjj5MjThA2SUOCjFFZcYqgOsM3qx)?Q zL%sV~WroS}gKP@m3_nAKCOj8qMbPdc+b@`2%L3Iqd3S?qz#YG1oBW8qL!2 z|Fi&q?Xl&fSXB~=!6e_mPPWLjI$Wwf(}NKWb@TRSrz06yR?VnxaLv(Weyja)))hn{ zl30>{F6u+a;G?b#!@_X)l8Kr6RheF^k7Z@G7PZ3kjB4gN{82i0Ncy9l5Kd6~71HqK_c86Q|A0o1x<%IU+8R1rxC5t1l&)mTFOD7Jie07ABy9&Y1ZuQO4%g0e&V z>*e*0zhu$2l5~NAfsfWA?-mc-6zmpvadp)&NFS(nQ8Gyeg`15Hz?=aA{YX6nXp(H| zUR&?x%)PX()5<~;hKHzy-^Yzu5+$RxiafxsBj~#;wIhA-nM#>C;6LCMOd=g&+h)k0 zdGD-lFxT^7>%BuS%uG^%BLG&Vwo<+w;k+?+9_=eDEM%v=Qyx4ULlozXlTe&jzR-vMsO0Ie;^7^XRoNL z;>p%1l1mgaIzkeX;^1KyX>+|^{;xvc%7hHkFw%6ScW|Z){L0wd+S+shn_@t=+x3u( z6uo@#*@lpD@M-ptp*l7(g=zuQS1ta8NUj75M6VSA1Z@9RNp)1Lc_L1(fr1jKLR26E z5Nbx+(-IE2l}>a?Wo3lyuRdb_`F3ZZJjU;VV&NIgX8iqgVu|iLiqbOwTeHd;_IE2e z{~D>E%;g)f+k}?B*eLlIyJlu)$ix2jk7hr15OhJ>PiBD{nYx%T(iQp%z{UzQ-%C2# zRf!@6fK-o0{j<%1ZbdoBNQyx^3iVYyN&lo8xrU0bGAkX42W*OFSDX;{>F7QH$e%-I z`$>so?c6TX>5F~Ck)&mn0U+|nm&CtDRBm5vY?Kc!16hm{V)Q?b#gD%N#p|BYBuX%9 zLd85P+XC*glj)j+sJQ*(7C<IwD3zy40$w60h1)a-7L(L|0p@Bg`G6(Tmk|$GoJcb`c!3*si zV`3{d5Q77#2wcFDiBIf9t!7Al?gwEDT?=C=iHZzW{JV z04guQip*Zj%n;B+fo-HEf@pkO&Tv7I61$X+F!9nZ@EAHvt zlR!a|MYJB^wjtJqYV}?Py9N5q9=;a6g4RDzo|CYJVv$JEeQ~mwcv(vDGu${w* zEvfGA{fOsOG0L}s*f`a0@V{0f*Btyw=fCh}vc}fOB#$(5+|Vm(k*sSvjK+=l-nED4 z<+7|m9^~Jp!@KqjhACTOsl9U^q21r1!fw+rdw4!SKM?1Hpr9v<6QUrv_;)h(vv0T( zjwqEw&Bsloo<4n(8^fGjW>H(Qr7`DHLjPKYUG1OhGh0JR#}pEN>Zdm7$@qvkR^Hp) zon^Sb)eNuiHeuxfCm#&RCmW|zkIp}^t2U_IGZ!7#i(rM?nGnS|CKLxt^Q-=Z^bo}a zcUt7sstOQeefyj=@Eg?RG{h%?r1D=qa~Jo)j>9F<8Z*A_Hv6Wa#tn!DqaW5U1-mIa z}HuH#8{0|QK*E&gO;Jue8O1I-gQv03HPqss^5(C4Yba*jX+ZjN@q z5U&{&Ua};3eOZq8ZfnH`W<5s>q;C`%$#h5nzE^5C6H&}U@ZPm?wxqH=2^7- z@t;2*i#z08Jp*lET-5b*c>n;lsJ*Ko;jDIwYl^S~QWzl;)S?VP?%#gGhZN2LHUN|) z>1qJ2E>89?d@U!o0e++%)DUIK>kP}w%aV(bye-FELtsH9PZ9n0?UJGT7f%wYjE}rL z2{vH31w8+tzE!IbB5xmffe*Ao_Cm1BsVuoWko)1+Lrk%%D9kq#8eHr|mys7#|5prQ zN)g?e%$VydJBriG`b)I&Bw%hWlpxvzES>_ZJK0r7$IH}preZ-m|8ibMXUgUFUXuQS ze+N*3?D`sT8^CSLIKsZ)?h*~Ow*x?Mb!_$NNuZl0)g{UEmf0QX$lu@_L-pUHh7`Et zzUcx6ub&HP_ynHh9kj+LGZ_8pQ}Z z6O#N9Ee?O`q)E<0DKea=}OeSBqhvC^5Gx#uJD3bxdv zGp?7`f_fT?2bwXJZ18RN*?4qxr!0J*k1>BX@8xVshCvzpVc?i8-#{mqZRyzCKwvVDgI(+1A zGzBFt7)$Q3C_q*K2<>e$Ba?+WnkW5fw7BA(i%b0fL)2LZRrP-1{?JH+2nVD=KtwtY zjdUYOOLrsPCEejykd_vZF6okz<_L!l=?3Y(ufIEYuKzgBpyTYl-&kus&*!nLSID2x z`5D9x{$~dl=3ExFNxi1Q7JE)#zKJInRP25F1ibuA6!E})lgF&VV$oBD{!Fiq>?wo^ zvXHBKv5DU7`wwjZxpF zb5ChHxoaaXf8Vx`oz}3%aEivyQKXfmrM`QIv1t3`6dCk+m4#NsXhT7Jd>+>^92RXF z=yB!KtK|8$f9?GCzPW-lCd{WTVBn?SJ$jyvo~Ccf@82uN!c^4h>FL&u&(Z@nU6#vRw5i5fd^iRQ5n5{#H_B?MDSc^6Bb}>3^CKMM4)!9om{yY44HF{SU$~_{?$2f z-pLWm3_Js#B^o}fVO!oyTwFB^w)Gn>X@->;vb<2Ac;j@&zLgI%X4P+EX;X*l^y0K5 z8wVVU^(%hcp0BQ2oLs$S{A9~Rj?MKoY#8J6`p&Vj1-@fm`&pM_$S8OxZ7nM*D$1Ax z#zA1E+n~>O>C@J0!%-KCV6#-BzzxM~-DbDs2un*1>t>yQZKCpq0a?gnpT=yrPtJ_zBq2Ifh?Rt88LI&3ZV%Pcjgp1*w++nEwDhobVvRT-~m| zlyxW|(D(xf&?rC0jZ!km$(Tv43iTJq+-WY_gLERjg$RzN7DW(H@f#~}v&ZzJ#hN_< zw1lE2kn^B@R}J6!p5*gS?cZCRp0h4^P z&7Y(s!Z*iC%F2l{;@Mj$!HM$+DHZ@TTw2<^GC_s2zP14y-8<*RnFqyo7G9qYBCfZ@ zhC}%&EdeS3_)24fF&o2F6r-6X%Ad=_6R+@y)Xxepq-|b*9S_y;MeCxECX`lFFJZ`4 zuKmP8yt+ETClbXn9un8T8Yg83`na({e!H9RvN( zY88x=bIF#MP;XM7-2^X~VA5R^QIh5z0y#VBC115D+%12hPv#`+vs>cNu2r!=FKWaOHs{q33`CM3;x6TdZc0?? z<&?oSHga;IBj0o2OTa{zT>Vg>&jtXkI`&`TI|b_R)+O|Q{x`7>TUt8-2s@7!ZeHFc z$3{v#D;PzTOo_RRt=h9`E1zdlockW&HVx9a$-_^gQ-rz+_s-K9rof^a9|wMta)e!x z!16P72{JH0rXete7OB4k#{fOKQ78e>i|Dh}&pW&!km3Xj%v`s7CKDU(P6Sl1vAyWH zl1xi^{x(i8tjhO%1hYWDCJ)MqBa$&ffY&BPoys9Q?rxus10l355jH}B1)u`EW2Z3c zSGwpPM&UC8Vyx4*Ev;bq;hi10CA2Is1aiMD`x{dGT)B>@MJ*h@b2Ym=sl`*=`M#$RZBJ0Ndmuk$eH?0pC7;`hwN-K$j?Esh*1n9k^ljc0LMTgk$Yyp5OhFt`!Wl_k5XPAPb7?<)6O4UjPNgmHsYuV%x>0aepA)xabP^E z?D;!0tRqSa97%_xQQPg($D6?j)e|LA-$!by?EhTNK)5j39=E z{g1i3FV27dU=RK0-y*Ftpd*w1(nv4B0r}8`T8W6^q@tv(pS35JMxp2=bLKR*oN)sm zJXo-q4DwYu(tOJBEETKELj%J~&kr1+Mg|tR`G=lSC>9T$6^!lIuK$LoAROqtJYkvNwbqj%e zBl@Gsh$aun49ODk(L!=PTEJ83@4p0Io4>+hJaxlh7b?wdgHw&B0L@g?&p8JR07lU& zYilNn`nT2%E4N&9BYIv$n}CSKM}5myV<}FexW3YjkqMN>zdkb^w@Sn7%*c`y z7=2{vs;znS$~61>E?As=mZ^)OCW{{#X#}90M%5eSq zU9bpbEeD5HJHt&N;xGy_3Z=KiSxPG4eCl?IchknCO|h7FuyAwpteuUO$v3RThurwG z{j*pSVxm5cqK!TI`O~XVJv_kk2c1+}k?ub*DQh2$JP!Em^5BA#21!FR8!q52RkQMQ za)R;QWh&VSuXVaiq(U(q%ym6l96oTYUSePhWamIqj?>ZAIo(>&gRndCI+3>-)!)3? z{xR9l0ZFtH@HY=7dmiFQ8gM1~<4<&x=x)o>dBtV>Wn1ksc9qR8#2EQYbE&OV%jo-q zrwNbi?>o|3cZ-bfmFaF10&i{1=B@}pr1pO@#I_CzK8#md|5|+R_D7@ zuE~xJEX*+$FW0W-AcMh#N8%YH6{T&})oox0c%*>tR45j|JMfs_JExV>X6bGJk2rzN z_-`yjbRK+X(p@A=rCx8OhgC`?!Ez9^sxhe`U_QsuzZuD33CbHBbor0UYBz5MUPwHZ z*aU2#DO)gk^Iw%;FRjvZ$YWL~)?|6cAfMi{y2e1g08Epzo=uCu?Z5c}Hce88U<iYmYPhcZ&i;O}ZZKS0}yf0nYOc4%ClV{b4pO6g9_}CJ2On z?NP5Z>BvrFYp8c8kA=AbTjSVPu}!niu%dca9^QD1%yg?u(+ud?pM)+SDHf_9G;ob! zb5BsfDDZN|#!f*^q`{V&pkXXUa-?1YYI_h&&rJLa;FtAtuvwJ2()lvLB>jCkiEfHw zA>G+nWKt$jwcGGL2V(AxUsIr!r&UJdcGhju!vV7Q(4{j*z!5{guu;=G zXWCwP_H6lx)CC!C7KHJX#68@X+F3*N&Scd}ETrTmGx18g-AeP`=3(N5^;zP4sCG`% zAZIsn5bsT2hoI-r9*Fo|LG5x-2ug9stzD{ipc^8g-9kO(>2kA87OCAAi=CSpvyO#1 zx17J#PJs{aR@XRIBMByXUgwN`qU8h#n*3f<@HIk$I30P&{h6ota~xYAZp`q&HuI#r z6I6`z2Qra#!y(55x=Xzr_LT_b!sL*U6FCN;WdbGY-8UckXOjmW7(fS{$f~&G7R^&Z zv4{r@Jvj8KL(!%>#684e=DK||`}ra;wey?%fKP(Eeuj72L$?wkaS0;5_DmR~jN=QpO+!9Hy=1+Oa~7UVif zVn&YeVHENDY;bUxB)mhqHjM5yZ8N;|@h{UVXZs9l{fES-c&W#Np*DGrh;e`+kjf=^ zfoW|WX;9n8S@#PhLSu_j;XVj-Nc6Hn&^imAQ+lEhL&%NE>UuqP*EO!kHdf5uXixU) z!ak*SFlN%DAqR1%=J@P|c=l#{qqDU`A)ThdgM(|OA*=wb{&@{R9D^I z7inrK7Lv3R8!kYm#=JhLdnOssQpxx{fyvDP>|FjQtMsc)`W41+3z+{?DaJ&}*mKHc zz{bFMs#WF=9PVm*5ouoZIVfYNc~DEJRto4iv{n(ZO}-(-L4QqR2PCjsWef)VPl-5H z@WZ5X*xyznKqIKA#MK1dd!Ix3Q(hus&r>i91aMS;;9zMDMLfB9C5h4}hj6b%$T3`5 z{}{VrGhNIq(Z}9|~i`2*C&3p&nyj$r2 zC0io5Y3>%6f8Q)F57X%Smp{--#M1b9ePD*e_=%Bk^B&hLoD1vY%J~i9M-3K`8E&1vqum{DUfjGm3R=<} z&}bQq=w9J89#=Ob+`(WVhZUy@tp+ujg)ZNSw+jes(1X`SMR6wd3vqCK+XJ=%jj5%5 zZ{10fm(eCUV@&euV30H=khAF`M-cPVP0*on9=r~=RM1aLt_=SPM&Th{1phj`;ND6b zO2TA^3W?5Bg0m9;1+X1lT$G@pDZs4yiRl_8+MXT6gKL*Q$T4GENY;0DeRjTQKu`a1 zSrsjWbx8el^z_b`j%D@0s}e0?gW0Oux?HQDNYEh0PP`y7fh_hgv-T&^k0xzyGV)@Y z5rhz=PNWaWJbAbqIK8()+6ymg97v!XJH67>mqRd_{3`cXnSOuU1Dg&7uO?GTxaxW$ zavNF%?dq%ht#*tV*I*I-Gc{`N^0!n(So%BFzvpdX46k}FO#Zp{-pYSU$N_`S2) z5k{e+hGQ1%+JvLbJz=ecsP}18krGy1IN`+&<^0BSc^GOv7RNN2O$})i%|P_3~eB*q3VV+ z<)A`-JO;pa7oi5HOrUrOed3ge?eF^mvXRz7h(j;(I0Zyo;F<1O zZpfiMYT>!hq-hy>j;`j|fymXE#nc zcie7QBgzuQmYR;*r;h>w4KLG>b&_(WdQwE_^Mi3qHB~3tSEO~wAyT5~S#HAPwroqI zBjqypFPHDZI9TseYI>`CCKNAt^iaryP*xxd#&};w+?8iv?S+qS2#l@==@Gk@8%fht zwBR*3hDA_;bi^}to%-FYm3T!Ml;O#!7&XHah&b_Tyim%|-~D*ed7$O`^XC`lXmG6R zvz6KCEt7WK@3vAkzJIG(|8_uCm3e2rIPIZkAYs%1z?jFm8S=)MPI>MBVzt{Ttv?hL-w8z3h zdCU-vlK~E|7yCknkug7lYEb#VC8p6^ZCeULB@0I5)<& z6cZ4e)7PiUBoPC7PIw4N=lQrM@$@}~-r*eENXoq6+zM57?a1Qlf05vuZL|*ER zM$c*Nlr099JLivIg`OlaRyKOXL1@+}N=U-{=S#0JkBk~eof`K_u^qkRk^6yI#Funi3zmI(137 zO*+pAK4ym7c3{wHzvk-e_2)n{bh7x7=^bKm-P|)frhR4g4 z7;|7kKq}bUl^la@~reAclnr|p?u88PK%FSH`!@eP+ zo^k)*-Ir(#D3o{+XkBH@208l+34H6ZdwjPK{>tbJ>>V(>) z&+b^`gygABZ{+QJz)qF6cBlAK(276V^2I3?-L8L%tFAt*FgTD2>HTteZXFwJlGtM+ zjfsLz8Ce){P!JxE+t)83P&VxOsJ%vHX3}r)>6sycrMDT!D{^Yw)29?Ui}Esid9|==nw}~*#R**O zVdt{{+6+7JNv-jv6EsLY3d9i^=%G{7dB^4J6ei)RRiV9RC z$r@mkS6T`Pxz@T^CB>($y+@ZoBrutQ4Z+NH6O_Ii^cOYCO*9gg_8_XAvc(OP$`}E2 zw*j1C6w$}Tvci8|*Aj6Wn&`a#wbvx43`3$v)$FTP9IqqMA=~FXDZEvHLDZ5a?E@z1InKQ_QMoZpDrt#5q2!sXCfJ zo4!rtzx8Wy*DLe&ASHr`Lhx2l6C>8A70X8@DVO1*vhyZfjN{me{=x&2yWo6+=X4jQ zN;G08qh|1pRDAOS7MDfG%a_HOE>*Y$BLb*hit?9tXSYvLoSM!In6U9)S(h$+`{nT2 z^;$ZCvh&+B7v(H`>5nNp?>$x7o)u;LooYdyCSk-Hv?ZyZjOT zYz}obzDZw8O)obwl9TbBQhdB0fp^4+C4K}wNepl{lm44SZ@mtFqek3k$t3`G)A`qL ziC@T1?k9v5jM_B{b+1O+q+k1KrEFYh67pjMC4sUT5JeFDYox&4YG*U6f4B%5tbUl` zaRyvp3vXxjKC;9FU}x85)l%L|>L76cEfL}ImY|U`q5pZD48ZID{w)OnXu0pCuye+? zM5t)Vx z|2ENi!1sY-0Hbq7PH@o4;*$ZF3sOtH69D%NJ1PT zq);agmRGMPcarziw70_&3+-}YzY2!0%@Z)J%#M7i8Hhfd^xg{VSF{pc><8~vgzV@t z-U7t&!>)G6%^%W^AEv$0D2Kx&27x=I2$bKMzS;hFzg7M2OB<1)`1jkTWr1gjwv9PA zOY8=ovt;;>2<^ZRmnwybr(;(u?vGoao?v8qZTH!AobJ{Ao-!yCy_~XR*Aq)^UPBN$ z{y?f|by>EHK?^uWx!RT`<;q6zL{i4G4lO#elgG{3Ux2msS3IKQlMS~-8I2b}-ZajS zSaO2~z}4ok!Eq(J1aTh_5!KC?=jNJph=HX|dF)p7jKd?L->h~P@R^(R8BoMX@KNZ^ zfF9cg*oY{UBI&58sq<~XHAbhrK_*|9jdZI!0$goyz%AZ3x+Lleuo+qCvgM2+Y^Sux@EMT5`iX9xcuD3~^>!on&b7+$|9;O8sn{clu`o7H zEZR{DKZ8)Pol0VI;wYkuH&*~xp0%5J$_vwx7Ow!pN->%qh$b(tq-#^+a)K~bojqBj zW0sk5r)e#1igcRNWnt=WT=+vb_Q8oWrP(w`V(BDK2sAu>GX}$Bk>lkrj**S9Zr$s< z=gM$=ails(A5y@UnDtAufvvp!$OeHVVfhu&w}KuHyHIIe+fZz{=; z#B9Cqb>r+d$rKQ9F0`OxvVXBx(U$Kvbs6A;-f|wDa5sd@)V9-%P5$UHl5jwMb-~V# z1^mH<%ReqURIhW`@!38%SoLRlc7N7Bw6hJh;T={F^ErG2uPeRaO8b3${CBEM6-r5Y z;Pzk7%lA(a;_++u4?(@A2j|UcN&wAGG4!*^4ArEpEgK+gUq-KjN`vteT~Fnpi>Qcw zIypt`yghjPNeVAC>thJ&G0AWQvOHQu`1pWkbh^SIfdDW)OG=(3SHB<4c>b?@pbH8c#nb z<^)7s&A2|#|5gY_#?7p7aL#95dz4fF4Z?T(u!GqGWXA^93orrr4n2FG*sS z0m}ZL0L^}>wMn1NX};lLEb!qpKS6ZPwtm2X*bIl52J1=e%F2}~vggvy z7w_+fsDD47Rrp-VM;!Fxj~53R68c>a-7<@I^~EXLez``KR!c8R01&bJ2Wy^`F)MKP zv)bW1udI2C5@2F|)K1yE_GM$G`)| zd+Nk(P*YK8q(Nb?>5FnSDUtlWn?JPgE7864KD40aup6fXFcjeW5KAYGrDe*MYr%P5 z6JQdCRTkM`D=H5>Me9GAum(iB|4CXQcv*GylL4mWpm(8FX$YWp=DLE=#eH_19%EfL za$Et53JF?vc_N8^4O2$Wty6*cHPFj{Lom6c(XwbbsXs4Y_DkQ(jsx`>0?YrIF zIeHRwqJKp)NAh_0yAlv_Ijm(P`C?J9bOtOwEc;&`%+=eCr1RP#Dn$0a*YY{cxedK; zyjy1yvuT{?PNhbVB}9L9g_CnCVCC=G)=*KDS=ea{5evdS#&qnTpRKJu@8A1FpVwwu z9Ly)+s#2Q}kwisPKib%S&R+6e0*S4Sn9nJ^u?_d(@MxvrlZK`U&^NNT>~pP(hwbYc z@1~=7ew={6H6LlpxlK)&`H#xXJro1|KPGB!k)empr;l!iN(Zzt2ADX_@tZhCYoMNP zun&Ik=uKup9E!pip2~sv%KVEbP9pa!^MM?LUZvtcvR8*5rvl@bYd=7d3*uBMEQ%Z( z&HELQWYJ<+X>5;!gY#E7XRrV?Ci>Slys-%djqQnc`trgm_Q297iXz*Zo{$4JQjgO_eUOq*CYA&latLy>;Xl{ zqNC7f1)`@TJ^v|wf+txt%^yUY&ip%Pv~(*jePpN4ouz2@^$9}XGA{tn784WbW3BcJ z3js_64iK4xxtwf%wMwz%_ma(J)rWfQ$p-7vQp@TU>;F7qG(^F0m8au#I5*Kb7}8 zU&-BsH<|a@c*d-Et#$~OnOgW%c+#UR?IefXbA~!bj)nznupK!1D60E=+SiQS2=(0v z7e1iqyN-ws_8u-)`SOE5Mg9>Q6}_c&@-GA3tH?j!+Y@HSc}6%c+opMy`8gpF|4pMD z_j^Q60NedThrymxJx_Ff=yZ;2&EBSL_RPuj(CA5BMqStz>G@wCqc7=mvdc%!*x-A( zzj3%+jefQA%1FTY)h^K{5~dmtF2IZA^!M}(Wva-6rdBN3^Id;=&x{eEtOG(8aJrLV z^RyX`dDQGV*vmOT_U2J2b9Jnf?K z{}Xi~9@GORmR@dYwVGw|g0*SNV=gaGTl1&56u;(Q}*cv+*2 z3Hb*SK@d(A>54~!)q9>_e}!*Lh1VXm+52=fr#6OCjoha+#enji+G_<#8E#uoZWEEU zA=n>;+gAm9Em@vBEmA&bUGAg)tOH3BrxSMt)sHA8!ooXs-@ALwe|Rt1U?6al3&o}00u{(X%Z8XnNRTVmPOH_d<0A;9 z45e{ zoIKzcFR%QsNKD$YDPV4a#XIq=+w+x|?$YgJXLiLtX+rF+d8??+0i*LUjp1C z4-CK(%$_`fy9;I+RvN*71EoLR?(Wd25z=4o3HLU`N}Kdu59~6nthcP2fcK1i!AUJE zj+w?d%`@&EQq<*G%sJg^xLXIepZLZNHOD~r3V#Ez!K|gK!n8+og>pnpLo($>PmLTi zMx1{N^oE2^qI@Nf1Bzp`xIQk(t01JeNLSp-kAp{J(R8Zt-(@-=#aDQ&7Q~w4^njsX zbY65X-B8Uxn>ZS&{F8&S<~%d3wPS^{wrkkSlxZ|tcxct{9EPrWxvNt*Uq8n zkW2_w5bj%}cd6P#x$}~vPl{t))9P&0?+X&xb2R;>ew?aY!E=CC0bh>wk0mZ^f zxl>pSo8B)jDztc0t@@#j=H1dV$BuiC)IEZcr*Nun!f+GpFbe63fR3E4*Ky&jLqvo5 ztec-h{*yIe<3Gt_)aU~P%AO<_aDgF3BFU-=b&H=n;Oh{x25#H1?k)^-GXs8DJWzoN zJION^lZ-c~)v<+2m~g$U)?gueGf0RgDfku)nCUowA9#RRnBMq1#K;+a7QeGr?aVh^}Rm#=ruokKVz&RVyq2i<*>ktrzHqMtb z19-WtX?FQd2&aS`f$&F~Z>4%H&k}wsl(3u3+h4quE3je77@;uBo#g>W)Ya2#U@GF< zP$=XgC8z1(fQAE64=5A=ZJ=dE0!+UWcF6t&6vG|TWeU{;!jf)RLkhLJw?44@8EFDQtXQ}P4 znu`V35e~>d%du10hN8^a(l;99NM$oqr5zt`0%d#vsaUfP@x3#k4z@b6b zL9!0Q6UU;!7iwkq39A#|b2H*W+y!f!BVDY@aJ%CTd2Td@<(O z_P|bN0DZ>LaXPCw20M#t9f{m3Z~-O(ruH}n8@b`1nk_o4KwwQl^Z#OVJe-%f4@$j%UZZ14HHPf57+9jQjG=P==bt^^Ht;90k=ciG3ADNqJV z(NF+dvkxjtQz*2D`gB;{B)tL^An41+jsOMF4~${LdB&F4Br(7w=;ftL$N8Vai}$b5 z%uXZQY4Z57&?P^vlpxCB=rX6O2m-Q+|CCgk7Q1UKhP;-N$F`am+4?r=4x!mXG!htu zbnOex^KmjVKc>pUtpB4XcWKdoTjp-dyVgsZ0j3CYjJV2@8#N`&Urcyn!o&+*XhX?o~% zSPf!MUt0NFwYlg?FMsR7g5U?C84J{{YZb$*H60q7ak*oHVClw(9}Vn`N2()gLP1cD zIC%%^8%)%XJR=|sNv|BB#w39yix?>2Vyc7!=BOgEQ6)g!X!34;ehdD#o1A_<*k(Y6 z8x6sVH_*Sb{U%Ei82I1)vxYTeupncEkz)0jD%=EMdjZ^+#_P|CRH1s(#!co0=BS&A z3|$h?bEz=NJ2bPWG1YuB2_dQUXmQC$e*P2Ll000bPkNtCWp*o?NFuroL z6bcVt1H!VlckPJ*Kk!WZwz2h8MfkA~?j*lLHTyTmdpC)8heQ{ulj2aHKHumBaF-z= z&bp3rlfg`-9gM*zqV18@w3y6LsbEOGpFoF4xdE|v*)yaSjZ)B+mX_{P6)7x$qf5k= zeypI6mH_0z!=c3-8p3YOrWZTPv-{p{RAf)`k^h5GnS2oo?Rnj?96i3jYxD6w(6jOi z_hN$)Am5LTd$kmM{`ih-&lx1ErcU9q;GjS{9gXL3EZ&Y6$LxIxIF^?SpllD|U$}pB zwX*TSn>fBTVMhYp226XuGB{bR$!E=FT0JFV< zooy*4PB>67xHKunijfGK2klgmg#*VgUW6i|9vD{XVnuX9xeYnm44u5ZqzHrob3@bj z)M&k4=Q}{NZCwLQPq`M4vPg3suC!W_4N>JUFcYZP+mgGF=HyfEar8tDp{u5={3kvH zGG0Jcw9)$)bpfQcHLTiYno-iD6X6b6A8DdjfjF0wvxxarFg{Z*ow$%!K!6q#1gds< zv>32F!xtcWN=qCi1xW5~hOa&=R9P!k7O^)elxtx}(1S}sqJpw!*;H@-$r1epyX159 zBIef=MG+AWxdhSuvq^+4@IfegipBZ$R$(<~{cPyOgbEPC$OFMEqSy(>CVlLZyNY_hO$+XO%C&n?{=` zUw;cmme4hBvF~W@O2~#C?jPI*odlCQup@T{b_NPB`QA}o7(TZ^3o7=Mln!@QLG^vK zM;-a&D%P}d{b}iO0*)LJ@Kg9uTn{)AW5>39&tHe+0bVIMs)?NShiPsAlKA1L1h?oXxv?ZMQ=n4MQkk6iLDS3@N+1Dz zGr+1Vw+R%d4DvwoGUZsZPUj5E4E(OTb*8>;@xW0cjg=VbMx}AS$?|{_S>$ zOluC+fmfM)VU78&^^?O^c+`G|1{GO@V*nL7)5KVQk~{6NcI;PvzJW5(+%&U3XB`3( z@21z1V^qRHPgdS)7TXj-SRqe>${`)+*L_lifU6G0ema{QL^w^hXsh@1UDPIfMpK+X z<1XIO6Z)qnwz*LNRO5S+OS0VCH~wD&Qm>QiyhIURR-ixyyVFy6uSA(q}57GRa8`(7Y}vptF+2~@43ET&$>`| z#{L+w1ulC0A{b3#)bz^m($Z&G-k~7T>V>3kd|QqDb}Fz$p-QwFvS+CfCG{_e3DBfi z04N_dwJR*MdPclu5zx0H(tLi-{Dgx39Swm!&pMzMH@Q{_C?y_!#B2bW3c^&CQ(#5A zKQ^&4;O<;Tfb)|9h$_F^kjG44M#DzIB*C(F=llkk2axO;jQJehFp$45s&L}45c{MlIqgj!PM60;MP=LQX*}bJD`Xz7`A$>iY7j1} zB&TJUng@d`AuCOu9f%seplF!ju}H_JoTCkTsU&3c<{1S$%vy?mfqxpaUxI@2dq~Fm zZ=;eAK2 zr+?XghUFtzzHy4)C)_hmY=Htv54TBfJ@!iq;u=YYU#r7fziXkyQpd_zfSEA?tIxDt z5GOhbbQlu;fLA37N##;LEldR|2*5vwB3_9ApZp%8GO)Ls#94Z}Z(6kD())^@L)<~f z6)UJ-XHe{})3MVI!|dVq$k(w)58YVo&o@tUK_~OW$B9a+fHl%lGbF~N`&oACa=ozw zHw_5SdF|tmi-zLUI=icooR-}-E2&pP4GYI3IilJc-Nlawq@%TSusPGM;S#ZchdHs# z>k>OQf!>oDWyG=<0?sQ519=5kXY+`&KI)rk&%nRy5!giG|4$2GJ(4`*cCKBivuD+J z_z>vpm$7uf{HiCzT4tw5FxfI zBKEj@8JOib-jnfgm_C+ydfeFY_rI$LJ2roMjI^A)J@npsf?fQsnZ;W4`f2 zk}m~-^Bte%yT)6zzXsOn*@Fd(j*ZMRAKw7k<=g=ta6s?W4MukKl3bL%nUe)Abm-+jo@Nil2r_Cp$7x+Lw-+T`2Fw4>j>VcP*RZy9Xrq6uE6`Tk+9D>H+xeR2mD6& zQ%0NY_uY?pqybr0emgsV)N~#^9MR#|yDJVe&wr!1?Ov1P5$wf%}cBRq>!2=?c>sLKXRbM@AHgx}gt z(v=MJ-2>wN!)m@01+(Mh;-ab(>~eg~AmvyP%yE@{hthxpPfgFfT*Oa8Tn$W?k_XKJ z`GSfHv$l-s4-H0F1`Nm-*IG8q-wyOXSK_4`iWDEt;=Hf&=$OU2DJ1u2eIb*#3Q;!Pb5(GIZ4J(7L#b`~5`!p({7F?Tw~Fa?N4# z7>=;l`RhiJ*1w^$+3Kq8o3+J@$MrdydMx84ti{xUwylP0dtp)PlJ)7ZDwnn1BY$5U zh)3J_D>2^#i~PN%lLWE5xm(nM$K{s8>~C@VKI@mhvG(47!y#VU(K zo}f3n;F(xf2E-`v5-gP1-wVBrs zJc<_&t@$!yT6?Ve67`Ac!*f+t;t!UE#W9^3KdpKP%+@5mWd?O)Bix3bXE`s;hL`6H zqt;Y5%~#y#QpL5DQQ-H?kDaDCrM4PnyCRozy?L}ln-vC&mQTI13z_j~zcN?dNxy8- zVVQ_{63XfCCoOylvz}jm!j$=8>x)~=UK$VKpurlHOAyE7xP zQ+J?Loxb7kaO)DT+tfKsJvTB>j^vB4Y%ZLSiHU; z^E+*-Wed>mbl9>U`N>FwrPNl8{2>S_t!Uyvu2(&G8YNh}Kx^y;V;%~M4Aa@QQ~TPw zEAnE$duW_t>TtlJu*(>A&Qi+VjV#+bGku$HvG>-!k@qE6cv08yW&mu8WkxNU0~Kkn zRmHWD(afgL8k!U4>}&g$d@MWuHk;!P>V?11cT1~!?$cP0rX9X)CQCsCbffIILT1zl z70j{DB^m&UnFj?Z8}*kNMH8|uma)n$i)1+HFQb8>vo}u)r(!FzKT$PbpN)^)g@MSR z+7xt$cirY>-C&cX12vibYlNsyl?b4O0xlR5xmQ8f>5h$`K^&Gi4UDTMIgtgHi1GX+ z(77e-18mX}aAKmNJZwbMFqA)NpA=pIR|_)(I&!d^AQ}XK6%gkoCI0T$y<_Cca4?jl zh#*#V&$R}@5S0Ye%ObB`b)RT<_J6S{QYf8NN3D8+BI?|F; z(hP$+K@%07xE~4c0ekyGfS6wULXGWbZVJnY2(k!m9yaLkAatLtIQnp2420F_3 z<)W3}#qA^C=2z9npR?J$w=2z|-XJO$gko>7@OZDPJ&w?=wn@E@MPaJ*x=cj`hfGNEdg@E~={(&3gWntw#&xpQm_1 zV5VFR;=s*3VAzqbgAjWF83C+3yu5GP>e1v(oNw`BOdPZ4CS13U)W3IDfborZzxPE zNv~6@@=ubx;Nj8%_xD@@mto_PlK2K!h%-RTB zv?_*8TMt$v1}(a8TfsxOjDvi=+;x#GCd2A<9^~cEnmqgNilp)KcLh_%UH|fF@an6; zyLLqn%#p>XHwu+m6H_XUWe0YzI5eeGu5w*L1~V_I(OqHS!}XlgLyva$kH4k(hR6Fs z#?MmPHqxB}qB+l1v|r43TtyhQel5SBEp%EoMu7y?c3a)AQ#LNR9r+@amCEGxhEE@y zMUsB9m=#FP^t@&7I14^_722k%%qaQ?J!pzFz-xUu!0p}E$3OwkhB~_r4n_1FIkYWW z5YdMx$N05F^^RB?=*WOU>8B~m|8{K!L_+g_vC5xfjV}P>BRX$#$1R_B%yo#gq+VGi z9{c0U>9zL~c-oeYcG*e35fZe;a81_Dp$+N(IO&#s3)L&MUV+$**_w?)b+wcie@_c+ z=C)3OI1TiqSe`|)nsKHon9NmlnXYp7Md!h?RQ^TvCjBcT#S3guPzbXdiLnH99ck)R z{gocxS0acDpJ7FYp&DVi7%`6 zn_DP!T}=nD(i~Kaa8HIm5y^;L|Ae!Xyq}>qa=i&B)F59@f@@b8?R@BJ5?3CR%))8yHEOTr>aL%hg27M zTz&dT-1c|6(%>g$Z?UTv@EB#Ofbi7)nd*?=O@`G-)lWc73oxTT)?P9yCo@>3d?}qf zJhW`j$f&HAb^Ht^ehU|u+#FxgXZGJ{!*4y7GUO~K#A2skx49x^?jDlE){`kHmi7s6 z8-XBuJl&SaEv?})JN4&Wws&@&SN@Dqj>%B!GKQJ(jU_N5IavbcIjyU zY+21XR_x(w4P;AfaZ4J3E+sIt=G@Wub*OO?JIOx z8J{$;_VB#6P4z!0^FMu|hGH8l-#A|s_qVcj^Vf`=Ca)T?)~kM=)Hf^3%F5`ps1ThJ z>sfmb!7QDWw2{r2UQ=lJ(8gqqQi^~6-0tf?zev9R3xxQg&qfl{#HxG z_+sRm_eU(j@VC-*2GE;rR}xe{%B*2+)N3(;0(UFTaTjk`Ya5ESmw%H!2zfufwr|pJ z@5z@={)q|lgn;rQ9K<@G3m=s)VMsvx8KS=_5)+|zIzOCLpRGnHh~k%Ow(G3-5ImRR zf_edeMd@;aNJ5U1A0mvR{|U0`m)DYaDr^2x^pGH_iP?@@&qNcvhmnq8&-Rv+BDvwm zo72bJ$LqkyYfs7Rz=!3>gupge*H%KW?5$?UYMt0MSacp~`~RWoyyL0-|G0l}=$IW6 z$EHrmCdnSB$lhej-em8Qot?df5JL7mWYft?NHTJ=v$FU7`Tp+v{C)#T6jRuWXT!9KXMcp{q24n16uuZg3OtgVw`eLd#3t|WN2<2jO%qic`mnpmJU zjGN5id?cEwpjHKN8s?l_f`UR!xIxD|)q9)zjSKlnp89}3xnj^aP10M(6^ET6ZT^hJ z=`84T)n@;cM#Ki22)p&|c2Lsr3PRtS1)B0kit+hX(CMEybGw6`iG0@BOg@rj;qdWv zUT2)o7tNrJISHF^z1|M}(|gi}S|G@lKl=y`Fw)n{HhGUNqt0aN`aK7JdKjebF+{prG_IYJ)0ci~vBH9_^Io zKL$6C)hyWG8u9Fm)|nFP>wcKb-}TR5`*!(x&g6ULtA3H}5vpE5pXd`D;jB}-^Lh|F z0i5>p^EJ9md3kwRrLNR|JBRmPq&gO=!+LG`5FKVhqTzfBdu}3w!ozFC{{9!Gc8EyV z$@65+@wFoRMi7KzOWD8J^31<8lFJeE&9(uQijZAsP)aSn^BK*cd!|7lYgXJn-^E)p z`3vp;tv6~zJ4S(mKJwEX>Gfo=foj?COZbK##h^UgCtMHqg!VSN{|UZf_CJc~6{)L& z>t-qRwvOZeeBTsT-d43kV`M47)&UM`>gem9=;>7AY}P5 zKX0R7y|~K~&T+R&j|(Vj6SjMsTq$C>UtS^=id3V*WL$u)CFYxBQ!;Yn#NT_`BbzKU z9b;dsNA$F7ad)Ejb8?-Z2?)MckUIZ5Qg z0OegHHT-vmlWjg5q%SJ!GBGHX8v4tguqr(h=_9G;At5g1eX~*U>xi~$##a28#q!zP zuEUYp@o{(%M@*E!-@^H?!xq?ysowg*qe)X&k;>gvSKZ%_IVcTh3?MHTi6 z$#HT|#|+sBJ99opgqk5H1*OjZVBPf5!8a_ueCbyC`T5~yuWk+R%*gC&HyS)mMgp=< ztUje|D6>!g%zS&($kO`pf}jRBW+{+bXi z;INc$wPA&Gq}VHT#?}r>lCzPn?Sa>$DK+0Ob6FLp?SU6aS&PWUmN|`T{ofgo_sWC} zpX?ij!(*_PLOHaNX=52%N5yBCsPw>uFrfCS1tsfHvgTM#+F54*o-EthD4*GYc3n5F zwZS0+CpawO*iT%s8J)ij9rtN}NxFXbygEEQyuP|9$*8n*(|f@0_%Mugc4R6|N3HwXqqC>Hl_p{o75XK$*2BJ;{aSMNB2wc^g!z zsy&z4I~SCPv0&U};JNwvmi4o`4uh__zhAw&)45-xCxWR`V@9B(Y^H- zu_^qySt#K%5=1qD|kUsz3JL&rfDJ^G`%c>>|96D87@f!x%xaRcj&(_-n-<$;B z6f<3|Uw|YI@ik4QH-x}&dz_W~1>+H>v);2VSt zul$Qij>oplZI8RjW z)z)ZmwU6CB@|&M^^y6Hnh`SS>saTS%YBTL%BOGu-t{Fb=hxRgVHqt#gKBkUstxmLi zH`>Sxs#B1Jn7T#-V~tese%1R5!H_3PHCyR3RG%&m&R3tzEfSzj4%KcfGg*^Y zKInavn;;wT;;_0CYFE50@uIGuYKiI%w%%s!`n=}m9QddG_#L3k4RX{^4JA5Wq-A|h z)O(F1Nyt!q@K>8cGfmEzB!1XqgN;3nTSrjnue{1`*8gR~RgZQ%8{~JJA|x%w@wH_4?_>AgS~0UC({ ztHC-z;3=N?G-2Ch(0&!<-DoiX%-}?gYx*Si@iDS_*(hW?2|%RG>ZVT#_X6ddH(;t_jpGo}An+ryD)GuC;AdO|>2&|w|*op5F-oIf{{;u!?8CxJ`e>lXUC z7KRf_XerDHogB4;GVM^3LzB$(^QlG1`W?_xdwrS;(m(P^*_0&;6n~a&vm0weGm(fS zAATCF+iHxk=)qg^lHK4>8CEzDX~kjWY0D$}DMeB!b8pCz`KyJjjAOSsmjx<1yvFGi zWVt%KLNb_+$HvC&8_y>uCi?p$)>^%*o_R-L5QsuOu7`@#f~3a5-9MN}GdDbb#uR<9 zmjxA?=5nys{I z8?P*vHBuVee@W{^415lupprnl67Z@M;8@{G>H(?_y!FOHyD80b@f;PK`eWRjRY6E3S0E0}UYymx;1Zj}=SYN{Up<05J6dwByPhH_n1$5CORdi^c*Bl(=82 z@1FGN%FBAdvADFqn`3>sWja?7)V6tY2ZNg~D}LLJe(+#JnLzx7)-y=RS%5tv*4o|1 z#ieUzOC*6|a5yj7$!TAuZxxV?1Crx z7Rs4wpdDzLaWG789R8pnN(xS4Yra$VDmtL9C#&@C;Dp0W5@@J|eW!L8X9TuI*zdVi zc{57#MKwq?#;RKVCGz3*-qVeV;)Wu=x;P(3vZ!uqQ=j?jv%_*R1ky}Cu$BC1CEW`0 zITl+;6IpWSTXJf}i~}%^3)1@K-*V=aw25`W5kfD5!Wy==YA`5CT}?^_s_YS15+C(; zZ1Pf{f4cZeNM=a0dg6s6oar&j#>u7dk(zaHQ|!Rs4B;!8LTS!`o~ET`{I7dM}( zu&VkLug-CsBo43loUhur0^XSW-1Y&g5VUB_I7ErIb>U4Fml)|(0i)YoQ)Dko-e||0 zv@TpYO7T!EFIHL3S;(+1mw^P-SfD@lDscim2}~9UtjX@B3YU0IKr26i8Nz~|kuk>K z-&{1l>jZuH+bm{{1{J*vns&Cvq)r%ao%m^#-MJI$lOL9J5yN}pkQfVJZUav9ykX1D zBRPazn9S}@&XkL*O|8iC2fLpIm%{~@{ic`wlVxhb|56ITKi;`Y4I6;4sB+nhDZiA= zxxrt)$>s@*rp>v{uW0bzzB6YiYPMVq<)fs#YG@Nk&HZ{GD>GgHVh z3YchJFS+SQ3-&FY7-(mXto?QrFwpjnp@2f7j(zOiTJZ=&@nu%#i?#X0e1G}^XmjIL zo0IFKcZTG>e090pR2cffjq^S}Dj5HmONqx?6Yw3kw6|v{mef3>Yi>T~1i9ceMqwzS>&>Yws3^?>DJ*tgu=^(A)ox zj||2$#@>O(482MP@4#CQhI?~)`TYb<`bSw)RXi)M=tD<)JLaIr2c-33ET@r1HyrOe zW*uv}X12X}*l1n0$&{F0f-AqVp&)7cV@^!3>hH!OKH+N*{Q2a59TnK*rX=$Mpg@MSGEbX>4IARmtV;7tm$ zO}{I)EyBc3Avv>@M)qxyB>;7*OlB(&L_Aon(lro z>9wW-)-+V^@Q&ch-sD(;F)Wd+;!>BPo}j^Z@c(-O`aQ$oB>#EtB2eU@9XQg-P$Bu# z-`IF4=mvG#Iy}@b0cclG0UFtfql~%*c!OC6h+ejaI^_rwtTLRxZ`iZYXXS38Kz;CD z8eyQeiU%7g-Aa5JVZ>p;;;k9u>Zh=?PAOVa9UTc_VZit6OFqq=_5`XKZwN%uc2O6?*zDU#RpSORc8TS-W1-pVnMZ;lUPx4@o%12 z0wi~EAbbNG9zb=oP>$^F+`Zr}SL{LJ$N=w_CfC1sxoqroB2z3=AhJwTx$rX)Zmw#W z*WArout`C#PeDN4Kqg!GkvIgh>rsLFBB^^29K4O=2yP-TmCm8R*` z%c8gsw0=mPrAU!O3xOB-xIZpw_~C181me}obgjXtEBr6Rc4C<|3YJ_acI$bYq@llA zg}PP@5ro-van6FZl&{#&vmSxZN8&$lAi2eF zviheb6tYI*b)vHzt!h3}$r3<5Q#QyUKZV>qP9Ph!roZ#4@N|>Aldgpey%#SRTk#Z7 zWC#8<_TjSp@ii%%fy!?4Pi;otr*7x9F0p z{@BBo;+l-?HwV4FX903pckM>aasWHgo?#nfW0cs%Fv#)`D3tVk-!iIV{ngGU6=Y;N zdlxlylHxpbmD8oKPen_Hoz!BoP=yOazJ1RyOb(I?2#&v%2Ht|v@pA5sbz`Hdb+bl| z2Bf|B^89C|)BIvxZZSia5)*??nXY%Fgf@@nOul+k=C8F@8*)*(__Hj^{{MBVak|wa zpNNb`YQYuo*n>!n>7(}-*6&t$(yi`3Fyu;4M$*I+RJRA|r|sW$0qcqq&AgG)lwqGo zJ;Rl(cIDbJ*uFY&RE4q3^c$~#v?;FDVyBcV?hcUb8o(Ca$B9YiPWvLW6falIN1~rT z`&s_M)ZjQxSob@ZY)tdLfQ+-(K%t3(gH0bsz@?w#A7?Z+(`pug_cbU11I*qEZ%@aS zA8q~bEVNXI8vp|3|yi9XLSNHn80m1T){08sHWno5=^ZYfZTTIP9cYcZRuY$qJTe?+AC}(V?4lHd3i;sS?gm>I^ zfM!g+-S7ZSP3Q$?==wPooJrslzq82p#F~~#%SWJ)#{}p0qw>ho$$BVk7-9*E=+{k z>7U`XD&4Kb>-E6|?B#JYQ~OS~RRkZ>45389li@2X(@5)cC@&(OYMG@_lH@elTX<7x z>T6?jJy}-m| zMB?)&NX~A=BNFhGv(it%{#jlQKzli}v*tLz#H^S%*3reMb8)sw2CexdV$OM9l&8k@ zC!28%V)E_<*@+CR=G|HYf`SwSgH4(!{6>cAKvhyPJGg=kPJU(4)DqQG zU*2Fr^Go^EW@K%HQ>-WhhaxE0_Rj|-a~G6B(9?GZB>m?4@NWfy$27fr6+bh_$}|Ln z_n3_DiZRB`b|nM! zk#o^5#ux-WifsATALmqIu@``7Cl_fn*n`tz6u^;YFK7S{ov^i>J0^&cBk5IFE0Qa2 zZEjxNXjl|-rxAY=tIv^U>^<*ns&04SI#;bl~X@Ko^H&BSJ3Z0t%*t{ zsH-2;j~^@+Q|efEJ?r##bv5ClqKgMT7Y1Cb5hxjW->jn|p3lzeau*pYg#AnQw0!a_ z;lF8nEu0O1!G&^r`=0@wIb$wizSo({y>**HDXD58^+wy z((-El=;#aX2WAhxb#MT`y6O$;a>!ow?2uBRxTj#wlaXQNi}otjk|61gKjZp_-SiU6 ziu-71AeyJoW$k(?hoUmDRW1RaB|yWOuzfkli|A^BLiNK;PBQZ70?i&%-8MGH z#w0*8x#cnD)@{y*fASpGnOA|=JT9(tA>DukL1l-L>-r; z&pVu#&)!~77AOu5a?6@&J{;m}nX!;M3y-(>7i$_fI*JMpXAdIVS)>RdXRy-0)PzvNGH_KbMOi08yQ_aQi4>SHv|J~xA{fEqJirPQ%*719>_)Y(+ zLow&jABem$iX)#ckFqC4F2d`_rd;WQRhz=2wt{=&yOEnbFX%aQMph2+QPEcVyOZ%H z5pp_JA1dtUbZcfxXup!WXK+f9$EEc476a#TP>`HTu*orJssIWG(0*KNj&nv_ej0~z zli_rDp3J~TJ(e#4{ODq0{!LEYRPGRn4((%FfDm%hXC3M2#HQ{Od7ReiR`QcPq9vcH@ec>FbI zY}VRcjgsk;aZpp9PzpN$cd zmlm!4-ZXT`gx9VM6IwrI9{bz*FlAEbDJY74v^GVPP&_w_PHw&wcT{OJ4#a0>4wr`U zEfIlAGwX#V@03O>qwW8LQ1gC6^#%wX^Drq2)`d8n}J zm57g$hQ(RX%OX&qLMh}~^3d&Ib_Pak0h-lQJuWKWL68RhFn=6;F*lXM7KEsam8~;k zr5}8AFA<)vdeLg+?A=T=sL-_tRDUX^ibEV7jZ}lGT7xRql!>{RVIDTp%h=d@&2pof zCy2y}Lf(NXuOt{w6qxTa?t+D%bb7H#vs8_hcZI$X;r!H>c*6VE zf8vI4rSC1eOYrvar71iG4X&^dpg1v|O3j2^G;lmk+CyMWq(yiX$ zK@=5h2foybxtx6bHX6hdA*=v}_$O==WU5VM;Lt|_lv)qeEtCsGj|=(NZ=d(-p0V$z zCI;STxtVVt{Tf+Z4{-Qhs9c$uzY*db0cSavLX!PWyJN;)y3#Nt1Cjp2m4{s9s8wk3 zGM0*FVSBG-zFajAC*FwT+J}T7J+{+wAjr~{xFHW6mpNV8nHrawBVEiHAb_(+-!^cx-rP=7Io74nhX3Il61QPH;N+lRJR z`F>tZ=S4%6 zN37_=xW-vvJN3q$1%+lbcHqa_M}T4S@^_5qW)9`N!^|QeCG-kJjE( zl1Y3ex`$aFI^pYb_b_^UHq=;pE)dfTA+9RMx{1={2NwFvC%@M$?v{>55Ii64pG=Xr zW8h4d*zhVN>&0DUTbajNzs~Z?Kl=KN@_olZNps)6=etxOGJ_Px+S$~X9gm-&@3Zs| z>kCxuEgPFMa92(J+&J><+(ljQ!Geo{yd(E2%p zdMdx%3x`_(H-Kij2MBwwxS>rluI-$&E&e<6Kv_^g>e=+HHn(u;`% zczd%p0W~%ffug%!co1ZQ1tf_D3VW@+xhWldvwEnsEnLZ_CaI-!1PVed1sKV0J(<@z zCHfFhG3yAhL{VjnH`%Y@W^sT`TbsGPv*TcJba|Po8{0iywpYv z@w|xDJ_vd=#?z*Dapfwab%2*!$*@q#3BBoFGgpQ&L+?OdHe`Fsd2Q@z+#jroECUs? z0oOtFk#R2jaRaM{y#r52v*?xwJ5t#lVh(t8&Kh-PJ5>EEqS zyYe6(G`X35BU!IxH+);6);B<10Vm{0L_VP2eWyR`=Y%Su@4@KH{0fFAF&(r1KX(!< zX6@lf#jB+tZsK9N_wYqM_2~$>7EcDoYRXfB!>O~M6}vKI0Zzhz1Uc(yt-p%#a`@6_ zDe{6NO+TH1USVC`L}OEi7Gyh24tXJbAh%!*MxIw{eJ(O zt8xMsEb~}XXcC{>*s%R?O9=jg@ZYY&2`u+(Bw=Z1{_IC{{b@^qYrm9KNq?Vwe?Pxu z%nDFkjAp=p1`3Y9HoC~cE#QL)i=MiWrb0vR zLJ5@-lPch)qQbZ(_jR>4M0`0|JIGq|Jq!4KeRZp?nm6Ns)bh;eJQ-jJvaugU^Nuh4 z^Gsfoy?z-71WlnFaBS^2SD0a|-U{XRzN|KP@8f@CL84WnI4U$3_ItefOWw z6xp=E^i>y%8dG}q04L-%%-EWRxex9?Zd%f~8~C9PewvRZ&=AB9t)I)Kqk5`S64o-<^_2Y3k2TNSNk+|LFW+( z^yQrf@{jRWpNHB7h@}rN#|Q`1IlgmX6n6jgap*W?bMY~M${-uvUSozpP~iYuAjDk; z#gl>2$fy#^CBs8rOoHqb9yIXD@A}L(e3SDoX=u0N?yTL>{_V$PxQm7tCYfI^Y?MMQ z?h(-sK$-glNJ3vJ(V60iqN>@!%sF;&=^18&!^I267;I!Qh~}1mGq^0QF+KY}+Ew;ZQO~!IXjyC#pw3G^8NqT`C)Se( zFmx#Oa-cH@p}l@?6aTzpRP&-(19(%iN2Xs11Nu5$j=PUL9L2}_Jv9|zggidH_>6(w z$y?1Gvw=WVDyO&NSKPo+vgRQbjFk`u3br&@@xZ{G`hLn>@|1bbF(#(xy(T+J_r}Kg zpT2ES-~Jgt{N&@xX=6Slj?i+J*M;oR>#iK(v#(S0WOXFWu87y9vRWzQ zdex^!oc$rZiH!Fkd@K+ME_2zo1iSFSr@5f>ufdn6A$oG)ZuvL03@lbJA+9KK?o}y|8|T7%_)K*bUQ|xK z5^gz0Wai)jQxe6Dr$~a<)R&jzIm!czxeJ0U;p*fL9BGV+QJ9r~_WLBg1TwGu&XqM% z?Hd`P*B%v%<#Cdt6F`5k)CUJwp!2DiZ}AjZQUNr$Zl#pZ9uVb~SyQ~*|9oK1h9@DB z3ZX^`0jFlAdVjV&J#K>JbbMiElxDrKo9o@}ZsvdDJCkZolSuI~oX@KVD{{r;k$`@1 z79({m7Gj3jtg)O+udoN&upsHApbJV#b!t+(>!0qOue*>h&r^_qqz4>&u|TDjz|>L2 z;KZzd(A`f!#@vfz!I9>9QAwt(({(ugrkGFWUaa)GuLJchjW`hqq+21B_YF~k zMQSypP=!s`#qxVL@eh^wcA|felG4KnsRUxUP`OA%SM)4A7fEPkR&MlAOmw5+;;6_r zVSrg{IMx2?BP?ZY)_wl~CBUNnH@Q0bF2CrENGe#fY`+WMK z>_jZFlB~GG9!&d^1*2=Gex<*sm$u`=Lhs1KlJ|k#H}!yVDQ7=FMekq3G%2F*;ZL)Wn)F`erEnN zO-`uKqoWBx>sxoVAj{_MP3vl?&}9w>R+px#=C;2z;eQga0L~tDn~5~)>0A)nlQKLB z4wpqH@S~n3!y&HaP|0)o>M2VdD=#mkf;q{3p}6(>v0T$D`^N~R2GmnRzXk_0P{dw3 zN!ZH=_CFey#!NY-IFOcf;?*xd(UYx1*7a4>)kT(rSPeLI=5EvVFJU`(w3i=x$J)Gf zqfkHHPQSE5m-0b@s?F*F4L4%3TWo>q$?FmF=c->U&nTggz1b@)7aB`wr>~0WTRHY} zK<~F$;D&tbcO-%&k6O3#K1Qf3a|)R2sm@B-=98-2$~fMg-#Q||z9vn2Pe`M0KB-6* z%PUMj6f>LKQxAba&i-ES2h~W?kdR0ki`Y+#Kwu#u&{Yq5wogAq?b9Df_oODr<3p1g z{5^!%6IpxjQl!a=7POUDGe999t7L~b&Pc9E3N>r|9t{!-R%skqFZ@*VjqEfUj85?) z^A7iEG)n1^(`Q|JuPpQ%JW|};gg9M+|DufY!Eb%t+4)NE=h!BEh;mw;oxHjMz%-*V z(kxZ)2{C*Bx`PfJZ9l%U+g)#&p;IA{7=o>o7Rfsr49oF~q8DAqRl$!@M~Ad`4`?Zf zNbg+F32rC8b>LT-u%#W))Tjdk!3ZQwtq{mgMUCU0})K4&;z*y#l2w8Zu`9s1(m_K(i5#m-)LG#(N34$*z zN+#fLBD(1s@FnM&n-yN}8T_uxlE?G|;=F#0(H8Rf6W=rFuzJa0WyFB`v3s)q^7B!? zGK^)=b*s_c@0=?G10GYaBux)57$6HL*V1Z1C7RrnMA-cyzH~ZgGCsh7$Wry})tlZT z^`qk-nM)paskM`ad}d<0+LOAR4|e>%)r`)Z>;Ahu8KixBjXrlW-UaLX{1;q9d1FCq z9R9ZrBA&GR&lcOTxvzHLirU@0K;wgt|Nk>d|F_luL|w!F<-g7!shb0-u@yH#^VjeW zfFkDf?-l*xO~CzPPds>cAxy5AA8{yk@mH(uv|UK*1T~Jb0H^f^jzQP|KA3eZmu~wR z8k}}IQ{rPesz)`#N54dEXX^g*QGkj+PvbJ*S(ksY@E%Y;!BJjnr_72S$?#p@xGP(0 z;(~&)rtCMyv3+X>J>nzQoC?c9UC;ZaUpU#uDZrm)k(@4tX$uh(;qOg6k0~V-PfQNa zwBBo9teV^Y-1NKNX2CHMU*?_GECdq%d1@2Z4GB>!G2lp}itYCi$9?k4t|Y^uQ2pzQ zTliAH`5BStPlwn1tHRY&KdtmjXD&2-ytf^Ko*G?GX^yOt4P?sU1!y_nH|%({vs!;D z_ZktYGQRC)#_|mLDNm36uA9qY#QnEc7g+(EN2D(wE~>&pTk7jMW4>7m0IUy3c^7%J z(ia1_){asgFb3EP4q3ae)QRS(?9z6hi>@<%t#ho>wb5S?RIwjF?cn9FIu#wI?U~)# zapp)X;`+m*t;s(So}?@{-C$2C+xz=-9T&Jh>fKMzMgV4)tI_}jHBW8D8R-VhEoK<+ z?x$kx3)R7mjolYks2=24S9~?UO*ek(nHL?~s za2Mz1ik$-E7I(J1?n=(u3NqM8FedVKTA5B^y0U>{n>dur=d8!Cq6XTVTTC1| z6CiB-1kqN`@u9x|^N=USn)kT5AP_3c?2#ni{*~A1OAH(d8y@G2z<7SZbp5-_Z{erl zh;TxUgY!nI%o9d^T|iu8u@q+%8|6?imq`M@a{3n(IIy#`^o@hP((dlq!2p)LaUfuJ zxXkI~KZ}(!z)$7-w+BD8*8}TPW3qNzX%#ydLQ>2Xd=E4<`(NXE+sxPh`R{EHgP%NLxQ- zY1w{ogR_4A;Ng^`5X-YR$=Z)IgF>2knBT9|xzdl1k4Y^=vf^AyD$WBmftb1D!DFj= zCRSkMXS;nI!5%ZRs#>nSbK>8*Ykag-L!H|A=ODs}XV;hK?tGUNTZ_QT0OB-=Ip)2t zg~Q`Q1FMr0u+CLaCk~gdyelk1bCUr!$)Y{v zua6*TlT=97)2Q?JkBaU8+O(}?i01B;_(3rU447ilu)xKWK)}0LyrR2T1!WEgnkh#b zcy{rvp9k%AoFBzR01F=)9p>EZq`x{MGKRj(zOpO~LLcA)Onm{jcf;-_D_cR+w{#5t zK#S%C1kxrs8+V<$Y<~}wA9#qO^}c!p5`BKGeQTo-UuJyEGXq8i8fX7+M*ujcq8AW} zgZXPFVvkgl!$tjxL-`8SoaTb09uo9rJ|jQ62MGtd=kf6m|C3aM_?oF7_Bv1qPsW5L z#pTGNa9J55B*xBdzWQz?bK0_Re$*Z($$kkM*TD9xrKM>2%tk{w^=doMb)f4;S)Ov) zxgQ!dS&XbE*wL2Sjk{*lbmS8dfdV6rat+E(b?;zr=^7&A8E_~sRR7*!Us81Bhi2Yu zKHQ%R7pr~Z2z}Fh4C5>f-yLOfalQW;!Kv6Z^|O|XGhw$OCJ9&?v{M}=3)X~9W(F}U z6dglJ^r&aBjg$7uG-IAhSmBDBFJOFbCg^jN12M{TzWd#CPlQXm>%DO0N#GDsl%1QO z2UC0Xmh;kW@F!;hz@v9d=9Q~!&_jlnro__Pd2ovrv4c=u^;Xjy^^6sbJez=0iJPS9 zCnu$u!QJjwGx{*TK15VqoM8NzWzkjOPT1{#X+#AhMcOgOH9*(i-O%zE>g~D&NgHMs zM}&F8BzW$0-dxFbEjDuDL3T)^*4B@-cq&UYXPdYU=Guul{QXD)8V>CRfYzmUK%gG@ zcF?hQ^UC9@q5|}JPS|=FMtp0=$J8M#jG1ac10ee9d7|X{Njo^b{Cn*bOV=OSg|c)S z%}Bpvf&6l&snII)qVGq}*eWM)=*M?|V$Vpvi`mFH@0v*XTQK>meC`gg{^a&B!yE?$ zY*v*`MO`^wXcE)-jlpzdH+p(niVl8mAW{E)(mqTXI*p26+EuM(LsStP_P(H7!4_%~-#HD!~1f+=ij zxP!07$5@cxd~6lWVcorEPYT9>xy6VFcxxAtfp43N8OQ*Rv^eMS zF!!I!cYh!^qD!|Y7kbo&1#VlQ#ipo#?wdX8hv&WwK|pbQc7kyr3iPaqTJhM=OqX}M zGcT{ZiJzO1zB&+lEPZTIHqqq}yOo&&QSA|Cg?^L3<0lCXSrU%n zHy5Fr-@dh!y*RJ6z!GPbP4@MZ0yT-TswrBKhZfI=z79T9Gwq*x297bn95y?vko?Qo zThmYf_yWY0h$BKPDz1WD8V!Kg30PYj>wq)RA&Y$;nT&jkET6CiBGg716X=|(eC*|Y zV#h}j|8~x+x~ugEz3ZWMSOO3!gVo30z(af_{LjzyZIb;z6dtD#SG#`y5?d(ZC$wj9 zJE2b5T)C|`i-9dXgY&}wad)1$T@CH+ofVOnWNJ~J|CT<)n0x=)8r8)a;4_?^Enh{z zz?!AOrqopU+O}&5*q>OFo*iiLe%anFeX&N}3n~6#`dsyAl=b~EKnZ6|NF zv?q6XPwy>#ZsJPjphRIYc>CLhJCt6GyBV_eCx1NN&%{=hNRmx92D^4e8eMr8+&)bE z`NcUxV3!ybjTHvNjEae}5~zE|W%2OvaN%1YTdOy8`HKt8R|u?Txi-&>fJLUnsIA7Q zSm@%V3LbSL zbhOgJvO}X^q58OIUbgalcmC&t5V*NARcypo8%PQoRHZ3u0OTtdz|zJgwPXCc$j+a0 zQ7KK?d)Df$pNGRk;ZJKo_nY4<_4mmEpH>nU^&I1b2L`@LyESIt*+}at#TfXy)#?qb z1kgWE8kqeJI@Uv^ZOKIMGzY!n9XzL28*8io<(mD>>={NzIH5=wCj`-Z+?STH!@%co zW!KI0m?ZTI0a z=C$vTO9qnrzI-HfgRWhRQ-VOODJ)LeU2H0iXj3e?hl#-o12h}!m#i8B323k0&!)!q zcJG_(E9Yhl{hHhRco|q6kTKPq2w3#@EZq8%A(r4uDI0-%(90Afo=8i&b4w~IRyH52 zo}AQw@3NnFHB81ld+%V(34;n{zK0zDD!qT=F68njLN?YtvKAQ*Ms74Zu$NDHvZYNR z1*uS?dE|FrVejlLYpZRMauM&#XyBrhlvMEP9>BOTk`UC-dK_eoUxX|~fNY;pHA&P} z&9k4Uol=NHu*5Cb*3|(ge|(u&Tfm-*eXb}-sOk9y9*pG~ zNl%lRf3*~oCsp{zV!gc%B;Ev52N4cD3!{_S*Ly6|tpS%UWP)UYlP~h|?cFl#$uqaZ zeoG_!zmJu~Q4P1_^~lsj!M03p-0_RVW;_uBklZrIu@R-S|$VkyS@F0q`tiH zvlL`1o+wn0Jyjq}89@NXptV-|LG)OVe$@1p`fsRr?`f%7;Ta$*IQ+~N*5Kcfz+iu9dAOZQ*~V`)Opc=p7AB12qBb) zgz#pu;22&UCl{d)JtK7cecJJTg^^=2|7QF z^+Oj{q-}VhhE@&uGO!-~_KmB)3opk{0&hb;8>fu0_3}lUL1li}Zwu0nbiWHW_SZ{> zKy1mM;4DotpT=Q<%M8@)BD#!SuI8nS!?`g%nSXb7h(f{AVWFEcTa!nnvUJi8Q@46B zYs{xynEo2HdAa7!&!hd&GMukWT|~7uJPOsdbsm!xdtLOn(x+S5GOW8fzC8^>!k%fU zv*OW`9-CfODwp?R1d1z+;7Joh7b7mZAl2MYy%i*N97tfn8pDh+PqdsRSU`xtf@W=YN~byJ#_W@QoqFZW zsfsOM6M?KREB_+RzOE5KqId(_mr_L@=ioi~HoN3wE!eBXed9< zrAZ*kkyCGj??c2Aq%_1_8Prgcdmi~Y(2kg>LSX~yu)!j8@6Jz?t`TL7GPvGk9jjko z<3N_4x+(uX^e?vM5vPqa6Q)ZJbrlh&KeBoF=Fz#ksX?s5?SNilMi`2{V65vNBR33e z4X##9uU9S#-jFXF%{U3sWtXnFMVQq16ETKfEp%>ph*A=Hw=+=Hiye>2!m4yJRaH5& zjywgthZpGk&AVanP@l_`N*%z5h1`KqK~i1je~wzGMN!X*P|y!@Q>|7RHdD$Duf>8a zMfLQQvDug%7Zo5H(+@TpsFdafsUAyN(*Og2?RWjQO%G8kF~NY1Jr$^ox(@eS`GmpZ z?svB#($N-gZR5(F+9%k#Ga{7bhSttTMwWgW$S1=~z8^?eSzrBTQYFCq<=7U6)165S zg+ib(oUt%;F9yd@K;m#60!g=;+G@|qc>yXSkJ_piTlT@u<3e}$KF&bq8t7PslReKK z5v})|rL6m?Q!_Kw5ci+LoH$sVGU+2Fn5r39%QdJ}^372QtYB_ael@qg@(=|{u z--(wXsZwJ5!Q-;MT`V?278U~E6JPO#$NSOIy;jQjXIvyPo}PVLpizwfL2boZf)Cq7h^ z1}@GmEd1-J5l&|5(@^}mZOu;E;jsZIQcgl!=~j6K`Tzbt1k2dh((h&+vsW*dFt}pN z$9@tr2p2~q15@xu-K?CVu(3?+amF$0gC-|WQKz{kHMYD2ksn}1UGxEMVk1b) z*dy`D=14Jy!lBs|2pC<&5b6*d2ru(t86BOqpx=q|WJ+W_NU$1J^W~`$gfW(QC+5|% zAi+geEJ=-%yFV#7+Eo^=`Q-o@3?twPgZJl}4$e^Qlnn8#d8!3)wzqJthb&YFJf`W4 z!Qw^i0bB!7U;}d0)SOYOu;sZnYg08vg!{QlmlDDbi}o~-v@$HvRD_Wdlz4~|Ll9)Q zFe@lZS^b1E%^0)w;)x}}M{;EUho)vpY=_^g?{)qD=<-JyIp_U;zn=H=z8`m2Zc}5L>KjmK1O)!G z8P%UV6Lg&9N)3+M<*gkDdCeb0cPtD*e9FXDcn2(wT?R=V{(zDMuyeS&@ev1QU@HZi zmo)A_1&Q6@d>THxWpmraJNL_*Ok$Kk#O3H0Eqvy1G!J~d7m)a%XvJ6}lA^QLnrhui z(x&Twxi2)heW>%yak=seXDZS9;9 zn+m2lwD0>PA8{s}5>0l@t`_}U!sk1C~c&-dvTtB?dbc@pM3}?q3rwc!^cNf?f9bEkCphU zjAJ;f*4(>$zc#HHK^O@m;MIvsjNv}HXTyR>GJIT@FSH-HL-)Mgn}wco-+=%zSuVwI z{$Tdwh)rfYAZ!QF=PA^R!)+y=>6BXwXLF`<^q8X>_V7&Z3O;(7|E1u+eDyD=1GSQu z3h>p#Q;Q>V&<61XvVMO}c2dYn)KgdE^XuTfv7XgWS{%*}VAXcA?eTtWPn8Y`d`zWm zW!9CyPkwjRF(S#KjC~a^gjPg;`G&bDLL%2~zhYxP3*RW~e-|xv&{%Aja*-b%S z_eif&y&7HnRaPM;xV>;{K0YE7H16?`#r*X%E-o4@rf*wHN0jZ`nB*sZBYf|# zjEMX6$Yf#J0VjcN{Q&SDN6U+2PO$3w$bXpn^cf_BT7|K)$v6Jv}UbrcmoJAOHYK zX%Rmi&(v)_s-m5Njd1q;$gs#bNnTy#3SIUM3^~Ch*K$cdk80AZujv-}DxF+c4lb(|==~?*I+QDHz`=9DjSS6avFx!1|VD zM?};A%Qt#L@By23qn$+FLW6N>MgN+@SV@RFW5uhnq27*BSLY*z_ zr7R+$Xbs!sW~@3Qoa1UVrfyG%}WnYoD3 zspsQn&4G-G7*PRKVf%^>f?J1n5#F5_E5 zkj11ZS}!!TE(t$?HFZXOH~Q0Y0Gc%Ql!4++x#rcn(K4!FsOw!@ z{ZX5Z>|R%;&hZu%bXfGwf>)h>LjQvew_eXZo$?Le<$I#t{CzbU6?S$D4WKfRLZkGiDhm8AJ;FWH?bW4k!EvBG-G;F&Fs0J zwzgvpA70o^KuXbpm89dSC#{MS+U)|Mv-G%B-Gd!oD3l1+WQgae>dg$gW=c5tf*+=8 zXWcCV(E%Qm@$Jl+k2*?IfQuA3cz|G^qxFbIrp18Uc^RRRwpP(I=^q8R1fBUmpc8DS|fHjck z_)e2eK~Q?jZ+X)sTG>uuUXj^II&qX)ebC5g)rC2o(`>hKL8S+LGsC>~u=cA`Pm>5%d6nD$`vtZI6~tCbi^(BE)jyWD43%B0U!a=c;o?UMw{1 zoMaXJ2d1=lJ<{dV;yHd+X(ZsHdl2nYIL)jSRF^)Xnn|Vp3S|hBs2D>|Ao?Atg`e>R%N~P~Fdf%!rDvw*3_8y&t^>^Yp9F zFd#EL$uiGC-cX_)Y^M=*elh3 zIr|>wg~3K_n}t~G)i!&o$gk04$O`o9{WjF^5hG<7y_TCVHw%{3h(@d6*oz-SiadE~ zqL43+9zWZgH}3H}R;G|gPak-&xDzP2o;Eb_JDj~r!?RRm$y3SQsk{nZTY*Kt#|xkS zEll-PWr!TV*Q*tS@9RRIo%Z=t0UOvZiskH|9Qp{+{DHcr)wlQ_zpBw|@!GowKlBlQ z6n7aeZsyMtzILI_bhPWzgcS^x!U_KB$XPefoIGHG`1$Vf+qL{Md#0o*&wx$@7UNf= zEW>|;IVU+MCJbMhHAaMy@~Yv5WFBhl0989upgnu~Q@;>Jvh66$5{+)^Y-gv2&W;Iu;T_U8z_IcREvT^i9bLQ`vGO?000&_xa*vf@1pF2Di-aU?Y zVraPjyIwhkBGjz~_GGkTzRWeB)s3;Wp}u`3+3qP(1cTh7Nr3lm|DT8{x3LQ0vD6QX z71IIDT4Oka(G(AkLmzjOcbHT^NMIG>ev$cJ#eG!Ad}dc9yL_xb=l{I`Be-FVJ!3!| zHJTN@4V~bPgbllXwdMo=QWX2<0O57w{wY9?(!ayj6AG~NWE;&NSY{pAR zK@|Cvd*l+Y)-47zLdQ6I+~(9+RJIK$#6YT0E%AhNOs2q*g;lX6-K8lELu^UkW~&r* ztHK}LlSo?er6Y{oA07S8dpptQIplZa8>=~fHg2(shu!5SN>7C6|3U{7ppJad?;5}6 zA-1Q?@|r8{RUv41l*C*HDBkOL%}P^Xd7Y#BRyaFkO+;E6${*EN|=;gg?z2yW}|oFalwmRDlMYSciWb2LaZ!0K6DrHFGW&09P7dThc^!1F>e193+ zylv@_^_r7nO|;34hPh~ctoL)<3gz7K&M=fQ0`4l712)(Yh!XEhXuSdVOy!ADs_7#A zCg=T#?rjg952642O%-c`n|gNg0H~*=kz$j9;@l1S7JpEU#efC7^T}5K`B2d#{9e_P zSiK&{tM{B`uXz!tzA^c+Gld_s)hJZl(4Hr&4GrTlV5 z>={_O3z9)yQn34v%BQFEZnojG8g<+IyCNz01#A$Q)i!8)*3n4$H#*ICpXZ+>pS6Cg zX+r<}dFdl=bJ8hCvx3ElgBP~y*8HnQwNmHBX@ZT#ixHcbWDzGPO2Cin?+@VWG?u-D z$x&~t9Y<^eB=W*u6ViUcI=xylN$-%Co4PV2uhyK3WYNWDlo!A zKZrb;Gu)oeDPw)I&R})0@6WS>9r7X!W{G5FV>_e?0VW5_PbE5UaDL|m?&<{ zC~Xr|ui^G%!xs@w5UHV!dLXV}NrbzI3%eVUg%sa6cOy2FAAR2(cM?e%Q+OPUe=Y4G8{a7^uR~77m9Y-vwik&u;d4~f!rt41 z1_CPDZut!sEb8Gii_-D^lciCiA{!=($)nJ< z5KVBH<9b_P<7y|IZQOYyyWlnY`TlUex&Cb}7b~ek{2Emp=QzVmdWt4{=3tN3Ydza}ffh3CE>m^!TpeVY~Me zDcQNWRBwuK1vo?meWeZ*!T~j6CJjxjt&Ye%h?WU`)N$fB-H^aY5~n@9yXz3ylLU?k z^34A2Rp^|QM7kZ*bk#SEz_WfpcD=701rq9pX*OYepo#e6~EzGtmEW4Y(J- z?imxz^%fFDbWekuJ9ifp6J=&`%k`mV)O~|Eh!HH()e!4AW;?nP7eID8;Ep=up zf3GiNj|#`~eE=JaqO4;{y=MUFI%AaWTk8mVVd^#9&0vDZ1A6Kno-G+3&gMCDoLptu zip)|j0wQ*cey+@#?yIa5Y_Qj{c7@GX-CCp|sa!Q_XRb^a{rT0Vj`?7ZI5OeY9pl*p zGF?l?I+N;bBn6LY$4{qcC6n9jUe<~l3}5hZ#HtJ-QrHamQUiRsfMham`-hoO?lc!1 z@KxW4Bi{=Bu4w+z)krfF{$>0>IVKVnC4x{u3`d|kk7-Xmo9|)8uRWF-w9eN|!p6G% z{$OG)AySkGANx5Dey{Hn>8CPw)s9z z)f5)yQ7K6_sg~P*>1}Slx(&}~QwZ^Dwa(hq5bx-RhW|KT?D~|zAKz>7_U+r`0gsvt z)O67M8v1A%z)7$$2ZUwRnHn5*TLC^jvHV=;S|tme-Qv%Qa1x0DG_=?_z4!<|AY?0P;J~{Pf3s-oT3x; zT?Ue<(@dkfMKJWzB1+Ckz0!!_2^b8eBxsUEhz1q2>H@wO6}pPDiDN&%#6@RfY)1Z> z3)_!;tSH48zYC%N8T5HQTlZSCXwmpK3_vZ=QalMrxMcIO3sUXG>7LW%#_5zQptDP&Vou_u{d%F?7F9eFn;E9T*16GQ&;Ca3Bk+K6XgjNnL zLgwc+v`_vg&uP!9847P{_ijImZzD@9O22{nDs*7pkbQW~cu`~;oj3tV4p&6fH~02LAAoHrMO5kwET29tHoga6R^Uu#|C8 zWoM@!@1Lt%z6VfQj}>~rroE5cl7{f^L)i_HDuX4_p0wcMKYWBhaanh3uCG7o`t&SE zmEKmo=JJ2_RI`{Q-0h{>lkIe~v({Wuvv}>#wm66r}6ORm}DMN(fqp1Irv{Dz5Uo8OpV_d1j zt0riH)wSv(#cphhGMnF`i5%4y7Gsnl0~@p_L#~^NX8SQ=6{G%6&DM4Lz=W9e!>@Iz zL(ni@^Si5#(B-1V5evAoWw3sn2afXD0A$`4QU8k~WrazBu1{0j9vM`}NYM|^ zqf@UJG(^r0%(1=N9I}c}js{a*gsEXTTUV!u(STKg%hC9~tLsWbuaYnl;9I^E9G2)t zLl|*d{Wq}i8|9E&8{l-O$L8d4>kNjC4U7VPy#EN`YlO4eV_F&-B(ecx+JBR7k=~}G zWHM8R2`mo*s7Iv3h9mOb6Wy;1dr}PF;>m$CzTRNDoFhs!KrqumAoKTGD|i$)2{o!g z8>T>6kY9V2BKrlx97y6y8}~I5??` z!~-(~UZUY8K9unT*|1e@=r@oTNF(y0D;Aq`e<2nRtVPEc2p(PFYX-Y8)zs|(S7)R< z(3yUsHQM;|@sH>O50%`BqDh@4sQO5yDPbjm*!YodfA|KSh zgOOqzrTgU~kM%ULlb~8;f8IR{pPdP<9qzRNF0a|TJbx#9O3hYo#8GTvZ>ZU@C{e$w zI_$g5FD&yd|G3bH&#VOW6%_yo*pYzIVOXt`Q~)SALYNH zw|qE#*D&6Bxy@HsmKd6Et)Ep~Sy`Dguwm@ta@sPv`C(wnLHMnZebo-#cTMx^@smt+ zbEYy8eC*&1ON6@f@emhqf7a*$@lLB;8+8^>7rn4UJp(F8vx;R4fl$+VFq%*HN1W)c z|GS#Sw~`rk6-`y%6Wcu><@J?vm074`2kPciv|mVS>3N%`Q(LZxR57m(rH5s{Pf`9= zlKVla=o1?p5^TM?x3_V6I>^_wWL$32h?Q6ifRg9$0z02)5{5~8(G$O3uS44o54nBZ zmRr{E3C!BvX7H=j5lkK^o_qwwJHEKSv6tD+dMFzw!&EqK20DWkk@?d<%r)keLOBh_g_NuQ_>Vu)!F{e24O0!D>+h65FKCY>P8GS zBuN`64DDij-540aZGpl!u4Ldyys?V`8UbO%%W?ef&QFGOLz0nGa(8mvXXLGkJGz=7 z9H^3FIk`95;J2%%^^7$7zp{5Qd*Pj8(V#h#8fbp61(<^cGQXDDuN`ffzYLKJ=k6c> zuYxU$;c(9@d771O_UW!JQ^G43N5>bW(L&jAm@3O*KFD3)UZ?Uj;(-o;e}uAf73&YV#wHVsi^WK+VGZ)RB*xorNt z1GrII^5#g;KpEd-UKNrPMS|@-OETz;toVNOu-eKg-;7U-;~_Xtdp+N^MlXt)cX0mW zx_YrB1GE9uH8w(@Ed|OrVuKm0ydEXjkG7+HxcWat{m6F%Sd9(&M>1!fL_tqs;g~19MxBajEv|a-z8}?gM=RQAmMB8dmldJ}vAJYZ{tj z4F?ZcjAKHCKYm0v<~~I@xE!*qrV}tTZ(4Gfuhcp*%?DRWjVxGtnCbqT92{9 zwk(&L{5IFMOJnYBE1qDckr36fcnPot&EU%E59y&m1J`Q~Z7{t7anKz#%Gv*|L&{Ph z^N)D7NwvV+lXXI!a1rFOmsf)jcQTUVZrHM0^SUn`JVkLSOL)xH2y3g zuk=&8;)Yji(at3nQAi4mLqS?w8zKb|eA>VA@Z{EVTxc2%DoqeaxGaDF+wto}PTau2 zdK}a&0M2U3q>ZIyUSSilG9_d72;+B0XH+PR48M24%3`5hj;%iFN%((dUP- zfM$-Fn@1~saTH+VoUd+{_N4E;ZQkmt3`{vqsDqpZ^sn;lR?2u-w`$4pDsd2{B_W`* z-n4e?wElZtQMRCaO(J+d-|#jLb<_PEbr!4Ui0Q@)TziZCXGHc@|Ls2O?Fjw0v!CV0ap&m`QhSg1W<5LTI1e*-dtvm~*qJ^4U12Jo ziQ~I9Tr{kqY|u?SQyCj_g;_>8fv7N-5_fnMOtX3x?7cQO0Y#x}A|d`}v^w~SIBr-z zJRcM)SI-I(Vq7*J6B7V6REYBLYj$f#M@tbJWgyOdVjGpM*%Yb1!vK|{`G4=(b-Swi zl||;fg9KIF`&T`y4(kuN)U~FOVa3V0%|Xfge(mi*MAz z9NDw=$C^Do8Ikw9pS44LaXx*0l0JhQp9xk4T;~j9Kar@Gzo^QdL(uWy-zeG_~XEEF!s52q%?2%2puw1lnEmwJ&4cN}ki}Tc7nVKe8uZDV=AicKCBWU9=wTIXUo1oAJ%rPEo}64#iHKnya;&4+B36 zN0CX3hp$*WcbW&C%}SuRiuSZYWgh^dvPFn;?mLM{VE#@Pj&IEd?#;r$P~VQaYME`{ z$7<|nRlCY_PJ0`KTa_locz@!|&-|8G;#3y>r}J|8_LrvjP5!~viQ3ZTzH>9FALa}* zd0TYZBY8p_^t|?_FX%F;t-AJnJ>hnOUS|2Kqp{u7am448HSpvP^5$^*bf0JR<{9d? zFer%oD5_F|0&&tMZn)|qk~8`*r5$ZIs{iYnKMgRr4%InoS3xQ!pVJDup4ZAf*z1nD{ zisw258`gP;nTEX_n`ymF1=B&XKRe2Mo`DU}2d?~-G9e6PR%LXbjypj z|H|OZ-Q47X?M_Q=%?4asdAAo83r|8}MwS1evEuI(ut}(=UrAVo1758AtS3kr3Y1Rm zOt;?^G}7y)KP|NPv!2y>mJx?I66i}}Sq0g*EW}AKicDQoO|M5U6y(2h_L3Ub)&>JqwM%z8jWn zM^#J1o61o)|DErB-3j@@+e$g6aj({TgPK!u3Z1oim$Q4|EBT|YOr&8j_<=9dpYD+E z9oEfN(79keF=8jO))}XrwJZ4m=b-IwRXc4PhNI~+mDls;y0G)OH+%8+Wbz=vZ>g^m zi8xp5xaQVfCY1Wyd7ajHU3hkDb3GDtyC-Waxv-1$SiMlg=%6R7(yuqqI)rJK&RcJf z)e-_v(*qA%Z+9J0H;-?7&e~o#ABvc`y!!IDSed1@p`oU_-xW@h+%B-*V3*ZwLfUNf~y_j-eOaL^`UP_E6IJixD`lS8%324as7W%o{6 z037cY>rKMvDkNXu|NPV29>dHA$n3M&9QO>wHbR0vK@QKse$b>&kBg=scn8YL6g0>9 zJZ1xmoNl+J*rlU5(>ZDS_ogRaSllZ%wO%|}xb1Vk?!)Wsnjy!8&^MjTBPVV#L7;Kd z*=HPeiCm_?!M{%RH8XKjL`h!WoKc`UZw;z%n-c<^F8|I37~)&V{q#8#)VBW#h>!N^_Ox%I?eCi5_B)p&{e8E@UMu zfvM$XWvebAV^0+M(q(3xEj-b>(x9@q*jlj&nCfS?cYT&E{X^p~F0OI^dE$CCZNHgl zJJ{tv9i7XHUa)>-I*ZyiSsNwPLB&XA87mS8VxD00M3yB3UO#$;96ZB7i##g z*sd(AYWiPRG@VoYbZ%|Q=_OaDKM@hoIX!(D_RGD z|I6L5HOB;B89lRSIit2&Gfs^}=3VYIk^G=&cGbnl(eZJTyl}RsSDW~VVKhI{-6A*N zk>l%Eg@HPKJGi`Ps7)(6L=Dl6$*1?rUrGzy(5<@uM$7=I8fWdK4Oo!GySS@JJs;x@$nCgjygiW&45j^Lm>qPopLe|ybkkLh!cfpVIR>7e-4-2%(BI_J z-_oP5>2FU^SI?_`Z`Ckke|S4pH@NmHQD=9MGPf(UL3>J*Uuv_$Ny}&u(<9U~c7H3X ze}USLm49%9uL~pc%n17{oQ41RSS}EZWcUpWl|2K0ztGLc6nxhFZD9^r68^c~svnjn@;G*^3e~l6-%zkM>#Zp&c(#V{t^tlz*puB z`40yd>ko}tba*1RBIHRhObQCQM|NFz+uxS!<;&z2g%4+-3t}e>C_v$qPdrs|=i36j zMMTG#QzL2g=Q4Yswg8U(t<2z@8r6GO2G|cPH}Qll6>=-QJ+If36Ip2_vS7ce;aAqJ z8EK|gAg;qju3P?ufMszA4@u;_b~GoXBCElfTHj@6rayG79z9Gm*K5H@6F+4?-Pd@yn&x!RHf+jT6ixXtcQArjx{Sia=sCpf}0N^ z(bRsDU+UhI=(UM5v+5W%>>*>(WTvgq%)uF97y#QI*v}g{E_hYXf?X&GbqP^X^-1HS z)nGGI8rs^5+oz}GeR3yZOyPVi%D3XFfX?vLIB&#;b)h(7q})oN)Gl+|Lx6?|G()cE z##ieA96fio^Z8*O#)R=Uu?uxHhq=g`MP2Ib?R4JA@a$=aS?iZibEGOhde`Mn5uprVk^-9F{yu2m zVoo>3IxhS|$5Bf|ANQ`Ln)BuhcoRiOJ%4`iD4~-af-gl8jAppr+8AOhW;5WS_>A~$ z-`-q}sMPHU6{5Sx)$pGE6w8a<3+pt>`3|bEL#gIvK%^hh3GK>jxYyBn`Y%%)11N1J z!RabPI0ORh*$LIvO}%{}H%^$zuVgVcgc|jeORV{9;Y^_?K%( z8TANp-JV5%sqb#h-N%S>PeWTw{&M*Ar*$`gQhA;OVo&0jEph57uAw4LYq1=UR@!1# zKcfR=t&G4wrIaS_Ro(o17@_K?)`vwnkc?rU0!QMH~ z2DW~hwSM5?4v){nFqoThiNVsyMr{PVbiuK1nfT1_MQnZV+JFpGNKI#5-G<2M1%>3A z?{dSQ%eDL3d@_U;3wr01rormscJ^!Cq>WTvtOf2Joj zXa&LJG8G|)h2Fseol)2j`}&{lzw&{WT=P6fhbhU(w9_ifrhHmN5>37t{bo=)tsVpr ztNb&Feu^VotAK_f#0`pJJdOVuKo3i0tMsMSz|DuO2z5{sn!EONTO__P<@Bl@Btiz( zNuyAphmMQAa_z!Rprq*sKs#Wix8L^g+W(@{Li>p$D7*B%le|xbUftrCUpAHf@ zgu!_B1riB5r4Z%JQ_4*DY!&V+Z!Udd}2d zzRWI7d7A}EBgrbLeY* zA5S+ELb-;|xhL92E?tFKh8=Q+Av-K?&DXXA;5D_?{O%Bd*Q+ z#4uMofh)lI*}%-uV;`)I&#DFOdUx$eO6FzUp3w*W=9OH~l>T|oB36V*&S8ZFhXF4D zE|R-Of(HpEa|_m%JH}pN3=W=XkBbX^ouFQ~83!UuRB@iIv}y4EeJB9DO>BR4Z$=c= z&N$3?8cQ~sn8Tx(6#zbrtO)GiSeCJ5P12Oyy=MV@ftorS=>Fn#Ijem7K4LkeIM^ZJ z)TEao7bGyJ)QZ-=1(=Dj^RvcCk;+#FIsA_ zY$*v*I5)KC%X8JYTQqu*uUPkjd7qSztEmu}NWYH)P-4Ylx^SqbB38$hf9Ec$1m7Lg zXW_<@>`4Qz@%jo~FB-5V22bVLH(6;!5#3i7yCp$gXBO3kmSyTcs&#bQJ9b1yUuw@X zfjpIe`#wTqRwxeLJg@9+j82Ih*q0Y5wG!CAK$w*8EtmLR!WhB<*nkKR2G`bR46mD? zYS^=+XK8&5mH>H3BziNju73@a;vWL5bu6FM|E#Gfoc+e_L7H{QOWCRblp6B~KzJ3R zGWkm?j{aD)3h1A#k{1IY$O+(&*Y=8tJceAkvy5b%D;$R0=cn_V_o)}k)weZy{1y)o zUAS`CjH7&iZIU;SW#iYxa&#CN*kgcGC$a~~C}D>r(JFUV9^>!@wxNP-!~zP}m?0~W zFIak5QWc^ZcNnk}?@Hk?;0#AC-#q>}>7FDX&d`mYy`?`FaTcl141$y7v7nXY$j77F zj14fRM}>fCNLW}HR0EEVra4MBoo{=Xkt^h@zkg*3!pu*fON6r!2qvkxJL#97oWwZ@ zH@3GsW|gr1m4}AFKv0eC_rDd6>i3<2Wf#6J5PsGyy*^)41EF74mbKQ?%jYy)$|ZIN z97TWs^*_dp*`=@Xy*YLe1}n1*#Ldt8eo$-Pi3<8pSkV7NGEjX5X->h7%9k^*W#u8z zTW$4$0iW2v1ehWEC2x+vrC)D)RbRlieB^Jx9p)AE`#k(Xccuj+oOQavxXI`q3WNC= zShy)WWc}19gMaZx*;#li&W3>aH9vDn-Mn7no#2-Ey%@BUTFVMJgBmt*5B*$hD`3O# zlbJ24|5>#rg8shQBng8M<`bCPH(wj(jP8)fGJ*U$4&*^F38WQrP7nVjc5p*W5ssw} zS;0ySekAC9YxPWbh}|3)T2fVd%)nNZ0(v7rWY=K z3ue9tEvxf`t$ep1nQ@hhm>^$(Jm`Kpmj3-3MY(2BnI+GxN8dcK{wY8u9y_@MX;lmB z_G|ZZYYu*oQQbIhPEsx=lLhz5ez%urd*|}Zn&s2LP5($I@r$`v>(YkXqXgC}qvoFn zXPfS84DYx&KY{M;nhc}rS>;It^Ut8pLDAgO(`YpW6AapRwR9kHZkjn_(|LQ=;?n<5mvd!lJ|qnb=ed8Ddl_=AxukLs45lp-9o&9VklKjgMsWGo)09dUFiNB zGHG*uvis5BT;&6NSYqkKbNiP9B@;8mSpl z!`oYZv3-}*{Zo94l8}qhi9gNqdMz2V6dxaCbb;`ccF_FTL}z`q z_pgH7#R9nd7y+(|2qFeChE&}-M2~MVR5@P9&(#{l9vDIH2jhU9FzKOn=LswKrF9wh zL;S?CI@oM8_3(Ix{AUY(UqCHjSqmcwVhT5!1##M18dFnL#>iij>X+=I53KEMKJnqE z0gnmg-vd)TcNZ9(axJivKCWtTLs5vzPUv@oBfWFaS-|Pr-k9E6>q-Dn-u_Ra4rk`b zr_G=e{38id5x*w_oWp=T*m0m+-iq$x9_bUvQB|3o`j_er3AUnaK{uaeo`%EXU(P$2 zd<6sM)Y(q`0%l(v(8=Mi zk_JyXoGMqJ#ibQN7_ft}^sxD`&8UObju20iYaTv{f}z7EB9+>u)o!aj{W3$@z_o?_ ziR7n($2Ib5P>}@Qow*P{EOjrkCo8Rs^55!r@l?G-=+tlWBN(nd#9nieFYL{1PoX<# zbS$*F(n7n`8y9j%Y>1yHUiDBVSLh6ZExoJ;LBuZ$b5)jP%j#4soz~(a%bJB>%gQuo zl#;(BzIaK;ul;i<{Y&yrfTQQfjh4JFz-(2X+&ybWb5MXKC|te~M4!6BTZNLa_K&a2 zGtSI=h$^tD1k4x5bnS$kUTxFEF&bn5DNYyPdsED`skZjXM3ItrK%8Ax-qj-7t$Fc* zn)uPST9BVuPGG+`LQcpJSs|@4y7|E7xG!Brc5=c%D42~A!B%s6Zt3d9lv*F>5@XTY z?CH)YRA0|m#HP{YQ4hNV(VHB>1#ig(a9Sp@as15Vv4qy`GctnHvFQm^9~g{oX}M(0TLWw z#W}kIiHtyrAyW2mI{3%6w&q#?Glx?g#^G_>JD={1VXx>zZv`@UL20X=ayKO`lq9iR z^WwF&FS9p*6LbvVN<#!7QNiKzYWt7!g#P$RaLCn`8!jtldw@_5trX@29j7i9!kePeM?P(s8kw4eBAox>iPWo>zBV zmR0Q}%(0ROT=b+fC2ItYbsl^1*82kzeEY0I+Av<_D{nZgRwtfP#E@;dHFi1ZIe%ii zJH2YK(gvNGykWugN1PZ@MT?}Fc<)jGvIir^A3<;9$%cFX4(!-cT*Oo__TNU zh_4=BJkOc2;4k@G71B)!!Y$h#HlWf~r`*Wv&6hX94C{R4v_z7V2e)VM^0CYy*nD_f zSZ!E`p23B-S~Fii6)?`fJQS5$|!^$b+~mg(bgu-;lRw=;y5ch0QYh z_)!{TOhEzLTWS$+TtLv;$Jta4i+KOY}=5gHFM?)SL4 z1+cij2hrcn#un1LjpTTSU9Leu{rF#tZA^i;NKiyF!26t`_k734A%=ctoeXckdycV7u?JjYQtr1)}`u zw|~${do^$8K4K;WCiT~;`TfIM``hNzn4>{-(68gh{Y5be36lh|d%ROXCFwE)Xc^%B zC76=@HDuqoz^@_*HfTU0INk8Ig))Xn@ug4RV?6OYdGu=+N!a(Jp;EP^&~Ce@2OI+1 zQ3n$4&pn-<0>ipIGr&L4X&^gn&iOrBm%7Xn2ds#Rof{0|2G%ubtJsT7s&yv?AnK(l zx!=dy+(0wW(65;H`RelECH~Z@$Ms=Aiz&%gm>P&baI2oiip*Gk8p)GVHCd)4IlZ`# z6sCwHu%%c=NZii#OPqo~-lF^QDhWtVK7XM`S^czjd@r#jue=DdM;Q#kJ7NvoBH;od zSWz)dr> z8%Xbm&bOG(tFxTEZ7D1ULI&&~W*3#o&UpyMiz(;pOXutDpqoj_+uwPh%HH=5dL|lV z%9%9_*o3I+l{iBCDAicjE)c~#7u3&8Y#R;h=GQHbVdr{att*fTs?>m&BGL1WcJ4G< z_iTT_sp(UMF3x_G;z}Dx2Hbl^_6~FHBZ<+0}MJ~)t&9PvYm^DhfJL`S+HIYziI0B3ADR~@@%v%wYi^n7vzxItl zA=f`)jH02RTa7T`4&Yp@yVn%3nO^;zT@E-~>X%?QW~kcv<3&4e3&tYh>=QYq0+%qi zdV@#rz=MWa!G!026UPEc{=?um^_SpECTL$CN-Gk0hm{7o6Z{;4QYX76=sYC2y)?!9 zbyOX=!5MU#ck{q<*FEpbs8R=*EXXZ)>p;sT=(4Y-r=`V!op?^NGIX;w*InD>xAVgO)J0 z5%%_nKr1ILu(p!b0AjgyrqNFfydz!??k@U*Mu$3%DrlmK^iG6n%fG%@p@MNeW>Wo1 zoiq?gxvr$W1$~^a5v!&A;Imyd$)>FR7KzF%6E>_R~hHNGrFvSB{vc8Co!%c=xewgqP4| z_)Zyw@*7qLmIq`R>zqJCOX8#ybybP_6Z7l#g7cE*HH2{&3#1*#&C}T3ujfW zMxA>G|Mq=0lumvl*YgLHR@ zl!AbOfONNlh=4Kz(&9)C-OWAz?t9;VT?-e?JkL4b*!!~`0Kmu&=HqVKVph8maI?3k zP^}jj-MiG#2djq!AvdJ9d~S!%J0Ua}-}##gz@z+heYg0B49k(Sz~;k9qb4vdX-!934_gkb+5OJL&1`HX%2TE*F|?1SCm!Oo8tLVjp_jyLPBsr8`tdwHkm>!BVwK zoTk|ce!2J2yJG<_W)es~026dF)22=HR~<)#j#!sM(yA1cmI02>lu@zo2h<_hGQU#q zIgRi)2vUL%OwMnehg1bKM7`WcmeRpwgCw7e6|6Yx z2sJpw&_JW>TD{TLZX((oJE}kw*mK)wA}t%cL=6(A%N+EovR>FZxKE>kB*i7o-aGy+ zp}rOw1dlMd@Dgi(V|KvKN?h5plI7?YTmlhPwbgZhvsG+fh`7wu8}bZ7G&xA`Md|#L zMjLV^tsUL5NMtQ7odD)3V8~?$yuOAR8=D)8El8wogNCn|RFlE_ZqBhJ=9z1{*BN`y zK>|nwSP4C@T}9QYQLjL~O!bkC+#&l3pv>OX?>@)^S7&gWiBa}(6nD@vvgk(OR*j`J z+njOh(^$`3h43co)&`#}3>F4?1Ce|4XuEFOaO#^SVTf%HJz+$dwh;#@;LIHdB(33_ zOv=XcmSr~0aq1@hJp@GCDM!JgkMa4;IY?V+<0>!#-Mc~#Kzy2cZc{~sgk>G)r z7=S109{tKL|KCrEb?>g1{JwQVdodXMl0L`gw(eiKr_nGYpaxD?NN?0!GCu8H+P>!J zcSv1= zDN%v?({zSu@8^Nrf=cOQQpvn0atKV~`q13Z!HBCY+AYj8$OMEhjPPQ)`!dJHCs(%< zPv);f1{E%CCmB%111&T#Ry>exM>qlJF&XHgfF1?h@k3&BenZJRY#<`C%gmUI+9a<> zYcCC0fCdacS?+^M1CD<&U{S=IY6BcJZ1EFLQ)`FkS+Rl7p_#-=>4)dxEXpmeAp5lH z`a0tJ`dYd4sy7_17Tq!rxYHq_Z%ibClw$7TYD`=bBIlbR@a)i}Nd3-e8D}|_sa}bX zkJk@r_q4+|elT5I+CN9_#ZMa<3mSnk(8r=gRt|7e=FFU8gdt!@sOkw^NZ2y)B!x%B z2w8|6jB?Ot5T(&%B;{gA1|bTAsE#X_KhIeK?@3l=2t%%Q+33h_&=%;cWP5ugN>vq9q$v$HDgUR4MRIlIp^XxVY zuD|zQLN(ycwu#zbb#zyv?lCj_P9afe!$epXAhe4#L5>cDeSqj_kG9{e;it~SaQaVx zZZPw~#n86NXy&Rr^E8~dnFB0n5X@K+ejN;NftmDA@X`4i*9 z{Dz&uZdIVgaBh0t>Hpj2!#X1CD-XW116O%qSGP;cVdofrq#iUbdVkaH>^wy3KCHDo z)cnEkT}bz1JnspI+NE7@(^U~_FZbZ@a;vq_@bBnjAndCGU&r})=*{}Ny`9|}bLasx zbA}QF@%i@{$)i!%kPKei*S2(NXOm#iQya9xezcfh)va%7*f+mYa(XHo%c9(7GKfC*7OMtH^|@U?{Mck`r?Jg1FJlVSt3cYv|bsPMHGG) zs9taZqxQqVBHm_$Z!elE%Ssz&=KT<>yDs(UAKs?AN$c&BaQwioG22CMfD<((l62%J9im`k7@IDx)NcDxKBLzdY;O0 z^C*+`2lbp@6}9f1rwqUSRNA{9Oa*Os%u%7|O~(&})9TRRhwWp~a6sWKw3!$Iy@c$s z{R?lqZ<(1s*{n&i?*43DN!t?~KPPYIh0YJqU0lZk(^~oHNQ0IhfmWOP*-k!LYBP#$L_MK?N zij5g3ws>Yr0*YvNwFekPvNIp3;@*$idh+={kI;0Hd0plo5I~v02qNW|b^+Kt&+uZv zHCG2H4;&U;z-vM4C8+(zm@5xFEBL9ziMu6&N$(rXE@qYJDL6xJ1}&?WaAvG|q4xx*Ab(P&!JJVX$Y+T4(bJ1RD*5V}LWnquSQ zp%hoWSi-Rro@o zzP0e{c=0+9-_e)+PJ|_G`pk5MdXq`+YZ4WVU|-?YM@beXCflNL-qdgz>IMMw#eMmA zr-mvuwQF4;Z93qQM)E!3^ZQ$+Q0G8F>f=CmRx?#ac;K_P>#nml6w=Y#*oUROZP4A} zm82hS4ZM6eTi&?`M%0ny;oIp&rk4@G`=IaJV?p+&MSP|7j{JLdKP8ZC{o&lEi21nr zq+pSRn;#AXZn>1PJ6kJTK5e`vtt3&}=axcj?Fq^i2(#9(SAXxH%UQxz@|1_KT)0-B z{M;0*EErDLq*Px2?1ZH^;25}*GFY0_FX0L?RM0d)=q${N+ z5W3eI=;ro?K3L;)5;_BoOZXf*y?Z;be}U3lR6s)HpzUhxJ5i~Hsf6(sB?YK7 z{JIt$o5YHwMAqO|iFJtFL~t$;$L(xygQ4KE8$|!z_Zw-y5Ffr=?McOk8E`|7mk~Ct z7=2vaKy7KoixAMrkeDxWwb=gI=~Hu`?0Ci%7*0LKGoUQJ)IoMghf9$q{t%hdR`=j_ zOLEnU!r8!ur5MxVUkgb#r2`MmDlh%EE()1fR7(}YS8pwU6^?z=T;-v#tez-PmVk*V zsymjCwi(Pz>_HU|ViRPVrdp1=C@_TDJj?Y?aePpVhj+YkGK?xJ&Ex+{^HG_ou8HJ} ztKLmpe~87{68P-yEay^<;6)mR!^o>wB3^E-(!FKDwXf%+iQ2ay!d{?%Pv5VEKe!gb(IUzQiVq3^Xo?@@UJfcVW z3WpQlnwvb!ZfK)lBlHR9%f{}@__m}->$@n)HhK3)Y_vWy_aWE(cZBW6$v(@QCBzp_ zqjJDTCl`HJpllWHd-^=J`lbNsArAlIFG1x#Uz-#7Sc3uN3F(ecg&-oNUIUtoA_LP1 zC^yKG6wt2kMi@<#Q&K!cO{Wh#RnKs9=)&uizKq!)&8V+sBo9#BxIeXe^c(s+FWoCs z@r_(RHxztn2Qb-ai=fN7B^-!SdTXc+$kRkoEJ;HPdg={0y3a>l50)auP5%*OPv%?) za{VJ=?ZKBPz;MJfcpg;P1Ge(M-G`4QNA|{*i*?Qp!+VxpZ?)&nTkn`b?n~p8eKd5k zz0E41UX56$dD$_h9^wcFbsVIgrrK-;M%iu4eSMcO`7{{V8$f9*GI7E{6c`V@aHg} zA+U0q^J$rTo2fvjrIh}(r0<#3mMKA^)}S<&0enxPO&W=FnkzylY@#T>~y#q zW7etNEsYN(N_j@{P1Shg=ZN%UWc_H?XH2+-%n3_9zO`iG*lHv``)aIVw$-19Hc*St z6wr%c2oG6OHYvVw7HvtH!#(zlXdYsQTB-H>=9~|6eR8rLl9{UPPf8=d242*ixV1J$ zT2%3wf2!x`6Cm>&&&K}5!WgNk0Dp@QANYm3cM%iyuq~EXeA+{S$G)4`m6TDe6*z z4hD{Z?`VHDQDA{U`r#PZsf`N-`=^T>DG}T~#epB^9w)1g%vI;S6l->_&K|UueE74m z5NZVx{L9Y~@Lc&3__dUAfnPU_Auxir2$=kHM`Nykglmq_CR_3E(Qqi5h4!x98=Ta8 zzK0VOQcLQ*l>4f=fqazX+2+(pVtbi$E&c=9KGkI!R1Hpn?fG9l;qJ==nUm##TcU97 z@VZoWJF7aD-4eH`m&{yV;2|hO=9;Lx3Q=@sEYnNM5_u3EaOD)aG)eO3ZDV|aKt5u@ z@903f@9z2T`*El3`6K8cmtnI6!m!;y`RtXaod?oSKd{7y)9jg3>pvWXtE7AFW~-Wq z(Vp9CQ^p-XuMrPj!oa2>puzO(!_S+n)xFmw`{JjYUQ|EO9bh|dKLs+Mx6$o%%X9r9}PHc8^nQm($y8@>$rQr zO_FfGT4o?mvf-NnBAt!K<>8>1pgflreoBIa^ZuI~i!QUgQ6{LV%}Xg-IW5HN>_Ip< z|Bp|Fm+C{N;FY%cBRB7|J%&bSpfPkZ7^*qp!tlvPno^Fete_BX!=#rOvR~9C}`dCkSvSi zvb>(82O5R-hEqw<0!sJ3A2}U9B*V2TG}l4)XKHh@`yr(xk zO@wl=OG&~i92tn?@WM5#^~#VN7mt%p`>JbzDm6~dyX(87AON1;;l#%>#|<~13oQAe zae66bJ4XcZnv(i>Z;!Nh>8l581`*)c%SwO2_Pq#%Ci0q@UH|qa^6aXa)%$T9wRzZn zo#M2&_>Aj8o$_sIrs$Ylq#_Gko#78V65-ixHhr9;9bcC^%z&WU-JaV8E^*Uo^f92! zv?n*y`;M)6h`E*=^ldu0$Q^hTISJi^T!)16o2DSpU`Z!W=UA;*Fj}U;-p&(FPV zk*GB{p`!4I*YIB*McGI`CFvd01{g&82nUnT>~(UwV(f2i2CKjQfx9S8kze*TlrnL5 zTBD zNvHc|eD}u(zEZO!*;t)q@PCK&L-2Zu=Tq96{M2|N^ZtJBdm{xu5uSN|ECQz$fI;6O zMUf`nVrt07i(t`QRYxOR1l56_@HFGW*ypYXalkzf?6}t1HJ z1eEj5M)!Zc%OBy)`AUBOX(BJs=wmS&bEvxL<_)YTcNaBlXe{|t(Er6{_C2Ye0E$Ld zgJ0~KUq_8yn|KEuZ9|zi+JtQ%sy;lhZF4_TzZda4VSDRg_~~FHY%rFOWAI)_LdL;< zM++>S_xo$7<&ESmJAHh-&~EV~Z`iR^;e6B~Vy5ia-bgYow4y$+fepoV7VOAU0^p(NdJ+zl;mZlvXBuH&M21jz!RJj2$vgiyKb!@pG$$ zM`uTypCVNCY0GBy@aTNVpcre{WpkJ`!HW)YvQUnm1`a{xmPTmF@X9K))HUQC`t?U$$1a_A zpP^EiIw$DT6r*J=hU(a}(w*l(u)qj*_ERXWStpP#?KIQMd{Kz4)}y8(kdmV8R*c1` zf&79z3lr*{gVf%|T=6rBSGXpOS9|_Ph8_z7AeI`pM;h2Nnwd{+h@RyJsO|3DcFl=y zdWBYun3+psB+I;t!;tv>A^+?1oNUi0sWr9X0uQldklFwWDOn_(cOSwOPgnYG#z~H@ z4&X=gM#+;d9tgc^Gh$&ZX4wenLmvab!;I75Gjr`eayz} z{foTp0a&)RJSnfcQ@orKqUiX&^J@YNgUpA9{nC$zJ{L2Xe~LwG!sLnQA)7U-349!^ z@f?;A$7=QNe_0 zT8d+_*F&YhWy!NVV31Ffi-d&Dlx@J`v9+>omZ`{Sr`-W4wJ8GbUJ$4bqfd62iKNv^ zw>Iog6iZHERFaNu6~dMw##V?!5zC}wWA(<`7;)KzGqBftnU=wnH%@zQ0l4YQ9chh& zG=LY#>p9O0y&4Lo#EYWp@Pw=$Um!OcIYz*OMkvpzwI@a!U=ZU!F94^Y(@)b#%E*4y zzMXNk##}QF%^l4!#$L#8lHWbJ{ilE2#k0~GmEIhQ=E>Az$Pv|Rt=X0z_cZt3S*#6w z4x)WH!~=gn=?L=8yVV^oM1E~6nm`|Kw(snpDVIJQFfe)RduuWa_%0wIkf-%axV_5&@ZehWt%#i1 z3z%>v-Tm70oW$0{ZLQWQnOjvZ4*4jIa!c`CPL|1RWK5N7}4H5~sdv>N&2 ztW)z1PLml(8Rp8KN)NjXzn)NcF844oG8$}BaYoc)r6{19oe6OyhTM4+s1uD2Wa-q9 zm@mzHmhx1E_IacKdyt8Tm)$`2W)bK7H&^L@v@Q^(>{t8um@u0cr?=iv0tTHzHwBIa zaKS=s|MOaGc+FPpq0=L~{JtjDJYrA+cW>3C$CCr+<_{U8!GGrKZLHp=cvWjDV`ze4 z9_#wUb1?foTzv_34sc72;03&$rU1^g;TyO`(c=_f44{!Thu}lhA>E8n(AVp-t>oCy zSRX!4TALRvJegqCXumoBnpY~zGw@tj)E7JI!!BpEtqWFjCdRgQ$vDx5yUOImP_t@ z{j;r*Jz`U$MIUK`-q1C7B8F0K1oSedO*r8G_D)<P{>W!iY9yz5;Zc<7iu3}hLv z$IC};GhpG^iDYH3FvB1~g7!9Zdus~|^Q~=z!k1OOR2~IZ8z48xngC4xj)ee^j>zf1 zZvodAF>tX3<|H+h)63vR`^#bvoYuQtCXzsjB<#}peY=?=3CF~i z_ihij0O#X`&!Cnu=P{T=^uBnju94DZwzRV&X_cFiA)aj`sZsmp@b61NDnonww}g*| zewg*}|NnZ9qhG4G_oH5A>?bOJMNPU0J^X(P3jJUjsrbFKj0Ls?8^B4 zR(+D`vgX69z2&o@?t%g^bDMLTy1bUm*Jqxei+W&z{Fg!kR&n?^b`7kd@Ydoxp*(hW zLnRIlMdL#&ZX z8|{lOEx=f{$|~z*D2xvL^e(x{B>0W@aD((Js_&=U8TGe(VaKFgZ|6TY8sW}09H+A! z-=rMP6FEo3BqT`XK?(t0co-=2{{j=CWgSb71~BVec|Q>%T|A@BQU+*_4KMB5e+`H) z&rSQ%uK&t|i=9G6XqV)&Lt)ZubvwMMf|UvIV_>C9j~^fd%T__HubYn41JEDCaAfNX z$3ly$GLnpe_BiS)v@#TyLi))PU{~F}6F)CTNwK1)hxwh`vABns`>?q;6?el^M zuBpr@1Ce>pu{!C&x_&5MtmUH?{`233<=yqB(y?mt!}JS{VviwH_y2Hb;O&W)Wt&Od zq+aAvnZDPSzqrweJ|<7;ks6mIk}YQOcvxGECz-B{zBS%+YL?ym=5SL-pz$V${ZgqxxA z#oSpVgI9bI*o#G%=5qGC7V>KL8?78XEyf+rCo8GV8HWjQy(Hw^9efX-!Vw0E>FMZq zdOe2QW6l^oIrl&mg+{@O<<5!b{9B zFXLwGuTL3LN%A?!(P%Q7O=*WTF6WASH1i561|LP^AUiF2ivO2)UM8k6 z2p>1~!bYB~098hTQkA$n28=Xl87$Ye@8DTx@^0-%S*3;jsLnJ(Rh{A^_!Z;dC2-IG z(vrYjfDjI4-|dHIFtFy0uKXkS-&~-VDDf|1VuZnm7GNUyXvF`>)7SU8Rwgh4ZZuNA z8cE>={70k%YrLJEod!v1OjArZsG;jYwm0Bj{%~o@8@=Es$v$}gW^Oxk1VA`46&c!& zeUyf-pnk;8d=)Dm7anaKIT|@CsDAqB`F+rXF=c=af-%PqP2|oCp8ze`pNpXGg#`&E z;*k~Pc@UG*giX*7dKlJ^=53F2F9a2!*Vzli^M*9gY?_WkD3-mrfCETJLi6_=IP5{q)TN)$$2NSTL+)%@ z=?1f}XZ~^hN932@!6~Ny&R|mSnLhgP>?R$xVdI~4vMzDHs&ZFW(;Gk3w zCa$~bpj;vg#5!Ml`Zzhpeb^yn+ zh=^QlLE&QCyE6LIm%KvwsH3A-+5v8E^ptwz-ggQggoxoqg_o5AF+t0m%zAthaZRvD z(RfO7a`s4R%_F+BFAvK04hEwoi==Xprqj*>j@ic~!9=xKH$Q<%0nmh}(Id9rwbLpa z3;TQuWLCh!MxK#3mbyW3a;?Dzm`1p#+U!;GI3-jB(C3L|@?S@bcG zqkOi!(b@bouluYb)3Od2$X~SNfy`07L-BKEYA6=?C(xMce>aAJUWX-BamrzTo3w`pC^= z@^RMAUaJr)p23k)@Ykj*aTaj{3$I=kE+j=n7L=$U@R%{fsCF8RgQgYhvhEod7A|T{ zei<7BGG^C*ZY1`2zyOigs?=l8ZfdJRa_WzfuLUTK8s46n(pf2_W-6{7$sW85IGXyx zO}EE*5EU6iB)fxm!XpcHk9$`(vDxT;IVJG^Rfgzs3@rAC{l{rU@W@__WdK(%wCj>q z0hjjdA}=KoM(1>$O!4hbQNJ{#O#A<|0N66?r-6wwY^B~}+oOqwp3Cd@0_6YlRwN}P z+)Yo(rVux2%O5qMfX83VV%E%g3}QWsS>7Srfez?c3|P85(zs5HTkU~u?T^Ka#hWv} zNUPS8AG@b^e1?m>q`>-$Z&ozgk&k57-nJ?lq4_ge*qs1>i#u17r0THqoJ-|If*y8UL0`ZbZ%i299^=G z`$^*ErP&b{y%CScO}Q|9|KQewkx~l+S+Aca>o6dGZzE!$_8t>L!%Cu3DBRxG!5DV7 zxK_)rh+mmD+YdE za1)w*IknVq9*8z`)B+f#UDwB9_qH*==>N>e3 zDOFj~_*yb*Jpe#fbgLc~X67n8#K{$d;s2$?V*F|);mOSMYZ>5gCQkyF{Njh8e}^lv zkc~?K%dd=Y+YGfAEX_{-Y&?U=4H5|WYalI;_b)H#YO!ld!2v{{X5X^}u$_;pYCH%A z!D<8{DLFegw*+*VIVvea9ED_y_zK90e<563r%iARTcFNQqK(|x3X-Hq ziXPYdq{b=(1x<%J&rg>Yko}H>x{1^;7*ADgB7HFqe7mabq9a_vx5pB8|zGltLFPhYG~SJtcrONN$ecjMc9=al;7)VbVh zGjfb&1t@P2nv7v}rW>=`i0>Ch)q8YsUEK_&ByFQ=J==zjQX>W+j6FM3MAidj`;3#w zn0(oKXFmM!^s>$-s!GY^z%W|KI zSyJHI*tWd@h(z1)>L0BLtaY6Bz7FZBc?5NT(e%~OX1uAft`%K3xBa#L>R<#+Y%g~^ z563(lzSIXz#+;b!mDgI<#qx4xsdK)lo_J>*0{vw@kS1ED^zm<+@HtJ3lRry1jhnAZ zU26ibV~a7`P>!`UoW{{eTX%Bb4vLz94o&Aib^=qcGdjcC7IfIPzxEqD~X{kmnQ3q^98J$oWSl( zDngTMu{r`cBMH{Bg$mTlO~UR2wNmR+or&asjc3zbwTjxwpIKC&IZwuLwO*BWMWYc} zF-!F*-E!52y?`uqduPX|qoD71n{{NHC`gk^S5hO13g{9lPzTAUloa$y73{ppj+~u@>dM}`l zTa1!soSI)^oR)___e)chL-L{a-!Hh(MnY0+)@%$xdf;^b_nw@F=vkoQ;w>5nQ%P^B zr^Yq$$GMhO7TfRVnZoHT8NOg}mJfxe=#0s{63O1yhG4v{iho*7@nV)$*I4E5dC5jW zc-eg5GyZnU77dD$*bw?hZHsm3)U4ox&}LmZjPjh@=bL{R*&6>R>9b{@xjoN1AihCh zpS^uCR-aJd<3KG;xy?CFE=~QI2=BY5=PB9)r9aR5X@IHh7bX$%-H6LMu>y6r(#KSb zPC^uf=yrFPyLNnSD--Ya*dOUGcH8m{9-ce3nK&9<{Qj*_js(WodX7o7AQ;FF5iQ&U z!0u8Lt{7e*?*Soe&%MELRFn6Q3n|cILW|A| zH}$lM2;DWG9@x_A2naAqmki?nmS`5*=<$mA{a^`g$i3MF_t1LCCsLsYyt0aT(NEGN zE4tvL`Q`$}=FP8@vcFN>yNne@6EcxL3{Nv)SZ|v;#b{z)(JoMkzqFWTnPjU!<)P>n zr(4B;JsIHY^h!XwW%l^c!Qaa2X-j~Ok8>6V_f$xv(UGiZl*2TtfOlb+u5idAz!(bLu`4i*=^F! z&@TuJnj9opnRYBtrNrp}syIIR9Hw!z4Y>_kVzYR3{0V9 zxj?+d#&FoW-i=f#lp|AH*#X3U9d}y5vy|gvBx{4@Qm|=%qP;cLcUa={6&c3H`Ets^ zZ7ePxSpPw%DvKI3hY&cNK@79<#++-9!)sfva`t!+&VVKm4Gb|5-5&PkHq=#=e?EheH3(qpV3O@f#arbUuT&gOoRT!35FBD>-)tN^b z2kaBPjH~l*S9RZZZd`j@90whel{?2@-I`M>hyBKwgF@ByO*_ACcf1V$0i1)F}k$-p0LyO$7D9?%-S4GdIhMKCC>Y+tFwb1hBR1fo`fK5 z#r%8;r=nIgoaR-Tzn51YZ}!LrRH9`2i-dt$t!rqg6mcAAFax?2pfkOR>@qMYZIjVM z+Ha#a%G6th%Zo@qgdxk8QFd@ZfFnEsy`GIaaqn30ptSS#1)%^o4KwxvplJt4POE9v zpL>#Us~R*26fP)`nD+MP(I;V?_8wW8uow6#pr%Wo+z=Q2bKrM1k#`rc`37_maQ6lr zMKMFeZE}Hq0J-byEm5RyhmGNy*)r+9AWh@u=Vw0$Ud-8V=N2R0*1?C5tW@zBT)U6n z5{9lzKdc`9hGo!{XUf}r`R5+@R+;W6maq?sAC0)+ZtQqF1%4lCG^gE7AiYrV8Dr=n zJE#Np0X9q{rRorUni)uN2QssEC$Oy^5=M6K4tt1F*b9MkP;|AH05=eZG*?bw^eaK` zHQ?xqk_Czi<8kpuchZgXEFymlLhh^kqkxizkzo-uIwEhLB{qzdm z9*KFP&|j}BF6z)se!Y)(57S$}AfSu?bw?O=&2vxZJ*)?~J;ve^HQ6Z?^sm1$Slb0% zCJ9##OwKSRwsOr}JgyZ5s~El7X?TQ*`r5X8(cg%9=C$LC_|FBJEIQy!n2bl8Df7Qd zh%#0I`$e8aa3A?0)S=5It7J))>k+t67YDI^%Tl$>B?P6v!WrHJg{Z-iX=up;wxC#&;YN zt&XhGsj;jxsG0;?*xx15%rda`t%LvgG4>1xszaCF?|YR?`2bD`6v2SMev@a4c5v@s zShxgh`vu=6J3iv=0;vh!(1+vng=@neTzOd?3ohk{NG47kRFoUg_?O%e-X7kPqzt88 z~H|e3h0BM}u6#AiBcJT7kb>S}_>gn$$9UbPTmfgmtHe92q)|`asBmW*&qT7LN z=@6ks0+3h&WM}oI`p}x0-{+tZci? z0t$1KONqj(Ch_u7nG)kD5y_kpW@22Vz}n$V>D@LmNi0mr%?SGWH2@^szI`#+rDsA zk*>`w+W?s7mTk~(vwfz5cTf(20K_;skdOhU`Zo7*Y2{#m*_X)c&_rGoSi}S8j=T$^ zTuLR$68WX|Gy8hefYFh~C|jw(OY({;(X?>QQxv2}e1A3XuzHsYmz?h3hOF0jx0^ol zCtA>`#J`PMzVFw=&tVoMPu`|F=TXPwkVkg(^kl72KdlDrmIV6`gRf$XX_P#8;2)h| zfVIg!A2`hZ;6(HR?ZTR_yw>9(_k}L%3w|iA7y3{8U8IvFy~MSsNb)HH2yIsnctowx==(>r_{>n&Pp}ex`_6v!VQ1lKQu#jG} zT5+lr{1O_adg^wTZb+AQu4+4TS|6W%}furmNDjhD|L>iqlDij8_mN6hpx6`+S z<2R*J)a!W{8MlAea>)`OVbUHUq)SKyc3S7QX|Vn+&_G{*902%$m|Q*F>4VCGYWKjR z2nC)XX&TMyMH5q9@V-RV_y_mpMH$?uOJ$d+&$D5V3Ml}*#?;dvTC zgxNY+qk&?L84b3Vb937#@Q1@G;&nP~+ahDue5?L9#6|Rj*nM{(wl6U;?beSEp-d3> zbtmr*s=ilYDcf`!gu!`N`zfJ-R8UARA;ibBurt zpdat6r>j&N`L9xA-o~;Tj_sb#0lwYRF18FP&GkCiv)FbQgKv58x34O`l|LEKZ_Ag3 zIy7x+C-@pFu!WlV{MUL3U2qKpKV%q>R zu28;YL++@3u#CuG>4lds|M;jt@)=kzLjj+7^LW;pFB)ccVQwf39X}M902%z5b z5qun4FA++|CUN;6_yZp~0D0zISw5Ix_KH@iEl3i0_`u3_@GMR_HXHHUmOU>EFA4-} z8*q?@xczx2dJ1sGESWwX&MkBP)fZCaks$nH`=my@!j`Y+!{ko4;OVu~KZ3^_1CBco z)rPj2{P&`9i-i9c)+{6GWgCqR+q$wTM|H(YakdS8Oq%@aIE0Y1?c2j5b@zd^?KeoW z(H1O^#2J*{R)>{TEIqvcKc{TB|(0~hmb`SuHB0&X2CJ4p0eB@Rnl;b zmxPNHzt^prE>Q1S+V!No7_tA5@#G#Z1M8!>$c}|ECn0P|XHD-PksUWT^sy0B#;7&m z?Kw6fDoaU5{|;KZt0BQFZ7(1a>`Ep(?*s-5%;%lj)n=!cUBLU?&mk(vIqe+*1CZ7( zbbH9UnB|q~Zw!e3?ZxU@b7Kv%-8DHja|GJ!9rtu7Ed4q_XpM+jfv#`J&c4Uc#oq8G;a=}TO-sie z1z8?qVuHD2pA;f$=+kgY$lFHkcv`Bk$6;UW5|GRzgX3oEVMkZk$@ zUammKFwh?RbVw8=(;hX%UvR*!WMCj^iGdhoO#XCT=YJve*FS`htYb$;>*ul?2pNBQ zn}6H;#Dj-4K_$I$i5kHEU0Q+{2lEO|I~Eq5nky?YAdky^YhG-(yU@T`NL7kiz$$UY z!=2$)Dl!$_zTFH&B4CH@*yPeuU4HjP5ALiI(?}agI2F0x_ltyysa#VpFpH?~y8S8# zp*laT`TS4*+RG|}C1fJzv60=wy~GCtcOaPa`_4NOzM{`P_LXN+sk{GTLiA8BXdcNe z0<8)^-ERkB-`YnN>^9xM-@$0|$m;K+-b|?KIk!n)Y7RNO=F+{cvUKEkx~_QQa&y5n zh|!C!txW|#2V5#;M|zYL+f`SYms zP*Fbl#b+UOt2Zy0W*MjtD9Y2mr*f#Dn$T5>acB>=N_7pNW4()9NRFcSsyYOTy5vyI~bW|#a> zp3`JIzM10yq+=5h;%cGhVX`tXy{b~1-1uTia;+{Gn!O((e8h2}R6M@;#t3-)kl%g? zz(@ORsifOvv<;ZsA;_oKJmaQcS3JO+0x&A4@?P!>foHPka(p-CMova+D${@9YTz=9 zVMLoP970q0XqbFSpV9Z{#gh_=VLSesXDvg+2d4_!uYR?Rwm1^saG+_eW^|MR( zS~S-$u#zp(7bP&vZZa7o`t#oY&FqiEPRlwh+V$grwNWd{$3RNMlas;7I=y=e1`NoI zi2uTiT#Q!^vRLA?R~}grwVU6KkTK(fzflN+t|UeDEOZXQHx z4kIKht3V#u-1ZOqUiWziNw;>5)~?{9k(K);Jh`g&9#^{7ut5amRG)@+Hnm{UK>cM%V2_j;2QU{Oca8=ne~wH~+UtC!>k-~zLKR*CZ873#PGF=~ z!Rj2f>@ak8YWPJr@ z3?NErY`z|_2}89GTRXj0Q~EkwzvK+w%dvuFeu9{iYP|vXizRZY!2ByP2~7B0PrWLR z)R6p_BRe_i=pGu{vf%PunCac z1f;ZZl6nrXu*Bm@KC3zOlKfcI3512)%_|vQL-bHuS+|}gw3pb1SF=$Uk^FwugD&c) z3vzTn^r{4@QVc(&xpS!-`Ep18QKqf=8*_VgJ1LIxgUh_8kD&^K$P&6iF}ExUAyC8? zF(Hk*>bv5xH!oZ@jkLc6Z2g*|if;NeJ&1LCcCkOWtzbvy=lhJbW$beB=Vi_kYKV<( zFfY2YN{6kw5*%e9_q!2T`(IEvzkgmk9Szn|1ULkHHY?O;=0TQB8M)(jU1qy8rqG{v zYV|;bT!=t30yV2qj&0kJP6KUr27FZdtW2$K5ODIW0uaIcsm^}MUp2jX#9pAz9xwLq zCcg9}8$pJl-9+Y{ngQckx5?%7{6?;kETOr5u33IEt5$~|TlULgzfXsQfMagrI|m?H z0m8JR1R7#lSa`G+2pu!4wb;smu%Xt5D+*b5c^;p%kNI^QBq|(A$k2`Z|K;ZAgVMqS z`*fK8fRL7(AV~+o4l|Z4{I}+GoE(8Ckqo7(OicKymoRnaPeqcZRJ19$>x4I#L$36Z z=2s~Ft{ACA5ibMoYzpe!qLOjcq5T6?mFAsCGQYhSG&__{tr#x z9Zz-t{(qD>Nu07yGBc9wBuVIGi;$gFM)r2>5l6B^$WB&{a3gysPLj|`LP95=toJts7ry}ZZqH|ivnR>d&rP4RecocZ<1zbJ*ipR4bEWf#^P zC%=7Pfkb78dl|yWslL7@FPXjA>LPoeP67VYQ9Cr}L`?g~X66!WUpk2lW^O5B#L*cvv z*gH@A5B6H|>zTat8%jFKYBKai^axqaXOZOXc`VQf>V>-SizH{q=1aHfPKVvhbCaup zH6~7`<@lbP=pe*!e$do zZEv9Ef?2@^Nlwo&K~uFVYgHCj;+bz5q6f%s;K&(i3VW4Q8t)O?FRBOeNhm2q}!ZAx2s3lo$?I!OD+U8qS` z#;BXf5^4yML{V0b*LDnQWl^zK8(-i6WFrRnX#Y05_cwd2G?T2&u0Sc4$M)`w#F|i* z@m1EiHGeaQXgCbPss>GPgymjy_cwgf4IRpopg6RM!Wa0J?wmJ-1=E+48fmMe~yBdp2}dn@S(F{+Qel1#rP z)H}N9BWhe`ucKEtc9QZ)MiFss^CHJ812^SrvnBeNaVmBAL(hoNkGbS`tb6_GZXc z7B61X&SnS@DA6zYl6!7{pFNx>X(Hf3pIvVx&OFG}5IN%C@Sqyn4``{v!Lf9pB*{AO z1@fEd66Hq~3W(6|kX;J*ThbEf3aXQ)YDuPoDaSkdY=fjSTh+tQ55=e2M89zJpI0S@ zL2r|3>$$gpBLt|S|71=|2g~KQgd9A$f#Or6s=%{znvCBWnys1pq0(l@`4aWc{hOCe zrO=%uNQtNA_Vp(r`=BeuU1<<>KYM$^ac0|-&8=@bUosKg|3Y(skHVPkWhg z1ABY(*e1WT$r&K=L@OZUlsmCwqx0skhpffoDUKjMQ-5_$-bBZqh)@R-Sg*_+sBD)y zD`Wnl#ESLv9Ix~FkYPnLlhRXlxl02w!mP^NnJItwa%^hMH=A2&2=1?kGDy;zm&{8^ zTY1g5KHAz4+;3HH4>dM2grhQU@k8^*@s0-5{iyG$YXN%tP}x&D6sGlHdB`v54C}+Y zB7lAdaiKnY-$YTyiqF%4)xNPjfk3jY-j`yHnwKaru5c z%uO%tPh^Q#l*cv=Lc3zPh}dI%#Do6fOF4vjLm(4Pg!q26=L*Y`EWOng*0@x48y(u$ zCUG5;Uio)gkB=I=W(dcs6?&wo^0ql4ZwEN8`0=sP-8FEOl&NXhbbN?{(z%62SFlb) z5P8>q)SEza9ern64tgp&?w=?4{-hlVdJDW$r4cJ#WSId&V5MYkhcpi|3mbiAM3lN^ zs(YQ|z(@L-lYI40XLA0&Wqb&>KmHnf0`pzY1`UZ;nsvKa#dC$a>2#FU&P4BV64QCO z@EtB6=QcFdzky09V4n$0)Gc{sFLUyFj!)>>!|Z*RF(^VaX^AH=^jCw-iyp(<>t`kk zJ`Am5$gsT1$ud8{{?2j|Sa6SqbG;3>9aLD)LICmb@FEwEFxHYq+jtiujNod z>%FON<^1$_bVatO&DMf?*vKuU*37=fn##0*|A$5?GC8w{u>A4eO@WnW!MV)zkPi^ zaBP4QN?jUdbq*=(-M)Yw%O8BVDtqvG2F`1XHAowuUO~M9`QFpc{7-_X0n32+isyUO zET3!s4g_2qcd5hU|Dg_X;(1Mv6}X<`8_9lU2BZ@r;OS)|l;|lFy$CZC-}jA&;~-#c zzq{&IMwt92g&e1Y_H%nG+>&?p_cO61_fNyq_kaI6I?{&cpKCivzBH;hJ&mm!T@A(%y?72aV`Yl!eTVauYn_nb(mhD75#9enQ z!oxhKWXNT%2TM6yu2pQL^V(NXN;*d$wjaU}#SfNu^GojbN?h+R)x)p<-8)gkquB(N zHqgj-*oCtwm03f7)I$%WS=;YqUzs!A>#{%m6m(uIp0gk0_kRAzYZUjyROI$!l`FJq zFG0>6-k~j5@n`dz%+|8AsYG`s8HbM%${v(?fksk(ic)ZtmVOsO&xw7EbK~WRT255I zx6vQB?9W2|jnN;|IZ;_PLI7U~P`Z8wb2<^PDwRc>6DLSdE)lYAbD`mz~t z_xi<-!?<$u7&*z{HS$BPaR1R1^&0aE;j~rqh&%C%z3~@#?QT<@2|1HP24P&2^I7GG zq-2Zd%~G%q3s@=A8%JJwTDyojPl~drNvexi&Yh zsC4~ZD+KL_xYChJw|yIzr77jzUPQ>JzT(P>L>#=#ku~XqprPk=Ij3HjN#YN0 z-m(u7A#mCVcXrd4U-C>b`oT4xTrh4uA5 zhng2kajrMR209YD?x&Nt4N5_bBd8h=n- zLJ}K#S1+c;RK7}g^uamXi~83ixDem-0z&4blW}kT7Vd>`Dd3*4)y~zNJz18u|BWH# zInwZ_sLcclf!xTP=Af*;dO-^p{NS(DHEXT=y#!yW9CD%V1xzytw#Qwd3oFSAMHRQd$9YLl z?d_QzB2-U%tYvfiL)#*M43wt!ldFwKB<~VuaHN5;-z)ca1Emw)-e!*Ys(msXQ8faj z5|vc&HP^qh>{T(QmUy;c9ZCPqy{?tr_ZrLlu2S4PVcDe{gv(3FSlgksdh9{d#PN6I zmg2&uOTEh{wzj(n3doa@H;GQ&B=Ve%kov&8JF ze1Eo-HoPL_?VX*m$d;133UY1>B+Ec%nUXiTF${=M2bI}m5Yx8}T)c_=C2gMc6Euu$bjtY@+;R@t`v!Jp zFfgX^UQN5BoPR?$=P`iV%_lMZwSH*`q&x9m?v%B$*{6Jxaq zKy$Nv7S`%O$J~FeC+NvG>~J|pqUa2)>AN0RU8UwA=zTa2JGODJShm|mnr%=r2n?IH zu;Vw!H6<=z0@|w}UqzG|mxZF;>#g9DWBfsZP(VJSoSZi(*Esi3RdOS(n0@*F65${m z!?m^4rNFyUq{O87qq9e1H|pT#8#co2;$#Rg?6Iam>jg1s)AQqz^&tRzE#)hz-#lj+^!X zHq~b6p%_~JAvI!m4kF8X8hWF-IWL&%J&%Hg z0;6`4;NJ<>G7v-Gh7ZbC@M*hATv|L`D|Z`>j;%XJ04eW#cQ*YY1R{U%2}wHEo%eL& zG#j^hF>#|`UpjD6?2TAV2WVc#Y3jkxxZ;LuUj&*6z{-=a;g(HY5dz$ zs(fiBf6%RNjDB+~}*Mj3e75Y?>q+`0yrKn$whMg0- z6B^zGyk@+d4b;||UI~_%t0yESz9Wzbu6idSiST8qDQTA)liD!@sZ7n{OX#M5-Ljl? zk=U^!PnSTBcz+uDzH=iE>r_^OfWetpP~Ldf2T6^>5Lhp0==J_%L&Dls%UF1v@1euE zU~&crk$$fuu728Md4De#fygNG{B~P7I`Bv~&Ri%}I=*!1_m=%WpVBeO%izQXa~T(E zccE!9_j=!M1Pa5Y_(MtOssVt zsXf-dUF}{PK)(QTf^->HiBQy17q8Y;e7r(xGb-#BZrZ= z<`#e$xQ_*23lBuoDnwZ6;mBHgm(a0RH;^|TpNQmPi+nMN?)HUkF3u)4BUR;`&S>P_ z(s6pKkGJo?WFxTCMcP)!iyP=`GAgyr6!$+AS4Lil&gh+n;6uyFP}e^j&t+bX%?qXV zs!t0h_nZ#vw|KVZHdSR@Vp{&e_EN7yi@*3e_O6jdA7LPhietKxxUznKx-+)|72^|& zF0K=c*rvM5n^s~1@SW{VQMbD|Qjvr)NM@x$F`6Xa%b9Ty*nDuyhPgg4*Y9xZR!cgW zUvKXEJM`D>@&P^d(OT#iJDD$l43l52P54JrosLRX2c;$)tRqev%~2oLRGh{n`fO!$ zREsa2k8cTzC7;4PE}8)pqskXq z7=w%+%D&_(aF|3$+n-qM_n4X4vezV@f{tY8y1C+j1zGxd(#B3u85Wch@H^=uA&4Jc z*z&qpCFv(LJ3*OUC&gW(Gp?s85vaFycKLmlyQX=5?Fw8*La8=a0V&h0Rw^Ue<*tv9 z=N^5iP~#uuemP|F9tYIeU1YwvvzG@m9rJ2&{q;M0Kc!oGtRcLRN$GmPpLr`gvxoTE z6214eeTHl-T6Z>D%&(wnzkLg2i3?tpTulqFge*qFS9qni6 zs2j@-1r6ch{Oei<|u$QIsj<~ap)gn8J zY5hJ?Tw2|JHTaU}?KD`V2OZVO1gcrZbBDmakUYvz2{u2dVEnXm=}h72*32VS8}Qn+sznll=#K zSAWQk_S5P|+50~`zFkY{d*3?^FVCj|Qt1J=e~R_wjMTXa}^?nABeLBxo#_tc{^!FMsgmm~)%8 z-B~6Y5HUz4KiJ&Uv&W zD7Gy^yevb20s(#JE1e`~38#(gEW!mn_ zdv(&`?#l!CKr>N+Xc^X%uv9{3c)jT5n9xY3&$VUq*!;OiT*&zl+PD1>Fj&F`dS!$mx=<*Fp zuMq10zP=*MtRWEHXkGz7%B5~SygUqQe}IDqL!Pz(jQp_K)fJW5hgu|AYZ4(|y<+nd z2R{`_R{??e;rf7v3Xp@}vk)H*Px|2zvk4_KGo5an4*R1}nIuMY{!(MWxg4;m0Zd%u zPx3QwF%K9IHj>fkt`)|?+s01&NNYs&haX3`%eh3M6v5u<7Y0q&mfd7=_3QpY0XxC} zIvN!e-fj(vy`gif5g%B1`+pYAl@@xzr_*oFX3QlnmYIKdF<*J#ZY1}RCs_A)t_v_v z>z`8~5tDn+nCEj5ZqnAqzcd;ne!p&UGQd2Bq+0N8_S1d!A`i@i$N5RonM$MA69-8> ze4xg{1)4{oUYneZHIvU}4|k{aMYQKS(Qz}oTZ@StW%W(wy_)j=aAo!V?I&8coiBJ# zmcuWncupD0Kq2o$=TeReBD5+inHP+k3CeWc6`Xdv$MyKu{Il2nQ~GQvmO#oQo|Hg8 zPD~Fphg!ICm$QgT>gk674k$xYAJI!`uyOq3rN#)mDMeWhQD%+gp0AS5{j0lfSPLo) zAgkD>N@wU8H#37+F`u#d1yT#m;Z2{?n*#kWlevqV)mCEW?1%Ue+s7a@;Ky?V5my;$ z)RJhqtDHSsf@`$d_5d$Na~IevH#ujU!|8hL2B0(lRBCW%uKD++b*}E-7xx(t$2+`0 zv(dHrNv)-EQ{H^cs068_|6-KcMPvWc0>54{3~uyX!{{zuP$Vq++-{@bkeRSid%wQ3 z2YI0)cws#PJ7JweJ36BFayO6GYuSdu#1$CHvJOPJETv@BA%N> zZRNj=g2{>5#6P9~;OZJgUJJALn?Ie*$6xH3!i zn*@oKJ1v;mqFV7O0&wyg<~VY-rUr*iSTVSe@0jldJp4kY%_}rYttLVp3f$Ntp(0r8M8qeD8vM}0 zuBWF2njArm;PRpnm7pR$I3`?n7&DLpa#PT(J&Ku1%d1q5tpqLP5eMOYlhNgSZ(Ma4 zyRc(9TIbma+v?bXccr8?aV!*`vq3%Cb@55XvR(!#JfDSGV|XrSf2D=(aFlCtz6-j< z%uF9Z8T?xcX46qexFu+L*y5p*X~?0+-Bpk=QXJes8AWv_eN%2o#6<^dvEZMY*Jo+F z&xYE%9(@>Eel}10Yi(JNbs)2jQl}PFqI-|)mVorod5lW5ysRKqa@iN7^La0L*v=@k zuRHflJHdrJHVThN<`u`5=e@8PJ^?O8;!G@or_KIH@jv9Mu5J0( z2OE9aewZk2tIbRFuG80!@gw>zRP6h5g~&k1LJLuX3aa(Zb^VKr`V42s$zG7~*V{yDaU~+64hte1m;ihpq-?)aU{f91N zFKu*-t>i09vO2bm-A7y{sYrd3(0vV2TtdAKZqh%bTc+H8C+};#19U_4N0*kM}Krlr~$EhZR(~&^!xu_>s0n52o@yYMe zFa3r5)?}A_LN+hPlR^%5CawaMIPv-Abyh(UW{pHu7+$smH>5;3!Paf_7P3Qk+{z5`xjfnqF>YnH{agOu^_1=`e%pB{XDL( z9Fk$EMj<8*5Berh!`C+x#n5RK-A4MCjX(N**XR`f%qo+pn%c{RX@-O=){_qtsB5_2 z-isA3J%glVQaWaFqV-dBr7ACsu?X#aolLFs59;g#kApzwvGZ7YfLLr87qUD+l{aZ< zc71A6igk0J?f9zGZ{ds{YZsT+u|@hm+w5PSP2MquoXJSP`{-!)gV=WF}n!N(ju+&Db0z}ksia4FYi8E7zP*3sP$l(le9MOK@ zP6w*H`@IfllpiXOBeuN0C8FMdoR$pYd$->o$et#GK7Xx(&0flHSWdq4Xf!TIsCmd_gZ(pq5QR{kA46fnI}jK>0Y(U*t{7Hswo&^(EkIBiV)sH` zL|22UR_ZF;$das|1Lq7dy4Wh2RNEM-sO27F~fUWCU3w(;Pti5=s4j)Z^9 z7*YD$v6Q#m(9e3gj~S;xl*A1XIt)QZ*9t)KS#oMV#?{_&gks+)-Lhj&WHj~%&T{P7`mp5KK5w|XHmX}Q3@7Ir+b z9B4aLwGCs*dSEH0MTfDII0IY#{Yr2I@F({WkJ?KTi|v(#n89AaBJ($ud1HMiND~Od z|AdlrShmEYkMgP|O+)bl2OV|7!J5?bFrGx!mw4NZzRszC6j3}eiWo}(2trv*Wj&|dUD=hA1CBh)a592a2n43>2lt2^0sS$d~)f%Jc zCD3xA(DY$V%l%n09OWvt<4@1e#0E=Tk~PMydgQB%Xgx=KEz?+Sp?%{$#+O)11TySN zpL(8lJ#og=Ux`FOf$Auu2+|W>>NFg6hv#bWvj_y9UG#4t=d26Ec5{`f2s~|R-tx|j zbDKMOyqN`rRXR$ta=qQ&zWF>^7Ftrl$l1r7$@k7OkO7HU+CTW4uwU`&zSu5|EZ}$@ zn@1~iC#qV;wk`G1^HACtr;=A2obNV`$CE_3q*jl;lm_4}wzB+ejtY3i;b_B2W_k-2 z?Fn(UGMS`8%~R);YQ7F!y<{Em9gK#5tXr;Nr zCwkxo1QCwTV<9iCIA~ntrp@yDdJ~AxjrqH`&S44wzyv+x7t5Vg^99=Op6A4@tMPz* zK+4W}_Hg^>;)fjxl@pvY?3q-o6Wtz4O5rx?(;m}{2m2GQb(z>P4!TI!SDHAPS_la= z{s@FWwuw$oZ1a~i9KY#B_UL1p#L@W*#hKmX+(szHPJzewp973*P+Gk6XFwV*R^XUK z(pZ%8CKkh4ZWjld{Z_gKT_Vkp@e|qE!DkR9hJHXzfe^X=r^7Pq1d_Xd6*L#pdtfdg z)$^=x-(egQi>@B|APL{!zVLL{OCdU{a9PpEFCL@nOv^+289Pt-iESE0cR}@4mGi1q z#|>wHpUA_F9J=jv(Gog9qbJB>ltMH}K&Ul7>|Gpii@eDImdT>muJ;FMJXA&? zx{Vl>It3ISgVWl-B@8uM8zC-|c5%LTPqXir94=$G>wiRvaZB)Gqs7dN=Y7BWY|Zq& z^@olxr}jqV*3szcl;Bgf9=uGP>dj0?VSw~EZ__B0NaCfB{0PZZRtb#k0e1wRa^Z@4 z4$t7UH#nZ~Wg6MnQLpK#4RwG!f+yTBr|uQM+2y@g9IZ?l>p;b*CBdy;F&y+qV_i03 zk36_;g~26=+&#_;%Bld`{it>i?aqspj4nE-xn!Ff!Mjc&i0nHEeIhaXBt0eL-v zmg*xs7f^Bi*8u=RHu5 z414FgFX<_Ojfdb4)>+=u^Ip539QFqIlRzjUkq&M1Bz83B8!#9xd(}lVjnGs%pT?*y z$L=2wC{_}0Z&eYow>-mAEbtgCBh#D4nC~A~x-GNNjSIh4)g{tLoxZ@uRX1jzVIY+H za%Cyp)R$Y2;z4ziP%m6V(rmstn`%SIV95tJ;)xS3R~oX8wAO^BJ3E_>OR z7UA1da}!xM>`0WXD949!X;;jwey3fNfrv6E0}nP(7ZJ+ypYtX3+1^b03E5L~-tlHD zs{M(h&i{1sQwISF9rauQMy$CW2zR&^982nu=1bs++inKci__TQ)N?MQypNoM$+OES zn&S{Lxpo>uc|(9vos9suSh2n{1~=&?)AdzfA2#M3FdxOdcs|!FDY#af|l-4Z3Uc@JhJf|bml*;!Z?$G^Ac_St%UWi^8`l8?64J>=E2%<2u< z1QZ*c3T=L9B~a|Y)py_W<&w9-qUAD{#0zkiymWOSt^Pr!(FZa0@__obHqgFRNUuI3 z)z4!Cd^Urj5mQ+lg*pxE-@>Y03MOvC6xgg}fn`+izW< zReUL(mcn<>{u~T?|Jh4jI-{1l+Bp^KKpft?m>aJC+FGLIkkcv{Y$d8(pLygU$vQar zJ^BUoEgEJq#EHifW**Ng)s5Y|a}OQM^ALe>4BK5{hOLDHgS>o88TrM*hqU}Vx#TXG zUfsmpq~nJrv;CiDO^3EIvEpJBUli(IMbkpjG@dp0{1#vzWd`v?(0(QHg0{1rCHJW2 z_-x~;7(SuitXs+`j?&45{a?$z^`;`1`+!Bo`JS)mv@z;it$%=`JllpSEyE`-=e7wA-lVEmmVvhOs&|&aIc3t) z@$B>5CXfbT2f%;jPhNKW%@_m2L<#=dcZ&k|Wsio_F7XRhfsx8oUU%VHfj`887JIFkE_s49(8GE>Pc?Lmjv4dr~eK&~P4`sY# zibzfVWZ+{NYhaysd({GT^C85=G~5L^H~gNvy|nSv<6;GL;Ai++inyp4D_8T??K-*iW0j{euv0zX2_2K2W&ZhbNEC=$I{jQcM*dZx>JYz2jchN8_OH)z(2N|^lxl}4UJ|^zD@eF z?+e`q%;NyRs4<2-4^UC1_8KDHQ*8hm8a)=0adZncddbUYbH8$by+)2&X7qeouT8Zv zVFtoVCTgR!GuI9$I0M<7`qoyUxo+>WAv++}VHWQ%{l{rcCco!Y__AmCb$i@qHW1z7_^a;O-QFo*ysX>I``F3KS0F;J8*EDXo_H-HZr8o z5N&mZIp$(C9L|tWIwHy!zFZx4-HEn)Mgi%^F|*zX4di0cgoU^*!5lKhB*a%7TElc& z%nynfcdPT$FQwMmjkJkhmII0GR) zGX+K@*Jp0lVp=p9yB2d07=m^re?vL&Oh(i03c?(T@DX_`K4g1#p;9 zAfO_eghCYGJ>WPJm&9vhSejy!UOty2C!Rgmp{~4S5SO1DM}C{l;+l^8@`0)=}krsB@t}gx{clL+WOq`3>+;R_`;&$gPCIN=;S`4t(MRM^JQP5hmMb8^ z55Da2#Y?~w{EyQs|9=1?Gh{D|SrC$JM#N~xYQa*n`VD_Q!Iwjo_jFZOrdIJ@a4u@X z7#&OzPr8z++2rh)!9h#aIKFURCF{=6GgaPy=%XYn2DwXG-1GR2y)TAFAfTJ94gUJ^ zM4*pR`$kM4*#CHp0f?BZAgE|CeLaSSs7@SAwc@*X#JT~uA$sMIHLJlkxMx5`%?%dC z!#_o`??30&GlSYt!5E!UwA?)4G6rIi16xVXPWP<2MnK_-Yo(=g2Bq%Of8-e>ygtSi z%{)~2Z@d<4-*?%oB2n9Y)w)`**PmAnl8%27rjy9~Av}KJ- z@}KU}E&1VR4g--$TB~q4=p@9@w~84KdDsEsb$`3Nm4}Spq~Bm|8MyMth`WNXo!Yv<&Ncw$^U$z)$$`Zl=R2)89b8xwkpZnb%`#{1FZT zcp}no$u0_5xoUxu(F#1$M9F+TK{#HfJ)qiI@mz*2w0e)qdE7AGD!$p}E?2Q68{)J1 z-Fw{7j}7DmrR_P&RGlntY#`=FAVyxjHm}G%_pB8$AAUUIT=WYJ64p6v)59eR%pEp@ zCchQtKOwSm{@{J_oiGkgdD!Q;y>3NcUg$3Oj~$_qikvi$+U z!9ecUd1to0y;}z70y$CCV*io&{@&&RREZ?yUcvXHDVkqVog$tlG^Tgp# zj1Y)Mul^Bm$Z#?KVp|=2GaNE|?hM`MLcJF9l*;_34nGuyfh0`v8#;Q2C1KmS{g{HM z65X)4;PD_*cFzhZYu8bS0s&bL3nAttT##I@Ky>WjHAj(OO?sa2tC-D(;l0`%T|U}g z7Cwn=*FPl=PlPIpQj=(|@3Sk_2DMKR9jr{+K1c4zLUsFAK06-v9IwN4`nK%9 z1`%-;i8^!#(QzuYG#vGVOlk@2%it{I?sX7i_BQjWe736pvD$Qz8iQOlH7e2D+Ycp4 zhbdT9KD+ln!+As0)OXkRYCVZ`J^dgV_NMYq!u>0({e`-P1_5?8vjoz0YZdj9eln2q zdD`zJ`{p;yngS>goF~J05QZv@N;-mR?b^3FL;F9dg(*e}`lg!kKg?U%Wbc_WmPd-cfYxqdKJ znwHm&l>vuJ97#Ov!PrLK3BKmD{pg6>?FBONSm@4*b6*C4mH@PlKW>kd`?VV3By}xQ zQzbu-?6>)p^=d5GkYdI6cP0)X)AeAx|Db7nW$44%kGJICB;+U)d??!Gk^ZOROhd3-fRZF}nJY z8nV)`<|assxI)=FMd3E2sKZD(=$$=}?VXFyAs-LZ7INr%0U9JWLebOjBfFS*T|wk6 zo#?7p|JZKc=pVst@S4&^@}#IMF)DRyVP#3jmW2xEltt1w>8Ob_dRu>Mrc`{fY;nph zIi+)tgf7Yk=FBBcJoa%vqYPa~SL3he_VcQReMYvQd>GAx7>*Bl)mYBci^nsod zUFv3yBUhXp_StICxN!0xP@%ixU4P{?C508J#b(!w@9PjH$7_Xi8byLyTvd?EJ4YYg z6YJi}Zf*9BMg2H0$*K&oqQnN$!i2+^{J^7+l3 zgZ<4AP))$)R1vO$&c{K+!QIm9D2&tCek$u#+(2-fqtw~h;~7P(H9IHFmjX~f`2JyP zBTit!_qlR;pOUjtGFxkZi_{h**M?_~2&uVc#*R_tLJdel0J5z7!Gd4iDDi0fdFlff zih7E}yh=SFz!Ie6!%=UxW;?0=yD#z~b*qk(mAh$YzIMlXikAIYsG!aADac z9-G83`<_Z5^iG2fWgc5<9+Jds0Ul+eMttCsR;;*sR6n_Nh~vdzy*(BX_}d?|Ne3-9 z-e;_u7kqD4P_^lqT>-;gG4ap(H=o+tCGqP;BU1r<;@yTT4r1K`HW0?BTcXKN0*3vG zZ<^;*#1`+Qg(zY;Mi(wAJU+t~uug0fAClI}$+$=$ddNXDX@U3JO3n{o*}ORbyJoRt z1X4w0z-ocb*q7k8WSi-U^UP-F<;-5{mfVj8ei9;v)$WQ{OpVk|`+aw9+p91VQl5z* ztS!~)6JKL)OifU_6t15|Eb*Y&DC(7)cbRFFqLnn00_U-wGVCWT9&E8EL@MWVNB@?q z;<3_W1k-D@QjjdiU4zZ(qZhUp`h(jDXBErk0mwO*__F*gAeAn#MEwY@e`F)E^ztKiNJsHCU{zty{8YIgop+JB(}BZ;}o) z&hc@|ds9<7!w`f;$_TIziQl~SuIk4owG4Z3^LH3=ce^1=MBx1+9dO1B`#qzXm`#I# z_?bVJlOJt8b#^~)^!fZ4yDr@OZIM1A40C}LxsbI{ynDJ3YLHoIs<@EZT07?C*dt5F z&Bm*lLT@k3J#PY|pNCl*z38sF53)bLUoO`g&DUN2I&I^;@00h|(CRerD=U>bQFNk( zRrD=jwd?*}bMb+r)9cTlswdqZ)`(L4RNIu?Lz&0vG7)(GyTf(XlQ1pFWUCcl!aeca z_t#dpsx+$kJLv~{-!KC-V&V9%71gB4lIK^*HLv;06@5Q{SvL3Jk2Z*0A^Eu`<8W47 z8+#ugSnnf}mS$rk$=X=n`L*f2t3`EwlX=DaX?3Vu$hqvO9yPI8p(mKA`nBrAkc0Q5 z)wicGFg#WP;whQie@DH4b?ydI4Q?r2Z|OgGQ+p=TFYQ9an_s)`WrX2F7FI~d7hq(i z{kyuo#@A`wYD@T%CK|$^^!@&B41-EJMWG}kO>fl)w4>A1Cz!h7Mcc>oml4O-o?#HU3NqfN)i<@5Kj}`By+64bzQ#8i_-~^95(H<6_ zT*;A1P47Bxvc(tNVYqK!8;_IIxL@? zmT&Ft(>tV1o%|gAg8#G{#9w*ZMNmx2-RL?Ms&PM7T-m1KnR=mZ^#yskg_?10G-=2I zrU=Ix>KiB^DJZcKWRyfV3bP%^%^cHEem%2~@`kkEHVAlcD3m*{ZpWi}TJx4Zh$0Ia zxj~TcCcRQKLzbwyox`4+vp?Vs*@F9D>^|QP7H>8;7t}}Rr`jxR?p%5We|?c7g7FAb z+CoaJS9lXy4)FE4ze-EU+dh%Q4#Fi!nYWg}nHoAGEh9W`)LU)3}`nxe_UuAffZZeeW2XpI-B~)&Fwxsgwb zK>_`HZ)c?oG+|V<$B;3_;gf#}&)HAunlV^G*O7}XOL?p23Ryn5{fqMi{MkI15* z7(~-VXcWGma(g+Pd%LxqFc%+Yc~M=5F#?F9!J3xb$&0lSVbD0%IKBZ?O2`u>B!FYe z;V<#(NOn4EPDW_v+RgfHDfZP)64ps?Y-HfxNq5?OpihN+@BbO{WcG9TEGf(!1C|fa zBrI15AVOC|VdPC;vP`^HB#{m&(m-GaCXjkU2I{Pz3kX`hQTp;~I~o!X;JO0%anQHu zsTuFxrR=9MT_Er{qpZdV6^J1#^C?e19fmePBKv`;q^)f>D0ufu!C}iriUJoDqrwW{ zhb@3fIYr$j_coB$EE65a5z^<43=orSTOIz>9+%T^U5h74Z=8KED;f!XTg>H-Hu{^Q_<8xhFKg89@94Q#vNE-E+QV-vgs6#9T4N0cqAv*(m(;#QELSejY&VNFV za=FLfMDVQia^nE`S=F)5zm}{<77_YYGI@J8y+=0s-+tiXY zrBcxq!c85%@6jNT@_yMj47HLrjJx7(pHXD*Uoi}Fc(jGp1U+Js)@4PFx;=&D&YLR= zH}aHQyP=Y(en6)YYXSiRxHD{xzhDFY!gT^04CIj^xru*Vq)JcJdK{eYkFRxh$S@aj zh_`B)PffF`SC2Xq{r6_h zl`SJe=iFQ9ec-%5+!YvUs(96kMvNMZ_vxHSqNtaWRf1hWy|5eYSd#(1H1$W@_k`jIoe**) zIuanf}zJ=1FM$=S*=o}TH-lx1J1_5i^N7@2458EMsH|A(PV2uM; z;q`;>;R&79BuM9xnmg2l>3yeJ-P(%Kot573%VTz0mJz1%t>zbc)ul44olA-K z7Gu=H-N1vxcb-uMz^Tv2-%~z@B8HdJv+S|mq`|(S?^_u)HtAvQ4mFVwIGH?*(}jWx z$udQxe6WAe#Z%k*V%-3e!;6N~F5A#9(K9S9BuUq`ve6@?nS4=*CG%Kuj2*}u4IB^k z6!vD$;lka%hn_)(P67CVbwlia_b#7~f{YtXv;SVg*!bon)QhLDP5Qt#wY2mbrun_g zQ=6H$il8-S*%vYm+a@O5qcL#a?Tovmsqzv?iS`+8M=m2K&-yYWmPDGp74&0L)V<|$ zePqfGJHk%ZqDej0%@7ST6bZeJqkp!%{Y)TwD7ojYWK)ihS;WxrX(dHSx61%^ly1qM zjmxRRr{YBd_!lp0og2zM@!?$+42$uGj1ZhAcYW{sTtkwVRfIL7J+g6(z=?RE0FAwY z(;g6b{g|3vk)W)Rcw*W6@gSNMf;dr@;BsQP`%dY;;>(?Fr4_Jr$5T z>R_tyZ}Iot0#;_r5p!XEd$-X=F@Nx|_Aj==nlMW}m3*Oe$V4dBu5L;X4LOkCb{RNB zW1d4IG+3(+Q2?`+eVC~#+A^P!28)SPBg^8bEpLl=!&BcY34{sC8+KB2bxpE+W-kQJ z@tUMwEhrFiBUWUj&qr8E}XfX++Y7CYcS->9@?;xYOz7Z#m}ID85S<$j8`%7$9cwy zIgc`cbi@gjNbZAWP9Q*q;DT(adnAUDl?wsU+*qym=7lqeC5|O8#H2Uc3S`GMCN(A? zGIAqET**0r=y7g1T)BDo{5VcpeOPT)<<%{{&V_?@(6+kuS8ML(j+B*ZQbEZ6>H)5E zN>6a_V}sH#%xV{sZIn_|mVKewXu)2B4>8H3;6^#=E!N#)-e23dBk*B~HPgnM_c#bz zV#Vdzrsqnc{5l2TEr;Dy)*m_UroPXIX$D`5h~f1F_yp$taLM8EaIqy^BkhE3iT+n~ z2D%f5Jt00KDC8mnkwq!XkMO;$-g8}e_#7@?rNTS}hSgVk4zQQ_%KqI8KEx%S*kfV) z&}1h zrR;tzBz0JdfeUL>&!^z&-@S+Gh04g1;e+}`zh8(@;^C#MfcoF6KetXk*zG?MWUiSA zIaplw<^5*0xt6=EmW9XPi#;3nx6Sp(TQpco2OpO>=p+S#jjL$b(=R-bKRLw)yz?g` z!!yq!5s3O%XM>L%L1;aOzXGTVN{8TqdiGisJd|tLep87yW2uHLO-6)l6|$BLnPM_Y5n3!owq%P*#Yom7 zOL3Uu3{gySkiAT(gi1(biAlq;4Rd5B+jqZx-{)_?`MopG`#jHmU-z|~Pp~BhR8by3 z;_iAtQxHVKr*>EPY>6k>f^E<7m*sLBjP}2Ok#YpD{uIc@e$|2Np|Css82NsJeK`Y2 z6Fo;e$Dk(S?l#Krg`j~K>Vtz?GQ{0Afel#Sfsctiu@H&1zZ_}>|h3GRwNoE>A%w5E%Hju4%KJn zV}{0OI=j4})^o6*A7A{nt!uM(Gix%x*BbTL%yJY@&4ldpfB_(c23J zd5ugEenO}NP`pk(75gL6Yx9`nsDfu_CCedQI=+b~Fv1P2W&E-enc0~<%4Tmfy95-v z$zVqRn^+7;Pv*jaDnAxxg`ui3-jazxOoLt$wFjS%Sic$h&U`Jo<|Zk|F9fE%w{3H5 zV92x-YP7uI?+0{)q{qkc50BY~v4Si+c;v!_qOIuZ9y~yi-ODh9vsYe(-#QY9w>p(2 zXWS9rBH85y6ZTnak;-ySNyI;ThrSTE>Nru`0!H~XO>h^$Zp1X2#vMniH^{F8^5@Rv z>TlHlu2K#;bOt)u3rFRQ8<_e<3zYt^!;NTYun(_ooOoMVvUU9nb+!E7$vLN??&@m@ z(jy9>DQ&HoBuqJ+N<<^Mi;Ex#=Z`qzgMQFz!9vkS3ur#}a7Zi0l?vsJQs{(`5 zVlYsF*~Y~LVb~@UbblA8s%zg7`b2ubotVwsG+|Eb(~Yw;WEL ze~f~H+h}#L#;GH8vR*2DUnow25*)k$)O~Q)(|?$9u?6sOec6q96eSd9-6%|?6Y&xi z&!)V}BZa+?SE7gDELxs9nCBU$p?ueZ`TEgaOjwsAT)z;YS`wtzn=DrF!J}*>z`e>T z(}M#phm@QHP~LpL1XjS8o%J+w;1zj&?zvsjaUyJ4<|>;5@i9 zL2CCn$#1hHmOT>C^q{zia0rv%Io5Ss0`dbcls-|GuxkCcox{6ZV^{C|IY^FR8wku# z9*pA}u0EVTe8(IhB^$W5{8i$FOs{N*`$j}w4e8s{jK#U=W<9m@f*YAN2|lg!ZZZio zUgbY7cb}>mOeX(3zfOvfhF2K;!vCZVHxbpmCkO_3`O@GR`XR`&8SA<)tIabLsKo-& zFV73b5w1AA8~!vEy2yFL?tGYXP5_P-QXz4b()R6&x^*YRzbz9Zk=QJ+pdc-2kPY^S zCM1W{hKjnJ8pk~w)(ZaWO;#xN!MZ!^2}j9`y$7@iQCO2+wCbg40!Cu9<)%DfX|X1M zf{XO|h~Zw)UZfGXG(#iN#GfUl_+`nsJHY&qIdl+1y{aM2YafYd$gn90>i2i%Y%EQq zE#-|{=*t%N(7@NSYf1q@`eIs5r&b}#Z)yr8V^edVw2oZR8f~Zz|2=}Y8dmxcQ1w0| zN;B&e|CS1bm2Zu&WEBI>QdqRT8DbT8QsW41FFv$+@UAd6;@(V)sl-iO`!PSbl0_Cm ze~C}%FJT(GRCxM}(5;(3S+Ebw`#Uw2<8~^jfk%m0Oo5p75mQUltYah~4Re>)MCo0m zV*V86mok^Hps!k@g}Z}8aW`D%Dc9j3<{m}CI!Wrib6QV44a|lud#b4nwX(V#MG>+~hztm`uxu!HBk|L)5LZO9c)5aoESKU9~a7I%S8_9>Ss$bP>9TeCF38i66o(&DJtZxEFY9JAw3_oi9mh~F*h&(T=ffKI0E`JVzuYGY+MN?lKk9@L zgkQ1#6^tt&ZO0(HenRAM^8?N`)HS;paBnaz8Em-xaz6Y{?vdR-m8`6`YWr~T22;>$ zx<>|Acq08h_<8ow+N<=Jb&U+cWY58VpY_Fr`k^!HaA5y?QuSo>1J7WR;aO1xaoG$9 z9z!v1m|{ZObpm)K6-panYg&&ckwR(f40)i zDz=k{v4_u@M*8&cXb9#T$?f$9;)J!@%v5^D%AhE2CbUtD$P?7|`_6={uuHZgNQ6+1 z2~rFE@hYeP7K{nIp;_bg$caLK|B=ab1&7^0N8m%~>C*%{%W`ISw7Y#Pe=TI^k2PB9 zMMbo}2dwkOhj(s~+V!_hpN-raeh9uyTdP_FQ4AT#sU^>Y96%oC*semdd2C;0h zwj?U1VeqW#$;j7W=mAObnXYRFr!P4;Q$L1xKaykYODK}|WwZjM zDwFsdAk|}1er(zvV7nXs42V8eE+J_KWJV@4uY=>KyPZO2U;o=;>P$ZfwkY*GD8@(b zX{UoZ0l}yAL6*n7L5L!PnCuP3ui|QmJZ66?^HGz(3vr3WK^^*ZjS3yQRB|C$RavmF z8Pt`UTo_tmIAj6GrmQN%&C-OXvlT)_VNzeN&I>gfa1R}hZhrkpIWG5nD*uMMl$-Tl zKt>t{YpNJbU z1Vbd1x27FQizJ>PGG7|iY)@)6`~KH_)(qxx;F-=dB6TJ}%}0bNP$(4c(EzyD}P$+TW zvB0N{a)Rxqv%FDB&(@rJ&!q#Df8bQ^as%pG^w#t*NAC(5N+Yz0dlSfbiR)*A@ozS) z5i0+77<4Riec;Hbkhg$>+XMS*fIoMfZv+3pTUg4>R|F&UW(a8>d$t&mN{*PS7&qwX zAhocElGL6dHw_Vz3SuLSgYn1KctGYDavzy7;cz_=Yd#?O zlHyz#?Pv2Uq;hh=eYtnK`q$9&40k~dJ9`C0?hk(aXpyb3az?7jg6&!5)Yn?u$l?NiNP4i-^~Zh8n1;VPy#L=*ltS% z$iPJN1QE7iaLp1vKF#PLc)L24d>s2{bBt@1(-u^(F}O4-36)=Hp&g(WNv^i*3mOr` zR}7ZL1Q>NyP8F=SfGWsKzgYGVZ&e!$mZMk;Pgw7Yt48vsR=u%kD|bE>>k79@C2M`; z$H@v90C19r{QX;=cEL!}=&=e=CS^CTqy1eCSgL8r!UN&&GUos}rL#{9YGFsep~}l)1b!`u#0S^PL_{eYk^Sh8w}xp@RyCYu`v>-m#4zETKx4d-O zdG^d{hN(|w$o{?s!Ek>;P>z_*?|Bio`6cY8nz5U_G&)tJ=1l$9g z3LWWnLbpK1V0@ zezr|K<`OgveWIc1tGGD6|FoT|^HXDq;jZzHr(I;JCYypL#poS(BK>J}sMv8X2H7Qc zUOd4+tVxgtw1#D=#O2z>+ffob>eU&)w3qS!#B_%ypvF_FmxYk@RO;-e?mKQRqC}4%&gFT zSit7hBAU;PkwHv3d1XpGC==oGn-eW zaIjUu-7(BnW}_$H#WEb`!|Gr{KTh9XWJo58Hx@Z2 znCE8OT-K3h=EIXO-GW`a`&teh$iQVlleVE|pMEFmTI;ySx#yh+FZsw1-xrEF0NSsG z^38TbrR(Rrb2(GaIY&-uO!(iV+FReWh$(pZJ?NvEs*$pDi9nFiWSec9RFX@4%37PM7&Nq~VcXmCYwfc2I2*7`q` z!2QsN!Pe)wl)-6^k5XlHM_-}6!tl)LN|uZIR%P#Xf(i%{V(Z9hR4 z?{g;V5bZ3N&e#AqI|erHKoXeIb+`i+h5ff4Lqu1WGhM@(t9R0q~F6ddVL*cjQ>U-r$ zK#&?AoOp|Edf+#z4zwS6F~P*t-Gx}n+OKGt+LXI1F5?+A3ynj77Bpec*!S>^V5*Ez z;XF?75>UW?l<)avTChR95f-wd&3q?#6qOt>ob`-u%9W3A@?k+f9>*bf z3n7^dQx57qaEMTG!o%7^yAP>>-nzy1tJ}eTh@#7VyZU<&KOgE4KZpErgT~nEOWNq9 zw4xYZKO((E$501Fl%LsO2J2{!X?v}CJmC779@|_2`K6?-c$;Q3+6&0i&YD#vmouGL z$vgpHH}s-#S%(91q#-IlGw>IC~AW?G4NTkn-y%m4~xt#)QtuH=5j-g zqh4QYwK1WclIp$k%!Q#G*GNylM6g}753%dY-9h1J?w^iS&3HQG|Fxp6%S%)lU8X(g zGJR_~nPqNkE>cxecKX8>Lf!4Ly{Y7c((|dVrFH zF&~dVguz?=I~U&CH2irR&kAN&>>2Fl7|rWAnm9eMrr+gEu(^n~gz^Lw=b literal 0 HcmV?d00001 diff --git a/doc/sequenceDiagramROSUDPMessages.png b/doc/sequenceDiagramROSUDPMessages.png new file mode 100644 index 0000000000000000000000000000000000000000..eabcde945b0de8c8fb27084d838eb65ba35e6141 GIT binary patch literal 67947 zcmdqJbyU>r+b@jRgaHTw0xI1C(lII}-CfesND2&~q9QE}L&GQ?0@5&)igZbrfV6bS z40Y}Sb<6&p^PK0r?^)|z>-C?_n$67I-#f1BQ#XE!@{;&CWH?w@Sol&8#gwtI&f;TX zozcI54PIFbcuo!e!{{Wg>11qY?`Cak=7c3_YHR9X=wxbg)5z`SV<#tj0d{tKYeQQn zXB%raV>_Fxcld8$VPX4NsA@X>ejV!+_?V}0t#Bo~t~*!iN2wPDLKXlP4Tp=XBP%+gO@BKx6rp>+Ta>SCii+thxrfyou%9lGr zD|=U)GuFmdSa)Cn;bKZo2dHj^d*-V57LCxVu{b ztH%14Xmh5O6y@S~`=DGp;?D<58cNPI9Vt%gj!rpAD`gPYkwOzi4~H4wIX1KL)!OvBX@s9JgJdSpZF>r>DV z8TVh8VuTzUCjnQxHGZ12L(`+@z( z^<9seMNFfYmXh3!PzD#qW+`^3dXe+>UlWE%ATGP;)=bD?MPBiyYm5JszE9(!?H$zi zIf&m%{yEqvIrPPCyQ+&L+-YCFCnr($JiIPB$w!kbIOG5M3fG&9Zx^ zMJq>5X+N!Bt2L+|TV(H-B6umujh)Un;Aca5rs6=OA2ywp%}3cEgoI@kefQp&XYWQ6 zzY693s$&VkUK|-nK6CDx-)EJ@;WmVk)&zX!TDatB3w@e9?4d1ByzI6&0NDhAe_H+MiL$Y!~(aS5Hh66SE z{+%*>F*U24*Ce`p@sdQ}$P(2K+uUX*YawgCPAEG;cb8S;PAiX`z?rUmYl$xP3pQ3d zsTLnnnQ3qqKS!zd8#pcswyWjpUpo{#g=ly4b)4_@+#cTb8ub|6T|4N`1Ly4M-wtJc z|Jh$ZOF`FM4-TkC-DjI;3!pPp>S0?n!-H|JWthsJxZYx5z_~;^%atBVWpwX(gWs#M z*Dp1<fs{IonIqimqMJZ9Ld-+7V3syy?e*NXOi6hPQvTWsk67~iC>cw z7!3$IYoR8qZM^5QBhlNgsG$&%qLi`FOE&T~w41}FB)-BgUL^i_8{fRNjCtSli&yyb z?tFiHrCC3#xrx3ReYn?dFfclG@boa^wWL5HKYnDl>xBM|tqVB*FGO9~%By|IP`A#} z-JAUS#a{FQi$`{j&ls$Fr9(khPOi13rDAK)%B~7E?Q{O}bxMyya{h(9jf{r2tc#{Gq=r=G9tDHkO!d9ciWVECa+{P)N%-`6`| zL%+Q@LgnJ>Dns>kNkLAo@&G-L7a}|ubYn}iQ%mVn8Oxd|p6s(=G2+g`m8C{YviPpj9r%e>JKv^hu||0OIJdMM$H@lx{j0eWovX#|GsT_(We|A9G>H zyK7D6FthD^zxhO~^Wh8*&d;`Er9R`%H*KCh@i?D#;^ zL+tdGI@NctN`eEvhc=@L)8J%5Cx`$ISA9ZDPe9oZ@@WfW>P99!+DzAd?GcqzM#NcwMy7)uby`Q z^5Kd`MoUk_@=dZ>)k_K<0<=rLAKqYZYsl;1f1iOIazu;b;CS&!U|mKP#bNV?E-#cHHIVS64rZ@X!t``Qg0FDOA%)T-%+7Z8N+r=M=KE zl!oljUOw!C42Nx$RPX!8MK=;qG39;D7v0oWUhB?4a1 znTBTTmMWH1?uiLXPls}ud-X&)9_-n9PLNZhCyYb(*9aB%T*Sp2l}ZyTgb~n>W?6dC z?k@Rnlu%ueePLQ9Qbr>6YIgP1Tj5}tQ@ha?L+tc2EFje(6OdQR32ovKt|wj-k|#ZfgR0y zUn8sxJ)TYUR)scXMiK|N(&Mg>NdQL;HP^cDgy?2y$lg*t#Opo@>^}49{{GRhFoP>T zWCiCZX_m7LJk@=Z3pYqgBJHj=w0j>IvsZ3hgnLcF+l4l}y}ub$qNZ`{Lk>%692_01 zP_21BQ?MRys7>+q4iu6tn7-{3M~e{NwYq&>soCJr*>z9feYLjjviFXt4w-K`vwYY6 zTWOnYkt&%4MHQ=cBrIs7JSF4X(}yN=fn83+QQm2^HgKYyNqQZHxQ2);*V~y)oEVZ4 zX)Mvp%JPK#k#eh_7_|u&GYa`kCN@$c6g=lHYiqaB#%G0&J|`4Stbx4|dyxR&)W0er zDq3`~T`2CwB7-xy-}f$^&=JDrMJ2KWSQn zo)voUwU-%qI9mG;DCM7?`nH}I!cFS>pn^tGLm-P;3AMl7NVWgdI~;avAl9yOb37^J zz$)H*uDcyN&1ExpC~;e4;EB69|842i8!Fq6pFXXGpd`IFmc{XV)uqquKffH;X>itO z`EaP3f^$n_SctgbycoxzYI?{}bIGOTI7$D(ugHLKQyz}Fq%xE%&6BYQdWjxHUA^@4 zdFWT{y3NhIeo^~3^}ME|A?ke)HOEuA`d%R3PQvU zSa>X%{9H$(!+vI6WS&K46iVYXSfpfr~Fo$P*fpi)ayhvfV~5@fnpP9B`-sKLq>yG54ybyhS}M@|5ToZO zCYN&xGv2QdO?(rTK(C>G;IC=4s^m~-RUyvMfm*3qZLBkf9jI@0g2P%o_p7=%Ff!vD>e1_ui|Q+VsAe7hVT#+(Y--r5|c%9I8^>M6k?o zSVCi#^hxvTE_UxMl2rGr=;-7H?FzVP#I2Htb$RMl)8yxmSapyD1jR7PP1_3Z(&+KR z)oVA}oa{iKq3Z2J^U1x;Mo-#7jm3gLI3yQ(h0Dz7V5;ROzgrz+Qeuhhx)tkf;mB$0 zctlgj*!xz0hC7~6hx?z~$>3KGFK>&@d(EkMD;gNk`XQ0^pbVOZZcKz6BIBlX8g6z> zD_ck~+3*afXABZv_Gw_qS2PTfZQ@zc5^xdJA{>WuR+qQ z@2;x%8ofgLp|_0GlvEhn#Pd$@?1B1v_O{Q%^^I9Xq%*=JN6*~foQ)B6cE4l!kk?N? zGAuzvYcQAX=H9{bp`g_*((3&t4H4$7pBHQ!k9TP}L#dyc_k0jp$w5!9NS3}-n7a?G zm?_nDHQsY~F)}mDr*4-7Oknru1nuPHo~BCIg!Tg|&-_~5puI~G*IB^E#G83z)oYX#SZtzA?>1$FHS(t)qKoNaFGJ{SEK^-1cmm2 zax5%U7!JdqkZOz2E}fUBo3=IQ;OVXGpWl93OBL(n6Lg;X&s+hJG7xo`p|JnFZx@Ex z5evA%G74RP<+}_ES`G+4^bVAMSYxu%5KOFK#PqmpH%AU)%RTB2dGnkkYj2@Ip;4s! zuq|}GAu5!e|NOkLzJvDq-nzz%&)bmIuXbraVGvYfFXo8uKUx)X@i*5HBr=~H=UtTP z#7qyU7o1gFLhy6+Ht zjP*?+HA8ZUDn@~)Dw3gt>!N^?@)~YyYc+M{!|sZx8>>$p64FK?Ifp(~J@p+UClAl1 zuxWu#3=nuyjXq{}@ICXtavZ?VGomM( znhZhwwE>%5lkTGBIcWpLUUYk*=S~fka=Y8^{-MN7Glz1ex3Wvl zg;hiJB*0Wtd$RixVR+*FN&((8pUK^0qpRn4}%$Y&ctB@qSTO*cLwaX7k zy;ViUerz5j$DL{LU$qO~$DGj(8~xc?SPC`baIc=AlIVTPRGjMQ1g){&n;Lxz zhy%Cz=FK=d2e#OzQ?jbzk=ul5DmDj~+Y|EL>A@MdACg`L`!C%)X~+oEFdpLd`qE$Z zi@VZH!-DY+<39G8;aSws#w4CjBKvHJ_udPl zU4Rg>O^@eV#zsDKOAK4yDXbucSX+>k-v;KHB0r++#5vP`7!l}Mv;u242dQ@5FDfws3jx zy)4fE7$+>`{Y zflj{f;!m{q*uq%|O8fN5i+_Sso%uDItC|e*ogkap@nx7gQ?~S7J4(pG1aWTo#NANG z0oKZ8?Yi07E=VqE*mL49eggwhW?T zb&uPp=mi=FEOCwN;zOeloYGTOTC-ou9IF{)+gkPvIaH`abF7w=COnVef+yS#J^;=6!WN_Wj0V zcdxEAe!>gE1{_u5+40AX{rcX2sG0~VBJdL5Lf(Iu*Cm|>{O*X-nLQ%<1Qauu` zAdjHk9Q&MKb422aiO%{i0K$8UO9)3yp5^+fh?;CRN5o#dx29IiPQG>(VB~m(BKy&Y zP8l=X2Z~ICh$$6eDPPIKB0%YhTqc$tD1yo7?0l?94f*=%3>e#W+lOyV+q<1vW?Q(q zxi|OL+qXA2otJq#&sq2t&TRG>Kp1S~MU_W`%5m@CSF&$-==*z+*g$xAQK_imfDq#1 zq8@R7{PdCcN3#5s;nMOeL}28Bo>bkx$o(VmeErnUwA+oj zm0N?YvAm{o90R9!eXaEdZ?cANRqSsKolk7FXo&bT;lvQMpTAY39`T(-H7Gq{k<6-qK1p7(+Fqzfg0jJcnvcoW$nPC4_oN@-0EW1oPO_vA`0qX&op|l zRkDq2Ew9bl@FW@NwEeEvNzWk3`qNiU>ErT(z2Y)7`DV2!_3P6Dqlx$Auk*z}YzKo? z?9NG_?-z|)Mu%LZ7$`en*p7d98jJd@;#I7*b41QpKGS!(-u#IbNOVsetASjR=m$)R z=86-R1kStLSd;h+I4g||1Q!JUyy5JQ3DLzf6wgAj(=TATo%Y9ua{8Znap}{;Q>tg4 zRh&{J5+N1GzJLBvG8Pl|y%8)197N#l=kHG6QO3G<>ZTnQ(JKXs(0kubU1xmekM))p z%U|G)2!{%hkfdItQp_V<)_CVj8M?fI-rhHQ9Z+h<~o13p)yC$EuKG_IUQBh%X zbazL-dv_1VLnt93fzrlSP*Bj((UI2M#Du2mASH#idUV;L%-zGIh%h*Ju7CSuKk?t& zPkaovEyOe~4!=r4LDAaWtP;JsxoK={99H^d;&tD=T6EZTDyqn@KYqL$TI>}m%gA6P z3-XtW$Q+-K%p4pVO1Z~C)XBrAq~^}rg?-`)Unz{Nr-#GgJ>A`Jr1T98`l7Y8w8pKo zwfBS-m@if)&IWZ+hM1e0iW6L>6uQIu=tGmc&VPP@*zM4JHy@P@adC2*nVG4kwwiIV z4)pe_>*+0Sy34g@XT0auH|aearf#Z@_17tSmblV*nUSgE@dkQxo}Zt8&KSHK8l9M! z*xTDXHa6z5y_B*9D<~+4jEtns%g;~5rO9q8#QM*P(a+_*aY^RO&a)?;p8J!N$uxEK z^_%OB@@bB?wzf7ltvkt2lo2ei*!7S!e)I`XACTP1mM+d&`X;aX@8Nh*!e?h^_x7N% zt#mwUq|-sI+j`*JWrCs3^S!Kaejy>2gn>mDgGzU9X9SBHJR%~2?}^c)NB6)-X6EO2 zj@fGxy&2Q7t8m^XY|r-MdU0~2m?W;T1yHMW=9+u|^s%elFg;OozyW{<H|XchCG&^F&aO z#l^LzT$ew)#8Wb(t8FI_Uazik`kRnp|5b6U3Et)r zI{cgV^E49n#|*sM2)jkxKCK3@AEHt4-0J7IqhDkFb$Y3?(-~kwKewvq-yYWP+D@uh zY~`6Bxa}hpX}Ydp{i>9h(?U%Gw}WoI+QDu3*H#koS5m4*2(6r64k>%~cYXc+uFBP3 zFel3uRd4=1uMbB5sm9>9O@OELfBS`JCrbP~hEMcK5C8ie2J;9$Ne#yJ!L&{MW}j?J zLIMM?H#1oC#CFYo$jsE%)*h6?r4DTn)d~2kkG)c;qqpm#pO@um9QQ3!!6>zju13nH-gkk5+}!qAr-<l$4Y(LcDXd*_<_FA1C{*c@XWq92|zB{KCR|ii$T; zlp$$pX_BVW=Tkm|%F>sk*OkpVd^VWYF^W_2sVim=T&r>Q{(aR@xhPdZvz4XFbBGbG}l+A2p1PO?20HQ&MVba zXqN2q&!3O=^%KNX`{pTr)y2{$a7LYl#YH&2)C1lYCsA2ZtQ#LsVS4vHrDqBv4@Cyd z3R1>l+|kj|I)@1Em6*Wy}bme$@7;f)3MP( zy;6OHVG6yG855zY`qf^-^z`+&3)0imi;A3|KHV9q^gzm6WERR1Ff%h}SYP;j`tPAr zT;u2FrmfT5OGsWGsU*K}MnY0@g2IgNhKoS_nyZXR8CWCX@641s5X6U(G}^X;yu6O5 z9KBD|Hc;y`v>n64tftDkR^a!ls=U0s4u*xhMh$dzKX6v+=gz%bgi=&W9kGan`ll{ z*>04PkumyWs+Tv4_Uvo2H#0G5D0UKt!{O-26dKS#R7BKORnu{sGd>j2B3Obhp7T+D z-#*h7*#$P|`uaL(+mrK$7oyBAUA`RP?NUChk*m*LHK;8R3xiSbst8(k{c9;n#cjp$ z&+lo3f(hP`n+CXX_UaMv#FQQ)H!;urp~Zx_xIl@d*49=vHMM{JLYZLHh;;k`-la?6 znWZOAKYxbSV+LSzx5IU{8og zN-RY;bf%30pbRGgic6AeYCUUfoZu98Q6J%1Oebb=sF_$@Ku=3ZNHjGybwUwOD@Q(m z{``|pPEKxiMMnMt<)2!Q4P856c3@}Q+S=Fv_29<4{Q|JA_q+pfKL19RM<)-$Ax z9StB5=6t@bPLq%CG)1G)aq{L;QjMLRVNJUF`fRMMMMI09AKf_!o^qUN+uYvPDU{^7 z3xVYFY&1}Z&}1s|crFeWRa6K``PLYsdd&(@&?-Mazw0n|eB3kG%Ac0E=LH+5hQLYq z{$00`ij*|(ar@xlpuVn#IT`j}fE~I*WKogu{oA*19UZqW=0$?%Lf!*M>@L~j(o#-t zu10j2Vz4%g69bWdM!|;pAM^Hv zAjX?;4Gj&M2M7KIa;opGwJpDml&7Xj$gZK$?$8NPFw~?_S>%kPb6(H0jrv)>hPAnXDbh* zk(iu8sG61*DbA}6t2{a8K;9DNq0RX|M+XNZoQAn3JDF1)oj~_Pp-^1rZQsjXLo6F0f80y|E>@=aECb#-YeU#fg= z-|kv7J98hC)oi_AkdupxbnD{cBJnk{*6i+#rEfeU)*o=YdwVklE2nfO)*FdM+^nr- zd7KUpJi+Q*>IVl0!}@>$-Eer{)HG$)eHrlQ&C`v8hW=@AP5|ZSzO2wWwDNO3O{ zVEp*_pbUU6+m^SRnE=XP7$|UE9tj#<`ts#P_lG|2>~D{4|J0UnrPpo~yQ8kGI^nt4 z&!4S&_7RKl3kvS`Z`a&C0}lNWWjs3cfu?S5W$)ho*fnzeiAVFVt}UOj-0`@usEB)- zBy6P-G_XJ-u&Elzu|VGsNxvO0Z+`R28&sKbSBd>8aI~qwdm{^Hz#As1GaEWOI`Z@LJp=Z)M+nXK{OHPuML0Rb9>YOHlB9I|x|3H_ zw7Ii7amhC+J^km_;t+W(`w|;FyQ@GvTVxgz>26`+cLK-IF)?mdzI%7`fcNco?Gd0c zdLoyN*}Gu6^X&EXhC!#Oy)K#5F*2f`+s7PD!me*^Y3Xm<`TaX|?915~m;S=F(djhH zyOWb9H?Q=!_s614OyP?z9#B+RSQrZBW<2)g%NMJ@oLVB7{BW70WD0fYLkkPW6SFC+ z8n!J=gyZb$n&rfIgV@TlU;rvI`t|F}CS7f9f_6p}Ktp)u6=~dLdaGG(Zf@kUCBho2 zs(kTnFnR@fIk^n%Fh(!6Oq_E*VZ~dGepO`T0istWSaV9oFg8qA7gd`)d$`-zG|0| zTORQjxjV}Vio_|@yi0kuXMPS7GqX$@cUT6&cnWBduFdo^$l~Iy&pzk#YXRDuePJ?a z%>(7+!u_L>yi%ZJ(pf6+P>{HN)j7afLZYsvMYe*v$CfKpfhW6HQ#lED;XA$HjbN}x z;lx=iRJ=UP}D|Wx4I6H{;@NY<4WVWHmR}r9q42uK8G6 zI)R!qQIf(g87nYCG&*5g$!d|@JQXH(=X!BtM>$4xf6){ZN zQR1HyA-y7WVn6MG4}9@kRy*1rQ-+(u*YUs^lQM!rD>5^ikO|<-v9Yi`d~lE;;LMa! zMsfXmLrY8H&>}T8HIpN#n1zL^4kqPc>d{?YUEqnsW>=rOySuAS1B5ZU>{_NXI*NApR+Q46w3$<1Xa!pV>YC5ugu0JLh`5}inEJG;o9l&B1a z;9T7p`c!RB+UE-3c>Xz7$7xxxFo0Ney1#z?x~aLDcD3I)Bq%6|cC!&|RgME5 za71aW0w%~v z7uHMN+dXFgAv@dD#Dqc8auGJsRgVXF8ir~Bl$4p31u!^UMlOL}RORwup+lG2$@Nam zFRJo=@V+Ze!JrDt56|55@-{Y3dOA3HpSvI*U2I7W3R-q{c1=yq_R=ty{tflZcXB^` zNd5^ErVM$y6ZIdT_NuDAwbf7Vng`hXVIl|?A=D&n+_@ZyES`aZX9j0z)JECc`^l5M zCMSXTPCN^rRV5QC1EiA_fr8Mgn7@dYx&@fsmwawe41oPD_+o0)(5#1>8w#WU0CvL6 z#3ZYi6B^5F*Q5ccq903MkwUQ8?azJpH~QFWo2EB zK5o|s%w1nDQ_8>%FC&ElQGo|}p3d<$SVfU>?d zw}Jx8xZ?iRMmOS52sHm4L3ALiO7eCn1#$n@^wv0UoJ&cO|JvHx>gto<*yk5%xG3%} zlmLEhxHZLaAMCkTuQ0^{@Z{e#LxjLz)?LZfH5a{9%RT9<=za4_R9qa8lYTtIPk$2+ zgmw%VxeUJz#DHPjk^yTGgq@MmgEHw?Om~h20aGDLP$?Clr;>1cW_K)EWj|Qhg#G;a z)4qHdP;XIDQ2>YQL#QGJBqbzNpMz@I*{R$J_*&SAi>vZL1QBS1jso$tw6uWnF%@KG zF%#kZV%cBifv%6KAimO}s|`S=**JHL>Vccu1dYfkMH(tuOl z+t*iHL`*^gb{9r4eFBeBdk*Nyt5;{G-uU!*IS&ozjYJToXJ^A(mX>S>a+)d}XXKTX zu7W**kuLyNI&uP_=|oz`3P6ssZeqq0Ztg;mnXo9**=z({S|EGA<1Bzusz%Pv+=7B0 zzL*cC0pCiSS6rMrT-0wC*<1^7;3;y&tAeL~tpt;}#0gDxJSc_ev6WR;PR^ElWyY>a zmu1Nu3`YE|-?~_MF_=Tez$93T>mRiNFh^x#{VZAlcvq#`94hGR>nlsZ1LOIPA17;4ALjOvU-G3jgx=5~ zK#Q29b@B7^(jVL*!Xc%C^q%eB&G{O`!^1O&o!Ue9MN?;Pr05sVAKApT*X3lvjGf8# znRb~(AnYJBIL*z>o{Eq@JIw>y%&$e03kAg+Z~>lJxt3&ys0RQQ){H66j*S^|AZ$x^ z=X$aRdC71YBx6EDI{@>CW;;QP$S+b}9c5;2?%Elz3Ux3yPg7M^ zQhLwEf*ZEJGU~dY%{zkJ^_x+zCcVFcb%X2=%Sd#%j@H-EaJ_lf(rlT^b3-X_>T)#) z&}a$1{nlvDT>kX_PrIdKI$ypF4mSvNj+Qy5y?ghldT`yn-Qc0DY1t~Qnq${wxn%Uf z<6rOD*dKduH`J>NM2Jzt5q9Dl@BP62)9n>Ao`}Q7(Ve*U$kb!~_8$=da1p|5Xs<#= zbuB$j$|kfy!unorU32q4QUdUt=$O5yuMHkzN{-F6A|Se&jGm^x*k+^$KqF{`5Ng z;W`>})d}#|f4a-JZR&bnk=+-_*VYx!WWW9UQ*O^~!_F^Iy(#;j{J$Hc?i1Mq^d6&b zo}s`z6UIJPb^s`RRdxE0yLJQv{!d@PLdc#_eE(mowI}?*Bi8iNhj7FA91t%oEN1t2 zw>L`wE(hXH7;tVZEiD5LvOj!y`QZJB4=m-w36YVmtK;HZT;LfowCdO}9J{k)5+5v) z6v=Kt4EZ1e=n~M6+FDzs+&w)#ot!oRq(gDk!sHsTfCQNUn1yq^C+tieniwmZQFB|gAzyIQIa`(k>y^$?aCItvx zJyS;1pr|vAZMqK)4u*xy7}o=2^WCO%tRDM?9{&PD*&Lq>*{{yN@V zKo77r9Dq`N)K_0$Ps;(Sx~;Bh6S0SfhpA}TH;TK%7)|S! z#fy+tRiwEevYAK5k!ao)*U_gf=b2wKcE<}mfUTV!kVqoG7|F@alk8@9p|OjKbAdw5 zl!rvd#K&iMnwpvd>werfh@?=COHR1Do0`tec%3YN^9X(aIW{kDUqqIb;Q7{wAQU_X zgIZ;ZID(yQY~-4vde`T&aw#ER-xCkSERvK!Gi2f-@H>NjYIWqKzT2s-m(~G1BaHg- z8`aY>F@(LN-^lCBH6W?UfD{)N%F4@=;WpRflCY&0MyWZsswYudj{rHBSEinNQwHYX z;K0He;P0=kqvPxAyF6T;Hox&y$Y>T&Fd79@Q7p`s0LCE2}14_hGdANEt zE@( zq;}25#l{k9+`xI|6dwjAHBtFZ+h((Xj)k4aLm$Ec+$qZ~3 zw|9Y_bne`_!X%#mTzbfZH_q)14fp;gMSeJ*zSI;>M{tZZNFp{iHY+ppZ+i-39gRIa z?`dy;2ats^d$3{?mE$MGhi@m61tQVu|BqhiPkC3r=e4#JIJVqV7Ssg1pG!kLyu2iM z=YT>hFW(0EXR(q`9==D%z+Y9z)wP|xTv1gO=&nR64)*qnYukDlw;4dCd_r9|4QJ=g z&d$!d>0CF8T`vMSKrF$d%aO7dUDed!;fC&KF6AG^A&v(9&%p$Ddp(6{tB0b#?izi8Pq^{7{Fb4)lK1ct_S3gWJ5mPC;p|d0n^N42IktIpvbT> z2~(I00iwxVhDzF2A->=SFs}sT+lGhN>*OAyJ5ywU-z^~72^#L~57_DFpW+2wRe?4c z9uXm(2=ul0?{C4wBmj(~xOBdY+WzfXj8AaXO==Q$CV{P!A za&y3>dgT=qNQj6YN`=%@Z_$P7aE*x0Z@Lp^TUE68mLe@YCjZitm7+t0)*323wq-qH zjA&PFN?jJUG4>KZ$Hf7q@$qEMJJ-8ivB~HCwn3e3HX63)W8vqCZJk+{la-AUFf_hh zg$u+%xL$U%jJu0VFYasRLLJVagXWwYU90cglH2Ers3h?CK4dVWwe0On3u;P^}Y0osE3|ZU`U9a zwaD_EOF5yIq#Qs|-O)|RxD95z?li;+l6B~jT2F5SP1 z?1T4;P~kc>SYbB6_qG30I8;(QMQ8JIRsxjA ziGHA}4-GL3suK{C`};+rHPzLLFPzbhZD5)Ue$o{tL30-@;a{5oK$}Y*<1irg^b`rA zvf>rg)g!9jnd_jOBr^}@8P&0t9prBxldr(G&8(9e|xnJ*cS>UJgM$gBa zX)EyEh&V?+`q31bv%uh7?J6Ph8cA1yj}U@D0CM>HPMQ`ZL8Qp7ksV^ut55EtH3RT# zzl%_K^A^2J5GZC~R3c{29(mTfap8supa(}n%KPPy^dcaKkR{_-cm6&`Fq1h6@Uzv_ z)$8^ILN||=URDNxbF$G1Zca{RP0i9CX#zLnd9uLlqLKEx4Is(a8j|sbGAQROF~-4Q zgerdMYbmP8mFJhC?|{DmNw*$;)D;wC7E{+TvHGxvhsTbkq+b#2`D#B}%BtjKnyOPx z^z=-O2ZvxO{3xZ(PZpVe3WTnXPL?h78o~mIZVnF01QQbzXw)wf5zIh@qgBd1;gd_& z<-F)pUR9OJB{yVjdA63_&%6A|L|xr|NcRG zJL{@OE!ossWPVAH=rD(ZQL|)TC=gLrZSE|70Y#L?6SX#_N@k5z>XPl^lSWon>g~^b zF%rcH%(k}bkcIA^9$GIQo2jWt19iGGz)*xQ*l0Tde_(DP+W=wae&)AzgE@TFRuM-1 z{S}gf%i95032@D!qs~BqGMNUt1&|+2{XY|GOt_Ti>Q`Eh!N6s)&?q???UMX_nN;i?)2a(!^h zMiBrW!g5Dnq{dl-%@b9(!xQCV2t4UdbZ3^cj~uUMj0KsbQour1TwL7q=cg9a!F?3D zFr#2OVB~c>4vr($Qu$U2%-b``XXRu7N2VcaH04fleK}2Y%#Lf=7tnndEKCO8w zGbcx1Tl>Me6UY;NiSaCO9PS-jE*+pv;u-0*SaLGdK*$N`Q+J7Tva$rd4=S!tJiZGO zQlR$Ju8-FS08g+(E+#gXUAOcZ-U&RmK@oP|)4_rB%7ulQXT0mjA&Z?gphN&%UH1i` zY7lM+V5Eyjf{rT<N;e|yC@*6$<{hG4D%~S51 zJsQTntql!tB$Aj|FQVT3=fEq|(;phRUOPY3)m4y(`kJ3#4symb;i1GNdKwz$i?H3@ zU0^NJ>VdhzTMQ!S?GF0J=(g0X5rHial_2OzL*y!a`Fj_qwo!uXwPY)OY z9o^|ZrwtD|xc+&9ni@9W=S4R@q)D{RYinqTijMYkO&+wNTWd`1A(OFmdLF-P;#-4} zQ#y^{QxkR5o_%#|-(8P*&@a%7nSJGNL4B~Io(ivhcX|0>^iP-ao+;A_m8!v1|NB6l z2cuja>Woa1qp- zcH(iYWO7J(I+&VHefsnaeKDO`BL|>6YwH6xRY%8yrUlS+Y;45;y}28GK->keH&q~Y z3qT;FW(9uuy_C)t7LCi>GV(XCd|NJ8mk^+)7G+7#=+FZ`JD@w9%I~+v^4-A>l0~$q zdFKt3A|+7vDjGKsj=Ninl2o3m>QDG?gg_22-#c`L*Vz`K+2 z@$gK{%mx>?LPM{@%PJ~>v&h7suP2q&0wRVlUSKx@f+j31%;b2qWaYX!BO@a_yE(KS z0|U{qu~r|10L~2$H!(HUD|cbd5C3TYR@C&c)d>039RoGpi>^H}7_@S$)Zc8F z2YJ({JbL+{p{hq3rJ8Y8Iank_SvH1?fwZL+V>zFIKulyLiJhmMj_F)bkVTgztBVp; zo1pUmgyElL6U4|wvZdr-E*Yknw~=~2IH=vYu(TAhnAsxexIpOQ$vGduoF3*qH)21su>LdFm;Z#+B)0m*T{mnc%XQ+RKb{39b-aitdTpvX zLv?C^&(J+y@5_3?d9fe7M3%)@50uKp5 z*Z8}yX8|BdZl}jp5J4sH6oM+ah?)e911PnwvE9cZE+9tT6&-v8CDQ7QWYY`#N~jDQ{xQR1+dRKCdTUKg9ncikQNvhl@NimC&JmPR76WjEB_5 zOL)GE|LD;o_Rxs}_J(_Jr$CO_AY-@2u6lp_Bv)&@d&WMw46@Z!Kw7=`VLft$yJgvJ zw4q(CURU2N8Ec*O_z8}#Km;eMQSOZysP{!6P$bJ-`X_(E{^g6dFJFw1Lc5T7bw5;l zWy4>*1`~R-FVwv5K1({Z3+K3WxM3%92#NGQNTb}1h0IO6bN&LS7}xlU(=%$zFvyIM z@S5XcJ!W8iheON5R31}^zC*uI?3R*ap#xkqx_wdLQ|QFu?&L>gAkeH^9-f-kIc{P{ z3gLM^|MXFXgYVVQyVKa5)MumYe)FvRp#A)4SOw-mjA#CKd>;wvFZ2ssE-=C8|G6OY z|J4hpPTWhugd|VqrZF=3Tgv+ovriz-8xetlGT!CD)>c!aMS-ABYHHn152zUoM1U%Q z&?1Ps09sU-qiYf`9i;;@>fW<>QzDDA#}D05P`7v#-H(|6K`3 z=>cKTt%9OJ$ZO8H<(l!UszK;{Z#GCIuI9W~1b=E^XSy{O+|!k!l8@MX{rVio+@EwZ zrM_&wt=eB2Ha@boX#=P!((5dowKE|hAu>il!~0&^6wbP}wbk^R<~_L?^43wr?oWSy zzu8E(3d1Pak+T1(V2|Gc_`H$+g>n7YlKH}_{OrEgrY2=SAPp@nSi{+vnX@u7u0pIU z2yA041}QTnWkHUO+hiX9)KT{H*nI=FHCsX5&z^5#9aYFZ4EiLQF$?e}k^?P-G3p#( zs;+(XI%z?d0L;v2c}PQW;mp@U5Nl~^Y0)$Xi=hUBiM-D7b>8@zb{CG)DZg{6_6?r- z_WNk()gZL7j7&3d=kq>7E9}Q!NC(WQM(T5;KTrEkz&2YufwYj!4sL-ENB^BD=yC>) z9AtTdT6Mmu3|#q_ow93k>&k^U&Z-uh<%+VTf zCyx=ekSxglD(Ni$_hsypJ3;abeZZ{^6m%{o)Bf;aKPHB(o(=>v^>lT+X(J;dzzNc2 zi)=MJraqlk!Z#2s!63@wzYITT#RU--jz=Ka<-(v-L4-#Q>Yt!7&=NpX0@;Jdk~aTZ zeC+!`#GU~n_9F-g;rzA-Foibcu5F12Af#kLpfiB1XP)SF#(!drfLcq&{LT?vy>KRw zH~REZBJfz-`gQN*k0mS`$icV1;o>VnH|L&L+n zWa9sN6XG3UO6Rbj@84Ld4^BC}w6VLNpG5f}_VU+}lgGmFk~;&@+|rWz>_Zx5W#uq9 z+<9@3+ou26xdMSe3{gJH^SQD{8{OOt>dKcsDi#1(-1rTWOOf|t(levVBWZ8Nwlz1y zHvR_jri-lECBXNdO8Qef;<;JNKt7LKr&PSY05M1X6+ogE)X3GFK1w^?{&}X@a1ue3=!82gnf* z);9WMZaNJ3AK!FP^RppbH&cRlI7%a{s|}zTmVrC>q~6rr9a*=YgJqX6Uo_PM?ijpL zwp*(!tTP#;YBhIFhOKk^1Vu!u@=z)*Mn=x3W*;zRcXHDY*0_sGdHjnZe~f=87%#tn z7le-&kh9O0zRq8qr)mCaN~KVOH3j}MGInen`O zNInbPX}c$x%8mbzqs_`nPIbn z*}_%jYoJXH1%R*G>y4k`w;)kVfdMO`@OL#z{s()=5HTOq6mnI@_R z>nQ8!0fPU_)vl5EVXIo|&DLR}zFVD0T5a^^-506mRas9_Uh;VbODJv7eG7@k`w#@?ItPBkO^V!K#=G)kw zx5)k__~70rVMhZ4)z(^sP>`Shk5ji*(%KmabU=V*04>iJD3@Fq9x*;aXALi*L17UW zudSO_H~DU;G;<2+U&)}tl^H^sH?#UAU?MMF(t*Tm|^#>USupict&1lu?UMnqsAhxMKn z_;U|cY>GiSFVtXnuunc-08q{B*sCD%Q~&F_#YH#(4_1WzK+bkEEzbynT!0h-O@)0D&J)>dlis1ZTx?)iT&Fy_t>4_OfS zi*g`vlm+sW$5o2D1{0uMSY9^3T(Jn()zp0Z^67#iLo)7NZf+^H@zb@LwL2xrUJ7&J z&b6ALT(%{WDi^G^Bqb#^71CQO%!%+T6$lClv>_nXJ(a9Mq~zqVuRzjF#?4r`5&za1 zTrEn8+A#7E8E`s05f%6;X#JTUNODKK-=jlJUUn~58eDzNc-cPe=Esn2PmllXKXo7-6BI99&$+ z9SPl@`LiV;bCR#;9PKU>#q-I1=6deA*qktTSJ~~$Cj&J##LzX&g$$lt`gvCskdOW+ z0M@ObZQwSNpm5MzQbp_c_--cqrC1)(TeUd`)d?^d_#O(h2}k`@eb)%Fo~)jjgq{YV^^?Tlu(xRYt8O!mQj}1Onk*GJS9`K5m4|{J3PO zC+Mrx{s@o>ZuvzTcxgc%Sr6j<4w!xGD-;&oZhUb6{%2tJ78jPJaKK8Cw5k#Ey z|KRS;qp95g{^91%X+8~T?v^J8AD~tP%@KH zBy%G3_`I&Y5zhC%fA??Q>silQPyd{=u=l?9HGDqr_iK7@e;Q6;3^%$w{)@x-TwB|I zk)MTyrQ)XES!-*RF2B0&Oq+qo2$DOY{**PkPj+v-e0~jIMeYiVgN$80%3Ek%Vgk8l zm$=Tt4SOz>#18BBc9%VU`f}T83Vxa=b_lu^c*vqPKifCuxHvgEkq^ULyU6Lcc!Q|U zdL<7%iH*JEHxJKQOj^?j1ncJfpMI5HF6bNhWc}`S`(>BRzl8rwO%#O*zjIxPkIxUp zo`v~@gjSzv2j_vU3;=wNcxz~ zPjDNkb*uMyeYDk)?6M_D=W8n*MeC2HIk%| zmESBL|I{cxBt*yFUgNX1nwlCEL$3~P^k(DuRKXIS`B;O;)i$vdXsvv>G~_@rGUz z^GG?qWZnKrd~E1^2-s&VfBV0qL^EkV=TSaI{T$!GSp%FE?ymV@$GY@Q7G}A5tjPpT zsSTkl(MJwfp4s;-?vezUr&&VgLiWX?M3(2+J2OS9`o<_o=ijHJ(R#Gs zVB*x_0z`XCU~%OnwDW6X26uTK*cw=S*TMB`CJg!r1&-i|~DAHnUkw3V3}%7M>M&^lObE_s*i=56$>4zZs4gg#*og~J z_R2iuKU+Wi^u62q(?IE~pJzxLGmqLPI(utoEF{NOKca)!!^AX@9ly%{uM#oro-gIS zURG?$I?uzRS@Bj2aCdtrsm|KdpG$*Wa*cdhvY8fbTX4AU7Q?I?VT71&9RYK zR({m0SFa)>BCsDq(WP%$D;aSB7X^0`eJZ)^>L4!X&m}E2Kb#66Ds>*G-nqBw1g@icbHWaURo+J&tGq z%iDdjdb@c{-le$ukRS<@gzqo9-k;}4rP1isSOdYZ?Js}mvk0B;U}Ixb$Xd;4t5Wu2 zAkMzq&?ZDK!46#JeVboW$NbV{8Z^V*1HyQ>s-;ldTI=iIYW1FnkXi}1byOKbbI5?s z+PQbc4t+n_1Oh;c8&oXT=TL6Qu4&gfOTgL=8xHdZw7+r8N-pSFB{DZ#rK*GF6)g#g zw?3U{c1*O0!9;$|bIK<1QU*__pC4R2wXR7`qiW?gQU@;7zuzpFps?FS)=C84Sgc*P zwqxKO!ZPLfH2Yv&kTVT7c!#G&t;5G4%wTOE)sI}dA6;FE4vhoJ4c47Mn1aNqz(kd#)*Muoz=i)96#|X+R=VbIJhbw% zvUep45TUSq+aE6u55-ALefP9QBwOQtxvL}7Dk}(V2++0$<(aJTyN9cW@-?>&`)4Iy zIXiNFsqnB<*66@5E`R?ycqU=|xf*gasqn&;L1zi~1;5+z_))_1=i^g|g_a62aA>Wi zCgq#i3FTkDL;Y7$&hD2IROdWogZR&-9r(&-y5rkUo+keIXMToej22aYoPMU*l;bOL z``ELmr&jxJa88NYaD2nrw&(8QRbN&3ZYW%OSg!onel_O}1&V$;e?&ZHOTN4R$zPo< z4(}7L4APDbxJ67YCwa=Y_cpiMPflc({2EMd6i%9~n;4g=p>y({hR@01b1YR@wf7Wh zYG4TWc-Jffyaq6C$AfRCsCZf&$IoSX-+k!l*w>@N{MunwR|Uc4QuTxGJ?T}{cTfNR z1)0-cr2N;wSOMvf5KGF{Vu{6r^U&iI^YQU;;kwbu{>F(qd!<#+DFO-zh~Cy9gW@?Q zB8aRg`v2kw(?Vz!N;1)GY(@0^V5F-<=R)ny03?P|NXT|j$}v4Tx%$&576K&B$fzGy zgo2o1qY$aYB)Phx0#KETaxB+-CefL59Pn(P6~ZujTxF`-?Sve`NA+fR=(aV%ZWW zpkL-Cj?{>r(l;_H1|>G3siLBysTm8Q*QHD-Pgm(C)aK=h7PyFpjIvy2@%7pf_?~Lb z3NWPX+~w^S*cQKyO-!P%@eL@@1z-e+Xj|K}A5RUA&Fuo$T^zAD=kUkkq6u_qROMo> z%HudbVTbV)h^Jl|?!G6s$6L!`q~)evU+Q`$Ne7TyTP@Ar0XRms*Wp+9b?c+74`(JP zGr0r=Y-_*%BY`^u#b}wJn^f-z)-kX9Bog(3Sng27Mi>}~ZA{Y%Tl<)x;0d84k)QH9 zlnf6OOxP?uEEQf3a}$<1Ih7syBSItN^50j|-!`o_u-8+gM@gp8gfH^s$)ub3Zl0ofZt};xxGauT z87c^1at0eq8e|4OOvB#{L3?ce}MaFO=aak?Ku*9 zmEhp|yLJF_fBg7y05OjHBL~pqpwr}D>U0Em!;M~X{c@bi)Qk-FSpIurZ32vfC>2~# zzjfaFo%R54^%sd@U9KBwE;Qt~1Pj_$H8lL-$NsD1=&0p?n4kZ4t~PX`%7K zyy|Oyb3;jwReHe684EbsxT#d=o7db6*=WnJ5u7PxFzs13&js#l9vVO*#l^;2@$a}N zmSgRG@Hc-+S*(6b9FVi6LO{wCPZC+J75&?CKK*%)XW*@-a?6OxY^T?C@V|o6bLWQP z*Y3)7vMj#l{5ue^uwacaH4a60kdaGTJ~%efGr0_$R915GkZ|w^VQUR0i}ZRtn`qK% zXIZ$jT{x144-%)<)ZC8mHvLsG{AMLycPsmBz_SA%TQ6VXt1)$&dbnr?ruiZf?Q?uL z*TI7kWdTxQj~~Bj{pE4z&V_8h_xj+^0Sxod_$C(O!fcoUhRxrh{>X3cwaI`m4AU)%1TAIHxK*{ z3kY~UVE-H)Ux#ZN8!OF%P!?o=rM(^=wuX7wGR{5W)P-A?$6D_^n3&zBiNv!nB1#hA zh`xUhlem2OGT|itbw&I<>sHTvUoB+r{3Rd5jXJ|8ohsonQmDF{zP&~_*K0&sLLxWT z?fL%x2}?+;Pk&ce^srpzwq7T%4bBFyT5Btq)X1p!N3=x5CcsmbPE>wCUU76Jq1&!N|033{*p@+?FsEV~A! zRy|8Z_!wi0R>=0^7IOi1s@T_K0ZNKrye-dBQBgg3@PMJWzQ;j1`q4|7B$ESFZZDIQ z-DoSdd}*Q$#JLKfFQ^i#?RU{`w(R4!4b5Wb%}#rK>BRe)Et#_O{@l%)y8snFv4y{Z z`dQ(9s^-><{C7M(;WQkujrm}Fz`Nj??fuY550ACP<=9*l$?;VcjvGIk734*zVl1BX z6KnagLeg323Z^-C@_thkySaHlH>;5|Q(nd=a>|WrwGg_Jp`jrr?*gck2}qc=Sv}+R znr81AI+=VUYg&cgj9#h5_f7V0mJ0|93hJo+1mAaa zc>?S~i7aSmUpdy)B=B>x%>H^2x-($NRwe;bduTig z^U>!z>W_T+azsJ`%qUl;M=b$LSC*AEUF4S%Yye=xd=Pp;&USC?k;cX`@AbXIe0kY< zYnr^8^hrYYs+lsV^=&;pS;&bqjGPLhS@^<3iE?Ph;P8+sap+4< zOZ)WoB2?U$daNAk`Gcg}Z#h_;zIea)?Le0Nb-md;{$@M@x`a;q-!WlgUJds@ET&jr z$!Run4qcFo@X7uPO2Sr6uv%DeoQmmvjk6nFLq$d6ix+Qa?(^w|l(DzKD&5}9jEhu~ z6%&lYBbn~Ke|t8tZlISnGm9aasFO%#5E|j-J>~Gy^o)C4`uclfy2i#HGiwTEq4xQ8 z(qB4Ujv4n(LhZFTUphJ>3ybv=po{jR_Yg&1*ZOtq(6$w|U_<8{FbzAgtw5I>tP~u( z78Vts7CZbLdS;c|BmS~1Epz?pOfLz@IbGLRjD)TmkIEX2GIboQ^I~4!|8bQB%^}&( zIg}+Xttn=vavCOAP6eqB6QfAiVF0-;H2(8g^TWUo$IR9)xBuuO*Ua*x68I!MQ8O2u zT*9j`Q~xZ`j`CquQ&lZX+E3@{mhPQXTV^2dhb66y`4vYV(CIyej`na;#ZH$? zaXuYOG&D2-B5X&5E81FEDA@UY;Iw?yFF*P`Gm~R^bl~2~cG0KtiKZ zU~kSwWoT+j?QLgn{v>OFSPpL`5CzqQgCmE(ch1+Zk0YFU1PifA27-idQ+H9sPJ7X@59b5mTRf@RPh+woEZsd zk!prcPo?R|&PUuYU2v#{Z)oDa`pX}SNczwnV=&vykaZ)^XW`w)PVU z*X=8mnLP;SYWN)#-;{3!M^PC2g?-&I3Q=}p7IMXQBYTo6oP?)FN)*E~7frrB*=7Od zu%n|RcL4C%(g473F2{FMxoz3Z7qqgRMygIAIaz?6z#%BE7Rn`>Jjx=^M$D>VKt_f}$H=#)5O=Y)D00KkmHhDQ@x~>u+*DDP zZB9p5)h@SEVv4c1t@Q7S4KEGE1J+uSt{fDqZMT3w&25ZV=#?Pa4+CCZowMav_QkxZ zaqeR}9*$xamgL_SrA5&`UaTSq&nDMRK%3lb=m+QnK%HIanqTd;g0I2cn&YVg5ml%V zmyl`I{RwMm#7SPkLKV3Se>i6o;PSDNIpxPO4BG-pvY4z>% z>$N_NuLETtbbrY4Da>noU!48@yFQ*Gv&pF;=P8NfyB&o`olmMYk|sw-lox(v_da1^ z@H5>P`FG!YH#s@!>romQ;EXpIxL%xlSZ(rGs;NDL-09($Z4aA6rha9OkydkXqGtrlH(+6*2q#du`A6bjw8*>8%?JIGp9T{3+A1h<*||Clc68i8)fxgH?{9) z%Bmemp30vZ=#iPEWm&=}KHEX6FkfteV46?!h^WYdcOd-Ct(gNs*H*uK_D2oFjPU_` z#B1N?R^f@-s-f_yAB{gkcF#M>^GLjPuO*-^p4Ow06Hr6<{Yhc@o<((fFDB>uBG{Mm z-$lc^)Bl4qh4N1*Ro&W?nn+%m*_r;kKb}neBKLdy>w_$-70>Won4&HKUG zE~8`c#`{j^Hxur8qS*O=>j(bIBJ}rrJEpdGhIS^#?(!~pwD@;RzKC`Cm&)O92YMS- z;%b@3CLDNXv|L1lbm*cl-i>X0al7N5p2kh0H>Z>dozA48r$=j+RM!nLHp~9N_fYo0 z4T;tR|DuW!E+fXUI~Til=5kf;mJssZT@~~0D>ijG=zt_t5AX;GsG{ZgxVW6AjErDZ zd>I;pNL_ku@*RJci#Ap|R>zKAFKP9@Wg)JU9(F?93D!Z+{N@20DAysJ0b}8wu-M3p z;-aLKLa!P73qpfs{EnNNnhKGq)%Jdu)yr!(i+A&~9{zcD=LXpT%I51O7Alu)QeVah z19HpH}-*n~H34>n|5&w!Q5GHi}{6 zQ76M1drDf&z4#9w=Anz-*dz_Jr$tMyrC;Qm#9yJJkAH=-S03jJn9)!=Oqni8ck5RsIp?@`Y>Ky?f^hZ;AfF>+~Iw4wNHopz^SnP zS7r3Qmyu<=L<@mS{I=_9{QBW}ALOZCKcz-cVHBp7g>>0Ufy& zUdRmUAB(Mwih(;A_vX1*hERk`6r9<{;Ydg|B< zZoVUq1?RNmC^iQu0Hl)W68 zZ-}p$zj16)d^+isHJL8(p5D>_yC?6uhgQ9maCs~PZ&^mugR(TH!Y>O=wKzt{I%1IhUK8}NFGbc)P=24YmB^R&2$8o97LtAIoa9h z_>OJyyzTUeNTa%Du&`}7brxyiYbI7^I!sn--6@^`Qmqq9UV6Oe_cC)fX7WxovlZj^ zAgfG%7aWM#pGj>Y=Qp!12paSyw!S$*gT&T1fBhpMCnA%7TDu%NN5?XQLCq1AV+oHt zO<8SOJEm9L4K2#tCG$@VX?)M*>Q>7!wDB@N_sA)zGmw>C-*(#N^Di!Iw|7evutRvO z$bi!`ZdB=TTa~xN9tM9y8i5bpKE7LyZO6J!wMUHdLTT!;Kw#@#cQn-0>}3Re_tf$j zKt4nnET`QUvnxoty0TJytwWY0EKwB~JFO#@gr7U0e}IQ)*iOhm%%2ChzR%{Z+qeI+ zKCBsc`Rv)Vu#HAW7V>WwEhGgrx%eJ~5{5AzK-gDjdcXarA`~PtU)CDEIdc)v(ar~Y zNkwyuzU8v_T()rx*u7vtX8f;_SJo_MN-RXLq~Vj3?Yti4Bw-tS@bIC+_il*K(!Txt z`Fsb)-yx)dSxJ^)TfO48qplVd5MXHwG+0~K2E!KvOsu(YsM77rm%v@FofOIjyuwVXgJj_c?XBfG-xE_bKe0K3#>Pyl>%Qofq&-$2R zE39O5E-(vsZvmB-iwN6ZSRQlEZ}I83$zYM6tlU!$>8trc@f~z@H0zcB3%di~(|B?lSF0Scd{kkymDy3>HEQGa`l_lue~u_WG(Na#i(4*~ zb-4_kk?ypt2^#aB&a18*-@V<+VaHEn{N#(Z|La`<0{LfhZY>iFX0aBX=U$dDyWhL;1ZrQef!W>XC1K=kgLG zp=Ue3`!Ba#4xUqT-DGS@?;oeWI=#7d`;upEp?2nn>9o|;ymN5999AVmY%j=4q-cA%?x>}&=Zo=2?Z6YMxDlsX>36>|Z*P+6pRin>_ojYLlb~j95(|nGUS1cjsF)agU|EF@g+FPGjc%y1Ltbxc>cM7>a4Xokc16+FUWW z0nka`h@F;}mZ2f5*BnbSv5IOK;ATgBH=;HeHr6&ap4dpqE}PzO7A|>n`~c(+_&=?1 zuO7Pgdv^K_&>ti6f^>A6;lA!qMsEi?pU4Zs{pz9BVxD?@_t#$|T~@Xj`1<X&j%vPRVvXvu5KvUL>j^pGxvFse+O-ik z>P-%O$0Hb5EvdesB(+Xfcxw7Yi5^JN?t8bbKVig$jj&bxf5o-g4U<9izo;{wKYtE3 z9u|{{)9UI9%W(k_3iIuF$SM1H0bdDmI5AeQxQ>%g6+i*X`@rK=RQMG7+~Xsb%goZ! zQ-VjzZ;=mYTA7I=#bL{~7*l2CYFG%k15jwb;CNWn@}oYzy0rAM5S2QYQd`t}R4TEs zJCp~CF?bbxBgAEq`>~c0sY2w{Ygc@ewwGl~ueF`2sSL3U%K4h81~eck#2|OKeAnpA zD(DdRF|>rU6JuDH$NCX^Ty1KZ5{}J=+fU1?{4LrKo$RP;RD=v@ zl|0XO3ma?e6o_S3x$*MGXmuq^cdo8T^F~AvBN3#*!lEER0mJF}G(Yma=b=rh2oYu1 zi8mqoOVodqQ8Q?C`wH?BBYG;A%S9+4Zy|WFze~>8>2JUne%xUmfJC1nv|{{2TVm-m zNEQf|vZA{Qt^ggKY=KJ`FFucnIcXEs$#bUyrUKNeGc#^{mnau8*&e2AvBb_%BiZ>D zhEi?*fqYPy$c5X6lpz=}pCwj=#nxWvzy6*YHf!b7Epk~F5&wyS%TgIFPdHRiWU%1i z^_1?_n^gPXB#@c?8E9x)k@ko+uJ<8Jj05!rLqkb>pW}z=syUZ-c65w(C6r+QlPUS3 zo9Q?Oj&x}Cux^CBBKM&~+Y#!ozjFhci^#gsrsqWD5Ex}D<%i_mjE;`Z@3@SNr{#ic z#F6ESkqZ6tIp81RJyZ|f`o+BAGP^YQ)-{oC@o(`s;t`}hXJKIhscEN|+$A=uOR4JQ z)D~z~J3=_Vd50=v^|IO9eL*HzIvj9GsD6QRLyAIJicN0`hN9@|<_upj+-5lqpI3yf zMLjmB_&g$_{73wcu*-p1n&zDPXKkyX37xw%ZMufwRjxm0&>5`q68nF{E4Ou#vVt`6;O{N5hhSLBrdK8Rz zGV*$DK#hE^t&|4ji?>z|6ILTMvUs0HMD3If>oy;0XnBJe#P{z{`hL*m#_yIdmzI{^ zu`d6n1a^UN4Zr|oMn#4Br^A@;2==d60QpUlA>xfJHsY)M{27Z~oK_Zy&{zWQ&S4Xe zzsMim!|EqB(q^6-79MWNYMwH@ml^8vfsB;CZj6mMdD25d*nSj7SLw^g${_Zs;(c0f zz`Q4bT-ZtIg~>4~!Hl@(!Bmmevt&wYcAFRmK4I?A%AxQ{*T#1^SDZ-Tlx`Bciy z0`wn9yDfW0CL#;&veTHS*N@m~+Oz&SqO#Moxmm~3_}^#b6+O_xUj<&WL*=gdn^uN$ zH}|Hb92Y-qH@t7dAJ2-xITaL$w^W%x?Ia1eYtdJi<43ER$><^C5$@U5f9&e&DlNS? z7<<6vb4^Xn-5eQ*zD-;XqB4f6*ZW~AZ|U#)s)-O=`O)a&uL#P8>s#nF@om!6(_z5T z?IN>_&#YCYJXwNYH?32*cplcw{hlX?YTLX1{=|NXjZ|yf*L9Ar_WAoSf`R!D*JN1N zEiPvp)n>4TqfL+V0Dw!4D35VvHO683Go?@0mLT`(Y0`>)m|(k!n#rZdzQ-0`-Q~1< zW8YXDk5`F?yWB2>?&eLID%!o3$0jzLMHp}iMyBYRt>h4xIk^=fD+1r^vlFEP)eq%6 z;G7kWeYO5|%Qi4khp(18WhQRy?e0*}wvjh2vgsC<9rz2a`I75k$gwwB8z7}mUOL$~ z{L$v+74c(*zeL4ywbdk}VzzK+PQF-WFkNQ8g>1oo+|6?m znRNPZ;m?VPs{433^H)=YPFB_%{pPl=%0fLXAgsJ;XiTrGHII?TgOKZl z=4PY%dzP3o3VK)KCa3Je?+)0cxp(-}rw0s>{PzC>LmAZZwFVsHgq`{Bds}H}yof|6 z4`)oP4Uq3DSCiV-hX0MmTx~!ZR z^||lVxGvV=h|BC*&aH!miBBzFTdy8ky=MAwcN0mT;#N_h;?G?a-0+0qy(wIPc= zprhBQ+jUEe|H6|u@w0%crU-6Bv3>RtI{RSQwpOo__G(O+85O+QJ0Vy6oH95Rb|E$U`|GlUC8t-rvCp!!=-W~P)Cmy|$pgisqXh8I~` zp7URh!6);Y|GBf~{;kcp>K1XHqQ-bR^_qK}-&=H|&@AE@Y7T;Xo9G=LP8nvpUD2a_ zFi6_JsIscc>f*&S^=l_CDTVuGF;BeR+L^Ux>a=>pX5Z1uc()JFZy=N8CS~0x*TsOm zx67S^E^5-aA-U7rGVH!?d`g%S5xERm`=g8TCG=ajwsm*ECzV!LU&g$VP7~08)dI!U z8dK@*-ddGYHXH04Qp~Q;f6qW!>@lhg8?R9BPkn_mBO+0hy@b3w0)^8|cirfcgCmjv`57O^7s$SK z4OYuYpr=dY_j=KW|Ikb%y>Yy2M=u=| z#Li#UZ3StDuip*3L@TpVzc1IU^7HZz(|J~RYQU!wMxdudHv;cGv!+?yArnpv1Ch%^ zPE-MB0z30Q%yX3g^zq}xAI9H8!)(Z#Roa<9a_@1kP17wr;a|inC>WD37r85DS@{>5 z^_(X43eLn65;MKm5zOzR=*`yMERk_>)zuog5BJs~7xL-JJ1MeyPjfRqr&$(#Vsg_$ zOYda?-t5-k*KB8}BS*H}C8Myn8_R>kcaV%aj4V-nxV&R>{acU50y_-~aqIJfOGOz8 z17g)lCRtYmP4bCyyZ}b4bnCt#QT=1O&@3crfy&y)GL2 zwgg2-do5Chq&ml9i?*GLSd#mp=^^%`CHrpg&Qj z19-pip~T)cX+U9ndFXD%9sRDZs|J=qotO~p)Q3pw&ah2;C%)QnU;LCyVc`I%A9%dG z*N8xP+u@Rv2wipf0ydzusMFj7A(0&-vQ4_k7m^Cn#2sbIqa zWWm962_rI`1sNn1g7*HV?o*X&cNhVWw<*)JE=3qy?zIO38K?& z@4N@%&n+?VNZHEtF&@*}X&pyH8Sw0p7-hkUVX;Yfys>CL53^X|#;wIpi^(a~vpn0{rAwC1Wkh8EqFJ$Q z1v-`4LjTcj9$?dR*`-A+N3#hLz--t1fBwPiO8L_2lB`c7*MOA zCoF!b(cAwR7VB%>K|cY!{v+{Wzu_mRs8CP@SAG=JMP-#Zwj9t(78lLF`kH{wXZxhf zr$kJLJU1*Ndc!#li%CRVXRDU+`l+v3<0l$}rYe87#x}|gTH*t{Cw`Xv2Vy{YtUOC> zDq-?q{)yFDgLNu;^AGx2+xGqzJJV_Yx$Z%+aEI zsidj?bH!U0oX&Yd*BLhT_bFH~9vAHN(fNb?u!zxlo>1?{>>@bM5Y}tmh3Z^!Cva9iJ_%_ano8;@`3N73SWE)l zhS=77uvr2*VZit;)JPGTPzTfin2#EtRQa$Jv6SeO#TiFwHVPUyx%2NzWa{$#BjTLS2ca)~i~efnh(uNIwqr#vX+}z9gcoxi5?K$+{;pZ-MH$oMSf^0cCc^i^YLIDMXJ~W@=TS>Zn?=c*O z(0RIUa=8&JUj`wRS6h2K5JYlU@LR^DBy{?r?!K)G)H*j2RRRI-p%0k0foiFm5r_!3 zx1ts_%|fKO<##^)>vC)D%1HzB{TNyrZ4^} zet+}E={_Sf6?z`~TrXyN4UTF+Hzp$MsOcFA1~ZddITHcfF%c1`+EMdVRaUl}h}jq# z7Ny;?fIN=@PY*?Ra?0L0J`Uo6nx$ay zkB5{{W+Ly#TG;MIu5#0w)d=wwvhS6Js)mrJOx$nmQI=@{Qcb2fLkWu0TqB%i1TGX8 zH}9OG%%Ke2HP_Z{u0A91M1>9Z5su7Lo^RhWbrL7q!8N5K@jjiR`iqpM)U-4BM8_!t zw53{GYs9yDh&3PgZe&s+=Yr$uu{SqMd%by!e+6Gbo4-59sgNiZlk*5%Xfby=cPYId z3rOoU4GNDA1_E#}2XvTRj5x0G{N>Mrykc{kVeMuc#p~>J$`Qp)2F&|8mM6<>7j}LB zqpeN0=Vhj>c+!b43}go#QNF!}P)IW_Iprxj8tOG3p5esMRVEFnMupV1jD?aP_t>=_ z!c@l5T8+-RoT&7h+fOAa-O%!Z9rW~pHr0K$)+TX<{ROjM7`c5#H6f5lqmoZv0io|^ z$xs0Fp0CBp9u*?B4ama`yp=Ow&EdQd-da$vErhp9{-uMQS1K%>vwY9A=krF15dHe^ zALM=D>wm(=&Yr6spPWRy)gebkC%F#OLnLX= zKGRWE|8s02&hma-`sC$urmV=Rft{nT%$irs-l0S)Lwt7NAEW;(&}-)UP=t_UQMsA>CXw^@!?&F{eDCE_mKnvAAG!7K@@t$SHBP zv2Su(?3|p`-z+RG-+%Z(wFC1aK@>_z9u-ne=eL)<_)j{ySk3PoAg1z_L(rUO`}X7s zg~J}p2g1wSF&~Y&83oWc0xTlP2xjB+=lO^D`sC!nTw-#r#=aX(VgV~OW+jX|%$0YQ zt{GhPaHdW+iOfbQ>20OiXN3sH#71uW5m{IRmdadAg-Phe4ZQ#6P}pW*#z_#tg9S~> z$PH(pg<;h6jP8M+F8*`g>iV$1xr0P?Cb)NX7}UWbz?G+$#7HFNFv`E()vdZdyh0($wsiF^ z*&WQ~k0c8KY#&r-smLaOiI*~b#`P9UL_(h^F1U-T=`6y_F_6>sE2aZdU)pVQlKQ7j z26C|tc`Udr+u}-|sC`q}=+qYB6K#)D{ zDgi;nSEyiw?ndZJ!q4@vmpknhiHP8%B_nY^hQ<_;$+SM^-0Nq{2nPAFe3cYu^=y)mvZ>n|G@Cua7fJ^ag; zMfUKMOW~(hVRSW$=jBVBR=>2|RcFdonP(9pwk285sKRE&hqa-W0Gd=jJX?4T{~-dn zxAd7!8w-$s-0>o~mszX(QiUn^7TaCmNb{oP`@NtP(A?LI=m@y z*-UEc)$I30o4?K}w_A^5*x66n_amvMB}u^-bkY=_x?b0u(Op*Um(8SHlTcxGnHAIJ z7g={}z3Ct7lEL9#9p81!mP9B-z7E0A<;e60jPk;fk($dGrNI#9SG4Cgn+;esVOhZ3 zU=-(#{Z>|dm|1XNuALYe8gR)treX?SgO+HNCzYFGKwhEtLvc@c*m`GXg$4=vZvn|+G=f3box8g#J3hGM+OEwf3VGVf>SlzUHY*B|D-;tb z{UtANMG4c=={l5*r@ShB7}`yJVva+Nk;wc<68Y)R!?+hrA zCY!d0yAeR_z=ci!x9hMPTeg%f5=Vamy{{+I=YV^v0kuAWq;S60^KgmdVf zn5ZaQBvVxeL=o=nJ*4sAb*)D+^TAbO;hnj!?Y}^L*zRbktK%j5>l)4ajq8**l!lMy z8Z3CUS1;4hIud*+A-|*Nm)6KhL+>@O2j@(6zEQNzViHF!JlRl8&qVtrYZpZt_jc^B z{y383OTlsHsXlu9%ah94q;v<#iTux>lZ8HweI;=TFEW}tw<*@-qvK$>qH@D&}~Qd*~Nw z(mizncp$K7UZ*zShH#wh5nb4bVP@R4aCAQWHxs)%P5jT`1aknw|HWT4gvLAme6upt zTxj1Jav|WMw;7U-b_xQJx8#s0!;BsV*kRVI`L01JsYvIqak9UrD!>UU(4q_fwKyJi=Z;a_CN;nRP}>vcUdozu9?O>UNdFMxTFCRU4}{SWwBp z37!=|nh7MhN^`q(Bv8NbZgO&R?iOznp=y`^d;AeCi%=@!yiC&Wrr&P;CARqkXyXllS)ReqdeVxMc)}wDH5Ry39pe zH4R8z^My|f{veY^$~4qrh$71O`*33SUjyk%P+N9WrsDnfuTeUH{|*qT9&hqBL)>iKtNl(#&Nw&-If|N^_SD%k z_uJNsW1=VIrsP`(+f`v8-B{-&;BHP%&JBUj ziAN1Eune{xv9cyhV$?-E_~wTR@xM^Rm)(6)PPly<3->;4)%I%n>1O3+{0HvC*}#6~ zdL{sFL~3JGdgH{8zP=Y6&$F@|ZLCTwp@$&`kZjb}h9X8nG5EbcSX8KvR`rGUAr(^m zT~?Ekq~hL_Zbgdi6hLH8txDjJSCq7Ydhrn@>ZFv6R|-tEw-#Z^n~AWntF(V%Bc(i! zG^eT+l`2QHd?#LCeXqYi=JW-Co*$DhP}_xmj;_(slRe4G!xsd~H>k2K8N#w_OF{(< z1d6#274R*4{pat&w^2X5Z(ij8j478KIB|I1!n1}q#AWKMxnj)(qD?HOEFXb~!{Hf! zU*u-)cO|14_4eX}>LbR?J4Mr^NOmR*542^oL2?~{k;&nS9!IUitpEz#*Zo4Qrl6qh zZDqDZ0{iL^Q3s%ffkBTxw6y3IU>I9~NIJZ^a=#$v7r7~VY5O0`Dri6DIeS<-VJg8u z{|h@qJE7XQO#bEKNxQHV%|>@<9Tb65V5{TC_9D)#iuDYJ&dk9|g_LywSo1$8LQeHY zk)egCM<1YYS?_SK$%?pbwdf61ANRht5I{7GA(S)j+{HKpnOFkYv_y9Q)jSrPl zw}m+ynF8Aiek!t2ZDQ&XIQHOOi}?k%yuL91Fg(9CbmZ~kdnh$A6_GT8F8?8LLSzw1 zOIs|CtBzXrE{o1H{}WSZq@55++K@q>F-KBaLE#k(i7i8JP*W9Z)}FSuyRh$NGtIx- zw6=zjigmd=s30oJh>t(jCHAt8t;PFf6t7=J+Y-(m@6{OE6n<_{u6H1=;{bjc+l4NMGh0ZLSHMZuuhHq~F(*5F}@I5G7ES&k%#!qc~UM zQKw9|k)m+uJda~ze;{vN`CROeh78FC$IS@u02(jR5Tj!h7I>a=?)Ni|2rR5Gzt1vw zB2@RY)RXJsl@szZ;c=}iz1;`2R?zw%Agp9d_J1aaa9l&l%scy7A8&c@foY*xRd+Ie zj5eMmjlXSKU4xuspm!)kD`wO6H~AhoFj#H2cI0H0W2*g&4KBx_=iYF5QTU4A>WNn_ z@!L)R?*6X|pWK@$Izf^GE7?J)%*$9%7XJ1{>o0C*oTn1}#7prk?A@`6*I+~ti8Q`*gi zeJ@yUg`1Smxzy=Z$HyG{t;rg7or5{P<+*zBWr1#aGlbEeJrAyU|_ zGY$0@83TJU{1aY7?1j4AsR;>}c9HBLSF^Da9QmAlF3_qtQ5C~RZBo+wSVJ}>M3RkV zo8CcKFbfMk>UZuenEwIa^GqN=NEY;O*MQ)c@CA2&_;Bm!E?;zSU@{ooJr{59yiDOY zE_72{GCABtN)6`+_nAHR{Yabj%!sa*?xH}bxv<>pi$=~Wht#tWbnW#K^}S_A%n zUlN{bFZsB8!Alpe%^;RuOPu}9;gkKu^ROnU0v63_y#5DC86&x01T`tj&Kag?DJ4YX z%YPHJ(U<%6|M05GslkSodtY>B{;Ev7KKAlYlcBJ3eJ)ei=co2)82S52`RzPiy0J`+ z*8Oy$=iA(74;Q)s?I=l4#;&f-r!QP^&)>w|DYmE2no6E-mwVpUvuAIJZq<=E&lbP6 zNJl5`u-hrUCx43S=G;}<_ksJqUh4$Uxl88t_C4Ko`^OEw{EASk02*5&*gBrs`gyFS zA#?3jnH7|8^%@lq`QI0BdFNK^#s92aq))MI19@9R`PF~=J(*kC%>qBCK?H&zNp`1=PlZ}ab@og@k{{g?>{zLQSA)_{G2PXhlPlxo%e(OAidj< zmd-g+%&W(X{$KjRnW@M&q5VmdJ350q6XW1n-?ny6@alc$MQY97mz#DN2HKnN+;C*+ zoElAk)gqxQCu|q9P0Kwqmjdqzd+jt>(1(z5Wlc>@QPDgkf)u*vYD1er=h+IO2eM0u zd6>+Y*AfEvu)JG((1?%*-D#8DPK$Q|qB@LtGj1*UfmYicmsW zK3>M1R=l~!S*W&StiTH{irUYgHzfF6=XYrO0WK*(KSHw5@HzdTClZiz^pJl`f*9gq=*^Dqqfwe9K9M z^ow&&*oj`{igFrcz?3{Zh|92P%?ivKGguszSL0Y{vFvBT{Oh<#XoS98h{PHH6qro4 zDjXC%;_W^B?L3bFsz;cg{+yV=ph=s7t|-`n@&71aQR#_4-vNyAwa-I2a3)OxG7wvUf7P8&9MB*{vk7_O~7ZChucnhpGA z_)=W8?T^m~gH9_dwpgVbuM$%%d;9R=jtGgy>&Bns+QTU)Y!OL{@^GGMjBKlVe>qn8 zm*t4<>y;NU2cdD>I^vwpOze~YvNQ60Z*D={h=bNDwmZ_aHND6q1;7ZN9-t-Wx&3jA za=OS$aQ#&~__x%jjeHoQ8~gQ-X~ZkWIxRu__MM(3@FZXaL0$Jc=WMuc7rtoc7WPd3 zk@t-biH(YE0ZXUydmIMrv&O1ImACCabMJRbSiq8%k|I;qi$_SCBMje_O!Q?ra6~Qh zUc>e~jbtBj$YRFVd!__~^dSk**813HHbtJgb@k2osv znGZL2sQ)}&eZ4wsd~M!Jl{pa+VXxmPmez4P_8jsIp6nQ-+crVXOT2M3_j9q|ife2I z7HV3WO4NRh{6lOZ%jO--qAeM=S4M7r_N4pSD6@j-Jvi zwCI%RyrcVBaOl%&T-;e3GA`~XrXn@KxET0|*g06CSoY&lP*MVyi~JC>>JOGK;C#6f zl9B`LAHA44!CrA{zIryao1T-E)!PftM48PA%xf(vDe*MCYOoe`(9N4S<&N##01H@# zaf;>V$k*M64(R*)_zX`t)ZXJTAfAh-M26%9B*YDB z$pvpR)|1s(aKyvi{areTKkMdI8ku$nIUcMVD%$-!_zvX?GEkC69bPcN=?#QGSKcK- zE&$zh*AoT~jkL{cRw(M@Ghj;OHqF07Th557K;N37v`UjM*vz`u1t!FT>O&ovG=yAX zLxiBbD95TJ4rzny^^+E3VaqW_ITtXr*FG!Rp6W6|9Fr+@nZhHtJ~yl+_2GYt8y_+VWqCD?dW5} z#w+(g*Bc!hE1|8Ympg3cyCK0pC@6+iCb~RwMR}guz|q#C%nAuUJMpZ(XFI(0$lAXm3}YL{fkYTrCoKhf5R zQpM9R-z46`%oPlZyG>fN;yT3HiB}bMx`g!vmME>Y65@7IG&sOIsB*gY=~BkEN|%)| z4e5PxagD`${jB-7-j@0(nZXe|7slLX=F3bDGDd-g#UDN>X+`4>tE8{4<_k*1M`3mf zT4(g%2s8`)bhLa4SQhm8v5`+n5(P|$=(m+4&L9%%B#fevr`a2kl%9SF5LfKgUkgv9 zg^bWa8V{JkCA77*k2vCg>J-@|fo z>zLlW#qrtRhBbAE^I1!kAU=c3ic5d_^5qzCcq*Xd4RW%exGnds+!VN;R)A;UzB9S_k3 z1%L1nxBT~(mehJoqj{B*a+_gJ;P-TuI-3SXS-aNGra_UHsyW#!0ZT3(U?~%(`PQcU z4w073tgPvX<99&b(c`o<)jq5tFh6*h#()v$AhhdSgrha{wBv!7AX-Ko5`N%nf}?FAUJ(tx+PKfW9LGLz?tl5& zDP<9{*F)m;xCd?EedfDXEZnM%J_K(Mhec@aP-b5tt62-guZp|>{yY1AR$3a22e(&a zqaoXwMv2(KfFgd7X1^IRbhfGlP1-3=pdl<9;FBgO*$l$yLJEt&-;GwcgOhd z9e3Pcj)9Q9v-k6?XRW#Bnlr2)17ATU`}OOKT3q~=J!Si_;G+iCF&15gFoTz;os`uN zG%^sDYH!yxs)6*DW3N{+%yF|I^JrcT0C5C#TYkLs=1Xs7kSPyhAh~lVE7;3VOickV z*+^2-13x0_x{y2kn&3-GPM7sh?(7(JMf6XW16nWyv=7`Mci=cR*aC#RNuFWPluJ6M z`Ify>E-v{mJ0V+wjn<^?R26#$8eE6~3J@cqdF*wN1{2TecjXGW@U~^OFb)ye-S2rJTFij z#(VZ`ya%(LT^=Y9CPF@Gwj6~sF)_*Ai92Z%D@7ucA(>MFx)wbxtwL2Jjk_!_=inCcV^Pv)^cB#H<2r&@O{Yo*x!Rks%AHduz_(qa8H1@DEnQaheP8le2lpo(t z4;p{sZp$@oCnQ)FhkEU~6%{qRp!liww`M!g8f-hf4o*0E>!}Gs9ehBD-Ca{tVOUf8 zTONz0jB+S-s`zcS(+-fJ78pc?RVa4iGV7hkI%ayHQ4cNMFlGYyp$*aDOa`x=x8tX$ z(#dmFi3|z~f;zZs2P}@Pj^RKlNHW|JEtKVOmz;@C&4p?KOj(1#Ht_uUSRQcs0Iqjw zx1jUPPef-)^X5(J4=j|-4w(yCmDwSKA>f}3gCU*5t_#i(N~8c{O#s92bC+wO8$HD* zBQGy~rX1EgsAX_i>FbMIYI5CRJCN->n;Ii4Yw|#4C&;1XY2#{Ofd8zB2(XOl&Yg_H zdD4B#5^5Vs{17z{A|ecjwqK`&x*)E$K{ig#doaA3$GP2s7Uc)~+QziqLGqB~w`4D% z{(|=ravDrMm8Yb7_48?6qeWsdpJ9ZTOMx1^0Kt@m12|Q0fVc25U9Z%a5CDN^Y?QJo z^bvycTj1i4P5QzPg8o;UoiIdgkP~NdnJHxQ9OZSqS$8CY6{Zg|N1Q+2XpgT5! z;OCFJknAJhxI5YSHgJTXNT0}CD$*^~WJIw74?K2XOJDgegffVektzYnE&gW7iK23X z)T8j)B9;Gmvk&vWBk7+ZCH))laz6qL2%g@gDLoj{M~{QO7A5&p0-=Ef&L*4K0Qn1} zPqG9gFHAM-!Elc6y^FfLql7uQxswtS4&tMoZg*pBHpbtKE|4(cg9j{iGPwDHve3O& zZkW8e?eC~;sF(7x$`>4|eaP4vKwRR`g4};D-0q9gT*TA{TXo z6I5P>Sw$Tprq1mAIUt}T+;l!N;AFt3+lbOn|5A-Vco_#C0GBa5Z)|!*D zAf2c(Z-Gu1B=|Bq_P+rN>wJe6`3O)Ee#KbECT1f=;6y>vrzs2oLR4pi!%j>_#T$9K zl^5{>X06cjM}n@gSaz4}#vaMRcnxqza)f=baXp%whxOK8P@&K0!6FXI zt;qZG8?6XoIK{;!byLR&pgWjO@qXJhAZ#}r$|VTHnm*PaH5Jtyu9-3ea#Qp*c&eWA zJk#`H_7tR0at7j!3P1|Q9g#w*C@=R1DU`4*W}|=uR`@rd?$&YSIkfuN4*uhAFG@Vm z2bC$*!qfe0^1|qCREI$L5)MyjgTTR`oqc4LNGMWsuL<>#t*jF9{AU_U>0165Y3K?C ziZZ{xxNqeA`Lw1P41n`%vqS2DA$-w+WNK6pZTg9twVD6#1q)#V8(G?AW?vm zb@&`)J1NeRlI74>O}P&}R1na^1hg6U*yb(F4`DVd#N5R$of}KC08yVZ;-bOz4}xIi z)hkzuUco%$bvEnSF#{|luq=lp#^Cf{5k6U}*@LW49*T>PhrXNp9;WbDuM{`4e29;i ziS-me9*{9zu4)dWg{8d^#3#Vg#P(E5gpU_*XR@gbSZJ=qcb0qZaOnX@~}^lWg7X(xPMhE*!2uLcHo52d}(clN?VFi4kBj6@cQWIP{rD-Dcpi za2$2@iK?zwA;to_yF_XcGcYtX$I8D@W!GSJI?$(n<3^^Nh$u_JwQap5tO)30W&j&Y5hCuLGTIgl-+vW6Bvif`2j^g z1|V+RgP?#C2JpM8UE3W>LCAm62gp`OYG+A~ydiS=W&P%w^w2Qia0aWh} z2w44)0pR5HVHqPGkB7+w->U0$b*lbS?LijrrQyLNO_kS>G&m zkTwa$*<(Nn+rEx~zBd>Mm($>>`;dVTR>xzwnxHK1y13UdBBhm`^HR)qwWv1DCLg*h z-KDGZ>+k@1P##gx3!fmgOkFmW(U9Oc(+`+8k**AK#wq4+?WmC94(oN1!Z6{ndT;LM zpsum)tvHCK+VU87lm%lt00kWlCxc0Gu|zS@HhC2iA{(ZC_K1o+D*WZk(=MV8E-nil zQxnq=e%f9t8X*%NFC#KkiLSla8-X8)1i~2+k&2JNWgYM@ODK95GEdzASs8MpE$xQ3}zlxgFGnq>>>lSfBH$@Hj4}tzW()R@U z0avzsm)j*0O^EEsH$IW)f-xi1HSDLrORGy1Gy;GNd}jnB8)gNeJ%8^|d(Nw=GV8-W zlQ1LXbr6(z`>MmF%TabVHj=D}BF*2avT*05DQ*#q^Jf&J#BTUyh*~=~MiW&P^xW~)&&f1{49|@Yy^OH?` zs_%xLw=ou-?GbJb3(Nwe=IFq+fsHB#A+MyS1}I2bb%o2@zTS(D)d^kudB4~`BD9n) z-Yq)iv>du)e{?+nw!MAv){^+hQsz$48d=usSWdrJ>6$D90nyubZ(NHgJn;N-`l$Iu zg=Gb81YiD7Ke+!>*?QoIP!n!8drqPdsY6#)IRalevS*2Vv}dk=JfKD&b_x0aRYx0D zw5M5zvteR4C-;IQ7J&Zr_fJ9gWHq+<@Nx9pkfeoMr2VEkXgqVx)`f2^(+5ODM!)?% zj{nE!z3`ma-1FC-K#?Gow_MD7a;FR1Oas22K6;uWh`-z;I?AB(FP`DiJj(a@VCaNf zyw&o6T-cfq{R6*T8-mKe0ratBKMZ*pou`5ri#Xsp{t~7{j`WeYKr`4`={h;VdS&~X zcECCg$LX=L@rPv@3obl=06NK~lzT7_rJEt+a;wxRwdR)fF!=ks5Bf_FbGbRY=CWYK zu?o<7eSD3D-hW28{!A?pd2|1BtJ()EEHKKxhBo*L!wR`UjjAgf8U5bJ#}AhH(2+U- z>;_1#yyo*~AcgYfLsryUU*9uLhBnsN_&8APWDh*(T}^-|!wl*K9J?(a42$=~1%W_f ze!h#DnOrUKlb{8Ic**L=+C{3}xDnJN?TAL_^}=wQ8Y5*mW9gwJyZ#3#Y}=;f3mcFz zlBEvE?Sk2!&!1(mTx@LDgS>p`1uex{fyWcfYZzLOr}R{dB@pdSKR*~d@GNCyU{Ki% z(MerBxCi83(J78=ibUBTOYPd8ts6inK^yxKa!Ex+P&2H-i6#l%&1U}dd69acm<7F7 zP$!59vbf=WkYqfL<-7q;r+5M|MCdFQOts!qokRv0@rT?sH8nvVmP=JrCN&WT+*S&} z*xDS`C_57qnJHZiD3<_gObvD#h;qr`XjidUDzjui)vMucl-AA4RMgS_Q4!Vu9V`=BSa z!YD%Krca?w5SvlC`7!VhhYF_zG-Z0qF&wAvsAzp?=;!8t--DT~s`a=wUmF2U%aG5j zq4|OHARn(rYO@<=u}l5)b%fa8I7Uz9)u(JUnR6Wg0b(S}+pqn=?RRYX^5tjIetD2H z#OGU~#xe3DEzQmLG~oEGjD-{u4%E2Mw@wT2@EqUXeJ=RFK(E&Bm$q4bivR%rw7d_R zwPz`4Xbj|E2K}q9uD4u}*(yV)GdLJn+H)?hh=ilEl!&^w9q6mzImr#-&W?@2&Uj$8uwRqJk zmJ75KCBN)B3+oDcF`#!rPenI!5I7HOn|rH>8Who!)dUv+fedLkthy>vH@7Q&8R69% z=*#Us4@nVFK)ZNA)EFEv#HAM3*}Ssjr&NXZ7s7!j0cSAKGRt!vCyl|hUO&5I7@`Y1 zMp5#`)o(|C3pF5s)tNqq5eX?zX-#O+2nJBOT@tFRW;nWc+n`5vI25Llkp|;b(02xd z*Fbo0Y>0?S4pF_US~~T@hONK#P=FQJjR7nj&~F>x2>Gz{>E_OM7AH6&u??$z)yJA($Hkk-Teoz$)OK>~}AoQ1aOLay2mItC?%BaFca= z2m@iu0I3_)dqr)C%2KTAjLSCb6m1HpLR4EWYxU_w&@O4B*#icZ2=Qd76iPeNk0DS= zAMNHi76sibjT?yr%B(p1uI&~U0rrC_rE)kChNcHaM`WB}Z)$63aONva|6PI_*rJwx z-PNnv7=h2!cv9BK*fyr=fRJtB@yTcaUC)FtKv_aJ&5487kSf_yJD_);K-n*CnB+dR zrSAFa1FSE8OPNTuf1R6izH=waJ|jLp9{R`;d?&fNaTLV=#Nl1U-{QRhpnkTl{X1u% zN!5lwMMpK*qp<5Vmj!5<=y+DaJf%`ix?Id3?~sY457miUEvOcQbZ^poU?|6#gR5&I z(QhEGO44rP%jG?wph_GWZf&}*tX$vN$baF2GtjWJ7$q^;IXPCAmR&@c6g)SXSgr9g zO@#_=85_nogh+)XZ`!b);8dFhW|Va2%%aomX95DKv4?KBPV_6p{N$2ayTPXZcVMc= zls3WtEtu*bO9p9({#a^=TIl|2h<A{(GPEEEWKRvH^qKYZ99+4aW`efat^DK$Soe1=Z$4|0Zp+8^E0Ke!q6cfm7c zd~B@U%uaw_TT@ei?P-P3@Kzth>!Fdj!a}9AG*+=0m;7zl`~aeVwg#XQ5Do221y9dC zOF6;JtOtIaL}ow^rtz)?E+6yr%_f!dELcsyh?1cb>^f~9ce=5F>5zrtW&O#4_88y$ z5)#ElMVo$wBt&l{zmRG(*fQJ)=>i7l)anBm7{!!H7z6in=nZM!R>I-bYM+85a6(7> zFsZH%W!_N0D2}`8OMly86V;Mp6$OuM_IM4G0Z$9RTi@5TP?c&o2P+TV*?@omkjc>d z4#HRPi73|0nzA9sd2$^9TUan9z-Oi2Z6S-sG zdEosrm!TXzzItdnd1zhp1|8B!eekAt29=VIlvaP$M|tx69XW(`o>CHVC;dK&{W7B_ zQMEBzgCT15Rk~_OX3wCy8m-qun_@@Via0Mw>Mo1(0{)`Wi-}aJP%URHc7W{M^o@LD zqDHNwn)UiR#$c*A!GAQv(7m%^dBtQydje(KG$Wyd5}BPD z?GAV@Qjy$dSLzbooxOx>-h(yD$F}S?8EYkitPK}AH~#p73(6jfGZsJ zBAOzM9^x##2X+v2O!)I2H_cr95s@!_;eFZ{5U*NF_xV~N)koSj2IMENS{SrbB(UeTzwNvZ`J*h*B zpVw~q`_p0tHsfI*eUox$22{pgm^6hS$sn2BzWse5slera2@&cqaye?`>u^L-L);CC z$Ujz{9qq)wg>6!22f>iSz<^cn<&Pp^+~CDyB;^8usI0^GG^QXl~IS0>x- zn3O=&VpU1`Hb5Jig$Y3R0>~z$g7qtf2w<4&s=)&mi5D24DGHhD{OiYAgN#kIx3q`z!S5V1YdYiTTPa6w{Mu~ z$B0RloO5akn1mt~Zu&GRknHCL5P~%Y++eis#)_zqG+EQYd;lx3;vh*>fnzr}BSUpA znadn&)JhX`Rc35RsOkBT9U`l8>zAxb?(_k|sJ%CL@p@utAQxYoQ)R?((?m!OTnydX z-(o-pc|}Y94D8DK`ua_e#kAg=8P_s^NC?$$k&qE#i5FNbsH_o#mRKfy zHt(luMze)*xv8m^3m8lKgq!XdVzF|jQK9}*@;T8 zI7~4`Ks~|yc>z`lIayhcGl!Vi2q3}aR`@+7B}KdsN?|Za>ltYz^?;>@^jk=^LAS{u z_WgYi9V~q}t0tM8od69rYor}AN*Do49aTgz-KMC2PL?;a62Pf0&yZKIz)ujgAfG=; zaf=cH5g7X4A~2m8Px`}$1+4p@zq~x_^!@M6@7n4QGab)!6ZseyS2<)0$3MjD)+lH} zNlIIn$HsEh;lree7y!?JfTDbOhueg~IDtTT^k_p+B`ZaS1blA(f#6&%kre{E(b}i_ zu1xuCN~!BX2VmJ#bV!!N7=;$ecozqhrPUzL_Vep1nSb|_E$^Mq!=9g~rKkT~S&1oe zFTA~^L$U^jrBDPZnf)r-Ex{&UsjP;m61H9nJE8Vq%R z?c&Eqr?>tvkhdy4VogWL=*0()4l_T$ySZ(aEW>YQw7(cc7#IK>N|=viCNgdS3 z+%`(ALCpfkErvh9VB3R@zr{edD)_@RJ#^ra`QW`ypgQw*CrApIo0-AXDLBJn*|+yb z7hgKZ$JbKNjXMvJgytRK2@GDM2Bi&Rchtd(M3A}zSe50JHn13PP$Q^^ARQeH^BfgY zv?VpC=#jJtZfOAfI$vnGlDcdC{ZBBBy~Kr`eNFBGh7j<&B%KHKnCO_8nl>Mzp#hd% zKM~Pr1%1}-XHp=cRmH+QF`!X!pIOc^xxgHx9=j2mpyHN#&*CG8))JtBNRgQ3*7PZ{ z_9mG{7FwhZW;X_>wgM0v|Sp>1n2S?wm+`pu#MhLrC^Nc^TPHE0YBx{UYjYr%nOg zT$RSj<{`W>NOM@V(N&F}Fbo5Be%df!6MGR7B^cg;Ubn292Z)iFE;DA<&t{FaDPHtW zy9`a;KR@}t=jXCAHGl!R7w2jgH81o59R<`#ATtC`6nHFy8p)M+L@`a!w=OO&wy*(5 zBIzGKbmvT_;El8L*;!jRE8jhv3E`pRjpG|UxWaLP2o>#Bi z;lmUf9uB>T`#@g-TS#~cxdX5O9XJ7Q#o3wutLtg`1E!dq{FCN*=GNUTYX&5}|^*4LVB2|4W~U zlH07Iwydnf-~FJK-pV5QZ>NlnjcF;Bh+dFyn^7wHm$Vd}OTL_t=Rh0hH@HyF{$JBh zU~u-N->;$HcV#Rv;SGg*hw{^4dDVYIFoCGHI&%zu0_0h!BCw3KwEON6SN6Ti4^X^0 zY*fyD>J)4VxrwwZ@0=FqW&w~(U1@R^(h8<`a$jDwS=&l<G^mWcSfz}jPYsN(MD4uT+OAvRm1&NjElEwysc_?9KE;LX@F@}XIU;yi zMSym7YRnS%FZRJNlHc4%E1bz&RG|hii@SPwM~>#eqP9`nUbz?IJ2G-pb(GQuEVGAs zF<^V}hXM^rHvn>vl_D3$?LiAp1+s$od;u}kU6Ih?$OH$PxWK$1VNijAD)&2Pb-LM& z8A%<1YUe#1TMefg)z#IZPVx{@a=qPLfeKN*cQWSd=HU)hDInjYz=@S@_alx>E^(Q&!7oiE2U!z1Czgy)Fb|jsphGEiW9u%B0!O`t? z)0ia9k8f*1xd*yP)$f4*ABU({x{9jL=cl}^MTXzr(fM3~vkr0Ty*=kL23-4`gdyZO z&loMQ-F4={W!PNae}i4BA392Kbhz+mz30b*}?xnNiXKt{!euWUQr$LUwKZr@ZN)=cLP2vquob(3r%wq&lp0l@@7An zvfKpHpH_}-RVQkMuJ1F?rqw`LMdLKu*f=&KqUWLyHlL#!{&x%!RCM6oM%i|?PrxPt zsNeJ7yc=Sa-b2ry@`4ecM9^rj4FHi_ScYdSD4+W8ci&RG`1h8gj0>#ZGW|Hm>^x!7 zm-_LpqW#S+dpitEw7i$`HAr^9{QBMf*suYoqkEehpPJgu69|}*Y-f5{I{=`GK~}U% zCm_`djrYA*CZxW&Fjam@fId7l6i)Otzp)>Eu9Mp2tW5wIEv-$?ffWW|pz=YmA~P^B z2-pwBa{>?0y;w?nE!{4?sSM&qHU1`Hfdo+!0tvyK6BHqeim7R7`grELr;@vY#ta=Q z3$18yI5XbEBm$~Kkvx$uqmhd7&{CsFhw$+7jzeEGn_E@r{1OouE6?w8!D7T?Bb#Q{ z{WpNHfSBIhRl*NclO1<^yhT2yq=5MPWzBoPNL2zd78bD=&mN&9^#W=`T|HX8F5sJ$ zcH?X#)2=NInWm896dx994>}N?loa$C0!~X3+D?Y<1Ya6(*KEb6*gSyMC0VEp<6Msi zCDa>#v3xCJt^*_MDjZAzkHSJmI8Q%`4RI0@5|9U7UL|c}+kyfWMq=8_=By1!(qFV6 z0rY_sh73*FU(i~}nDi;Fo@VtxplF~k-m^1xGb)VFKH7M0xO=Jlk(UHA^f$9oQ*}i* zjG1YMsV>oY*oxs0s~r7d)wt=sriw+V_Sb{2(BLt1%>5*qplIcb@}T z+9#Db0%s6N)-pIY!7#3<=;E-;>fr;w~_J)$QUX#ZIIFDB=!hNX4JUr0SH{u(39 z&ae~b4A2jnsWI+G(xF3#Ai1YPMERamSRx87kMb7>NqCugJgR_{f3@dS%L0)g?UZ&8 zIENdr0abrVC1my8*x{$o<#3~gXGRxX$Akg|`%fK=n}eZU|D$la{qA1(JdP~O+F6z= zy!e->{qTH&yW}0(4XYRx&U+8e7UYeJlApt)XT_j1OEPzvb6fnN zJNK8UBiDGfTkrG%9Vg?%^C`R5uj+7!WO+K1dq>cHU+ZcN76wM~v#$8OTyK@N*YrL< z3EA!AVY2{%~Jl#a`a78+neI%V_yonTCKacyN|g2tP7IQRKjZFF74WPUxq=6f!g zsjWtlC^N^m|9!80S&-qs)N|PUKdk5QODW=?f*SviNOk;D)R?-D=lc(u9neMkunTm3 zecFts90pm&}_6=tPJ7+$AR z{xTi>_EuBN-;!uQ-p#W^s567blZQ52{{4v{epB`w%agYmnp!_Z)OQ<@Or(Pff~*}Q zG(zg`Tk&{n>=YAINUphtlk}O}yK#rOoQcdimZA(aF?GCLbl84wD2QxlM;2UL1fDS>ApUymYv{A!6 zAwK@JaE8%g!NHWs4{sk>sjt4&(1UE4gJHbu)a6E_ZBK{{(sml+BNSGJoC{`bJL^q9 z)m*Et@af~pvCF$oJ}C3>Av}H3Ydjkh>6@h5+*R}j>WQW{q8u{G24@ue$%wP)`~miFt)~ZK|WC2AnKXQ zkF)zi$vs(%3KhhOW<91RFJj@I#Y)lny2X(nRYARx+Xmb4!@J#GuWA^Cq#v0blE4l2 z{7mbpY_$!Qef#O`ba}~#p`5+zK1FNUkiTO3l_y z%pTdbs#>bOc8iXwWm3g9AsVm{YbEU|O-*AkA z)a_A(V@}>7j3RjQ{>ziWHFKjh`S%rRFp`}6o15|Qo)0}fa&CiV!1OyN;rEvnRj0ng zquAc##qBcO8&nWoi!2P#duN)^FwdK;Lf++ZZtgzwg*(pXv-*=vIza=%Z@wfAP!TPj zf9T21_Vc_Yerj>DV2Z`JR+`%eO{(*YJi8}TH8cuyNp66bS6C4n-HQ^PeJZPCVrwi@ zG>?-Bvv}pgKa4k$)L`8l?if4t<&DYqhokYA?zr=CNWG0(8?ORqkuRUHQo3 zV{}2>>B939@8!abuVt$;7YL)a#1&$mi9Z^icD?xIYqQ$BMPXCSNKb!qLfr8kG8(v( z+LZ(I2HOp+#uxRh?6fs^zm=TCXP?8<`)Af`IlWaZzriHpJx!#&kt+Wjq3}lU`A!=x5kZsXZTreQ5u!?FkpS)<(fW` zCSCd`;*zfutyP0mW;>?Kar1+&ftX{oRhf7f!gu$@$ZFSb5ApWEcqA@fIW9sgFfS%} zTq=rQDbvVt)8m3EL)WPhiQQAGQk&+1lGC4g+<&Xok( zFIG52M9aqKTvJ!w|4!tl#^N<L76Z@r<8srxWZM1h*Ue_d_7%(psj8z*NV*@ClqBZ{4V9?T>9<(t<1wm|>je{( z4<4a8(S72>l^fMY$J^cHU&!LTo|*aBsmIBl&=dPhRDRXNk4XM`&Y;)-pyXJ{D`U(L zA;I&5%@DxqN>S2-J%c)r*!mOF zJ7>4w;8wa2s_K629i^e**bb>rswhEzq4e|RDU11!Rm5d#FmbUiIww7n?8e zG=0TbyDR1P@tyuZU@wem;2kSClzBLd=;B=G%EX$|3M>RIN)_gL8l1_C=!J>*7~r9ZwH8zn1WS=Ob$8;7aqv_RquNf_>aD|zF zShb{evSwOpqU!k!$gDcdj9?!f0pCeDATYi4oxD+OT23c5U?H8OHVgQ zl_Y(=x|k5!+gA3;*iP=%_lT+}xOfis0W4zr;fc;LZ$eH>OTqCzYT~1alY^?~_I8j9 zB15IwhMObsr?{vHAv)e0?;d2R$7T>M)!Mjb^xu7n{8}=mYaX%j?O~6Hg(xeN?|Q@f zBZ!0}qyHh7AH1$6M`8D(l1r7X|TR)rfXNr|9lbr_=%!hO3`9-+Tk1n3!IJO&8&b;wdc#-m#sA;W` zd>KBx3w_ZiFBKQq2nM?*3#@uB@Rzw9weZtl%x++4kqsVKQ6 z(ED-KbP7YbR>wPmFfV)>x1^nMJNfb+;akpwA2C}{rr3GfH}s-#fR*Kmx>8g9nA8sr zH!xs&q4Xrn)rJm-PDrA!C>O6q&Yx3fn(4#ihs&j2x%zPu^O8K-PIow4wr|ffa)_%T zIgbQw3>`b|PGzvzf3=3S^Y2@WBiO)K{>HbR(uFRxTx%T*v*Rf#Q48B+J}{|Yr>9gK z$Id>hUyr3CO6lM* z#j9<0cKFE};UiJ9>(*^il@u3Kc3sd)xl*EWi_vvXltsk6`<{-|CD9-CcM`6+I9=N{ z<&N6tAtE{7R*+{hXPBark9k*Ui#(^@=+vS!qyAfg1gX+6QmOtV8>QMoA6LuIliV7H zxf5}-S$jxzL&o`X$rv|wVWV;n%qUs(_2OlYDj{cqngwV3oRJ*43;eXM%&Iz!GYiuN zmQ5nGHbdFjwM~%Peh!v*C7qcR24hm!$noC8G2x=@k2x>3OXAvV$D%`VF?hv*7&er# z2VU~D3sXn0V~wFGnTdghJXe(bLzR4HYn zlFlZ<;AX8qjm}(X!{vQ&fL_-raUnz|7WLW31k+Ae)=Kt$Z}hC2XgU3s>tH*Q;7s^s z1W&ONNPQK3iPflX=bkI;i#noEhRxJyN!RZ?QIX9`^64#=l*qQUK`AE$d-|8o z@-m|kZ|r#otA2f7ro|_p(dpBo6{kh*4>@LNq9`L8 zdMZZ#MZj^IOmbc-HfS+X`3T3kYcFwzC%EWc6o+GKp+%+fj z^*3Ccd;Ng=n^G~y8(Q<`J*U_yC(?x7oBDGX6<@h)u*rqs-2!AcOqb9V@+0dQE8sZ6 z>`_-m{E&Ku%}CG)+mIa`LKX|TT4C|3?4yZPP0kAkQWR^b?c#j=kkMB5il ze6C_!*L}iJm2}Rj{<25Cp5~Cjt!y}pPn*f@Xp37qieoZPn|0E9klC40(^XP5M~*CT zx1`rhyPQ#$tijp+aA+#g!;EUBJmPT_6fEG__;NySKXQ(=LV{k{X6r0EyUxtW1|l1SYTQnmd&GvyV>5Xj9Px0{6iW3~DytF<;la3-inEUys`bvk1@R?+ASn zX&G7k1UYex%Z{wbUWNH*>QHBi1gqSUXPl~M;Pz6n|C4R6V9Iw)%g^!| zed|xR{e0@gL7|lM0#atr==0aR$zRzD|59%9*DqhE5us)HhG`Ly-Q>)Z{P#Pk6Q9c8 zxvXV3gmIl~DeWE4$&sW}e8ouk^5blK=$>v{`l)R@JRhNLxpHzaM^;ysZ3$dLxKNRh zal&7=euY^Ka9;;DlLw*vT)%V=hu3G!CvaKe<^WaD%AONWM|XeFp@)(>c(J~djB@2T zI8;4lZC*?8w?%6BzfPN-+O%2XFA-*+6MU=d>I_+}X;!U|&>PXV|Lz7t|KS~1T92Oc zpUR#65#khCW%O+PcKc1rU0yjavw|3$?s&e}#63HJ+!Gv3JK6}Hu(4V0A;wfYqsM9D zt>XXy40-UsKgPbhyYbTX>jwsTZPAL%qD7xJJPUmQ)%>lHdTcuisjZXprd~NK%1nJ4 zKIRm}e@!|<7@RQM_nXRHRyKXl_1Zl9Ad zAKzr{ufGJkqSM0pJXm!O z@2ofdJWrY~g0(hWBh&0Z-LDN(<(Xyd?YGeBGB9?la&Zq$k(k3-oqRO%JCYJ|;)$1T GJ^EjL0LSD2 literal 0 HcmV?d00001 diff --git a/doc/sequenceDiagramROSUDPMessages.txt b/doc/sequenceDiagramROSUDPMessages.txt new file mode 100644 index 0000000..0712bbb --- /dev/null +++ b/doc/sequenceDiagramROSUDPMessages.txt @@ -0,0 +1,20 @@ +@startuml +... +"Lidar" -> "SIM1000FXA": scan data +"SIM1000FXA" -> "sick_lidar_localization2": UDP output message \ntype 5 version 2 \n(sourceID:160, \nx, y, heading, \nstatus, timestamp) +"sick_lidar_localization2" -> "ROS": ROS message \nLocalizationControllerResultMessage0502 \n(sourceID:160, \nx, y, heading, status, timestamp) +"sick_lidar_localization2" -> "ROS": ROS TF message \n(geometry_msgs/Transform, \nparent "base_link", child "lls", \nVector3D translation, Quaternion rotation) +"ROS" -> "Application": ROS TF message \n(geometry_msgs/Transform \nused e.g. for robot navigation) +... +"Left wheel encoder ID:150" -> "Application": Encoder datagram +"Application" -> "Application": Encoder datagram conversion\nto ROS message \nEncoderMeasurementMessage0202 \n(sourceID:150, timestamp, encoderTics) +"Application" -> "sick_lidar_localization2": ROS message \nEncoderMeasurementMessage0202 \n(sourceID:150, timestamp, encoderTics) +"sick_lidar_localization2" -> "SIM1000FXA": UDP input message \ntype 2 version 2 \n(sourceID:150, \ntimestamp, encoderTics) +... +... +"Right wheel encoder ID:151" -> "Application": Encoder datagram +"Application" -> "Application": Encoder datagram conversion\nto ROS message \nEncoderMeasurementMessage0202 \n(sourceID:151, timestamp, encoderTics) +"Application" -> "sick_lidar_localization2": ROS message \nEncoderMeasurementMessage0202 \n(sourceID:151, timestamp, encoderTics) +"sick_lidar_localization2" -> "SIM1000FXA": UDP input message \ntype 2 version 2 \n(sourceID:151, \ntimestamp, encoderTics) +... +@enduml diff --git a/doc/sequenceDiagramResultTelegrams.txt b/doc/sequenceDiagramResultTelegrams.txt new file mode 100644 index 0000000..43995ce --- /dev/null +++ b/doc/sequenceDiagramResultTelegrams.txt @@ -0,0 +1,13 @@ +@startuml +... +"SIM1000FXA" -> "ROS sim_loc_driver": Time t: TCP result port telegram +"ROS sim_loc_driver" -> "ROS pointcloud_converter": ROS message SickLocResultPortTelegramMsg, topic "/sick_lidar_localization/driver/result_telegrams" +"ROS pointcloud_converter" -> "ROS rviz": PointCloud2 message +"ROS pointcloud_converter" -> "ROS rviz": TF message +... +"SIM1000FXA" -> "ROS sim_loc_driver": Time t + 0.05: TCP result port telegram +"ROS sim_loc_driver" -> "ROS pointcloud_converter": ROS message SickLocResultPortTelegramMsg, topic "/sick_lidar_localization/driver/result_telegrams" +"ROS pointcloud_converter" -> "ROS rviz": PointCloud2 message +"ROS pointcloud_converter" -> "ROS rviz": TF message +... +@enduml diff --git a/doc/sequenceDiagramSourceIdExample1.png b/doc/sequenceDiagramSourceIdExample1.png new file mode 100644 index 0000000000000000000000000000000000000000..8ce69a7e18d255281b4a38416b7d305a682096d1 GIT binary patch literal 41405 zcmd431yq!6+b)cPVgZT@(jXuL(hU*d-SBpw^@YL!oNpvK|BKizh{6wFA ztg&x$UjDgqt{4ptY5D$nO1_A4(C3TdOp>Z{n!;>!7s5<1uU+rAWG7$Oe-szVHwYDhzM?!0T+3ng>U2 zJmrbr*T$oZbbJ=4gf|Dd;UeTt^GcP5^I?l&`~6J(x(@Vur1cd^RoK|i-}6^|zBsBD z8QcG^=5)^Us00$5o>P#y{5_5W5`)>f(#giIuS)wFX+gfd0NE zKV{~ITioc554Jt(YwLB{{X<46N0xh7J}Ocuc4#=LT4}$3QaCC3Ip6X+hWS$ES~+IR z%+~W4o|*YwiC7VNkB1X}_^(J9y6cnPqI*;HW~c{`A?cDm%?+&$9=_`IW&?#Zti&E3 zDzoY0Th{6JMx-RnV!{qgEQC*48{D4Z*X}I|i+_5jxBDit816!%LN7$b%6zW7@WO6V zxFEfM`sK@1Gk?&~ywM~?A1OHxF4UZp*Bo$}&dZ2hH@i8!WS$*M{qVNb`xiUKT5E4U zV7N8uOS|?weiJjD`8D17rXlIm;$Dt0>U@>QG0L=}_Y4pzEb;f%+e?C3RG7b9dwz#N zznw^ov;;$rouWgOLi!m&JF}=TNfU+}fiUwjk?h7~<<77a7cMSVozBR6?Cehd>EX45 zrCF~r0gvUk3}9EGd9zPn5<&d|4YLQnKf>qbwlme&-yb|Q=3(s6{E2sxBC7p*{hrT2 zuwBTzaf_FW;i9nv@KynjCxNI>b;J4`lM1k1E>W|IT6^hoPH0l*I4A1zQFTojm>zuC zgA6fk78lPhG6^D;BujcJuBA=-Us}pOIQ`^r)F%xOmc0(-`uo=%&8nF)2j;H7mR}XY z*zECQPP8e!p;RqXMDl0mGyFp)v7F8p-1r_1O?GznnDazP*_fxBp`qXP!N%+7_I(*- zIyqhjmR&C0BhZRdFO8aj)J@Ie>$tCE#%jAFdsV43mWC@tE-mW4K~rpt$(km7)HsAO zv>(hU&7je`vhH^$ zYS+=psq9shyHY|@lKa{>uFGj!*KX*V4s@>{&A?D`}o9;ePZdaobcxm~5Y>-@ei zxHg1Aq`@0MD7aJNN%g#RP;f{agDMM8(d}#54riynsY~LgSJ$uP*Z~{1M!5h8OEUDc~8~>gb!G zd%ESd#?>dA;trp%F*b6|&7&-{s{7bi(ksQ}AUUtIXWGn9&^v+!DlJw$L%F2n)EKZ_|S~f+*~ipn@W{&gLQjD0k2;Z)*Ya;3QkWS zG+6Dau-mW)2JZKg?f>kt;S)I6Rg74E=rbe(hx{UAq1ein-RtJ6UGd|_S9`X#M*D4O zbJF7OQZgewz2f+zCeD`f5A@!b2g>d>6zz2<8&CPi@eK03?<-z*;yO*XAf7Snr4=C*)ez+>F8+get~AJJXy0hP8GesaNN zGl0f(i_!P`%@0;GZ?v{BO-!eDS6sc61a5G0?(1NaVNRHSZELHrn>LiF-uhKkogr{< zAE^^2QJeeI$!l|=D}8{m52xAVp164j#aQ8xqo3f;Kum*};pkhO4|jjAOt>8E)j7?t zvKmWZMd&E3mRQvwZ%5NczDe>~-D0JgZa(;dGnh|OWVRl*pF?x~Pw`Efmn}LRZ)+uR zLZFhy2CRW?yMLNf!&jt<{jL8@@9%b|_W3BQZ2V417%UsxH?>?6RGbS!ASm~Sr#;)2 z54^9*dU(K6)=5?;aK%Dukp+2kwtm6UlX+%THs?%8?x(+VeCh*{F;mQ|mBf`1NlSIz zn(CywDT|PInaz~t$yRV>D@r5?emeJ%t^Zql6PoNkTztWC7^Cpvx0DnWfw7%vCMC9r zmGeXU>@Zhhgr#&SwT+VCN`TJ6dUofm-Z*!ohq`|o_tF00s}5@;NRz{G;q#n>9F$K~ zdyq*N@Y+y$;_5_iD)J;6gnKP-Cgf8l%@8wF>kM`2d+Nj$rGwKq$__TwVpmuC4 z`5;_vv>fWr=)S*|O|{a_#kXTQL^Hy2Jvv>lGF57$T32|KcpWvjKd&jn*GWzCaH zP4<1X+v6{=9_~qtyY)k7f9l=o<}R@cm%m|0DWLH&W)ng(y||-qYAD4HTQzdsSb*l1 zNHq2EeioZPIiu)ouyLMz8oBWy-;vtXonfoT>B`oJQejswvOL!_=zaWX>y_@q-E!ip0N!5r zX{g-6h7}E*LwGAAwjH$(7eN@fizo9ybvUoFk;3C!zbofJsEUDjj(9 z1mh3upOw}92@+JAw!6Qs=(U~QNmqB5?E2J4iQ&fwW``35>9h&qm7c;b33yYc-%0YS z+JEKNrbXzh*tMq%jpo!h4JBGS=e(q(4q*EOKI;hA56`l7t9A|874Sr5N#hG9cez5d zWrwi*w3KvBdj{c>?77S5JlD7mJR-8ItG8*qRv!;c-Aw(11ZlM@o+AFfOjeqKQO2Yk zmf5`5{&Z(v>h5S~&s;}xY+fEEV&2chW)q!&faN)joB-XE+zBenH=dhLow-+26%;&_ z`n%wRSo*nJ9gnDGXS$wviEViN^xH7_wOF&C78f45HX$PuHqZQhudGn2I7Ph_eUopktqGQ%*D{(9qr+U_gy z;*-9{o%^N{SsNv(7O0~@okOgGcaPvbui)WBQyFJa5y49L({T6=_Dps?xC zi<=x2-b$;YvQgyxjU?T*FAMMH2QuleAcL*mnC2VX+Fp{jFr4b_L#X7K?az(ZN%Dyw ztv0M^f3v?hJwSCo6L&t^Yp=ezoI7J}>e@i@bX5?Ie`9i!*6u#eOx1hw&B-r0+FjIE z-P>1vm_TyVfFV!iqI;;rEg()_naOlh<;miNkb9Ti1(dTQ?H} z(*i-85{=8bH(7f)L8N;1Dj8wJ<9O2{cMJOwa=~Zdux0{YhWt*;BKJKMA&@F1r z&1-lP_S@IMCTrA6RG0pW&PB1)0T)2Ry_BRP3?o0TOs+T&+gef;zKiYjvrVcy*r}tK zmGjz8y0x=ltdW!nGh>Xm%z#gq>xATRh%wc`O|;S(_Ee+4Qp{-Nd;GjwKz8uwrfG1$eZ8I78D*^Gta{y8@$<;N8zifdUE=q2kUi!+#fG?Wzk+inx4+)MpS2;Bpne(G z;Ua;TjNUbxy!F+M>rOhIBy!py%rZ(Ua=;wVC3Qn?#9sFz*o+LV5h$qLM;1OI+as91 z`g5lT-YV2mpF5-*5Ehj#t9jXUuO+k%`6YE5?j_j`A4EYRzTxgR*DA&vPlX=~sB(7> zZ9bPN5Eb^^mz$B}ZXye8acc-g?IA0fufFUsN3-_MWIl$}ktxNO?m69cDJ2_n*h1Pe z)jUD%I@gg`$)Wp@MSkxavHmJ2mJan;ESbwDV!irsXThr%Ok%wA zavJv|78qtXe7}nfDV~$F^J@k&z>_p?Ih(06k-2W9n?$hio?Thd4F3~tGNDaCGwDua z1CN)ST;A}o*RS7FSst~!LZc;(YU1(%t+wz%VQOrsw4p-#Pc3rBX3O`o9Ak_*qJ%Dd zp&Is#oP92%wSrE9;dU|t(^R!|wKB4qNl9d}B__>QXaETyUOi-1Y;%k&tMT0bsV(SW zqJwo~A#V!P9MhTiZVq<$P{ZaTnRX`r=MN-dKC-Idd!Fo>1Q+^Q;TI&_}sMTGu#uIM?xcu(d#q- z5Mtm8!U`b&4zNACmOFYr~)dNKRwrUP*W%-~)|Y#oQ?4!9=~QORw9|J#}> z#N<~v>t90*^-J~MFvlJasFFDtRYMrjkG?o}0Ip40ybPHcEP(8_$?;R~loZd(2;V(Z zbirBA6kWEgFmv-JhOL1>iqG(+n}6@%_#?f|-1K0HFHfpZTX9HL02#j@lU?^ab;#9o zqAc?+XQ{DZU&(~IL%+!V0E(A8=p_WlC>^%gV_G-5@0JAkZ6*JYtQIE}$Jpy4Il@C#`FD>Et8*}n0 zt@Zly_if0@FLHJDfV%qTmUlApiF2w{L@njxYv&`*UElSd@y^=0Da}yqXMlzwNY49? zHY=w8JQX_mpL1R3WLRJgc;p0V^*C>^Uj#y^OVL`;E_sSRv1f0Dpa0+a1}5qYsQO>m z6h$+kF{3yuG_*K%)UTi5pF4`QiBLaU$X-ZM`j9d}%fdrlLsPtp`t|68Xwnu5UtBFt z2Zy@!_uApt{{DOu?0MMRYu-OFMgRT1y&)G+U;YHo;>qt5V?}#OcAez=t)sjBy>>X{ zlYu1u`tJwn7W z^iFy~{lb4|Sjzm|nJZV1e$*4iPjFm~(|HMCsCvY1vz%Eu&zo%arcqBC^JH^w$R`f& zQ1p@}4hoTfvPV0aNEXYlKl9Kvqtri#^6Ehc$7D0PpWMrgWVf(o3ZdGh_v_y+I)m@X3@0n7u zt7~f$yt?_%O-*x)isVf%VVvjZ=huk2earDeX=xu#R8-WTJx>$y*pH=V!%|o5?d_dw zv{O5|xVgDGIb#wN%}B7a&`)+)m5y}5NP@ZqI|qk_rDdT1O`2@h^sXFdJ_*elSB^W^ za@#8_E0>lmC9dJ%qzZVb$C_JN#f}gW651z6R1_7F2aJwtxAb8lk;sCAf=1*wHD7jK z0RhGUAD?r@i2;aVwRg3(+DXMq)R*Va%{eaSMz0bP5!rriY;3f!u&_z5Kb^D9Ac%vr z#IB|$OWhb#6JudU=d@z{sw&@SA@ZWiO1gmP=-cy4bQCJAe0&*iD71;I*7 zRa8|meIKPmIPi+*gV(g1ZhV5DKUuGjTrh!Drs9mgd1X}=E-tQ;4n3!;t0gqm=ZPN=j0Z1d?zkf#{?gf+>cd9$3rlxv9r93>q^mKSIBYvzn8yOon zrm5o(8W|YOIGk@fA7KgRUsPW|y{m+9^E3SXZ|zHm!BB=sasIbRu_#elb+!BIqy)>` z3l}c*L3LE)=QuA!5McWwM{wXF*rBBSgJWY>S`V)Wh-Mhvzm*UlZ?o~HiSYI7*A3Ec zHKRfJOmpq6t&(L!i}FIb5v0E+C&iUrXM#r ztYL15zCPsn0L;(hUo*b0?1p(xZnQxu4#P!gmN$sh3ZLeYveMG#mX@4cT&l{-{QVv7 z^9LS}ZoOTU5=1T=3Ajv+@GYZadl<+7aq8ryjz+q=Car|WsNi#$&4kP|F~{8IH`-~S?wj8pA7zq%30KEK3H5{iXYuX- z>6|;v5CIJ0s)~ttMr{?Zg~+{IQS*MZz|5$K zS0Q}4UDbQ$#g#a9y{n35JO9tbJNlL|>G4mkjB9Ia5o&5`+>Q%stmqsMA3lIqY8J}h zw_hBDadSkP$8KFYOuJI%_4O>Em@uX8g2O*nRM1`&HxF+O7E2#rq_RQI_3AR`u+GoT zRaR9+_wagbe`FjO9c8TIVrQS>rB-xLq;hq0qt@Yq_w|*Pmg4ns>0@=z{P|N(b@AfG z2FrWucKSZs+pacE3ei;gm^nkRJe5`}bMvnh`1tr`Fj!-Vn5I=EaeRZ1g}M2yD%ya; zLPm}UeArP7IqjP>GdcSY-{CN{IL1TKjsX!dF*x}Ve=5rLJnM8cpK3~^c4o6qK^wbS>8ggNQccMDh24jIYY4FC*u3FMe4fY z(a{|I{EOBvuoqeX?l10)EX4F0b<8c1to*n*wiPuxHW2U`E^29M^;XU2y>3~rR}*>q z^r@6o8;G34!%1CV2(DtB_W>EGJlAoUo?0<+_v@X!-28m=7ccHJG0B;{%NQ&yEKEvD zDnH*+)^;2zs7rq^Ck(z|=Vf7`2v}LMsj>YC@+({_=cJ!wtE!m;NMdV{=mjA4l}=4O)ULegF_8VZ{``PD`U$vD1cbjyDD&+LA2G zhSI#1sQKGlTHfXc>ogN>O18l739>fj;^E;@6*L<(`y?bJM7-8yjE#D_=|xQ zg*vFHNUL`>{K1}@j!vIWGx`}|-F+F_$H&4_Tv0JFJglj#{8;=rF@n$xzHsNx9YD_8 zRgL_#cDAv38-9Y%h0Kql{uz9J6nKj-9Koq{T3yoshEvSkfLH9`P1VE2A~Q!-4DwxT zYpdl*Wu}gnnp#e7Zp3bTdwW6x;k*>slUP_-o^^thl$3&k2cP|}zBzyT2utw>K0@Tw zig`VWiHULoTN!bx$mP{lTMLWDg@ybKE>2FdCr`+{c5RU18jk`U9368p%L<`TE(>4A zlhgq=#He^ocVy=Hl^`h6`5_&{J!G`1b^tw;)V2z?cSi%zQFFPS(<1n~wdW602CjxR z4popF<5G9G0yi-py1Kf$sb)<03sW{WHs#89?}W78z--4GE=OOw=nKG6OWd!}P;6)) zeT1Z+SIR8rMdRr^Lp3W$Hs_GBktg%%bHY)wXH z%O)!vG-(AX&&-ztJkZ(MiSIx7{W~)|`}$lSbkHFS;IsDP{(@qv^ZDsn*XC5}iNY*(SQC z9s;S(RRxPuMT2XNw-Im5+!urevMBE=kcNWJ=@*T zrHrv<)c|nl78cB-8JU=%5Xg-+(;6l7c6QQoczURMXk!J%>BNU$%t9n^CMap?Iy-aU zx?+M}3G=wY-XQ?iREj`99a^{VYH4Y?n%rfQmj~b<9UEQ{MET~kXU}?idOG64V)XX* zc57&5BgK>d%iwFYp{!Y86OCU;zUt)Q5WojNND=h%)YJQ{uC~wbw3H+%Wie-(BgWJu z(*h@ilF?^)&ML^thKd-SjY)-U*Dt*}7#-A>e=99=y2EtGBx2saO=BuYAP~6@IbbXE z6+&)*{#kTKG+L!>9e}Z?2ag_Ga;_pYR-Ow)H%s035VUPOx9pH8tVXnZH(7SKHgAW80=ScM=m4*0pKl z)n}EdaNm+jRt*ZtfvtJ#miV^_XmGw(mYOw7)p0x`BKi7sdUA4obJJ|c%=}W^-#kS= z;Q7S8)TZmgNgx4{$GmO==}L3&9sq@4&hv6}?_58wd{K2-CK)<9x{Hg8Wf>nawnnV< z393IX{QntPQ1xp7gU}glMS|B78dtt)tlI5>cl$OLHg=OC_O)x``}N;HyFx$ixfg+| zfkrN6-T7gBd_0(MP<}Bzr88u&+nhp+URa89VCuY2JEpS>Tel@r9ndmC@nRI7P`La1Swsy6%Hpc_E@=%NTz-AS=Ok|RBMlEr$j0qIj4b>L zthfO)(2S{GsaVFT>FK=nZ;4!2uU>WFqT**`o6!6MhezFtY!@Pbm$FU|sy(UDwy7(A z!hMBWY_6>h*!@WPg{;1LL(c6RKbOG*j~ zdJqr!*e7i(i1Tw7 zG?bMy2PJFIj0IC4ATb;4d&L?(HpFndBRWjzrPIKZyfEBf%^11KS#{!#F1DX{jw zzXTE0y5hhLL$n*XmRC(ws$wQOYdXdUe2K_lw8^`ae-KC`;4l|e+4e~C%huCbsoR4!o4aXxVD@zQ@pp-`d_qgDRlVpWNRK_wi7vu2a@L=ndMb37X)4gsQf%PdC}Ojw3NwxeUf z+bwP;jlAOYG~zUrd9wUVIj#Pk2c*(II0%3r|3bIM`RcyR+S>7PJ^$A!F24vQ1VKUs zD}4gvR7(oSqL;96aPqXDLCMGdUMy&b5(Fk&rS0GMhh2l zL)?4@ppS3gzRjg*#xm*P**%Cil_)MP3OsvM`$dk*ak;Fek4&YIckg~|Bj@Q9M`nar zzx*t!-SOFewAYpXWM^lmKkKJ{ z_8J)%mx{`n6o5(Z(4CEE-UilT&vbO;s`v2DAU|@f->x+`Z{D1n)xr7wNaqX->pQ~6 z%p4vYJMCEY<>&A5@w;cf^_ML@0eWZR@pTfJbBa>`K!!hr#5s9+)wQ+vKgmAqiB#{U z#9eTFrlG;-xDdCm%1`uQDJEymvywE7hK;SHveLDg1~xY|Z^>com5Y{ya^Gj`a8E7z|YsqH4Vz4s&4q9%DbJ!IS<(IkBY^b{V81k}# za^*XKXWd`Ed>NE~5o6mj%U6VTe( z?jdRC%0x2_4UO_SiVP2;w6b8{e`jc&?eLBwE)GNrrp{%BM-|)PTH}@*lP{etF^H?+V=AATU zo^!#$E&(am#y>nK>Zv`Fc@h9{deuTTvPv^^@h2~zYR)eO6cA1PUY%;g%{wzo?YC~< zo~2J1r;2JOBq8Yy6@8FyTcgJzn<@ariAK%Bf&vL%!VtPmm!tCeiukY3pI=fnB$@a| z1VcCm<&!~>!^e!N2w^V<^jc`6`lxePU!kyB?A-i3fbWxPpa2^h9Bd%dV4@%j`^p`R z*ftb`U+DroqfN0yDfIV_o)W8*P;Mfw^AQgQWLiOzFyT8S#nLN`6r=*KE1{0}OY7IXSWk=V-;2uG7xq(tPs7Sk}wN2n{LUmdQ2gnU_aw6b6lEHdI{5)}XSX5k7IX;OqkssLIX>O!?=kULWu1>!_uC!n?TwC% zOy5Vk*37+(cQDN5q@HtB4`^xxC3vY}b#2@nPGgcxfxSZfpg5K7Jc1#*0+h)L3Lo&Z z5I+M=hMCo!nCR$CO-u*~2@?_%rCQ)1`{l5Vt!Q8A5V4RMqK&@qdP17cJv`r%sIEWX zbS`S&Iuq|CD#Z6B49@pK^X!@L5R;OIvPFR^V6M%h1>Q#A%M{Y!$j-@0Xz`4lP`OT- zjEt@C@a$hPvNl>!?g`&UFh(icnCk<`m+`q8i`aL zDg5()hn8@mlZKVK{jF;96{z1uoToTZ zahi$HBHnewC+h7Lm`ThC<=Zy~uZ1Z*jE4}W;j98Y%H7aJyj#RqlrD6;$?u zhsV|--S>z(;0qI4%|i57+MrGKSL~eoJ9Lc}U?+9jHQo14W8%*mxMo-~epd#EMw!%Q z@&?NxHE_h?wV2aBc;LQ=?8E7NktFD~PaZ$W&Yu)j4#J%%EeZ}DPX$ejn3xzH9o?Nw zk5KIz>q~F{C^>By{@rb-N{Uavq+JW?!fTAvqKLePno`&MH~Mi+4OAlX-ID{MYwB|% znE`zd1+tgXK{ds&C{jTEQF+QE%-=CxlWUVYMQT&IVc5fZ1l0Z-?DJh8p&;s6J)JPZ}l}B;hd?tvcQch*^lJnAmF$F9(O- z={1%!AJ)~08w7Q7G~@mI^7wiMN!&KV)GzCG&CKRIrhDH~l8}&SLscIv|M>BvzhBML zvhdFM+qXBAbpa;J&zH6Z*su25L%>AyFvil~x}sI(_>IEuNZ4CN_Ysnl3u_H-)cec( zY@>x>ovzSJUn5ghRn=7Y)fNyyAYK!Njdbe{!yuYYPfrJlSiE>~hma6u0$-d1oB_Vw z1INIddH70pfezz!5|2-+oru(=sN% ze*K^ZR`c#|{MlImB7rbq{(N(~=VG)0e4o>i5KZp_34FgGFVAgzHXAHMS!vyOuV3-T z0LM5zH_en)meA4Bv9T#`y>`(TAi;>D!dea^*M}(s1J8-NY%1_aE#ZhZ(MLa%pvMl_VViL36YUKV`I=oXz>|_&D&sy zWMu#l5f~?|%LTowE!{Z(g%v)LxBrC|?yodBe`27x{tqerkfJ%3S&p^$<76XkV};V4 zB>J8yDY0{N--+d6W+val6uIh=KIY;1KcH&@TF;g@|D?HD74j0|o3?%wgeu1=#Pi?}6fGy<9-Sg3h zZUG(x|JMMn03NP4FGAe?b>sGSW#wFw`Eojb37!sHn+0dJ( z>RbP=H9s$JerZVsF}FV3Q)%GlR<$tt{rkK5sCGZU3li%a8^0`=Qt4L`~+lVV}sh^bO=R5$<*jbA`%ki*S+=dIY2uV)z*6I>x+ce z9EL6i8?|6JYHVFSOa=avXTZEm#+IQPVf{kfNv)3zpXdFbt+i=Ix|Y9Ek1mc(!51mL ziSfX#Jx`BkvJ-1tN?E(Tzi6*t%IST7ERYc!pae3_K8U0MAYSzSx)gWso|cHYzq&g(f3r9^H+0XIYhx7$X(gVPG{vI7J~ zZuh698K=02bpt8KKo1kw447m<_8#xepLfc11A9GJ6*1qu3XQ7+BzJn3bge(%Myr|v zudY^0QP9co4xJLO958T+Dy@GC+u4;=()3NW#WoU4WvMIVGvwdhiZ}&*8{dxvxkw1# zVvq&h{rlyfdzGz9T)g4!*4+8ap6@*6z1C;C_V+#KBfNnThgu}q$`tlb&eDeZX{?xg1V*hTF$LDKmS3oP7|ff(J;X=Qy3dFbvoHGqWCxH zX=t9hf~&Gv7M#|NIaAPu$ldLPA4AitR+uYoYqQj3%ULFY*AoW=-9O%jvbliGE?+KqV0|h@FJ^jQLnuOJ>_>91s z1Zmdf;NnW3|vw`M6qd{d}ldap4MHg1`eCKoK~N9Ri%ifY4p3ft@bmF#x-_!c6(4v zuK)fG@Jwvm?JItTT2)!Bu`w|Xa^jvK=k8;V{6SNb(5$ql6%_O`+Zj3l#aLLg-R_^2 zmKF(RA%1Sv+(6O0bI)_Jvk*&}#l^+tNx)47cR#_dlBdp_tn?Mm2FE4Mk zHnek^2v|O|?Ck6cq$q=*L~#e(AW>2aPyyqG$jL(=wv=WF0l;<*(!Wijs@RX^aAYYP zrl6uTyrso|jfahG4G41x|0P1A?zg(P`YPS@=9{>yK^fdYcV?E@9zTA(9hk*^d8!yl zqcF-FZ8@4ywGcqJ^ChaY!~!4{5h|A6>Y;t)0y}?b_PWesJot`E-!z0%DH{a2Mjt~< zN*S=+x%$O1T-xifyzhgV$LxB{v7XqBkoww0$%>s0^CY+q6SmjY71A`1u#oTph_K}r zPlnd?mtrDQ7!~Exb=+vyKt}4Jp&>&jh&)-SmIyB{pdN}HCeS3KB=b=+$O)4+vEsab zTgJv8Wlf-JP@g?7kScdOyiNtv=%aTfUELV8hpq?@g9NoW*i1YYC46kZ3( zZpPU8lsI+6x60}`L5#W&?@llel1QyuNC@+znR|F>U48C9B2R=v@su`w2E;d{wV`37 z3r7CiALgbZfJ2cFZ1KlKW%xtelb?Z6{x2pVEixs8<;=>?zPb1YnVZ%XLy!lHfzOlZ1qXh-u)3i1k|af|FigW(q*?*u2~!==JrDvV1e7l04AmE4c@)UJd;4 zXk=u>^!6`MzybQGm!XDHr}n|UZkIQcZ}P|XX-wEdo){2|neExWK*fKVf*{367MO8I z(%VDQ{(esbeD9B+MBpsF3Z=uU?X`emOfUOhG_g}2WxVS-|e?g$M3u&rp2cp(Du zTw~+`CB(sX?TQc(r&of+G_q1W$PF`uEfNejL8OmQlNTQ&;EMNW;!dPudDAUYHpF1G z0*5GaS&c@u1Na?H8xg#+_4sjTEMP#oX0vm6ZR?B+I_9WW>j@*%% zMD%l^n2pZ;-<|yP+doPO$lO7j&zmaiHuuJ0OyJK(6%1(I-d?|9g?bLX8$6qoh^u87 zf^4L~)D4_;=+p#6Llna(8{SqR7cI(ZjVctvQ8qj=z^vqJn%C|86x=QT9dt0?Quim> zvJlQXaSq75K7f4lX1Du@8tsxtnCIRkLCe;D)7Z`3cIPAWVE8q1{_jqLMcN6}z&L*5 zsLQ}QuufIq{9+SpbQyTNkIyjLY&{@8_}5zK$2{!b0=ns6-M{~)WI49Z96FEx?|gI*QuO z1o{>rHT+wty9Ng0V`GiAn#kjUPCy!#osl65)h6+U)MN|t zmdpbtCX`R`d# z#>NKVO3j-Ji-*DjKXBvaNV_Pb%qv|0T>H1{GIReMUSotsU*u@l06W69A3pKwv2D@8 zkY1nw6x#zvy(3E{-&pV0`1pG&0KH&_(!KCG#}FA{u#Q&K&}aj2diGezg;rK;Wvze$ zz~-aIkg9Pqk>20cLEEJL1K1>_PO%v;O=eJehnV$~JX6hr#9)Yntj4!8&iP`s2gKM? zLH~590O;QbsjB?P00l01f%XglJ@+@8LWn@&C`LcKD^ffXKNuYyU9d!W5-$)bqu;^?UI!2D3X?*>ACMA63g{_BT9;E-Z0_o^Qo8w23_sg3RG zCXkg>%w~T7_5-2{ptnaXogP2-t2D^tH&juHSr?53h>d-e)%=MfQBWhG&Xn$4@ms$z z3xPmhzC0h>M!hwdMZ|_8$xjImax!!fE)9l1?s0IQZgVtj&)?ZQBgTDweU0vvf7?tz z{{@*g)JacI57Z05;gFkqj7TX^fw3%xAQ~NvLP*HWf-U|RhQMARuoHi5E7?nplG@tN;c(ybNQk#@WCVw z0UW&8sezI4m?r-3nh7b?*Y$1o4)*u=A2{)d2gx2qNK{=w{wHXGxIlQ%4Zu-U75;V1 zpVU=6c6Mi5Tgz$Y2o4F@#Kj=Rl`+I4vyLL zfQJQ6ACUCBUMLw#3J>V4RDlu@Tc%ALcr3!&%+1ZC?ooC1_GUVAsoa;@JZvkFP!Bc% zL?{&is?pzIjINHNiWpL^t*!>vMp$w2jaa5=Q0+9)u$Xr6R`gUX<3_8>r#ZTbYHZhu`ZtvuDFe z>vf(zGpR}J&4bqF;&++y-M^^Rs-&cpBUP#~6m$-p*|;|O`|NCNH&u-t9XH;RQ5BDX z-PzK&LrDK|iTjYK1lTMi*tSeV(0S7rn6X@Ff%|LO^M|f!AeXXyg3QYF^FJkU8q=8DRvaQ*$Uu&jIiv(u~?Ty0~mjwnUy78McK4 zF2xey{PjZ|gx$i!yC)#@(a!5(%f80MWyMsEc?_MOWD?Nh23$70f1H5 z=Dz`n{p!n4%&kIwR+xt1A8yV6Sm$0lZaAPI_~e7N570m8>4_#KCB-9~J)sSiesy<8 z+!1YIVqkFaJYPV?s8t!2npy|jTl4}!xOsxdbN3I(4|L@5dW@O5sBR=lKT|;>7qVl;G&0}dIZgx_p;Ac(issbQS`JWKM;3Q&G)RkKuFGpox#ax*hqAIbRO zeK>E!4m(c(3@E~=>)mbCV}W&()6<)|y7G1jn3}yXHVx@jmol~Ysp5j!#Zp zojXLcz|qY8wce^mAurtP=s3dbP@G#itWdf)MPWpizUu{wh$~(9(@y7?S@qWgz=9Vd zZ9#=w;V>W5s;QwtPfPpgu-_1cf~|FZ>vD2t{%xI=pzc8S%qARFXQ>i~hynW~6^np? zrIsQeFh*;89eULPQD`qRTsqetnx!)51thGf^hLnW=J}xfFT=z6ma`69t5Y#Cc*o5z zpxqLa^ACtBfQC?V1^Uywcb}$g1B`oLqr`=eAC+uDvS)z z>}^YL#YI^~(!y)mELm}MthM8r`S|Ghfq`<|7Z8#TYrkY#G&MDq;)TKb)ed})ndrW7 zn&ZM_>IHdtT>5Jh`uY-&4l2q*{;B@*{^!r1`*ghaeg`)JHuqFJB>wn=jDP@=lcO7T z3SCY#iht`2J;}q|8THWRZWxSfv+@JN>-s2VB++}ydyXuhfe94lAv%R?d>CHj*ZX_2 zHY@k{OiY)1r(Xfx5zy9WLJY}EFKDW$^`{hj>r|P7>)8IiB?G79xxV|@F-FRZtrqEv zvpIL_#5uBk_iaZ(L3a7@fwcvg-L{`={e!*7oli|jpnLEjiWLwL{H|Q_M~qMN1T8J? zGj(-a0R{c$jMp6<9RN0zivU;`ZW=}=D8R!5Va@bpd8?2QR*NY~zEi2Ky&Waq3E)+| z21hv~rN@jNh8Vf2AxA9q6W}b6c29vX`2amkMNvaXr>?k|0MmvSFaaIQa>=i=vtN2)8%z%;!TcoVm53Vdl`H zY%jb?uNY*3CLmjbS}~{n6ot1YHTDX!vs2Z6n@4I_JF`$L4gnw$eFOs>vAYZPn@oWe zj6!JCnVm;niei}mwM%jNukj{Izif2xhnv+%?N&TKVxPAuxH;e&s&xf)*zJFG)%dUl ziLZ@tEpnNB`=nt(-45@`y~p3Dz1AtqbUZ@{!fq0rGysDhwN5~O{P3%?nGk#a{JGw~ zj)$W-do*Z5+$xTj({|bH;A?kI`ig2dZ5@h<9kB9Qgd{ABx* zIln44`FWr1>5MZDvrgFDML)Cz0T|JZHf09v7e7-A3AY1uK4_OewwE6 z48aWlbdQb_50ef5peOrf2X;%XUpKk-NxOL7{xw<7)`NHF^m?gT=~l1@&73}t|Hnro z*`g|Llb$e+}sP`CoTfquSSxJG?;`E$VN7o8LDv z{-5j}KkoMbPYv#?K9~P}NBFlQUeVTO29e{zkUhB)z!810sZ}jE9MqZx%;%VD?5AL;fy90edV#Y z&KPTt(>X8UsdY%V4p?(JU=fF%Aj7wCXk=v##nPXyI7XDaB2Ag^D4{YTh{6%T;Ue%~ zT1V}Uo30|DM8GWq*sP%W#Nvx4_U`VQxPSrB8DWc z*l-|20(b1V82V|y4a%zjw=XnU>%Z#@%|DdA|6^b1sj&+5U2(E3+Eye<&E>@*+Tv9b zbGnoVkf0;;0iGE^0ELCv7k$MP%^v9X5lq(vQ+h*CCcvY058pUy>|6&{Q#znM7y(A7 z^-zyCI@Y5tSwYXcypj^UyPFk=Z(Ll)_Nh(hf!^og!C#n50@~eAdttcavVa2tw3LhM zf$4!lfLN|9SV#!EH_c1|j2#>tq_Wvqcs9QTl)q(%@y`?-}1$Q!rNh(nCYy_wtKwi+dZ| z58yGz@U_P)WLsZ#^S``BcsR(_G7@0mDlij3Hs@}>`3uG8e22kWAm27^1rmtsiJO$j z|6u&FMPvW&i;Ka!NJImi6-FP!7TFbdd?)gi3~e=15rr|tA8`>rkBY6g1xDv%dEf9&_` z(lJ{@(}1}-XSow6PB4f$o(Q@}2l&6%y4XP{tTTKWe__Msspzm{4 z&0u?`{=UrC3qHw}$q>bi(ymxoBm@>2^4~m_RkqzR)V8xqWV<7yGTMYPp{@~?pEwZ; zmI3xxc=*2%l?09=r#!cM2B@vdxSq10G!?6Z?wlZ29ETo2*LSFcpz+xREK;`0x4sSh z^xn1o9zdurS2e^&{V-T1w28NdhNdRyt)TrGdrDQ!5~4Ul7rOVWZ8PZG{He5+`f~=6 zDKt7E)E}AxviNY4Olcl}k_tmx8*7I&p@2 zM-uk2b#1XI*kMEr-vjs7!Z$B~8f!AF)$qNXR4~7^{GY=2?kZyVo;|Y~zVW8YtA;4^ zD{W%TZ)Iy13JnTMP0m-iw0(U{>2lueHJ+^F@?aKqRlNL{Y+dQ&4#ycE>pzjV9^mI< zpK^KN8d)4Lxy!(^;=&mNegbLFD#?zN`}9+C-oKw6 z?Z}&NfbI&ERTU}<3LyJUFU-u(Z~y)sQZF?%H2|}DufD%~{G-dNs|$O!VL98r-495E zbVBt3qJVB8qVES;pOO;fbly=-jg5e4GPzG(CW!N&dzzJ#lW^lIBqKtW_j$K`$PG4y zfn$pTk4l?BzUX)8)qI@-U+HVDnjLM;ZruT=J)E6eW>vNSXk7D(N!vxLaAEuD{5Qcyq*f+>Q-(Z)((J8K*T+IIe(S|2kj3yaA)HzVhT`T575oFl@VkI4#;tn1$8G~l93S- zvexBp)HaoW24#7`W3~vAo458{*${EF-NS+}MfZr1kV>(64K3;lYcj%xm_HFyi;Ibg z0aMAqz?+tqJUl#ppSoFn2+y<{&D@8yoCJYsSpq^uKrQ40UcXk?(C~833PVWXB)o*U z%T-rG=(lgKyPTnUl3Ao&!!B@4fec>gEqyS@Ipg6TFkpBsAT(deonm5Y`eDplSywNs zyytQdz*9r=V`F1Q?hDz; zCqdo4(%GE<_LI{2%^mjRqntkm^G@YG2+88`s?dbW$&b-|a^a}aK@FXbIslS&mbkrg zb48adG9dPGguC5_7iv7YZz(p+B_2B2^nli?`$315mYO=Q8u}#s{BLuURPyLf7U++` zPQTLp`0;MN*eIwC*lU}c2igy&>aQE~h`h!40TG4U0Q#`N@hREYkjrj)YqE~tDZ(xD2R3-$kp4J+2WAp9 z;DAC3Z2JU2ZKc{RRiX=_6Mzp}(PDHoU4aPmtR(~XZg zqQ`FQ-9V$!(11|94&1n3%w#-?GxB0z9_U@YdV+@sv~6Z)X3!poQUHSx5Y*M#f&i=n z;XDZZM-|dHmazFEDv#DR0IwMpbww1v;|@C`ndeMQxa(Q|KNX)A>%X^&z+%nZU)lA4 z!+L&xB+WA3&V|y~5PoK3fZ2$!#T0^Bu>FD5Dtf67kUq~cT$#9f_eU}yWGN~sVW&QQ zk_N7V;yq}25Sqzm*tItf*YE?ZUjUe60M!YlrUr}(4d5LZX=?{H;U#Rl5$dju>`%=Dt(2tFQu8y&hP=4Y0@lLQ2QkC0`KY2IJ8TBdYX;CK* z?ir}RO$UrZa8!bjXQ-;jlbe}o;+`k}AZvW^PZBBvHCMWX4{180KFM5#5x{KB%seG>~}htl0zd_OGM6I&Y1E1*SjWraosRQpLl7vK8e zBtREmTAsxKpEC4mhQ3-5xRoS-1Ea!5>!yC&oLd7Co=osmbxpydO}>CSgMY>H@^V{_ zb-A}}E--Cg1_d2P)j*i8y_q}q)4$-hnK>0>qAeot&)oUo+~EcPToB0QIgQ0<{y7Q< z!SB#MG_>EaHuPJL0RuHkS4#_EjbmN_>$odfLgJD8)(&*c21K{Ky1Ju8x4bT1{r*s1 z2P9UCoSMR+ROIHNju~fsl2VK(e50wg-9;J(?K}+frv%qB4 zLX`ItBNJ^R!T{xzZZ`e{v28kBJHhj==#8p;f;4)RaB&#a|LvP|zRfR82EEt(}HGJ%ZQi zVlUcLqzRrpd6CxAqlX^DE0=~-f~|&=n*kJTR@HV(B-(~4CIjs}oyP*t7E_gTls|~c z9962~LNxssZoJRTv^Oz%h{V*@PI=HP6A-1( zmn| zBhvkr7Hl1a&2CnSwFFKh2riUv4mN1i%6fQOx&4vImVEUC=GCi=w7C{G9n_3u!4mz4AscEr+hVWA|JpPReN#q6Q& zh4K17Q7a`S7xeYRUIP`V`->i^-GN4KB43*L?D#j<^x&cC>FMF&;XsxW?o|#r56=j6 zjyE~r^V749KDKuVLmFNhNR(S=FN2XNT)pZ#ArB|6oIiiQ_2m*U8>3XD*hVu|tblpHLL^0dDfmg4U&W{L7g?!sy8 z+P-bI)!$L^XzH5C;mvAyd9w;CN9qZ;uWI$7&xmOCQI-tS`D!w? z(A*sQ33Q0b{a09vTX1x`!pd){Uy<`5$>f?^ts3}Sq54;@s2Yd@(HO3%vNj65_W4Mj zlbRMh*xFsAUAQveH*azu#5h)MA7^d7O&9$U2#vtEJ|CefZCSeSCqIKH7U6wAwMKZ~ z`)_d~yl+zblja-m$ibdHBMhtYr3i@2kaG%|ro2+!%@%mA5hJNhx!^D>nodX+*C=r_6|6UkzaG(-7bEe{S z*2cRC8AXGMYD^v2mOxzzwQtBnq1QvgV;CyX(2@W2Ym-$`DRLpi*ZPCM3h;vD4`Wq> zuRFV*qVpr_d%W>|Klgn*Cb$3H6as)%12vKW1SpUn)b;^-fJfzz`o!2?C^O4!g!SYr zgk!2#=yrw$)do&mejrlDqO!?8+lCGKICXg((dUdD7?L4by#Q>(w#}^WVbkIEr9U@7xgMQ7p6=eF<#syT&^e{5zpzg`V@HbDkq!25E$)9!N6$HU{S^$HX* z1@2>>CzHZg>QY`OaG*O}a>MU#+sx49SX&BGmgY*V!&g4lNKIV*-6cL5cK?Q2r_@Zl z)?YqpCuR_pQ832sB2=In`gX*5jKs06mXd$7Xaj8Fud7i^CObV{z^rVLJKfGlGZTeA z>-v>%ago)!eU@%=$Ch$ZF#HTOnK=#R8FtB_3h5s zT7_y5f6cCVAh|R4(B?}h)+heiLYEKy94SQ=S2wHw|H1$K1|?w7|KEi87udwELq2tg zmbRW|@P+0}Rp{1K@N(y9Jswkc22Je*+yy;Em1qm}(uP84Kk$pI$Co zpT<%i*w&#?kg&220_6ZqlP@v5s|z+Hs3ig=WP-gQH@7vD6m?*8iKkm|Tn2c8i-wNk zkOE%;HL5T=`XW0(M2T|%f1r!PvAZ|-1j#2{OmsBX9=ai-6c)X}y5pkQ`-oRR|2+Zi zFbr(%;F^A_s85HH8TAH}~@A>jSdoZvL2 zB}1OHsA#1(z#uyTD7Hkq#ea*(5Y5j18INJ0L?uu(Ax<>zhw5*dqfn@%6-Xw*%M^)n z*T!F#&6jfHGbITL1t1kx1ru#QXnXnba<f>YOx}&;W-;I(zIThLN(q7VZAWTlOQ1 zKo%Epoq^kwwXLIBoRrR(86e(h@3b(8M(mKDM4 zzx-bTFTVqISSY=ooKrV*P)HdZG$W+2fxHU*PjN-C(?CZ03lgNVKH7N|34%Hlh(d}< zI4sxT=qTda01}^@fXq=gCRqCf0sZ^>b(wX-I^-f4Xbsw1ZNb18q*2`2d<^&y`+ z@|*y^R1?M~Cl}iFKj%FoC1s$dhVl3B8@~gG0)={o){;h~_^0S-R;Bm?0xyGuxwlC1 zffiU5z^4mRe0BBLK|w9`^^rs={zfpoYeE82e5myPBE`p$gQdHWP&S}Okg5Zex_x81 z09d6|T!JAJa2=bQo3l}-=?iXKv++9gbiYUEkpgkYlFZ0SFUnih>V{e?TRn-uLn2-Cxjuvk?&&6*ZrF zJr0mWM6*(OP5;co1~6=d00Dud-XA_1yFNJmyeiNvWJ2J)3p=UjV|!1B zC4rZ$Pr*5#LwyT6#`{LcGoYlblo~vn=QBgffYzrtm+%z@%m}S#V27aHl}y=v1nBDa zy}8O76M(HySFyv)8`ohl-4j4+dy#h-3?@FFOTgKMnk+^WL9XV(Inhj@kh{>tjf8R? zZ;+KRPldNkcEDMj36%I_NpW$imLIkj@g9nnZlYzyB>}jwGIOg$f91%8r`9(e9ff#! zl=f@7xXgq1ng3~MWnLwQGePRTgBT2!_o=Tu4y#InviNFW|9Qm6B6c^u6mMSjteGuV zp;}{Sqem$f#L0v_2DYsaeoi0@+=~m5sRps#i2>?h=pUDG5-trw8^O7qhu#IS6@XTz z2r=JI|LX4tmRcd)8Pg+e0<0Kbux2s2e!UC_<-GZ+H>0laO;fJEX}v&V!GI|7c>tFx zD~#r?y*UM~6)v8~dEk~4U3xzp1g~7}GFyNxz;_xO8h`;PX9Ue+1C%Zb70Elmz`%f8 zbxzF8lqH&8=R9k2j#cRBfEteMfCK@D!W7yMs=1MLTY#q=+~1(YZyJ-I0eD_LC9(fS zuYrIELPw4qEcDb}RpJ+5uFLdz+uYV+ZF%@cExd- zzu|_+AcH%r&WW7D!ZYA|vFe-%?pdqOiC~E5>f(|ZuoJo}oG{w}t{q0YT!_C>1ZT;9 zy7`5L(uO%=SjA)DaMsDaC}(}-_p?5XPeMX(IKVcFxPsp7kV6oblCp)@fI-AL5kzl@ zbK)%GoOr_F6$V4;P$vQU7)kZ^E%EHGN$O{SJj=S!&({2@5NCehowII*X=wt4sTB9W zDe)J!0NpReoJQ9jsu0oHdffh(=Kf@lOrTZ=0nb8qPf!>xp6R9Gj6dA#BusbCt|WvV zxSr2$t|&(`HR2%5z$}|)nMh!M+*{W{jmYn755o~-Jbd`t*1|y>kOlBdTz-Qn5E}6W zI`Yc`-|Y?8Mje-6TJ9*Wf2UUsAhHN(zJ`uu__lPFLz4 z*TfgDS!!UhFD7Qe;|9L^&@vWgcdBt1ab5Ck!|kPv29^DmDw?RW2S4s92%EFAFUqON zJTG0kq|vvym_JKe0p4H2in7%nfK zD#J;^g&YvTVS2y#t;p>F5T=7oP>`Ac{^--mCxA;76i9#$?K%;f&>}ytte}tw&Jcu% zyt2pkY=4$!6-pF37&CxMUc<<53tklj295w}_#NVi5N`w`kRzMXVLv=gf-T_PpwI5R z4ajyK^x-N|o$qZ~srO>HW6nUNBns@`3uMXA$JfIf?*3RO^b#@Y*V8o8swQgdp=)qh z;oP}%V1EyUX99KlYE{Zd^)C4!sOxBG@##FAswfm|&{5A!yf{N1*2>)cDf4O_Z33i$ zd_6AQ=QIoOawJ+1hMe_M`zt5}E(FcgBV>@)l*m2Fs@ny$4^UAgkyYQ^=Ad!!?Ah4U z7%Ziclc1oW3sBy;1P+8WQWLbZlK?>ip**osINLxe3<^et*$mBl7X%S?`EMEcUX&s6tF(zS>fq?5#`4fERzDh+wKw2Fg|VyQKH$xPUyAV{;SI&80uoD0D*+U zs=S9{-Q^Hw5)fSu>+0)4v}2xW3YRUAjnrhga537QOg=K~CmG1_Vm-Oev-dOPC?6b` zfc6(n27qwTnBoEHQ051KZ|A8~TqDgGUfR+n5nw%^SwjaMTy>Sd;IhF5iyd;bq1Q>D zZ9-yQdOBv9pJ;)lCs6KIFMyB@*y?Z|VU$D)raJ0|qpf;L_H79;o!8vl@>5fP%YJ<< zNeDFIe*KlRpN&!Zo%rJK&qj_(X8?I%PYqXE2(T`kRoVdF9+`}ZUmgbk|1+W)wcr#R zsA!2H<6wanH=BIVWYNl8itMeb>BTPY(B)Y|&e)Rg)_nz?JK$CYM(qp0$w*r1IQr zQu*_URGy;!deQIgcp8#Tsr*j(&@x)|^2;0IyDGn+fA%wt?pwreJ(Omoh@0KIB} zUA45leC3ZHZ?n9?X6sHtCv-}Ik0$JA{Q^{m7febw1@qSRxGjSD!otqBHeGG)53Wn( zyB|FH@)U6}SQE?}AcA>$`KKLuYABS`_!oO`V=CgSAqtr9dvGX%yA%N3fQgX#DZC?I z8Er0yADDn!2bgt2pUa(aKkK?*V}R(Nc|HmK9c5)ZasmJpezl+h#vAA{gKd?a>dPf9(j9hr^2v*AuwGK{>jZ6=`7%4uv3}*Mo+qnApO%{Y3B_p?*Z|Hp&_-Q#=ea z82&>0xHb}zw)Kgeio5FT!E(qJkow38M(+i-{`%ZM38g?%N(#6&CBJ*OeN#XGl5ANI^z)-&-w$0zp3oOyjr70P z&)+6l0S3Zz;n=VrKL{?XU;|*2PWUGd%u=V@GL%>29&u~xk)xN6r!cZn?CA);Bct z5?p|B1fU0zp8;eJz&=mWIV^Xh!BJt^B=uAj6BqXZiQgZ0IMT@1Yb9T;sHkXZc2iEt zA6lba-1KG*czzLv`T*t=#TTclasr$ro;x$VsoMJeqe#*CpjJ4pFqlQ|3GFR&^SWIC z=m1R*Qc~bksK>CqUZN?2335NaXXYmWb>dh?TH56|z83&tbID7SHiHRO2#2E1ND%7ODfHz)3pCErd&!Hq$wQU8i|P zW;Mo$jm<1*$jv2)ai$D?BGb}tcED_&ZnkKwMu7iQXC)PtCaXG~v*Ban*TMPqPYZv# z_=E%k%{~D>PCTc+<_9_BM~yK^R=8_-T@Ea1An;yKk=2`WtlnbCt#elGjSj+Fg;fZZ zY1joAs8FZ-Ppl-pc{$*JSX8W4SD~fWTWF{NBpVe~67lH{2NzRjWF#vTwJ~?|^@5B! zk0dumLteRcJUw9ws^dhJ=bfm^SQbmj)v000BMdIv}VD zIKYZ2^Z_);n2Uq{&}k@tMG*l#5MT7-3=3cwR2-yxTJ4nyjTYvh)D7PH(tqt)hQUSn zjzoR*oT)oSQuYI*v(bt`0unU^ilD$*021w1OJ3t4V4#RhTXnaE1_!@#ThfR15eD%0 zS6`otI1^`N`$$>d7#emM8y{>nuoHqg6My+rQTvxc?+=UN#7Ohp_Nw8=<@iSh)gr>! z0!M}qA82Cyx4bMAgyK$FHlu99V|$J4#RnjN$0)~AtO8O%j=VC!6WV1qs} zCOIJi6*jR-nWFKnUgJi21vy%qA1LRlQh*ZCD6bw$L?b4qdqjyQaSX1f)GW{ip*(c- zgdR=zO=!p4Zvzg~-Y?KU?!RTerHpd}q;0i~qYXF&5HFl@fvm(k>+kEi=5K)aiCu0j zx~SDIcd)ek%Y;zu>CG<;x(1 z@03I+M%hzd`jLb7b6{7Nz!h2o>1qV$>SQpH+r`Kj%>USU-YR{EX;%cV7!DI4|sMGykO3ORa}=m_MS zJDQfqSGkjH955*-kNJ30a99``SQC-lt4u;aLA3~>uM^WSswN0nm0gFMzJ8_+Nl^?8 z3VO)|wZT(zAkY_ro<9RCaa1UPX5HuEBgNk3@$qrExL8lq&%2#m%j*%-0P*7RfPfib zv@(RYfMdPP#(A=7zVBgUlL})iw2d|o=9Xz3|79lfx@zyolifvy3Qc9B?f6Qam1`n0 zxxw#@k7WydhUyHEtj#!Y`0NMdx_PZrR!tuKN+Zhd%18#~Ji)e^RW=`;by|?y={YP% z;(E*cku2N0u&-rXa^squjH~m(<33JO?FpOgl|taRfE@}RRR~uzl!fdZz$(=tPG8#S zu8kAGzyi!E<$?eZU@E}J@NjnM#!H$mcZYm_^^MfEKmpE)}#9({OnK2hXB9ceBzHIK{^RoNKOoNb*Y|dtEzsl zt4l8|OlI;)*o$ju0J^4}^l(h})rt7@c!Utstc@p!@mPCnJ3IAl(|BQ423QVafPBX} zBKiW?EPw?$^pa_reSuzk@phfOc00hZ|0>(HHx<0}Eqa9Xae?fE&sJGeJZ5nwU3Z2L1h6 zTwu-u7*TP0IOqZdOt3LCt8m`^t07QyL=o{#+$o<1B*DM_A=7O>>x}8V1tMd*Vm3$N z-YRGMv2?`4*1Dj1@r2Jd-D1}hHH*xJ>2r}G5+@Ii{aE|Z+{352nZyKF59>#qRXIX9 z0r!uwfq^fOt9rOXYy-yz7;R(SRT%1vg?VGG&ElxM-U4cG#*>=(nFSwfts8Qt)ZHgE zt^*%D*Bm@jTAX*c6K6w^!fc3`L+hfdTNI1ndeCUSqDS`?C{M8PPUe5>*(qox5#UPt z8-?T@!~<~9c8)50-g4kvhlU{ncQ@z&+?{Oh$1-4H{?D9})tQL<;c$Se3cNR!a5ylT zf!a(!A8In7aGP%2u@zc<;Pnlru;Z4J;bTyHkp{I+Pdj3xz}Y=CJa4Ht5nsn%Dv>D-5J-uIrR@BVoCR!<SuqSpRjeBrLS53 zltP$Ck1#qd2v1lqE_u+}bsws2*%X`0^;m@OlWEXy3#7_<^6mMWE}!h$?+nIANh@QA z5=w??^$kmVj_+Pm?4xD3TNyA9qgC!bS-928`gv|;P~i;oVqMB&qX9Z|a>P~Yg8i0n zQ76*cj~?vWzcTqo-=H>pd4aqGP>-6%WxB23qM~?adB$!?a0ec%ec{H&152?T7?R8~ znEl{sto-$;==!!jGRtyiwgPXh?6Ekno6>P^%imj_g#M47K!~t?L+bq(6?p4|ZB74j zMEdRb|8l-O=JUTC&;E)b`CpEW|7G)!Q`e^@f9n3Rbu{Ncw};o~pZhl-{Wsbsw!~k9D7m_2c@ojZEo7bMMibYQ!+P1F)4rLhSb6#`ryvd=k^?# zI*i2!Z%bWF4Oo7#@qq)8pwRWV5qF=X3TI+whAHiCFioNBPLB^T%cXD9qjt`cXR~#z zekjSwT>h+Eq~)lZIS!yk&(Z4N`3am4f8SiEF(#HwA5NG|qKg@|*h%9_n*HFgUZ76) z!=6FAm5gY}x}Yy1EicJc(a%QwSopWUe{6jg`4Sqm5)WUysnantdyHf??TN5dq%bsZ z!PpzH#)&AVGFA_K!lkn_sMNU4l6u9~pr0#%&5{c#@_3R8Wt#|QbCA!5SBTZIcn#LpI|@_35LJ^4eZg&yV?r%$Qx+CKJ*aE7Blz+-G?sQU)1)C#lv z_%oHV{Bh9N`MUM*YPX6|KD81^T9J~x{MFj6$4-DZHGi>*N+-wZ7e9qvl!A)Nt2@3Q z91d$a?&4=5X?)o1CuI}UDB5RP%{l(d=I%=`zlKWQDD-^2)T`3teLOW%E3X+?y7yI8 zF8m~40o)ZIobEoI!R)*^UY}=aE;UIZKq!k5@qjnUziSGHjCxuv+&0qnS1nTWs1;LlqhIQ z@lrxn(%|~_&FN2+|G|UmC-_g93OwlzGxa+F(8@-OC#bpE4Le(VMGOAn90Ug?5@ljyeX2RLWXM19e3&X0a7CZ$f>kd~~-;8S&B(8KZ zi3h!yaX^b0hDzqk?fUn#}x#i@hL2DjGf(GL>*!)$2^)2N0Cl^n8P>k46n3nVx|#kxIDhD*`@ zU|2hzUBW2tu+O=ZCCp62oeM!Vi~4$ckJyyMmkl*E(r#hUQ?(x4c1fM@q#UnUq*{Da z5^kSrX^t!L&B|}RZMSkyzle=uPrgcYZ^rX)D;ZJ?Jv^>V^#e=guf`j^y^B~C{O0%1 zz%Jl*eKJ1$X-Q1z1_ulC*`k>O`k_~8^QRJB6QtZLf1*NZY`!@~UameC?#_6>URgCS z?j!D47M3O_ij1EBbvL7&pU3*FVJI+aWy(J#bQ(A z$gQ0|CGYTCDd{FxLhgx(?uRBmOG8@W+52`2Tr)ChkUKZ`(2xPG_?);#lTEQw%j1Ef zmyU-|wI{Z@8k$1{IG1+Q=!20y&+$EYyRycD3f^SmBE3(v98*jh=4q5DalV&f$R@L3m&j+R7)RJ}rapVzxyhF;R-Zdvh}#MV2auB{zO zN}nOuyW}3TMeo~tdmF6X@skt&VB6`GbIlwULHP1e42v)~WpT(%hB%5`Kj?Pk z%@~=Q;#>;(IY-e)PO=_L%$%Y)jD7wpkaPZllt_ZIo4g$1@-+pNg|LrTpBRasNW>+k zIgW|W{xA!N46Cte^3sRZ)dsiBUDQ4AjTRAdsqvjAv|7Y)NEU+i3DPun&YPKED*D|Q z%oit%skxtSUl#tXU!_OLQ&VNq0Qf=kh?WVDaps`M_NYw?kAE zZUv1czH~bnK>j{_**+ujlXd<$O@Cxcs7+w&XE10VXNFrr{nY$&#to11XsrAE;3V8w zyytptOe3leHq2SQ!zrET)nW_q(b4r7h#*Ol^67feA+J~s!Q6I5*tn(KfEnE{CNbVW zq%M6-DgO;aQ*Y$`TB*Z)QvA!oHw*1lz1j{LEDUF;JSm)45C5E7kZ{A?l$M)!`R<*s zJdrMKF^8ybA5{Eu?_|~lMgJwK`POMgOXs;1*ne2N<)L3i@?x?UO(DTnY&us~7T|8~ zsaaHDZ#=m&|G@a%xhwruOzEaIIkYNdv`%zglyEq@XfEb*Fv}2V^ltk$&frqfN4r`Y zh9KsjP$If%6l0nv*&`r?tIBl+Xe`KQLCR;BdBq4me$j;c%x3DPgGdoE61Aays z&`9O<((D;`fEYns1>y<#EP7?BcdT<*b7r*Qik4PHyFO)*4ql~wIC*CSskT{7=t2!8 zrK3*yuVx+`yzHF~&-lu*F2J&2 zB@OS|9intHubjV9U0G;3Udhj$b$PGL+|}bf$i2%psNz0k%Q-z&-ya&Cg+vF+A-n1n z8Qf_ZzWnc21v0wxDO@jE26PkMN9|~(CSI1~PPf9=zf~1x%^FrX6)pAp1Ey%SXRtb` z%ilphYq|EtvheAC^YOX@Ok@Bdp*d79De5}D#;jpF?Zr~^e9OHl&0`m?E9SCT6ckFm zI}gXkWL!h)t3RXep>ul8biSJRyzd*ClSgCyj$C&29dBYQvq_id^Yjc{aIyL@3Creq z`Ar-)Yu}HDjy{18XR89k?T4qW2w5o(;uBw_Y$Yks{7OlRulH+q>{f7#@)li|SH-J1 ziigd(byKZ;j)sxUkU2QLj}9O>>K%Re@Tps}jegF|k2gAA4?{u>8pCb8rKn#Sm-r)F z$WZAE`i)MWMKuVgGu<2mR7fWxtUhKAx;uM1vSd`xY9^d5n4(5Vu$c0zOUbYQrju; zIh@v)CfU(bX-FIG1<&?}^3A3vav`Dw`f-cpozgirW70RgE1{%WerRfM<3{-%Bi8-VfD1-b+0u71IM~~EN=4TXB zDfHS-XLT)=P)(qPgbL(j**1%;82>Fr7F2ENX@`Yp5@=8lu@XmO{C(DHl!3^qTjn0~ zk-c-Z*6|}%;j{KoTS?7G=_b1m%tRj*%Dy3KX9<;HoTu-zzg2?xW`EbQ+1c628mTTI z(vTXSla}6o{!>p@lRoRiQM;#x)`q8ziDlDAmgmVyN+V!x`{z$k-Z`(_*e3MS(AU@Z zqwjC1^n~|BEQB0wre7}}ZJtD0SfCb$z~FdsqH03fwnXBOU|D`ySy@BbJMDQ+FAnC` zZ22zRJVkP|g|dw9^-6R7jXzxrK_fkXQre^^cDYHB{zclxe0hE$}xNl8if zlfKC5LI?lXpMGu|vI7ta;E1EPc*fmb>RZ{SkSSMnrzXxFK`i7hDql#JHoX7;0B#ai Aq5uE@ literal 0 HcmV?d00001 diff --git a/doc/sequenceDiagramSourceIdExample1.txt b/doc/sequenceDiagramSourceIdExample1.txt new file mode 100644 index 0000000..23f317f --- /dev/null +++ b/doc/sequenceDiagramSourceIdExample1.txt @@ -0,0 +1,15 @@ +@startuml +... +... +"Left wheel encoder ID:150" -> "Application": Encoder datagram +"Application" -> "Application": Encoder datagram conversion\nto ROS message \nEncoderMeasurementMessage0202 \n(sourceID:150, timestamp, encoderTics) +"Application" -> "sick_lidar_localization2": ROS message \nEncoderMeasurementMessage0202 \n(sourceID:150, timestamp, encoderTics) +"sick_lidar_localization2" -> "SIM1000FXA": UDP input message \ntype 2 version 2 \n(sourceID:150, \ntimestamp, encoderTics) +... +... +"Right wheel encoder ID:151" -> "Application": Encoder datagram +"Application" -> "Application": Encoder datagram conversion\nto ROS message \nEncoderMeasurementMessage0202 \n(sourceID:151, timestamp, encoderTics) +"Application" -> "sick_lidar_localization2": ROS message \nEncoderMeasurementMessage0202 \n(sourceID:151, timestamp, encoderTics) +"sick_lidar_localization2" -> "SIM1000FXA": UDP input message \ntype 2 version 2 \n(sourceID:151, \ntimestamp, encoderTics) +... +@enduml diff --git a/doc/sequenceDiagramSourceIdExample2.png b/doc/sequenceDiagramSourceIdExample2.png new file mode 100644 index 0000000000000000000000000000000000000000..452e6e184156550d2513abf753b0d28c20a02d76 GIT binary patch literal 15411 zcmeHtWmr^g*ES|MD4?JqARtO3AdQ5GAl)!@NS8E2NGV83cXtg#NlOh%N%znpNDdv+ z@m*uQ&;7j5@qXWNe1E?0$Ngv6>^-yhwb!-QI?r>h6(BDwhJ#Ilje&uIBOxxLh=FlM z3~5*H+n@Zx>FK<=gBUbP^qA{r*9EI_<$<9+j!cCPkS1b7Q6A;E_)> zAdy0HwJ=#PvGqBvTKgTf59Y6HVMUesv#?y!>&`Pc5=(C}P2=sqYb%TSORYMK&c1{x zdulwmdZcjPVe_{CeM8v`-Wh@ZJR*gAOH^xqrV3;8mN{u0Bo=sPlGwdcdpJyj&4hS< zIyM*>yv!0JLdwqL>&bXF(F@6&)!hS=W%P+Ti8+%|orWu=udlOnR0QWK(st)0W}9)v zE*kr_m*&N?Ij}v>9%57T{i1fe@L~C!AhZANTf*i+X?Mbf`t*ZLWi+#~Gp{^^J(rXz zc`4Fy#@yRupX%Owf>;v3j7W-fd$udR_*8EC;OOAoqhaafoX@1$1$YETo15s9Yv==E z6{P#&iQxT-A5!>c@&kUG$&Kvnx96^hU_GZI)-u^sg^uT1iVz2I(5)P9=;DvC{p;FI zC1`P>n&WF#(g2QED-{c!YW!>hgaq6+(ijihUp+O5gAbm2p6^Og4ZO{EN;NmwZrf9n zp8U*u$)C!5Aqd8+I6k&Y(5dPKh5p#vyU%0uZMi?w-QE5DQ+-yfuU8*p(WkR#pv28g zir1N{tj9`?mU@z14>qFPQ+RB>o`^lBnT>l+MM>=-s!T?|z6L$Ri?y2kR8m%^M3ZlS zJK6u%qJIn3eFA@~toJ?s@JHFn^+mNCIm5#$@dZ6EYieq6$@#_O9uY>`NI!@O!{>bj z4~cTzuUR=ZDjmTjcTTIX*QR}liF^M+*X=+F9-3Pc;#kSIA!7R57{6Bs4-o1miy5+@GXU(G*Rq7Rm61c~zFCrMs#CP)j{Zg5=$(xu6{SsvqMUA*|$5$0wGNecc z@g4ax#BwL|4`w#at*qMG1M(_;eT&aFoN8^Q#V5oc9g0Co2>!O>7Yr=o!vxo0lDZ{am~&zwDW=6h!x1{+d&N~9o}75dJGQOYZS~dpd72Q;kdYbRDLJ^+$2S?AJ3V~GN>r)?^fm9vLa@w8B}hnf z`L{j?mqIc{4ND}qX~pqv@GXn1;yG3}wLFiunuw@!`N^q*ozH&Eup-h_2$>S%HC)0B zB(KS)o0eDoOGsj1@`)w;94h=z89xUPBr$) zi6>a=eAd$qtrmK_3Uj4t-;`pt_n(sSS6TBq8??HKUY;SqQ8HCt`7uJlKCVS77bkBh z_ZPY6DQ>i(k$XYbytUK1#=5Jib|QOy{prqJSf%1dmSf!}BBsPZEML&kwKu4mem=|v zHNs)eCNP~rS(~X8&?CiuA@J*#0(AD-oCQ}AJ?im(E2#-Bw4bro-_29?Kl+)c1X9Mx_U4I3GPJU4_KLKNaryN) z(+w*MLvta&uB!9J#p@%tDvGPGTOC9oX3AH-cDx?j8JwGI!1}up_ZtR8DQT|=!I{w} z9Q_`LMT-5w3}Jv}HZ&qIFsn!>KX}M&k95>}=0X*`#7)J4OX6 zBxU)9qNmQAmGr}=RE^A(tTLTQ1v(B}{`qr%3;W6+TbFY9*{#m7C?>IZ4G}*s_Nzjd z-5R4-i+dQPH62-8l515JciZP!-$S%Ng&rmZ9~D3R7DNoC=T9Rv92L@8vrT%BbFGDA zrsO>bYBgnd$&+z;p4MZAt{xlvhSh+i!Dh|3xG>*vk&uD~;Uy|gPTgwYHFARPy7E`U z;E@qZi@+J;_?)-7HtDyMP@|#kF(=QImvnSFV!NOot1Pe+o5ky-jAgT`ky!F3 zXj|3)aHWUUJZQq*nKPu|$3btf#3*dyn6a3@KtXJVTe8@z(MyI_b}fOcaJ=66t-%Wt zQT*??Xiv@$?V7lb8LE3aPrKWl&0=XL8-@?Bc`zeU$D+`XNL8I zlq5tum#@k)97G{-oMn>yBo+%AksMVc>G)QnTe=j^EO|z<_#W$J$8wrx=MCKyZ@B*U zJ*yI)HZd>d~Rmj$W=?P@wQS%!gDV> zXJ@PX)XzZhKaKdb8P+<3U?+Bw)SJzP^3wL(ZG9W2gZE6o2yPfmPZaQQUWd6PgREU&I^kGVe&KpRsQcXt(i^OO=U1p`zh8Cw$ z2V`F}WVl$@?t5@qH$lhvfV;1%YrKi`X5B9Di2y5BMW7=`C_f{;HLYxojJ@8R>M0c$ zr+a2mQ6s_q%o{mrqMZGU*EpE)jf`Te<*o^wACjef4O{;{YmKPxrn8+9CLdDiNWO_Z zv+)xIj)sdJcDrYgW??6jp(mrYE?Uoh^(gM*<$Y)|h=cL!QebhDjzmza@az7Fl1E-6 zcKo^hUit}}YWQ5{Z1`&Xi6oPebTjVm2Ct&TS3OQ!ScY}ne-JgY_{_zH(S(akQ{Ld7 zx&DxnTB$1Etxj&r{h+a+Ae2e>+}j^6%hp+>#9Lk3`+-W6e5adcqbjD&9^^8vY_jhS z8uP=NfI0SvG`QU;$+7Fth{xtw)bwBKy@*)~WJD&Op2{sQdc3eFxj@uMP>sC1lK9A+ zXjjs|M+G`SZ)vD27nvm=@RT4pwHbgKM6b`OICpY+P;SPA969u56y$2h6F?xiZReJ{ zRIkTncNXa|D8GW}wav{={4r1qY1k&^ZsAOU0E5Hk$Y{MGIS!8Q;Ac)smb$H1jc_$| z3fTP-Zd11HRu-@%6`0|cTwJV&>0*nmySz;L%XK2-K}>A-s$;H`-nl{`s&SC1@7xwS z#Y2;&Nfkca9|0GCI1-aLv3h6w8MRSHx0g!mA^t8INo%gTIYQq@rgT9lT;v=UN!L5r zI^go*^)~n2Da?sOveAnqs})&^eiI6^t6u%Nro;)ysl!pc*-0))( zt2Cgg-VuPM^P*|*Pm-S506*EPSNiI7F_1+YQ*32j?GA`EV9GQQk%vEAYdpyU#b{pq zChe<1kMMh}RaHk~m^8VpCP%TKyltB|bY^St#>B&4WW)Wf8k|j}3s7&~yve%C$H!N3 zaRuXwSC9-1ZByhCnZTQ>Rk`a5r6H!2$8u)FsFy^8V*!!$=e=dEv-{JZ4DJl_55MdPywojf$?nx<85vx z>LUg?0j`T7^)7)ES1{nX{y)$M-&SC}k1;U*;|FNf<;wu$MgLVMLw}~B(4QEP*p025 zoERy%7|y(KT=W@vDEjl)SDz!%QXT_tW%`AE2z&!P|L+(6+ynFHFKW`S^~!@4{9GaW z3E{QbhO7yGlEsXi|g*dNQHfA;IbpEv$(3gH_m>DPao`j;twUika7 zpCfUYoPA0DuNP&L_YHCL&j#GU__J<8P(tAayYyBK@4pUyo2>~{YtU{&2Jr)O8f+bm z_rWkQDEdHr;Ib%BvwjJ^Qcm5;M(uusSjc@dQ&V{tSy@>FgUpj+rCizWWIk>|LC^WN z@b5sb^@n!zJe=?}iOX_) z`}^1R2HDhS0v@M_bebPFHa5=VO!NiNo>7xtfO>sCS#4i6X%{#Yr0rnR6<6YU;jz%0 zB2epovTspTE$Xw_F#Z||hcKv~cg3^cU=HgqyYp=NTm^dV+BJz!9sak08XGQZW2UE< zz$B(}XOZG@dgpV4h*_h&Ey_X?MBNnmbxSi?UY-y#9e6MVlOE3dXidK)uHB-=eKFpI ze}YB3X2?)9C_WHJ!M9Rg|$?+dwPVm6j?-mgzNJ*UZJH zmQl_qPql`oQ>+GoX-!(wA&fqj)%tM-Bm>#D2AU@^g@+;E18 z^4kOxRo2{dG%)$OoxI!>UeDP)HY|E27-4q(P#BxzTLez^`%u-|VzrVNP;*_)r2_Rb z4Nc8pu7s!di!C?D1a5UyRa7KDa~}_C(TdcpFpsYPYRMHdx3;pvs#=-VJ}G(KRz+ZN z`DhuJ-BhYw$*g(z%w8tyXKcW&=<<03V~{I@xf4=+2nJd{zKOHZsVSyHB~8uz;EMT^ zVQY#D#c7?JWj7o>JP_^T%|YY>pP^Ad68NhrKB?+C+qlX9bG8`6Lp0V zxMc~^(RUS)*DUjPvF(w!ew&#p7bR`HI$TIiO}%mD5co|>G}`+Y6Xf|>8cuiOSPfpF z@H%Qs2bg#3>+2VL7GVmRT???VMrx@T=|nD>`U+@`U#^RFIR8YgM_+9YL#^+XRm*qan15x&#z@NKKRfuXHudt{H zn+OdgVwo;839T)8HcoU`J6!K0-aK_SYK^+cS-GJ`SxxPpqMC}z@W4Q+%dT>y!Y{=qoa2hyY2CUr@nPC7QcS|x*Tsb zyQx4$RdvGpefV4f4E7gE&Sne_4$h-<#zPj6?&YCj<#0aF*$R=u1sZF_%6FuyE+<8_ znUz)L=GCqQ&ei=1YeBcekLnSg$AhT}weQ;Dyht+!GYbnw78Y(FU`5R;D@d#R{qCwK zgn{cb4Z7w{?vpY{cNtaa92MgdANH5oEl3`;baixeG&VNw?>puzyOHkPV$<0zT^cPh zfaIRw7LX_=D>iNLeWbrxjX+F4Yg&3r2NDP*V1l^z9d@*!!?OHw7rZ8`yX$_(3;tr# zTHzZr_`m(`*6M}eqHVb}h0lD*2{la@0{~|<%-^`jJioZOF;@2VR9{F~SXealWu~c_ znR=ZwYZ>-W)Oj`9avTy8l97?IwzdX`GaR%U(clNRa9|%y85-XO^x|LO^Ye!P0b6OF zOs`J%*Eu;ky&Z?nJhEQ_w3(>1yfMD8w=($sYiJckZ_-nOi~0(L59R14_0t(aUD)if z;ODZ0kfLYu^{574McCNcbbMI1xrIe{=vKzhWG|ul+|10Z@1P1N<~%GbutguyxUn`? z_T$Hol;H1>JZrtb0F0dRcAXb_el#S2Z$yxKCvER^vWWfMzlh4W0( zsZ?H@JQ$1z_*m_B4Rm$RbGWg}<`%RSqw}${HgA5-`;!i80YRN#sgkPlZMFSUWo2c; zDM;niS*4|=l9G~+o70xqp%j8v9%uEXrEI551X0ziMYXNLq)z9JL`%a+WQ%?Y$kGl_ zXgp3=FFOp5LYbckU#2|3cE6}F_=+pn4l?2R_&EQ`F`;ik>4vrjw|%d`0ob0!g$1ai zBYcI`p!JiJpS#!{!QhnR+S*zvDX9t>5RXS+O6V-jyg~jom&~?+%10nOItnx@;4m1S z-i3FK30{#@U+cDI{LE}yd;8c&J@4Xz0G;SH`N*);)MDl%5(ziGJ)w5}ZtFC%r*_Sg z%Xn3qx|rJ)o@Iew@0GtJVe6Jj;Ap>7q+TW(67Va1m|QY4G6I{*?oudi{AB{+UaO6w z3JqF|RKvQ+Q!=8;0<^&Wys_7t^HKBq06>+Kyuw(vaea71$ZdV5Dxbt_sE*BC`4Oj&oy1d`UzsTBTC+ZDVTcMjCl{Awpt$BJ z&d$zG*Y)F7WkdeD@ws48Ou zNCL3}@+C#o&}g~YU{t^EZquh($JNybi2cop{GOhk@o^2K9NA>^_i1^OCXWF9evTBf zBMggrY|PGe6<-Im74_^OdZZ3Wql(u+gw zq4z<9r{zVAR|&}V0iCu$=a0W?RZLVXDlA3_2?@s;^^7f*s?TJcY9Gh5+zQam2d0~w z*r{)fTARS1eJGq9L}Y{Ti4{TmXtD1~XV$u^tE)>%bpmREN5&f!1qY;#-9BY2c-$Y} zQ+0t=8#~mxagA$NemqYp*UchOC)&4IVoUk1Rip$C9D(rIn5^C>L)p~+fZozQ!85Na zEw!7jb6LEc9{oluA5ChgEH7!S>$q*djAUVE=Bi54ddUeq$DUEiXTOAUcey5pwNMmc z0kO9)a|zf4T*WRmpS?F7(2wZYSii?ml<$1biu8-yImf9ki^OFG=#Up1bGsqj=RZlB zb~`!-y~q89y229;o(;`@C-2qoK%CYqMi??@O~+Y4QDEJ(al@qt`(emS(#L=+#UJf1 zoeak)Ll{*Gcsyr`c@8e?_{-36!XWu7E4n!W?|*N$BhtNZw{pTNl0&P^IGAZ=Wo5Sd z=VlKOroHUpF94C{>P0{+3&3IkZg4l+1*$*|fk5`}3TCQ`29soGw>bs#yX+WRS{7C+ z_^5E2AAnSIHzq1-)VeKjhpBm%+oVDx-*0SeOrtt6Az|A2dvID~SVbKG6`kI|qH;H} zdA?w)vqWy|VaZ}2w}p;qi9Fss9EhT-stNPB&rRBlU$0gzLJ{Z^>996hvcA5KsGx>K z<67zIrNc{Wo=(z4k_?4E65C_pqx|i|)=sv;LTgjCBhNU@jHow1Uj{e|@^Dd6(T5Ko z^f*cPy(EoqQwgy-@Wfu-<picTI1 ztI^ZDq@keWakMbYP6~Joxg?xf*w3Ez7oshJ`~l>`Yg5y<%2ux<06Fl2 zXaUc*sG)uGwU~{qNZWox{K`))h*s0!0NnFG=)nqV<&kL6Ukt>vPweK~fKaNQxCg*gzeG(~ zxCyAsOyv|3z=GpF{yMh)D_1TR2qCwNqA#&?JdRFIx(u!$!a?0(YcC6u%oLRs`KGL~ z=WGN(GcPZ1j!fdP=NStfUE7{;pPVp{>;7xd+ZBanCnS(4ll{zG7;nF*LPbY|?>}WT zEe71iL+c8gF3#TIEd~Y#T#9E&=exVBx)*O2yW(NIzpZ4Jj(Twp1!)IxyReRE^$K%{ zfaL@vn8{_myWo&EiNc+=6*k<%13c0Jl!*h+AUQabL*Y+LxFj^)iPiO3hmkLoni zDgDGnIjOo$NZ6dr+!=>9NIE~+e)n4ZGF%)2(t??HM~9@V+}OdlH>RehqgB=v@Q~lG zs*%qtQ4`Im3Q(6%3(2JR@ww(3=ELqdR$-sQ!ou$EZqTd}serllBt13hO^N^hIn0s6$K1Bb7sp(jc!G7t z*K1LoPcn$%5o?wiR($Y#q;GF;oy+dfdp3)aBF@?q71-3o_&6X9WE^;v=jvs~d9I?T z-APZ`=fBm|9i#H`!Enu|!ONrdXnzjEoE@dngA^J%jZ*J%)>6FP{3W>dfL?>$W#BF#)-f z4HQH;i6*>^AL&)h?q+s$?}i*Rk`XGWJ90n5PQcV`2&ouT^qdkV6x?M7H(MdP9{It0G~Oz!kKPoTnkFDurMp6DIsKMT1c*D_AUA0DP$wY;8*l z2kYn8n@O)GvTdr*Khk>xoTO93Z;ih|kKN;*04gY;WrtOz{ z3iI-?@}77&_40pe;y}rhithsk_glR^vfvd3@%`3gd#|X7nf_)T;ld0+6Oc03C#t>{ z_W@lN+@in8JWZ_(9no!?KE(yu5R)UA>fMd zKJg-})xLy-7I4dltU0U822B4KZ6 zVlsk6#&;^KNC%N{N(z){4v&nSc-Tw6fQ(E`XliR0VoOO%u2HxDQf|gZMtPGc<(bCr zL~f}CagRc+>H+sD2=AwlALVzAp`q63W&XrEaU!-~D-5~+G~;62-JQ|F=^z>NfJ`k| z`y%4lY3AKaWXZ2By*HeavSLx^@`Sm!jkneg9FjIu ziHIhTF`ZQgZ51eBIzM!U>4(-lW@X!qD=I1$NBk6^XwS$Js4p+)n6K@-{?b!?phcfm zSI=pGZS45?O>gTqe5mTl)f0Q%GZD`bLA6pWh*Nv8P>=J`LTn}qT{4z%Jx&pD1>Q8E z_YUvq9a}753Qc}^wWP(su|QHv>2|w;sbF&RW7i90b{Sx|#afDJi2`g!wX_0!*V59G z^Qcg>N>UtneRNdR+I0QI9RMSfr<1PW%waDUo&AWm6HrbYr#{wWh57kFNfOXVFQZUw zq%a#$3WURJYBY{)AVhn`WPFa!lE&Q$$l>9|v5~4LhSAW?ftq;NjcQtMZf+KqVlez8 z6H3h9TFx5UQA?!vQqX(mPbdh(Nk5`%WWcSL~-SA#a#r>Kt? zLQ`d!Bh;qf4=cMi73b&YUypwLqB<;6Ea?c702xd*7XREsqSQO0C4mCMXE*O(-A`dv zg}|M&xG*LPWi`FRX_%16VHQD;W{dX;AecZIi1!S3c65NeY_g*f-{n>1e&Sd=BtcF* zMq7e^KA74eE)FVe$EQ9sq?|jeC11%I0Y4^%^*w&2NbA`DAp_M|>^L+uWUAg>{Wjsr z%#|h0d)qq!6WO3dmn7h-V(<$HRshyc2Kpl&?Ier#S{Ei@<^trU`u?yo8^^dSF8u`= zZbhOOT=U~Ap{R3AXfL@|Y+A7Ughq+J5B3xVQl^kWCMqi(J30V{%D^)R%zYrdqd>cM zxJ%;G)G@Dr@!5$ZL^v!#&~ui^l~YlPE;h;l&?4X#?JgkO4x&sK6hJ~R_b>OEdH_mu zuhSYf?3Qc2#^F1=yOz@#FCzPSdEe|UOJ$>m7&9}5GKSYcg(j`>j&gFecgF-!Mu#D7 zP9)x~`1MRDwIwD!NhO#M=^;cV7eYUpDf+^KzfUmG(LK4cwz?|ie1oly0g7~3oNtf3 z4bk2ck_eUo)i~la&W87-zxM)Bk6K$RC@h2+qlWTC|4M*6aC!Z4MWA!IW+o;qHmHM1 zIN`auv>w;&ib;KnAyyR|F@&{WTJm}E5P}0?Td}10A#|qRhqtMdL@hrWw&Mr*&dtqb zjeiilC6QONe1^A~BDGiY$$h_Y{b4?KYWcEv>6~;&*IymWjuw1`h8NqlFf8KSBN;u_ zzi9ZIVZ5M;@ohzK1hodQbX*^AY<%HL-Bn=8P$g(=9ZS7??cufsL`O%*O%tIS7vZk? zP|FY&xqZ2(YAXU(6J}wYV&>q)!pLZ0W;O=UI$hWgNLWCljC%+W3Zx3iqkTcWgNX6b z`p?GXl6+89l(l7l{=gO|Rtmh)k`2`5M@D*+`9=`JWWP-$w63C}(v!&DtM#Bc;?tnVpVoYQ{4ETut|<&3A#q*3-(@qgBTE-D!X)vp!`D;?s|nIV_=6Ye3PT*hlT0M!Dj5C zP3n`t3{+A5zJ?LUeVG$#1t{W7Zd9OGU8uRl)H_=$mVw>#+-+t&0&d>&;qDR(|CJ@3 z&o@fiv#wW|BN@&*Il}v_+{v0p&ZmlM@ZL-V9E$J-I8;I{ARxf6`ZMsx2P@j*{VIBO zo#kvmj{xkv2DBi9t(X~}1&4Pa=1lfFfJ`sHb5s;gE0+TN1<3{PgNv@~0E}sjh`>L= zaZy0{@SH9ds95}X!pEn{=%l1HNNQboTlrpT48Zn@RhRxh($fuIypC@ zrJDTpTI(9TvU&-uZ3xto`*|eBE+EYFcUKy*j1W-&?7PUy_ zHfwO$_Y3H-^5AegYc1o4C2G={HWX!%?8oQ0Yl(OQ^kV0Dma*>06l-SZi$1>J(SQ*a zURV45$PWzkkX7rR;kg{lbdaAUUMy5QfDZUD!OtdZ86aIr^_=H~95WE23`$4*sn<`Y!=0kKPaT zEqpV;0K$PMPvvTCR-i;F1`TD!-mGh`|AY9ptsv5-ujtl%PdHT}zd$qb86=q)T|HUNorR!J!eFnK1=RUz( zakj0VI5ni1Mf>x0$E|N){x$&ZzV!w3ePxh07~}?X;@79q)5d7YCH#9P_t)s{fcFI^ X@1$L7K`oyY`l`fBS&^a_ue|;jRC)fI literal 0 HcmV?d00001 diff --git a/doc/sequenceDiagramSourceIdExample2.txt b/doc/sequenceDiagramSourceIdExample2.txt new file mode 100644 index 0000000..a9fd940 --- /dev/null +++ b/doc/sequenceDiagramSourceIdExample2.txt @@ -0,0 +1,7 @@ +@startuml +... +... +"Odometry measurement device" -> "sick_lidar_localization2": ROS message OdometryMessage0104 \n(sourceID:155, timestamp, linear and angular velocity) +"sick_lidar_localization2" -> "SIM1000FXA": UDP input message type 1 version 4 \n(sourceID:155, timestamp, linear and angular velocity) +... +@enduml diff --git a/doc/sequenceDiagramSourceIdExample3.png b/doc/sequenceDiagramSourceIdExample3.png new file mode 100644 index 0000000000000000000000000000000000000000..ada7fb75ab26f0653a5d25de2b091a3363cd4b99 GIT binary patch literal 15382 zcmeHtcTki|_vR>9R1gCw2nd2C0m(_SC=w;ZphLQ37?=ShNmdC8l94D3lEW|rnIQ)S z$w_i%Br1?{0Cv!6f6E_AcCntL` z9v*vJW2BQa!j{|A4snH7^ahwA%v$@g)1Pt3DKO2m#OR1FwL0FbO=~I#Hx2K~oK_Z> zRk$Q4@a?Se{p;_~QfQVc(Nwxvi?<&vuL^fR`}Q?O#b|$G*K5y9cYtrYRUehYaIU7L zlfPHgHS=YnfF2FXah73PK4RnI1@08nhkGTlw@fW~oLkes|E+3u&Ei@4Bg#C zrzzpazmn^VmtY17Z}DpE1YZiN;i9Sq->X3aM32n9>68|`Xm|RhE)m9u~%OO==25pTBJ96D?H(n143=Dp>yTDI#NR(c*5QNTiAj2?gA!&JPaEg~r_|G@H z?KYl^+qioFwArIq50tnW5)kjb*HQ?p@KanwW_4mrhOK)KBn2(yiI+9|6|OF2R|a~7 zx2wkTYRMa8bLU^qRhFr|6kmfy0PsP1zCH=NL}@n4@NomjH>@s zWUClT>)BO~-Zjc|GT!0R=663@wHiHPPg+AQwNq)lCLs^KkIhDG2y3a+JREtD5L8!B z?sfX&P(4~he$O5P5hGKSmC=4SvYJF@5A82sEAL1tUsH7K*-B>@ndKMVvcF5+KGY|i zsgxwBqJ~VEo9P)#Y?-moj^%gazmcHX_P4+Vxrf+|{vad$%S;Rb3c>HMMoiWR@udnQ zqB(*uzJ7n2U8sTb3j3}R)Y3WWkWh`kq`1NQh}A7DEr~fTTs96pr(8D< zR%4QM1tX^<>M{PTo_u(j=#s>jiHZFBH@;^tk{?=E*mQn&1Idu5>O1?KU~}G zeCN6v$LAyMzJ(8_+oztzd+jd1rwpbM%1z#jK^-}`*!u)Oep+F(>ih|>vQV)9(g<*wT8r^+;;Zd84 zfkErj(jLG{S`kuo~VRyFk%B*|Iqbpf_4or9b&QFh#Q~Nk?3q>eYjHT4nOnqNZ zYKacpcre?W>9tutKj3z;6mC;%;X@cJ*Ho7JF(XNo+dtuRT;38T?bF6}?6xt3JUsYT zPlfVwLAd>hmU)Uf#=?&KCG@otnS@^xwaxI6hXzFT!VeMohw1&qXqJQ@gsM&V21^z? zRptCiWcY`O^pup17iW<%7@82qH#$L5D-n01t~&NN&&D1{E%V&;{8l9!+2oskfGnG= zY^1_Q|Jbx-)}^0`>v7S_@~-D9CsZ6in+`$j%)ezfN)q246%xt-i%jo{x%1;i*0-a5 zJN?4HGh5Ie#TJKp78Y`b6InMs?IT7dLu&kTXW-V0RCv$L^P|T)Xi5cjOUvW&2bab( zTXFfHx4XPuvcw0TJW2ji;W&5TfvppgW}$X;ly)9APwwq>9L-D;aapls9+m9o4GiI^ z-Wf5KbFi5Vq}ar?`y8x`Ye&ZH6xG%Fj8%I?ujM-egVm!bZEp?5u9h!3OIxX>_zMn=bv+ z%Ne{@X?VvjjH6Ibk*ONIN1IhzdTq7T^+F;viabcl-{s(Yr(%?pHB9YvsGA&m!ppTd6}5Vd8$3eG&2-DhavpUi{@|Lu=CIP)TSp=XQ=TR1D4p1= zUU;G9y|d!ZmFB?CxgSX<#DYPKrA0`2)6QnZ%~xIkUaikQ|CUCB`AHwf5!;k#pAuMzC}<&rlHbJpG0Zg7Icu9fd$w& zx-3u9J#sf2+cTXIqrkR#E+2Q;(RXXSWFIu5Opv#4YyQ|_F-xma6>%k$`d-vd9Sq6Rk?AC`cHG>lI7=XA zzpgmboN(1CT|;L(+G8#0xKC^M%tMH^(4v6(gty15@&HQ2CW^f4RPbTERry*6oKSwx z(Opj-gDfX8@>u0FXBHGP$P9-%?&o~5*f(X;a60ySH8h7y7Z;nn(h(ZU>|X@IlipOc z>ucvD@gyUQ4nn!Ot_ZLesZkz7)os0%ca`61fDThqc{A^16+N4 zUQTFFkt>3zNAwS1Xn(z$0=|V>G0z^3QvA^&GZuETO^ei0YvPCCj(i@=uH23_nn*Wn zszpj*NS?a9Q$>v#7#U5{FMu2JGU9Vt{ReaDzQkLbC7(V`Q%V15(RWNxQckEx#lg6m zUCFsFg)xi0>}k(-zUk#uPD`(>Tx;bM6Ya&maNbwBp#Q3k#IAQd#r|Ao#=>jLtGIe1 zErsx)oYM9uO^uCWo6iG0+{C@XCc5|6YBgRBqM=-0Uf&eoNw-AtW^FkwB!*ikVSUes zJW7Req4xSaKpctgRxOR8l9D{D(=fv)amzM*_N=v#wbvQ4a?NJ48^AWD63rqM{cs1l z!n-0%$irMTw`(%ho2*ag8@d*fBdt#2qf~Q1r3{BW`L1Z|0;v@%lUhsLKK5b{^TUgD zBQ#;qVk*A00%uljdU{3XTP%aZ2-vNxlB|yz;*wcYE5jk)gK*`TgL{aLt5O@yn)`XO zii#`*4eu3$ms{I^xNvbZ2w&OIqJn$-TQ?`}mnsSts9X>aEjW<-1jpF;p-YpVbLFzH^Yl{*vF0FbdY-H#OQ_+}NRq)1FP z<>Z)~qm`6vhsF-*8eTA*-F>^jt0^C_6GFcutD8E@7-6H~-9^d1V`VQCSfFvqSYiR(h4h6p^q7&%_|&JJZxIOvZgR2RY8#%Mj}lLkjc z-hb9+hINlA<)v5A-Ob?(@eefW_PvW35wU?QNq*w$<+Sv;1jkw01MQ|?45&PS@ejdB}0o-EUitT~5#jlOkn~l{;WBP@$#zT6A z4{}X5uJ^z?1~=+MKH=09FL$8>P2e~NN3x9$SsY9~ePdO*JtQI6EXwQb3y+V}mHBpN zZ`iymq?5hfJA?*384s{5;3|_V&d`0Z-$aqNFvV9SRi=3@5h~yH_DGf34quw?gOjVd z>~u3mRqHWzZ-l$Ll&wvN&vQsETvz0js}-Ey8LeI0_miouBGr8$>T`7A49zC@Sh-{E zs#|v|EGlZVB`;6S>QP#_#Gua-_fkyN>6Db#hhCL4U)44V}gpznY2AqH}@}S7zXxMU4HDOD1bEqo5Vr3=c{u$`CfJgK-qe>MKGLxfp zMOH)`0J*TmdJUO>6JJTv@2(WPwe z)d6CB)HBR`yWbXS@5{lzuHh858h_tRDF6&~E&c()w{e`I|5o7DU{A6!q)&D{%%<_wHE`;h!c+QkqF*L9_8_74w@1|03KPkX%gp+@E? zPWZH)B{BX;;Afl!*qFTLEREeBKt^+2$&*rXawZ#)TX)X865TovS&jx;p%&REkr z1JI-b?wk#`h-_9$CF2+w1QP&d;&X%i29=n`xX3t(*S`_-ODGe7n7_g3U4Upm&zzEd zOimz{CCAbPex8vz!NUNSpZWqX;MPmsR!l#o%rE+%ko$UOze2i<;v;(Y>&A*@w2%n1 z!o+SPwAVMnB87*c;9{UTdPFbg1WDrt@u@)y>E3F)1?C$HbgzkjK5d`mpxwT{y0kR% z!MrVij23o^_;P&W1+_WXg)fYC`a!>01JPP=5e}xN7Pe(zX_+IS4HG$OwPm!yLkf{_ z6#Yza8gGJkDngsj7xMi0Gz4{YMFxFk`4r^%%*Wnt_+tpt8up%P%86hx!iL+wq^+@tN39v;2M6_xCD)lGAG4a&SGSy;)7QnHCVW15;rIK(8()Dk^ZP5Lkdv9d z!0+Xq{k>J=Q@=dp&+-1R{9@!>;d70P5en%aK5QhpP81zWx^Gz-7$mg{@blBq(2V&c zNqJS|g5t%E5!#oI@e%i7~)@7qhRGr z9(ADXBg4&wE}tXEu8lX8T>SCfY4Vk`JtV`!!w=lw*6oktVO%L!}o zkHbl(GOMaQkB<&n@uQ=9Po7wBWMpK>hu(0|yN*r&-e2G?WZHNEO9KuHc((B=DHsgt8|lXcIu{mo>d(3rRSmX`CObmEPnbeu`0h*9CAXkqT$DQcq702`TCB$}olI(D=B4ws!i)*w`4(W^g3XsFi_@Z9cz}@PTe? zJY4yik6Pkg4Jb78)00~7YK)dY`Hfty;}2APQ41fcFCc8x+nT~|794yIqzI#zbf28s z9&Y2Q9pnDCw_JdpE=g*w-Du^UOrnd^=xA?$d+mv1k6P5=-DfLYR*D+Bx@^?1pbyZe zPTcX%*V^`^EVbmC)soRnm3J22?wyI$D^E(P44=uE+~-Ko$+6y?>i}v9X|B)C%5cxU zgj{7MB}y(>`jaQQ4bX|9AuDV%h|t>67S(70+kdD8KljlIg9Tjg7eDT=3!>QJ<2h zvq~P(!*}k`4fpn%cHURCE|0!2mF*tTz1h2J@g3 zm8FWyGWNtNySrEH7gtv5kz`g>z({Rw?PBl~(2Occ2lK4S#Kap>5rWhL7QrpLIyypv zf(nvlY!#lQUe3>#_}FawV!x3!^ubGN%gf6%nY_HbN;+3oY>OEWaS5#D+#c8j$;rOq z;haewi`KX7bA4|Oo-OudM5?s5CkVAkj7E^8CB(!~W`}VhXyk!?kXx=W>Z80MjxDBnQkNU*5H!d55)m5QEN&x|Zj-0gcI)73s zaQD!-5>?%ses;|)RkbqCa>^ky6*sUk3Cz{mF=e_JI!*)EZE0=}SLms2XS$NZn@h-O zUr0vTyzf?~m+~B{?t8PD+W#|mz*YcsbK;X+M zr;p8sY9(bxmXwr4Mv`ki26xbT8EQT@TIET~6w&;G=xjRU*l6=xqZ-e0{>ZzNv`^2k z6)XvM`E@3V4-Vwac61oRBRy(iPG;7TjrWfYMkkSj9o zq~+*X>_+iw?8UiUr-hDRbj>b@v_jWUDqi#mUIX7OCQe5hHqb)#kAh z4pXu^Iy!Q4axfT7RkgFqZF2<%j2f5{6hxBq7h-TJoj@QcMzQ8tMANcd(Y|fYj$>pm zHfbQ)o&5aa!-uM>s+}Ddw6v$l3}brj+>0iM>Bbz@T~T#}g0s?eMb`_~?%9zMn1@}W zW!B1QsTvE?bmcUM_R+V=da!VKB&C4qZPIm#r^_x}o{ImDU-dT~-wmp-`O60HyI+*M z_6I6lK!8sI7qFQKFw)f(N#9R3#A2~`9)mp6@GGespQ`r@4GldwIM~|S0;jawGpWu@ z9+*u<*enm`_>a`}-yxIV`JOhHve0XPCpR}&W^~!x?xSn16XEGnU(V9fk^*yNM1+Qs zkGS|Lf5s4jg1ZMxUZ7E>H9QZZxSkej=iJSR#!23c{lX8c|T5_$HcV4xaKN8 z7*f z%7f6-+S=OLNmyAKD>7{wDl#2M=hv(T)89}#1iAL%!-p_d5s^X9XB;Sm^$Q?ETfGO1 zFg5JiUTtfQ=G@%eG%b|BLHJHP_~BKyYyI_VVC1j7(ty&!|9nC?`wa3e~E9Uw6Y-q-VyC`7UsbBUzUSW~koZe%l=;h1P#m`AP{$h1D zVZ%JbCNwx^a_xQAQy?P*SahMh2xFqS!t`{r?$n2oUIc3iyvyFjP`%m;Yox-`!a|{u zU|2a97q8cz(=~WFZk!pLP=5PH@u5sdab-J;l`$T{1u}>~A@)HOT8W6|Q`UX+sXq9+ zE4(vNRP$A9-jm|SV8yauJK7i4F$kB_m7~>BQ%Sj@LI?mL4okyqaVkRLGb#u8B;3j> zoHC-Mkkri5^4*!O!K8~`mg;&ss;Z$KdfHa}3Gz+B)KPv=Wo6|`W?09eQpIYX!N=01 z8ea;hVa_AO@Fg#lq{qNTyZbP%&YiRU6xHwUQ-)4Jk;weTzm1HH+TT2%)XB-ogwTNN+QEid>O%Z`}ObU$$gB*g!cz_uAoV7V!w-&O?R zs-$OSy}OiEvB5pZEr&kEs|9$+^TJKI3skSzLdDP!^&^M6vmHS=GUp5AC*pP7*w1u~?@V$G&s zW|WJQ^PPZYsA#<9nH%#z&2wJwxkV)aDxYRZNl4mf8FkrIlBLGSvNG;_Oox`U==a81 zFyYH{i;B7>HcD&;xp%#V9DQ5?@Y%EE@x%qobo^E{P7UTQDF&H{pQm zt^SKT%X=g@uJ*YPz{lu9G9?6Yk4gLac|kKnB`buYONmQBnd`X3g#Q99(U@gy_bt}j@xYE-7ff#k2 zk#aXTx7^m;Nqc4GY%TdP`u^IL=YD!=1;hI=oI!&SaS`Cu9s;S?-bkD!`4ycjDk@A2 z6>pFaMcsVxhQXLmw$f3Nx73Yn+fZTX+O=!tEKzJ~F;k_|$KU4G2X!Ug=T;}erU2Ik zKp^BC>6hS*9%UY~Z7J@@g@50*#xag0h24ij2PUdLI;hw|)(CJi>U#qqmMa?pUyElN z|ExD!G4t+{e9cqO-8Ue@TfhN9zT8}b7=^>(*E3{3Rl|kr78e$pySfISzm1KpjJ^2k zR)m6VwY{BD)SDmPm$pJ)q279MIL{rlDRZGGq<@G5Tp}O@BO`@8zdDsf*ClySI%s<^ z6iwS(Q{}J~>*|AunHQuzBK`O%)ITD@0Ux&Wf>hdXSJ3dbS>e>Mq1r|FB<~Mxz#7;cr-g%TRpe9w5+|6 z<#-d=ro9h9bqIu*djCeY$1SqsGk<5w0agOx{eCce2w&9oP)(ow_fzrGRc;5-4a<1( zElQA~t%Mi`{xJFfshIGS3_u`27Wk;FS$rCLJj0EzHmC#x(b6R7{NN4ae(-p#YCe}6JZfv3tj8rVL-V6d`v(3ez2rlo4{vE3=4^;IXR1a z(r{e3Pm;8c6cZCu`crdgzJ7di@|vNt&LrS7w<2Eu^{U!$X~1@4#~p2VxI5;k28BXh zTwMOe@|KZPeK}gu(a{_^+1ct7SCQitIxHXn`uqEP?5vz;Um*~X&HF>ebRf4Gr_p0EDojV}MUuPRY+l0{&_x^wZ%X5a0Lx%zeG%uMCV*$%dr`G5Z3f@+jrV#&2+E zbu{GOd5$}`Zx7*YV)^Ol=rsK@)%ElN4;4-iM#QZJyli~Jsbs>z6qsgwo;oD1KOn3t zQPdH8-h3eMi79j!EV>kjOA>WtwYp(@2o73%GdTSnpQ&7Pr?cB^v@SCl&xJReX@7j$ z2o0EbLt6hGK-V=PfQw!ngllSd``cA-$M6G&gj2e$fw3rEt_=K1+%ErD;`U}})|bR< zKh-^5xm`5(8`+r9p1kFTXub=WE(2P!UOz6Jze+ zo@n}v8&FDaaQ9}a2xKjMf&X3*`3_!zdFrU|hOIKW*eqo}qX`EuUVL(@8$Ri#s|6z) z86CCZo-wzu*xB0hqvF;tQ@@|}{{6>+MU)r`UR_-)!xjYfj20{xXC(N1)yTK?q97&m zj%Ic|$#}n46Jwx(g{bHELXRXWOS50T8y&DyQ+0{0w74ZLqx`xV6 zbs{rUi*-{CZ!$cf1%|67qV9qwP+CXVJfILA3z1#S{bDfgdSm5uZOgXhbof%l)1`cm$XW_iUFCfrQUTKCv zVAjNCKrLfpVgj%*oyU(KTdCc2adlNo5M<}#QkjK%?NK5D#~pc?3J1B7z?7_63ep~p z2-*VhFtExRul*G=IAhwC;*q$@>4omJy#j;5()+H?cnAArA|3oTkF`7CXjq!xX~TG- z_JP-&ut*|HY5reE8X8x`h`+#3R6*t>Tbk3iS>GY*NU>n|ja9*hIh zrLEwh#s@@Z4|_#FYBuTb@1NtuS_y&Z|Fza9B|H1}%(#JXDhG2Ph>r#O;;saJ zU|Y*cE6k$a^_Pd*_oTc33*{0p{7Jcfy=)A&3>1YNUc@WUp4JR3cB?spiBM-Vn4cu+ zQDVu5uanWfM05xB1)h`FZ<5a$`_>c)7C`1ZK8gp9J1_u^!UG9yMgwFNW8+DHx*vfq z2)6d7DsWxujC2ax0XPGd`|qSw_-&Y$7Db>et7_sZS$CuOplYaGOf`^t3lebqjws_r_)_#Wa9)6$*%|)rK+bWaV z4i(Bg;K1c3MP{EC#yw3odWHlEO%)4M*ObFoyh*s@E?m5{insj2zFsyh`l4pg!oczVo; z2czte3AB-7Vqz;zeWpld(nrZs2L2;-BS>->Vxr1z9eYAA=PUl=TB*d$w#A~q9G1bK z>R7*L{;r+Ztrp(Ng@BIilVGP zGyV6qG&(BEbd&O0La;>>Pzd!oFqu$l zL^>Co6$L8D>c-@-jv$HI)xx1OKbJ1!73ib4v!8O3F~n~%Vkj;5eU}0!QW#0)?KlBz zb}B3=;F){)@mp@6c5fUI3LA3zr`FyILcP4I`S)yUUeh2;Yc5XN9M@o$R#x)z^PwmD zp4>!yu2b*}C=tMLNBfolP1x3ymJaH7w6wRcEG`D3bjKVeCI!OvFqP>I+~2x!31{(_ zAfFF7?zPjO0hBB)u0H#}QnFN6SwIz!c3z2eu^iQuA$BmUOwemmR_m^gUPwsDoJ@&9rAzrPI=-@GbYw(HN$EZ- zuh4^AJ%X&6Sj|J};~!leX2U>bL0;M9x*#L@lt-p9C;8_QBM+BGPVxx*n0P5j#{ftr z@h^o297b9R;dh#BQS!@8!&F>_R^7ME=Q@*?_4MxR0I2{Z8;`cJC1K=$?x6;I4pJ#g!|78e&My?;eJsuipy5>aEn{-hj;bpWAQa~FxVNYrFS z0ugLK?wtl>e0+Su-=3B=z?DE}p$)Z;74AK>07MyMW8)OBG(Cy6Iv$GqRZOog>C2k1CUMlSd2RtE-UJXi7g zQ#8IqrFO~H)ZIZ3QAB5cIxiLAWk4>H@3Z>fB4(gS0A9af4EpWX0Wk|n>;}B-lYI~T z0apB`e_mc*wZ|?>+NTD@MgSxfb{|$-Sz9}}P5~ez*`rd0!zde$9j&7cD|fH_OmA|D z$H>tVOlD?)hLVGc6g}V5h5rdR6WIIB&6tj#6lEAy@9J$%h#v_5iXA+V^vi22&yc-% zFC5b{+J_QxjQL*V^Bs@swY3s5k^IS4o_~t937dn)Iokef^zU=~Jb|(_G1i;M*@E#* zm)2xK(G}D|L3!>1>#IRKoBhXu67E`!LgGQkYtz$N5=UY9y$%d!E%|_M{-odvWX+FX zNpbSho3$?bqSZ|3mH1=FLveA`esB4uSBaot`+EDNY zE4sf+y&1&+XI0k!&+DICeP907V7zx*krI^PW2K($3SMD$z8>HG_sn-50x^?lWcu5z zS9jBDp#pRa|Fjza(`x)rtMNar#{aY$|I=#xPpk1it;YYf8voO3{7Urg<%ZkJk|Jhvp?+)i(yif9%m|K_0>_s5AT0V+T-wr-$ mnq@Hm(=>ZR=NKH0q;1nNdzO#3fHVw&C_Yq`&A "sick_lidar_localization2": ROS message OdometryMessage0104 \n(sourceID:0, timestamp, linear and angular velocity) +"sick_lidar_localization2" -> "SIM1000FXA": UDP input message type 1 version 4 \n(sourceID:155, timestamp, linear and angular velocity) +... +@enduml diff --git a/doc/sequenceDiagramSourceIdExample4.png b/doc/sequenceDiagramSourceIdExample4.png new file mode 100644 index 0000000000000000000000000000000000000000..054810e09c98d62c04410b013ab8b7e3f35859d5 GIT binary patch literal 15217 zcmd73by$?`yETlD0t%u?Do7~Z4bmaf-65c)#4yqfLrEzp-7Vc9jidt7Aq*XZbcZwy z@m{FU{yopT_xJ7pzT^96=9szby019bTIad0Kouov94rznG&D3ESs6(+G_>na(9o_C z-uw&vlks$v0DLhxKGShDfxd>>n3+4GNt@Z4*}rr&Go>_!QND6?d@aDn_S)v9t)mmf zhSdZLxyR1`5ZoccQbWh_@Bh)Rf!nwy1&13cH?tFbn@Kz-vvu{ku_Pd-Kyf=j6zgRO zyBLLn%s8Xv#zfYp`BF~x_3+~tb1ey#4a-wT{bVHal`Ncg{zCmILlV_|PID*p2N~Jl znN0>Iy5v$mVK{DmeCfK|h%c1oMyDZxewi7=^nm+jVfy`{XVBZi?4LCI#0KqS<9$Di zOg438FBZ2BGDCfTM5y9uWN!%)G@r-ze0I>Ue27S82^IUv+}gOUY_vtzY+iqZb+7qi zD>ONkSLwR&>!M&r$7XXAAJjST8R$7e@sO6t$-^7c52uTkw`;F$ZJb{Vvd=aM+C{T7WA45w z-R$>E-f7|HABSQZ-)O}Rz8CeF^QP8^cU7xJYX0HZ z2sJ3Pvd7XNFM60cjTFNBCQus=)Sa@sCp`&0eFE?jFVqpLXd4Mn_6SJE1T(|?gX#UJ z;2VuS%x?m->9XagK@)ZODUHWYpQRAjQ%Zs#)@YIu7fw=5DhQ6E7TO4z^9ZGl3mQ9? z{~T*$Pdn@iGHZ9KjF9n&G1P7R&`EW@g((fq=sIP@ek@nOEgrJVWzowZ$+hzR!^k29 z@(1?~Z=oNPpoM2PCEZJt>UskAa6eh=>+35nF80N|OD^bKn3MCCUD}mq)>@4EK|m$$!cX<`0j#i^TXL_zmjX=rmqC3B!Z*t4r?#yOX%Gt(`j>yJCX zJ4*SHFwAc_Au78~OOB>pjP&&ri&^fF3(3S$)ko~`P)6KVw2;gVj}!9V2`ag2oOo`y zi~{-ZN8sT}1h+0+`}4z3&ntW8EISxqs6*;Qr|(Wsz7^ew7ro36r@C}L z-f1G?S#y~1Tu#pM)nm6A`((JL?|ewd|Fwa`cs04~y?uJT5QexbPPJduM(fr?$Dwan zY{YyDG!SP=I>kE8?Z(ORF`d*%e09r%gPF7GZRdIGu+nhJAmhFy%afDTnDqNxOM9aR zqj4*L;nNxJ?zB|5k{y44+8wpMbhfGtZx12cT5o>fe z`*R_>@7gQes#`@gEiUyWqo5@XRlOI2W?iGpy(n7<1eS`$BU@qC?MV;|+iny~PF|l4J!F=S^=SB@~;X{sw$QhxXFN%!M+vRjG z&z7s}Op+5(3}ll-`z3+9BWFwvIx0Ky@~kI5N-2}P$@QukB6Pjv#5jmtjn!do3LblX z!BA3dQ=SWx(CO@?!b0V!sI&88gMx;fkxG8VgghI|ojj&ZskJZgElYA?x6BEXqfk-~ zKL4b$nq8g`Bt1`{s*j>cL)#c;dQy46NJ4v0TgK-)*kwU1IheH^I3 zw}p{-`^iAGZR5#Xmzjp|TeO5U&lXSLJ%5VDVCz#*Sig}KOJ3H<4%;PMU3~jooZpS_ z%0*3^RVPxpNZ9gU&x9v03yM!If;*@}3sugNdDaCdv|3B)lm(gYuhK6vanHEU-^IgJ znk=_a9u^^q4GJn5Q&k@sRVn&K(sN4Hyv zLQ2Fjr11Eo%x^rfa=r1y-F1C2R{0Z!rl!Y1w6?%=FOE>+`6MOvoQ78%m)Wrto(1|p z#fkj}L+oGo+VL6@r(+YjE0baq_c>Cm9@eU0>n)q^IW1aApPejkS5HSql%Gs=^j}tN zHo@P#()=j=sbZgE`psS!Wi{?IwPXoY_{3g;k#LynDWZUzbyZ@-hMpkd3HdHTOC`TP z+!Yf+{-F9SlgZpiDZct_=Hl?B!Q(jh^I?CVyl!%u5{FPZOCb_ve8dt?Vtv>*GTFZ7~yIYrG*ZwP2`4+wUdGM`GPu}%3A8X znUvGP=vE_qR$X}-pWqtx5OrV0PcRpHGRh?rL%Rd(+)6LA6SfULE+Nsm`Kp{c*Or*} zz={|S(8ylux{YULD@r(F<7GoFx6$PCZnNspQJPLDeS9E1g`Mb!$3nPsmU)Qkk3?Qb zS$fX2QI7Ov1l6b^>YQGJ#g<-e?S&i_{4SOafEQc*&L?3dG3d#EGg>7dhP>{cf(P?))0}q~SPcpjI&T~KDuhsPxfm&Qbq1n; zR)d|y5;GsC%!!5hwlA)bsKxppE|MJ*Y3H9j3O5}s9*%gm6)RQwvyC*=I>r%|1zB`0 zQDSRUL1^kd`=*^atPrI-4InQ;=mZOup8}?uk=OaKd1c9=<7mqoeL4Bz;bciEo1pB~ z+v|!HWUvj*i5%qqnb+(C4b*RGfIm&;|zLv)RSY3muL@?Bv}x z)z(K1C(Txkh{^g^*=Fd%j}4!YUDe59o!xS7&w!uf${%B zXk}P_xBABDlPu9WL-8n$T=ai;3lHg_!lBdkt*nqE9jMNGJfUf?R8P0fXl+l1vjCb# zj0bqK3uI-l_vElGsp4ysYw$hR`UHth%{+`xb}6I@tkjg8*9HzE3^K#5JUiC;r?jCR z4ulkrZ!)jr&xG3T^@{F$W_{E)bS+4GUh_KpuVC2hW<6{s7@n4{7nypwIyI$ises?~ zvY49CY3Ik%JNs656A9vvwINYcr8CF~IhBylH3|<~EmAC1&A(eWB8vC(a<(|S$(=ZP zA*XrMm*WU!$(BMDr-x zJLhaYt*<%u1+1G%q{<`Tg3E;PQ;799% z_;1SmC}KZA1#Wi2Nv8bxKsTb317`ZdmF5qbw+Dn>>hXcR@oq=Oj@+-No-cmzOgsE4 zn4`RLktG|-W;8wG-hGjXXlQo=i9p!v^{2j`TgaN<1I6I)EDtjCRtiE%J=Nrb$$s3<^TX_jY;_Z7AoNvzv@=B(LGsbsTZ zZed(^T3)#Yj=aQwa04xg7;R@i^twc_&Rw)8Y-lMVDlI^yFQcOgk);KoqoMU-quu18 z9J&6Z9?d(4YUmRh+85Y0v^0!Xw_le!`jHT!U0wKN^(GH98ro|^G_l+(T@J?j>N5@F z>hmVg)u&kQ0c)W&#?|%8(!Wl+t%Pg!&*N7YQVvn#j!^ymysM)abic3nBf0uTIdt`j zYlVArJ^UJY+!w^XU-$6E|9$-TbN{~YO}~SVzncdx^Zt74zqiYeEEvd&ieA> z#;#FyzgR|}@{oP3L1I_!_ ze`2}fl>fhZdEV9^tGBL()>S|P2OI6`)p4!F3Nil-&C6?Of8K^_06a=+8kRiRkz8;+#8Oa5i;6BPgD!?9?;{h|zwq#b(FEawcgR0sTEt~* zN|A3m^FiMkd~GN%ARyp6=ABoljq&oyYG~71enFI_$gpjJR*_m`)r{BW`3Z3cZkm>g z3j0d`s>+H9fo;QqmWk`^lE7=lJ82l+Do=AC4fWOOu@JqFhxB?i9e-n+J2WaY4IIBO z;$D;Jb-KS=UtfRwo>haYc^j;o{cMqnk&*FmV?1)`Ic9O^qan~)H+lRfyzW`?^Yfd- z&yIgC1;lq}#Tr`ig60#m875V%;nOK;Xlcm}TS`=hzKzQB(i{lDA+@<)4_`ynZPhaI z@o6)D%E&MQ5;a3Acu-`r3c@9rB;aJVyU^K{m!HpBt-KNWT)&yjWs1YR=RPEqly7Tg zAY++Lh$@l&rH>1@T9J~?bgd@8uC6W(4NaZP_MOhDIv1#=W!^3}7S>3Sz6Iy-`0noR z*_nGKf_G9sd{U`86zRE&2qxu|b1rxt42d%CRRw(pUdCEJpmbbOQ88bh z)Oxh|AO_z~s3Bv440k(4pd3ugP~+kU*7hL4fCW0lh7Vq%!U9_1YSFl{VRJOo06((2 zD9Fnj=u3Exf7IXIjS#Zf8rHQ`Q&FK*%?(aTAs1|c9S!A}E0;r{@nadgdwZL`(cx6m zZWfB_g)1v7D(aOSW?ck|Eyw|xjM}xeHA_UctXPeUV|~0~R+ha2HqY)XA^I&IXj4T? zBD4{9(TpV_n4%h_xZz~nkZ%TN`^0ynyd>OpEDGgqdKhMFT~1GBQ4vefXY<0VnFvBq z_*SlEEeiufse07sP&_(L?nP?~C_h`{@m#KIM)QFmoPx#ct!A0;AdgEu}iU)^GuY@v)t*h}9 zA<@Aa@?m(voGD1v-8=7Glo?nY<{9(;(-2h(k79$mkttdZX1$6IW<=G>j6XJU!e(n= zJFBh3fTL};@@C=F4HkTd8Kv6qykF`p26Yk0n}O+f`;2tp$f2PHXD*tTvqgO$&8^X} zv9X_W(kUg4O-Vj@ZDVt0BEi=`yfxm{smV<; zX%#;4dO54@`i#|RI0=e&YN!hEM&mj?YuXVOKQMG@EPwyuZIc2@aE1J>lmX zkNv}LcQ19+(8x%FzO`!5!QsT@26&Fuq`u7l&;5`H7csmejmSG>0t;Hi|5Awc48QjowN053W&dn%N3K*K|{M@Ix5$Vh5z6qc8+25nUmnmV@6H^+;zv)j&U=>hidIQmVfRC^B&s_hBT zqb^Pj)2q9;*=YP!>Q>q)ee3rJ<$pd0_y*_#=^D`|i~f|ZuCB)LJ068exK{DZLlNXm z;^;f^8oj;A^XX?+bK_*PdNoSO7WPuLTqA~ywa3^iZFO_qiTovvi$3*>5Mv*E2Qvz>Y7x><3W#c(Pm5d%U2 zcyT}ldaE&q;^8c!9%YSCQ?(OZSYA%VQ9J~JiyH*iVMMlKq+B^F^{(dxVFN2FF>t%- zvN4*3;a26l&AW{4A(~Ng`0I@H^z39CtE;l78*KITJj2{eLwV}={Pp&gWM3#I3uuy_ zT6^js1m&v2>g$En-(5`Xr9Z`!Kdj2n$jHdfmLgTpR^XWEBZ!WS^xb>>dm4sSc^4Kk zmxN)ZqUN1HjSXJK`tncrsH7a7oM_04$%xntnaNb1KTlFK;6)(ye|)wbHLQ=PFGb}h&2Uy&CRVX|BB(6)I)A=Zhb~I88Q2UnfLq?s?TK;V+Z@TAnfH|*7sKt z$iZ~ttSxKYxu7!AQ+f`rEG5u)z42V__0=@5qNX^w-IOe*Eq+X$j2}bv;hRF&&tvm3L<0z zP^G+tG)H*LvwV(srpi((0>PRhp3z6DlYH{~_ZKnL`OYrE2`3Xvk;)?RHB!Ai7^RM@ zYIzM{vX3Pd7qgB4^7$t~p!JTMlU08XH1?7gtaV-6+5$*5Sg)_9W{hlizGx=C-5yGj z8XcYGo-sDpHB%2Or-k_?zHH_PC(26*IY2LSM>DX2$2$7w}b+2Hwzg`#3G zr`fGT<1gfMB)((S&{PBOSJ97WP9<}%0c}^AW_v9;IeBq$@p=}Ocz!eT+XJ7tEQ9L} z#A;4iSy{GynX-}8N0{rnsCm-%yG5Q0J^IrW?N>@MK!p^K=;N*3Z^T9qze_*{(w{xu zOj=r6+8Qrkp8D*7O~jmAQbO_FLzOKdF>yMw#_RIp$u#e=tAl>d!@aL#qaoX;G!i)8 zmLx!q-Y5e&JTWnGZQ$O~%W>SChK7dRT$$@?y1J_(91q`t6?o8WP)6(f5Uc6nWa7GV z2Vb`%!3O zUe=X`oDMFVUpHj8{{Ekrn%P_OF;30?sjncAoj?U#$=`FBbkSy{_I{o)sd-bo zqSl^p6Kt0uw7BeFm}2TDx88A?gL!${m1DicxZH0c+6ue&=iolwp?>NX3-^B>ExH$b zlxt>m&jlN28U00q)RpG?o_h8(c%F@IdS`2v&+eDZE+zk8g*wn{_tvk0)BXW&|8Fv$ za>!ff?jP|75&8`{zizxEzUzqBo5C zb6NC#AQP-|$r*lc2Wkz|@Y0QIxK;p6#d6PMLo)}dI|{WNL>CRx<71Ejk%l8z}SKVNQ=)?t05sH?N9i;;n0yaDba zvxIDb%gf708>y&#vYi%)90x#%vAn!IW7kerrHKrha;`PF&u2RY6mVr)6F#lN%?H6d z#{RVr)Bn;8H%-dx5F$Sy%552r>=p8~r!o!!vM+`Fw?PRTUN7yu285QPU)6CVO3e0>1D6t9WL7u7sP|AF3)b!;wHOHNFsY6l#Fc&^{Y6O$=+NeC6_=K~k zMZn!BpmM54I><*76E+~DXLEea&BK$21t|oi{^1sj%G>Iysua-IuO8Z*l$-ae?R`i| zwMvx)&orFfa6oO*}YDndOl9@==4&5QK9 z^kDK;BebeAgc6>doR~jlG+pQjH?OO$b(^TL#Cz;~`B4FCq!A(+_*sz9Q1$y07e~jT zp`lkMT~Q26F*@I0QM2&6yKB_w3g$LNXo;h*y+&kwwEMKU{yb6mU{u&FkZPL~$WsT0 zJ85m)!B;6QN}lE5Z^m0q3EmJTIljqebV;?7MT2vqXSx2+I-fzT?^|28duO&l6d4#8 z%*F#1AJfIa%35Vs%NN|tgk_a)s_5)obt8VQ42$6vck_E33JRv2%>EBCyF@GGTV!v! zmEspW!l}0A4U)qDOkS)$LD=p>tdZyVMIDH0K|xsC6(kpCKA>EztlWQseH6A4`*<^_ z>+D#f7kThAD6Z0al!%BZz!VVp($AlP>giP@ty198gdo~h5jhze3!6R|pY!rM&+`ji zxFd)X_Z^3Rfn!c>tw83N)|UCUubbKT+$Y54Sc6mwKvX?6`brU>&G8ptSdvc2zCNWu zj9d306atR9Wo7mtBN-UE1u_L-RlwYx@A*%Fa9lYsIQV$jcpD*ePY#p5y&;hB;uX)U zy3*2t!fYr6!otMF6%QC!HdXQdzIlE(=ADOO_7NkcW>)ZTL4?a}g=p9%9W=$*KnF#y z067&rxzu_!l?D-|R>O=QRwNHKKEi8U9&X&h!ND;{PZV()&3$Is3ERr$Q2do#lxcxY zPE1IJk{9Xfdd+7(?ZAez1*t@S=l}+aq9Pu?$U>3(0Lk=>j|vM4_8Kp!@>JG;;ilRf zkOnzyn+41BZ`5QGZir9hgT}lLPuKfwpM^qKmYr;FmIzLa=0pZPpR4@@oe`;{XEFWV zl@Ep8G*Tx_8qjOs!rQ-|kK~*dhf=RhLp>f3{fX1Jd6&sn5LLRSG00LiI6%F3_d%`` zL#8q ziPA7Y(j)1JN={z>DRN+#Ekc43B*b8q6CjcREj{O~M38{&!QBYGwvX3f;OWKi$Zz5q z9|r$C$a4iK;&Hd4+{Ne*A(9#0AfPhh-<1WvBI#-V|X$TRy0{sN7o-Ev1{4 z3Pe`2q0#bP9QUpO;R{UkR6H{#hN!&3X;6QWNRteODidq^)^Xm-*tlt*+kQ-tO*okc=4yxi))>ZZ~+;lMi-_+tYQ`6%`sN0s?|KBhw(Y zSm&`CyNm!0HBCAi%@b?SlaIN%^p+^!1PkS2`Ck&qh^M2obNtgwU+p|eHaX|q-wG(= z;`CX5a>Ta;qj3SZ{ajcxxox!}=Ff>He(Jva6~2rh5oc6l1Qx?X{6C$ZF+(=f+oAa$G*Bot}R+bSKpXNQnWEe&{ngR+P=iCHL4L0BHp9y1hx%Utcb#f!g9( zilmcMrFmBpb}rVQCnwarHSwWsqCxWWNkGw2=4b`6O)sh zC7EPY*x^d8t2@A`3{pa=KBP|A?cOy#Hr$wL#xip&<=PaSPIMMD~kmQJB4$=^^&mQzu+_dh>fj(<73m-?d4tB_Fu&03#{M5%xrw~D){4C{0{zskwI`5I`>n% z_fAI@V`L(YD(_oRL6@1^=gJcqAIb3GQI7X3TjsvK&$z3TZ)KP7>zNv{^Ihp`Tz z=Bmc^C)$}A-M^>1bgi)jvSi%Lm@ID}?dJL>0}xt~(HTH+tc_R+O9j z%F2qf`e&ire8^S2dW~#Sc)?b`<1^06%F5gC_B?zD=$n*Bj0o1R987gQT$VmRl|+Ms zgO{wWl|@c6>!f;_5g>01FakTiVdyr43?eSGR&Mcfj<|`P%M9eVbcvRFZ;K1trwU0C zC?m;XZwFY646gEG{}f?EWH>0m8?F?MVbb@|G2+cnrk!|@oD@{|RQ#yC%e_*-= zslrWE$WsRy>_O@5piJj=C)|?rIz=a9MOK4a4J&AG0uOIaLBV^T-|^;>b2+}UXPM2N z%NFG8LDoD$rcj2{XhdDf%q;6%Eis&uO6tS+jk)AQB_Oob)iXRaJ`(x})B_S2e}yc) z5LH80(hCg@{7-suAe+?b3Q{9)?~q}EGHwcpmm3DvD|4NbRNL&ei%?{}Ze;b+QZ$ox zHgJ+qYREt!MV~8)29w`O^iE!6_BsS2iT9>E0Y|K^tc1zS=g}um0c0XH%X(d-m_3vS z5@%~vf|RqrUuyE{a}!*E*5%l^MQRKBslVeVF!+_%*SpIE2Q+MQe7dPdc)dc97`?p0 z`s0yAesM*`P;Wf9WyC_``B5nJp=iZvI2Y8(>mkqsKz_dXC{RKhNNnV8xALJ4q}4DY zRY*ThpFCOkUt}3Aa%zNu%@(z=Sb{ufm%ss4wx`{&YRIG(P}lTkPh^|!ayb5mw?S`E z{-{;Hjrq7#N1@?$Y+>hvhCiY#Tr|RZTzliB@608%-v2k0V57x1PYR~MSD=l^6x2Z| z!K7E>@yg8kb`7b`O&(+6UsA{0bHpl?KqJ1++Kz7w*Q(XcSon*WlObLpH$7tMl4IPa z{^Ey{A4w@W$jR*eCDvqT+EO*59MzdY(e>HBz4a0`7RL~Je(nOaSvQ={tDo#oVe@-G z<7RmOc?nr8PsOs9(4JQ@4BqbGC4!pu-U9_r@a)%y-s0a1F1PRPy+btk^NIXWi|eHNt;XPI0X~ z?)-mH;k>F>f_(DTrv%PlFNHb(E(?M`UcC1CQ@i{}yV5Y;d?J7FKh{J8?h6TD`*#iT zA63FX<>4!i1B%DsG?3f;pNhwSRBZ#)|G!+j9!b>LFK`FtDe4^(Zbm%1-K)axcvS^Y zdnn71-_Nd*XhY-ipZBR8?`NjznP8x zQ|s@3(BhX6a=Dl4^$b`E+)$lbzzA@=W+<892mKdEO3FC)mLFIP7@m<$pH;uTGeijiR>dN{WgUM~Q%=n7ZfQZ_`9THrL}J z;Mf&&{Wf~#=cOEyp{Bk2$82%yU(SmnQ3TWz(RPd6l&TFFE56D8{B^!au?nh%;;<*x zYq%raOVIt;D467cAJVkfhY)AE&ugQ@cEBQticI=}ykEMnH2#c#K!MzsvOYjxLeAOP z<&MCbv48A)((DLc!Su-N>3o-&O&goS{?5R>iqli*#g1oCW;|~H76khcikW!B z3wDaGRF3({e&K47Exm%`Ez-l8WI=7qe!7&J0%iXR__i>go|tGQAVf!wS%%J@;3iEU}g z%T>VlwZR8z?tPa0hmp@LsF)4)D{0WxDBRqhg&to1t z-)y!yesvL(KihA5e|5&*VX5!D`pOM;nasJkzPIE7M0CBfe**PHnVD!%cl{A^oropD ztZKNSpyVR<9+f>7wkZ7aTz+cHaz9HgOS8MX=?u8ICND}18)U2m*tVhMu0LoAi%qf$ zy)O19r%U^K&!a*hR;QzqFzbtGLuUHp9-3Hpak_p;q7pJ!H8s*a^nHM(M*jX8HGuTLadZf3<2y&VFEEvFyCN8F+0!fKnPsP^Ev zL@$6M$%Cw47xeDv3=8Hclctz+?ae7$`a1>W!PAXJm9=FCz1x8>05bgQftpx5L>nTioViw-+-<4trXUY-HoBx}1?2 z=Sg=ejqQ4eH|Z&xmzvt=f>s0tz9TFO0I#aQlGci`SI5IcagbihkZ1*Ozn*D7HTu^#v zdKb@1yozKY&aN@0BK;%#;-~_+j&Orq^dg6{lUn;qs*AI|qscAV&T)6h!m`)I;Y@>A1><*e9lg`g ztuHXMF#UIr^OVxgWj0TSOUPw}&Q~=_VjUk@^AcbwKD-MHnw>~060Y~P4E><*IY`JQ zp3|d$0rf(CV!fx(c(Eq&b;v97g{1-A^xpQxR)dByFZJFdRuzZszY<6%YfYW@qEEnzuzJdEpj z3sNP@i$`-fBiQP!53kL@Cm+~Ykx{;ny(6+KQ>Vt&PQRm=$g4Ym*eXF}Ksv*%OU^wB z(unv77@XL%!UG?JLDp3{(KbBE0_OLTw$p?6PU5L!j8H=H`OXE7*T2_@cS`q!6u;crwusKix@@H)d$yk-Y<`h3o_YzKjMft2 zu*n~|%fzCnaUlm^Ie3C~N~Q!$hYRrUg;LkL4_4%wP{2(6Ny$Ovu(>SCJ(l~fjm6ri zqFxxNzino_n&>YVc#nnN>Mdq=7-h7EO*{%v_=6?V2V3f!D-tZZgYfMJrO}ZBZMMO8 z6oQA6Q$jComsV@}X}(7NGPi2@>qYGj_u9<|Ris7Qvaq?k-C+#sG{N;7r7Q=tR_!F{ z{%%ItGg4K*ghYykIAHgEH_K$4WxE+`B=Ys#Stkl3hd>DbGFl{2LHH|R;$97Fd0Q=Y&+2g8Y>uigYPW?dkRY>S;^|$MNcG9Y8N6gWzS#|r zU_)Z7?wE5KNKm&sz>bYrDp2&bdFph}vMxtZ`YBrqCL!B6}js5$qpm6zKZ|?0m7d?w58m~a=B zk8EuXjIHUmBZqHP)zCCJ=N(v=K)B{6;9b6Ja&_V2vy)_3n>fH81UWwB@pXgo8f@Ds znuR6)hTAQyb$1xR`2WD-DH(sO?_-@bNMTn(DF^J#|L&Fq97|eM?X@Gdc6cFQ;j>#Q zTTRNM4ToJ!O$44Tct*ar1F3iK=+?lp{42s0rj@1wMVywCvCGOtO5IOFsjzq$=mZZ| z+&WnYWq3pv4jyh5@GX1}x?3wY_$F|>y#^TK-I~e#aSEzunfL zqFU71f9YtumBXDKIK!?T5hURH+Ch@vxRE0bTg5~=+RYbE?x>IOvy(urmS}euu;v(}I2kiFqv?U(YYx#F@Vd<%E$Mkys5$mfh zE^T$!8?LrzWJV_hgZ)0yHMjX!#y(zcajCszWPZ!+-Zn~!cpSL!-dy$>-sdWXX{4ge zK0_eRCK2~I%~Bk(`2E!U;){e~#=IrWXLu(W#qZ~|w&ZFV%4kG-9f$*e>Zf`=u$7fH zwC~=&D=|~Z{Ad>Jdc*Tv=dwE8X(1+JOzFmwQe*!SB@#HTf!iee0<p~VO9Uw;k<;s|RzW$*lA_Qt-u^hvq zf3;ceukUX=7EE0^n_Ax9#b4sQCULD1LyUSAZlS-tqGc>j?m$Oms "sick_lidar_localization2": ROS odometry message type nav_msgs/Odometry\n(timestamp, linear and angular velocity) +"sick_lidar_localization2" -> "SIM1000FXA": UDP input message type 1 version 4 \n(sourceID:155, timestamp, linear and angular velocity) +... +@enduml diff --git a/doc/sick_localization_services.md b/doc/sick_localization_services.md index d00db54..f017067 100644 --- a/doc/sick_localization_services.md +++ b/doc/sick_localization_services.md @@ -12,7 +12,7 @@ gen_service_call [options] ``` with the following commandline options: ``` -: name of command (service request), f.e. LocIsSystemReady or LocStartLocalizing +: name of command (service request), f.e. LocIsSystemReady or LocStart : GET or POST : parameter as json string, f.e. {} --hostname=: ip address of the localization server, default: 192.168.0.1 @@ -44,7 +44,7 @@ The following table lists supported commands using `gen_service_call` (supported | LocSetOdometryActive | gen_service_call
LocSetOdometryActive POST
"\{\\"data\\": \{\\"active\\":true\}\}" | Enable or disable the support of odometry to enhance the robustness of the contour localization algorithm | | LocSetRecordingActive | gen_service_call
LocSetRecordingActive POST
"\{\\"data\\": \{\\"active\\":true\}\}" | Starts or stops the recording of sensor data | | LocSetRingBufferRecordingActive | gen_service_call
LocSetRingBufferRecordingActive POST
"\{\\"data\\": \{\\"active\\":true\}\}" | Enable or disable the continuous recording of data for improved support in critical situations | -| LocStartLocalizing | gen_service_call
LocStartLocalizing POST "\{\}" | Start the localization | +| LocStart | gen_service_call
LocStart POST "\{\}" | Start the localization | | LocStop | gen_service_call
LocStop POST "\{\}" | Stop the localization or the demo mapping and return to IDLE state | | LocSwitchMap | gen_service_call
LocSwitchMap POST
"\{\\"data\\": \{\\"subMapName\\": \\"test.vmap\\"\}\}" | Transits to the given sub map if close enough to a transition point between the current and the given sub map | | LocGetLocalizationStatus | gen_service_call
LocGetLocalizationStatus POST "\{\}" | Returns the localization status | @@ -78,7 +78,7 @@ The following table lists supported commands in their shortest form: | LocSetOdometryActive | gen_service_call
LocSetOdometryActive
"\{active: true\}" | Enable or disable the support of odometry to enhance the robustness of the contour localization algorithm | | LocSetRecordingActive | gen_service_call
LocSetRecordingActive
"\{active: true\}" | Starts or stops the recording of sensor data | | LocSetRingBufferRecordingActive | gen_service_call
LocSetRingBufferRecordingActive
"\{active: true\}" | Enable or disable the continuous recording of data for improved support in critical situations | -| LocStartLocalizing | gen_service_call
LocStartLocalizing | Start the localization | +| LocStart | gen_service_call
LocStart | Start the localization | | LocStop | gen_service_call
LocStop | Stop the localization or the demo mapping and return to IDLE state | | LocSwitchMap | gen_service_call
LocSwitchMap
"\{subMapName: \\"test.vmap\\"\}\}" | Transits to the given sub map if close enough to a transition point between the current and the given sub map | | LocGetLocalizationStatus | gen_service_call
LocGetLocalizationStatus | Returns the localization status | @@ -98,7 +98,7 @@ gen_service_call examples: ./build/gen_service_call LocSetMappingActive POST "{\"data\":{\"active\": true}}" -d=2 ./build/gen_service_call LocSetOdometryActive POST "{\"data\":{\"active\": true}}" -d=2 ./build/gen_service_call LocStop POST "{}" -d=2 -./build/gen_service_call LocStartLocalizing POST "{}" -d=2 +./build/gen_service_call LocStart POST "{}" -d=2 # short form ./build/gen_service_call LocIsSystemReady ./build/gen_service_call LocGetMap @@ -106,7 +106,7 @@ gen_service_call examples: ./build/gen_service_call LocSetMappingActive "{active: true}" ./build/gen_service_call LocSetOdometryActive "{active: true}" ./build/gen_service_call LocStop -./build/gen_service_call LocStartLocalizing +./build/gen_service_call LocStart ``` Output examples (test against SIM1000FX): @@ -153,12 +153,12 @@ gen_service_call request: LocStop, response: {"header":{"status":0,"message":"Ok curl command: curl -i -H "Content-Type: application/json" -X POST -d "{}" http://192.168.0.1/api/LocStop -./build/gen_service_call LocStartLocalizing POST "{}" -d=2 -gen_service_call LocStartLocalizing POST {} --hostname=192.168.0.1 --verbose=1 -INFO : curl send http POST request "LocStartLocalizing", response: "{"header":{"status":0,"message":"Ok"},"data":{"success":true}}" -gen_service_call request: LocStartLocalizing, response: {"header":{"status":0,"message":"Ok"},"data":{"success":true}} +./build/gen_service_call LocStart POST "{}" -d=2 +gen_service_call LocStart POST {} --hostname=192.168.0.1 --verbose=1 +INFO : curl send http POST request "LocStart", response: "{"header":{"status":0,"message":"Ok"},"data":{"success":true}}" +gen_service_call request: LocStart, response: {"header":{"status":0,"message":"Ok"},"data":{"success":true}} curl command: -curl -i -H "Content-Type: application/json" -X POST -d "{}" http://192.168.0.1/api/LocStartLocalizing +curl -i -H "Content-Type: application/json" -X POST -d "{}" http://192.168.0.1/api/LocStart ``` Note: A REST-API can be served with tool curl, too. `gen_service_call` with option `-d=2` prints the corresponding curl command, f.e.: @@ -169,7 +169,7 @@ curl -i -H "Content-Type: application/json" -X POST -d "{}" http://192.168.0.1/a curl -i -H "Content-Type: application/json" -X POST -d "{\"data\":{\"active\":true}}" http://192.168.0.1/api/LocSetMappingActive curl -i -H "Content-Type: application/json" -X POST -d "{\"data\":{\"active\":true}}" http://192.168.0.1/api/LocSetOdometryActive curl -i -H "Content-Type: application/json" -X POST -d "{}" http://192.168.0.1/api/LocStop -curl -i -H "Content-Type: application/json" -X POST -d "{}" http://192.168.0.1/api/LocStartLocalizing +curl -i -H "Content-Type: application/json" -X POST -d "{}" http://192.168.0.1/api/LocStart ``` ## ROS-1 services @@ -196,7 +196,7 @@ The following table lists the same commands using ROS1 services: | LocSetOdometryActive | rosservice call LocSetOdometryActive
"\{active: true\}" | | LocSetRecordingActive | rosservice call LocSetRecordingActive
"\{active: true\}" | | LocSetRingBufferRecordingActive | rosservice call LocSetRingBufferRecordingActive
"\{active: true\}" | -| LocStartLocalizing | rosservice call LocStartLocalizing "\{\}" | +| LocStart | rosservice call LocStart "\{\}" | | LocStop | rosservice call LocStop "\{\}" | | LocSwitchMap | rosservice call LocSwitchMap
"\{submapname: \\"test.vmap\\"\}" | | LocGetLocalizationStatus | rosservice call LocGetLocalizationStatus "\{\}" | @@ -214,7 +214,7 @@ rosservice call LocSetMappingActive "{active: true}" rosservice call LocSetOdometryActive "{active: true}" rosservice call LocGetSystemState "{}" rosservice call LocStop "{}" -rosservice call LocStartLocalizing "{}" +rosservice call LocStart "{}" ``` Output examples (test examples against SIM1000FX): @@ -246,8 +246,8 @@ success: True rosservice call LocStop "{}" [ INFO] [1626875300.376469527]: SickServices::serviceCb("LocStop", "POST", "{}"): success=1 success: True -rosservice call LocStartLocalizing "{}" -[ INFO] [1626875302.384810233]: SickServices::serviceCb("LocStartLocalizing", "POST", "{}"): success=1 +rosservice call LocStart "{}" +[ INFO] [1626875302.384810233]: SickServices::serviceCb("LocStart", "POST", "{}"): success=1 success: True ``` @@ -275,7 +275,7 @@ The following table lists the same commands using ROS2 services: | LocSetOdometryActive | ros2 service call LocSetOdometryActive sick_lidar_localization/srv/LocSetOdometryActiveSrv
"\{active: true\}" | | LocSetRecordingActive | ros2 service call LocSetRecordingActive sick_lidar_localization/srv/LocSetRecordingActiveSrv
"\{active: true\}" | | LocSetRingBufferRecordingActive | ros2 service call LocSetRingBufferRecordingActive sick_lidar_localization/srv/LocSetRingBufferRecordingActiveSrv
"\{active: true\}" | -| LocStartLocalizing | ros2 service call LocStartLocalizing sick_lidar_localization/srv/LocStartLocalizingSrv "\{\}" | +| LocStart | ros2 service call LocStart sick_lidar_localization/srv/LocStartSrv "\{\}" | | LocStop | ros2 service call LocStop sick_lidar_localization/srv/LocStopSrv "\{\}" | | LocSwitchMap | ros2 service call LocSwitchMap sick_lidar_localization/srv/LocSwitchMapSrv
"\{submapname: \\"test.vmap\\"\}" | | LocGetLocalizationStatus | ros2 service call LocGetLocalizationStatus sick_lidar_localization/srv/LocGetLocalizationStatusSrv "\{\}" | @@ -292,7 +292,7 @@ ros2 service call LocGetSystemState sick_lidar_localization/srv/LocGetSystemStat ros2 service call LocSetMappingActive sick_lidar_localization/srv/LocSetMappingActiveSrv "{active: true}" ros2 service call LocSetOdometryActive sick_lidar_localization/srv/LocSetOdometryActiveSrv "{active: true}" ros2 service call LocStop sick_lidar_localization/srv/LocStopSrv "{}" -ros2 service call LocStartLocalizing sick_lidar_localization/srv/LocStartLocalizingSrv "{}" +ros2 service call LocStart sick_lidar_localization/srv/LocStartSrv "{}" ``` Output examples (test examples against SIM1000FX): @@ -319,7 +319,7 @@ response: sick_lidar_localization.srv.LocSetOdometryActiveSrv_Response(success=T ros2 service call LocStop sick_lidar_localization/srv/LocStopSrv "{}" [INFO] [1626874812.001814744] [sick_lidar_localization]: SickServices::serviceCb("LocStop", "POST", "{}"): success=1 response: sick_lidar_localization.srv.LocStopSrv_Response(success=True) -ros2 service call LocStartLocalizing sick_lidar_localization/srv/LocStartLocalizingSrv "{}" -[INFO] [1626874813.582692773] [sick_lidar_localization]: SickServices::serviceCb("LocStartLocalizing", "POST", "{}"): success=1 -response: sick_lidar_localization.srv.LocStartLocalizingSrv_Response(success=True) +ros2 service call LocStart sick_lidar_localization/srv/LocStartSrv "{}" +[INFO] [1626874813.582692773] [sick_lidar_localization]: SickServices::serviceCb("LocStart", "POST", "{}"): success=1 +response: sick_lidar_localization.srv.LocStartSrv_Response(success=True) ``` diff --git a/doc/source_id.md b/doc/source_id.md new file mode 100644 index 0000000..1ca4638 --- /dev/null +++ b/doc/source_id.md @@ -0,0 +1,91 @@ +# System setup and source Ids + +This chapter describes the system setup, messages and source ids. + +## Background: System setup, messages and source ids + +System example: A unit (e.g. robot) has multiple sensors (e.g. a lidar and 2 wheel encoders). The localization server, for example a SIM1000FX, is used for localization. The sensors communicate with the server using sick_lidar_localization2 on a target platform (e.g. ROS1 on Linux). + +Communication: +* Sensors communicate with ROS messages and services with sick_lidar_localization2 +* sick_lidar_localization2 communicates with SIM1000FX using UDP +* UDP input messages are sent from sick_lidar_localization2 to SIM1000FX +* UDP output messages are sent from SIM1000FX to sick_lidar_localization2 +* sick_lidar_localization2 converts UDP to ROS messages and vice versa + +Example: +![source_id_01.png](source_id_01.png) + +Source Ids: +* Each sensor has a source_id (e.g. left wheel encoder: sourceId=150, right wheel encoder: sourceId=151) +* All ROS and UDP messages contain this sourceId +* All sourceIds must be configured in the SIM1000FX localization server configuration file (yml) +* SOPASair (web client) is used to down- and upload the LiDAR-LOC configuration file (yml). Modify this file to change or add sourceIds of your sensors. + +Example sequence diagram: +![sequenceDiagramROSUDPMessages.png](sequenceDiagramROSUDPMessages.png) + +## Configuration of source ids + +The Source ID can either be +* set individually for each UDP input message, or +* configured in launch-file for each message type and version (this works only if there is only 1 source per message type. E.g. for 2 Encoders this is not suitable). + +![source_id_02.png](source_id_02.png) + +If no source ID is set (sourceID: 0), the default source ID configured in the launch-file will be used as fallback. + +### Examples + +Example 1: Customized source ID configuration for 2 wheel encoders: +* Source ID of left wheel encoder: 150 (configured by customer) +* Source ID of right wheel encoder: 151 (configured by customer) +* Source ID is set individually for each wheel encoder in the ROS message +* ROS message EncoderMeasurementMessage0202 of left wheel encoder: source_id=150 + * sick_lidar_localization2 generates UDP input message type 2 version 2 with source_id=150 +* ROS message EncoderMeasurementMessage0202 of right wheel encoder: source_id=151 + * sick_lidar_localization2 generates UDP input message type 2 version 2 with source_id=151 + +![sequenceDiagramSourceIdExample1.png](sequenceDiagramSourceIdExample1.png) + +Example 2: Customized source ID configuration for 1 odometry measurement device: +* Source ID of odometry device: 155 (configured by customer) +* Source ID is set individually in the ROS message OdometryMessage0104 +* ROS message OdometryMessage0104: source_id=155 + * sick_lidar_localization2 generates UDP input message type 1 version 4 with source_id=155 + +![sequenceDiagramSourceIdExample2.png](sequenceDiagramSourceIdExample2.png) + +Example 3: Source ID configuration by launchfile for 1 odometry measurement device: +* Source ID of odometry device: 155 (configured by launchfile): + `` +* Source ID = 0 (not set) in the ROS message OdometryMessage0104 +* Source ID = 155 set by sick_lidar_localization2 in the UDP input message +* ROS message OdometryMessage0104: source_id=0 + * sick_lidar_localization2 generates UDP input message type 1 version 4 with source_id=155 + +![sequenceDiagramSourceIdExample3.png](sequenceDiagramSourceIdExample3.png) + +Example 4: A robot uses standard ROS odometry messages of type [nav_msgs/Odometry](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) to publish odometry data. Standard ROS odometry messages of type [nav_msgs/Odometry](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) do not contain a source id. In this case, the source ID must be configured in the launchfile: +* Source ID of odometry device: 155 (configured by launchfile): + `` +* A robot publishes its velocity using [ROS odometry](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) messages +* sick_lidar_localization2 receives the [ROS odometry](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) messages and generates UDP input message type 1 version 4 with source_id=155 + +![sequenceDiagramSourceIdExample4.png](sequenceDiagramSourceIdExample4.png) + +Note for source id configuration by launchfile: + * A target can be used with different localization servers with different configurations. This can simplify maintenance when source ids must be changed or adapted to different localization servers. + * Standard ROS odometry messages of type [nav_msgs/Odometry](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) do not contain a source id. ROS [nav_msgs/Odometry](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) messages are supported by sick_lidar_localization2; their source id is configured in the launchfile. Depending on launchfile parameter `ros_odom_to_udp_msg`, ROS [nav_msgs/Odometry](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) messages are converted to UDP input message type 1 version 4 or 5: + * ros_odom_to_udp_msg = 1: [nav_msgs/Odometry](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) messages are converted to UDP input message type 1 version 4 (source id by launchfile, linear and angular velocity by ROS message [nav_msgs/Odometry](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) + * ros_odom_to_udp_msg = 2: [nav_msgs/Odometry](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) messages are converted to UDP input message type 1 version 5 (source id by launchfile, position and heading by ROS message [nav_msgs/Odometry](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) + * ros_odom_to_udp_msg = 3: [nav_msgs/Odometry](http://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Odometry.html) messages are converted to both UDP input message type 1 version 4 and 5 + * Default value for ros_odom_to_udp_msg is 3 (convert to both udp message type 1, version 4 and 5): + ``` + + + + + + ``` + * A customer does not need to know details about source ids - except: "The source id used in the SIM1000FX configuration and in the launchfile must be identical" diff --git a/doc/source_id_01.png b/doc/source_id_01.png new file mode 100644 index 0000000000000000000000000000000000000000..651e6fa7d4d402ee4925198d9dfeebeb1754bd62 GIT binary patch literal 47584 zcmb@u^PD+gQ`OyXtof@tqRQB;0$k2 zbrl3c3z3IPX?kUBWlGw!>daizwD?5I3)armQ6+7$#n7{VBVDF{aW}*Cb^PMS3~qPg z>+*Wq(s%5o?{bM3v1V~qLgLZYJ5RKQLdt93>O|beN?O!OEmgvRUqsyL7~r}SEPinv z;6~CF%DXOha4qJVb>N=_Rbv3J|9b?VWXn_h??>gWIi~;q=0f}b^UwFp9hQ~y*JUrQ znz2j9S)WwtvN2Oyz2ZnV3sET~3Rz}TVvPUl?CJR+B$p!!O0WKkflz8`3M;-hPxD7Z zgJ@*Pel2f`G^wB8V-l6&Rx>HALgz(p*N{<|?$Af(hR)<9;=r2$HTk`W6x&?Hxy_Yp zJ>Q5qe+Qf^AU_pU1OLX~tyKNnw?}BpPau{FZI!BZ298mvzvl)d$&7FPz3GJV=0QsQ zo}Qjz3wIzvEVs6azzME#+CyycFbwJ4tp3%s1ggKcx!&v6febLG33BE=0w;os(4E#_ zVp!b|dU&^e6`W|@dJ_U($|Y`sx_5Jf$vYFjyRA{Tmt1as1-%a5BZ2VtnPMeNijVX~ z^zt+PJR}nqPXae)+_||Xh5Eh0`Jr1)UEc88+FAe#;r`zII5{aPNnqHhuCAbby7F>x zoTkEZB7@eF;`Hp%H>+OQbinccl;DBpZAdHq9e7R15`x9Irlqck@@1wCPU*~Y`Q>(r zP(w>qRb5?6OJI`!sQ)cVi{T;Ev7q32(`Ds(-}`agpGHSBHK{M7qqWXD?2%C~+}WJ2 z?Kgyo*f?@<3Slg$LPAd*$I(FEPbBP)7f@)7*DA>@s(L(#zuQjbJ}lbrh+wk(UG;HI z3Fzfh&f;YL6k+t(GN>A{)5Vz?Tj)mV%sFdPONhHsTZL4{_G}A0$^*Mtu*pb+Q5*I( zH^X^^o>DqjanTQQDO|Z-qh1lM9+|?>}wTQ^kt$U@jzM3>Ii_O&{c6lmF5Z7{G zUB9a|Lw_^EtXy2pJ|eSo^#er07lI_yWG$oA`m3C^ILaA9lz8-Km#U@3sx4O;PCCEJ z>A*0!PftFhcjhN7#Ft%KjWG7FQ+=s55{H72~17FVI`>xHE_u0|97{RI2HmBHrV%L+K ziv=*^@yWv%u2K4uYFF#V{1=6NG~OrJ* zg3_Ake%iWLoFnCC?0eFbr*pEIPMg`dDPEG5%}`sYmd#U5zh&&YH7Xv}gps$yVWoH0&O`m*r&b2sa0|!krI*4N z$=PyiPc4pT;|;`zh`R4Bj;F92WDOb+68N9iUCwhb+y;A zwlQHLu~14j_C**PTviB^uT72-7Kil(UbGg>g@^5r%^!mi&^m3tU&(FusnGAr#qLPi z^RVnZ;!d7F83sj8OFueyKmlJY9l=PpReFhjazyTrY=^+d8r1q+~|7M=UG1P;tqvhoLI)LAQ0Dk zQr=E7l!>u_p=#x5Q*FISK3&L1Eq|`RG*CwjV|EGMX_54YG^x6 z{FU!ImRgE5w^!5bsKjdmi>#F0e|z~psp-%a<*n-wI8k_?!pNkK@x;TFjA}2ixFBDY zyN;0UthScE)b9XE@jKAncbk_^Vub_We2O<;;=O}r96GYgeI}nV(+@;}R;8%uGO-88 zrui;J$&Fw9Bmy7eIF@p-J2;XXwkwT!v-DXsf@xc-TX$-46gea{_RtVw61BX%Jl|f6 zo$UE&@Z$PRt?0q?%ZXYpw5+r`KTl707)Rr`b)Cry zo?xFvQHgwqBQQCBzA|ib^yCXp4;7L?_weR=p2gC1R53FwE{1yx0vW)0-=kAi@msj@ z#{+4#ubQladq1)fQR@fKOP^bsMSr{I+nkTT!ujZtlu)BCOhA{8=k;_^w#n5bg)36*T~bn_4~{m)ki56I4k_OvRtFpA`h|vw!OH~ia~MOl zwY9}ULmwO;k3L(WBW_B(ioZ7x`=t6ENf%o;ZX~Z?lyMt&WsU-2b=mXqsM0gB2S#CDpcX& zfsVjEQVQiImyq+rnqA1CVii)(;7b2UK3`mSCmcEYBXOqV4AsPEA6%B3`Qd4)&xgw; zD>Gy1sjqe2e7-1*RdxC%_`?&HV#y|C5uO>R6MU7r+qD4XoGb2T7jz{i&@26L#l5qS%Qz6!S z+J**PM_(zgn45S6k1JK-54JSUEtK-|EoRGlYpxG>vJae6ht#T>Xr{z0X160Q5*;0@ zUwt^FUl}4Ipk(H{y|QVap|TFiJa}{J&Ij8+H0LqV;@f{Ne4(es&x3*M_#&0l?ChjMUt#(!s%3+RN7gP zV?@D3>VM4VL3EoA{%~y5{ZOo#uy~#m@#77_t<8OjBkmVFmktX29X77j zuxBXB$oV#$?t7m&ZwYn*z#|`szqaH{^O?TP zFI9BuG(Nom(SpnWhXF^}&LH3az-hrZ|JzhqLjpGt&`0vM*yWjPmZgX%0HZwl9GvoV*Xg#R|H!itIx$Lj|6w&n!gV9kgEXJN~D*-nift&LZCaqc$|IjC-V zdwbgi@I{TKIzDxu=3jzEjBmmC7zkP#dxx|?*v%d?G+*~F=E5^0?7t6Z% z`OT#ZKj`zld5LCl?ZMYzUQ7USSH-~z6I5$EC@4~>xz5qRPYBmDuIAe&G7rVh-?bXt zoPfBtonZYxw0!Fy=v|Zmorh@PK5GGw@Ogo@Ls$9t_Mp1IuN*DWQ~3~cb9Vt{W2O~V zh7`n-7&G|>>{nutf_qyJgQox1F+l`xZ+eaOuK(tNkZ#<+aQ!|92KZr#e{)OgAs61U zjlX}BE?Z3f0|<_3Jn`l@Nn3lOKb5h8f1Xf%XU!Y5xMa# zh|J*L-s>`tQ=z;^yK@*CcRA!Bt@dvUC;kmWj`zXU4piwDgzYxw++D_spRa0lPe4y# zcPz78+uvZj*e|}gL)5m4X8FLN3Dgn)8U`T~{QJF?lzvds7`AHu@4A;O{rCQThgSdF z*cco?%ilc5RWgs`ER>%2y!j@?ZN41IcIqBCU4;xh{`-)_;v}NHN3FNt{`WHQ5SzGT ze~H$IXy7}rQQeG7kj)+J?3DT2eB+aVW7u| zk{+Uy2;d9pC#h78$Hw;(F>8(oYq2PdFtJa0P6~S3UpiPRob~QD7++P51FP1pmu-W}@0_C@uYj03TEr^?dkQ!f!7De-?=4PI7QMIrBL+_?q2RgBn zs?fvp?BcSoeTnMn>E|0->h@kW-l)!Ek7P|7_AlyMBl>RR8p?)G8Wy&BXNzj zc;T2I>yW?$nt50hA&`zc7-T^YrCm|sE0u4GB?nEND+L4S>Gu~j(KQpCe*c=0zmEQ@ z@_3t;KGe9f_>qy?ip>ZG8iT88Jnn$LKwQzP$9p)%tzhQ z*s88d?Yjk5SIN?#bck0dWz9D!{Kw+wbN^+*RkYZoA!SjcC!$TZVl@R9Ua3Fn z7wRG#cMjgLSlv&)WwNM1#*`-OD>BD4O$J|zeUc<;1EZD`t;f^xO-wLtOH%Jahg;%Mdl2enpBpp^gwIeew}DQpwcRIFp*$?e-<-ljYZ?_gI?Lg6kV|c+s7b``1+XY>Oy1qxQy^y^j*YjKr0r^u9Rc zIEsru@r~a2!3VdY9gl0;)3EaR+EATzd}uoxmG$qXDXS7%j=uv!w{EpbR36%Igz41d z6NcIs6sXt5ISf;}BZm^ig()Lg_U0eX-AcAvW#sVvcBEITqpYTQwoSV!@a_y`xW5&s80zCB!e zSK%AUS-1Q!#;2rQOx@50D@4f40<_GYM-xQpS$p|r&L5@2P*(|oBEJPUbj2S%k~OP& zD3QMQW_@UiZ2yIwv91}WK5{{07~^4dHXqj$hN&;-eAjKY??fLAuoXm=Ib%c6zrA}+ z7!LKp?s_cba8VJO42%4;dDs(sUO$1sJHwgf+$*0a>MQ2S$!9KwMmg=Z z8kh!Y)pKDvmhaIhaOTsG7iYm2ls$Y+G(Z~ZhYb<_LC84dhM9a^Q2`LJSmTeDt#?xx2gD+1Wku@=m2uaZ^;CesK>b zY|ay^^x~?2Scf=&df+j^X;Xz*w^I!+#9?ZDE$rHBDQ>%oWVkEV-f#X<4+5O{$y&op zYaWQ{5l`3aT1-CE@4!JRWWgH6&=cNKIUpGMB2DxVS~-^w#v%)!Lfv3s)Zve~KDTr_z_pHKC(#;N7Q-wyL8>6XU;h ztb3&FhRyBPKEeV$8c{Vb&Q!sWsjQr!C}K^u70k|l3_gkZj_AP+IyI+UeuA8fcJbjA z*s$bW7*h_MR%!cEnK&c^>svHKC(VkFkDqV1!JM}XEEvF${G;^Lo!(%EbGwGu`E)01 zC$?m3(k?u>;U*6+hiJ3#Rw$^2C}wV*9aIQqw1bX`OjLKmmN*PvlML;QU9KtwcMXZbL~E9*S6t!_Ljg;G<(IRPCgy7mSV(`p&+g2*<6f} zvMFA7%X8wWwOs8lWX&Om1T)VS_KJVf5wWW~04aIgk@DxphW0McFf`L#=eTdlf4zBr zL(>RutHVdx$!Yfug#A+XQpakY3`ID~qrRTp&po?i#Dn{fdQC%Hzn`qyTaJ`J zrJ=2$AaGJT~T-*RL+BhxHVO2@R9W<ioJt}$}sJSUo?Q1=uzF?e8ziyQL6gSc`FeG#N8WPsb`pE<==<#(r!^>63M>44JtahvsN2)7#e_; zH(}k&(}uGR@$S9HCQ6a7^fE2_*rVV;-OZYDf80+Wf2;QRaWTB8SQU8*tAuX6>?hI^ zG;JrK-uTh<3R4Q(Z=GYmnWEFOGGDz&UjK6>%W}!Bg<^fBAAC z1M_{Qv*J*d{%iBAU|3ac-S(kUpw&}R2Ho75Rta~MYR|`^b3--5%I~$;I@C*TJ-FL2 zeccs*!S??CNLtLdw0!AxY)*hAFk` zwE5kqH`7L^1Xs5y>}!S(CWv>R-k>3hZ6aMEXQ`NI7Kt$#8C;Y4l;8a}D^bh>=2>A~ zrcm?B=`d@o!q00%{u`k_D1$O(WSAIx^7Fk&f?QmI{AJY7G;LBchlzK?(*7@3LYGcP z#AY<;4Ddj~@l^0JeSdgfsu*by!fe8AmNAGH6ROEZN)-NXcs;#JxIn#R1WpBq-y^DO z3;P(ITY|FqGN@CqB#@(YHWM}9H?}MuzW?6deJ3U|LC$s5v9Ylf z6ch`A*Z%Zza{1~;WrFd&bMx~mGaURfJvyY=iT(E9!Z+NzR7b20t#SqY3E|u`S-+fF z2b3oQ#JWf$(DEqNsNgzh(IX43jH$?}QLSnp*Fo$4DOS zLh0%3{1i$Wxw_mF+hw|UapCuD!p6+aZ`}IVbZY&FW#%}p@8tpHb~!q$%K;+i_s5jJ zij(6MENyG{Gm}=c>eM$s&J{e!zBdhT}qcd~xxWH7{n-sB)SZ?ajKkwv_^O05`J@`fSBJPVSPEm}f>#FuM9$CduXt zeSXD+d^5cALlJ#{c4;aG!XeGYNvQ)KpJec8FTT8>3je8&!HY-w@9414t$e(Ay=ZT+ zs5stn`1Mv<4h;DuvaGV(JwuH zk;1lc{6QI^+=A;Ih_3hF8x^-Oy5VrD&SOyQmsjO^wL^AEorT$HQot+==2**4j#?mfH)T-2Fi?1*UL7i-DM6@q`Yp3oR z>4_!ABIqF?Ac=Hyd4{Ocq^gDdt(1CtdYbyPoq>Ru`y1Zi87*TrsvRW!X8kldIaywx z`yuJU^4i|s-tj`<&XJFPDJhIzwGif5n;zD_w2MI4@TAVc;TDPgtNUkXBEttB4dU#s z!UYK~sVLN+y>k8E9vbvg{+Hr7X}9j^w0E}sRTK--q$$`lv$JQBsH3AJdx8Foe3!bd zJumWT8II)2Y5P)bJ8$p0aoa?N$5Qw8N+(b#f#Cz=z{_e{O#672{E<&PErl?cV>s;# zdMTrwR^aU>gZOpcEyj@z=6M*8~trYgN({-Mh@ zVOyOd__*ygCBdLNPp{JZq-4Zl6-CAaEVUx2!~$CMZAc@*KcdQ{imMzWX1N$>;VjAh zprxB-i)R1x0u*Kk)HgKvdU@SP`)t7BWN-gngtEuM$!TGJe$7R=Kt}~SJ39+z@#?At zy4V-JXgs_>s2Y9KS};GHQXW75N&0s-{zr4go}T>h_VlzW*Ud9fqK;kP+lyQNp~?Cf z2?rBqXh?;NEUL>?DKcYOC}|I51l7XALcpVXGV>Z%>ACqRECi~SYBxadGn41Xbf1;9 zeR>GWStZJhn~!HwoLV?CdURAhZd*NVKOk!Qds%y$^;2|ov}yUziUn#as;=eN+8mhe zOG~eqiPJtTb^mC}557}8UjJB0e>e(J;a!i@st@MFYht_Xn_#|m^VC*94US|_5099b zn6RI=)#$fx(f672?2Cj$bH;7UMMkVO@1sfGH!?EH%Fb5a%j{d-9~p@Qi^fZgzb^Yg zX2X4Eo-wv?Q*;`6xcju6Y)|Yj={Ey|=irQk5CoVqA>KoeZ`vhw1{}%#2rUy14c0_L zX%OZV=HnWNwzoM5@?kb=#PPih1b2g_GzP$&hISr^>8q|D`6ydgO%vy;#Vtc~P?A{> zi0*ll00@Ee_2jl0Sm(9IDy_76?g#Wc|2zW&Q1x@4CThIU$E9Lf>-+~(6PriX)%@}_ zzc)5)ot$FXJw8spG&1@dUem%RCMQ8RIyyQi#(Q~F2T&*vX5t8$T&N~Ta;Z}?UQ0u6 z@Ez9VhQ|#J_TBPE*f%Z);=%L>fBgv%Bh`}eh@NF27L{uEZysGCodVATuXnBu4Gs6i zjG2iUN-@K|!~)#h80xs~%j5e*0iQOS-DUdP-ygnt#N)IvZtvvuAW~ZXEH=!xTCY^w zH=j+mNkvxH%^%KQKFu8WDMsZJWmFmDUwL>HtN(W>sU4l1CMPD^Zahfh;huX#%I z0*JaGP=bZEzrX)0@{@|HjYH|C=$=@YsV1}anaaBxDp!$#aDfpq?n8eO(-Kd!9x+!5=_X*Oc4{nh8B zkrtkw$)%O#rUYXh!Pb@T$-)HT64@sg_BpG-^I=6<*$aXO7@e`EAViyGB?(rDyguMc zUE9ar2XODb&RU;-#(1jw59v78iULIG*zdAf0JABZ)GwQKa&q!q$aok&Vq1+up}v)s z`AaMqU!P4b1e_y5taPkhcd7Gf8v3X_Z7;x5{A<-^+?L<_MYh0^NJz)n%Q-aIOv9hK>EFXPXz%10lm^BVl*&! z{N3EfY^wpz<07-?BL`v0qv5h66dw$Xm6cVr%%kM~BL#yhZ@;|UM?QXANnT9}avx~P z1Z~oWX(6BRgY$1}GY~F^Ms@NbG4kkc1Ojn03xK?llmr3-63KoZzWl?Qudj-xZ?&Rl zd3t`HF~?qDcEOXLK6}_IVh5~^$G%}-jLItcRoH@@t*m-BkCGJfpV9&|(WEsW!1>^j zGcz;u^V9^0GnHs`D#~BoGLxPadMxSrZa#lwycKZgq~H$;0n!}9Ma?C$>-WKFL>K*m zR?dhuGqLITN@T|K&%b(NX?jwZ$Cvj&lGZBGlDhvT_ucl9Pgz+R(!-aH)GY2DfDonH zC3>X-ILGK9vf-;pui9KGpVXsk{KVzTHVs-uCbzV6*S19tSd5}-plFt(qHZ4#cNMb!7CMz zXM2{5CO6A$_gwpTU1*9Oh3?PeG4e>kR1Q7QL@F zHa0-s2=kKw5yOU$eE&lu(4F;4QE<#c8UhTIf?mpX&^iW_YR5}$9t!O6+VD|NR4KBO%IP?McD9@_1^7m{8`>!NCFGlfWFe<~!Tn{e%=v z>|b#i8B&?_bZIDh@yU9OZQsl&xwNaoxOjNDGE&7F4ORy<&PZRocm!ywX=q$+Hl8OmTpiLI@;S~zTMs3{berzf+VnD z^!A2#nU>EY*Vor$E9`5)R59Q<5DN?l7|JKw9`47=lI0RV2Wk!_Xdno5N9XJ1`phW(@| z)$l1F;4AIP5E2} z=w#Yvg6_cl_&7=AbfiqKy+nl8x5-T~2(q%W0_p6TD(OOShR}6y(mYuxfYqSX*Dm2t z?w>}YfQhr$ywS)BEM+J?0M?HSE2izCov$-|3OC&My?!o#9^zrIm<4M^7iYu=67)H4 z{g=B)X710)k`3u#1t0>hv~Z6atTJwU3W=aZDX-Eawk9b8hdIucUx(JqH844d&M1rg zPMlZQW}f}#@1?(R zb=v!3GPz2V9QQH#(v>yXyaNI(@hAvDqu1B1PRo=A+t&}ux2Lk-(psak1}%kSu+f8& zE$PbK47S(H-rR9qUG~dS|59g~s$3V5Hx%ER7hXuwGDDa znrb0aq)7;%?YpP6-y0hG5BxZi;{(9_r|hYNI~FkzhI1)ydH7aN1C(mhvZE|JNHf)ven&*J)-!f%Ow(kQhN>5i+m4%-=fMzeB7=?1mX$2`E?-kVzzP9Y&+KgJGMy!% zY5N>+j)m`w)xZ?MbFdw6R64&u*`SJ49(O4B&UXxEXPbX%iH zlcz};0?~C&8)Qs3{iu2(_x(ui<2ge_PFDPZEdc&<51*dw?%oIWbvfBV45*<9?!En> zQfOA5(q%g0#)uvA4CvtL527Q)%EBfhy9W4ub%CYeuf3O-!Qkp}bJ&|+_9EN%VN;@0 zv-|y#oxrrX%b&|fL?adj@$D?>bqp?kOPB3ZH!6(B1Euue{lkf)#4%1s?2Fkvj`6iGKU}NE61?^(#=ID=(d^lN6HV*sAs&TkBNUFE!owa^S6L_(Aa^mId zdk#neuv|b9`R9+dnOUw;nLb<63ueu-$=cf5*qE3M6)S;~IP($9O5seEX5GAMeyq@< z5$o&k4T|}McZ1i`#BW4BP$ncpboKO%jRVhD(QtBD3?yQP>4JT^`FQini{<67F74j(i$G%(5l`$sEZt}wqjz0z}2 z!1%D*2&8}gwSJH~r6!Vz@@ayuxQXOvnwsKo9a&aRKl}VbBokyzDDmb1d7=VHr#;%Q zYz{8iwzpYxj=pNY?(A_Gh_V_$FQ75FM`Q)!-vU~Cpee7IJ@udek68DUk)H$P_Hbsx za4|{ALUoqf*+HoNSQ_g>m1TUFn#dZ=hiEVXqhIX9ROXz|Fm3Ra+a7?>t(7i#jn9= zsSB(5KaQ&JiAm>bvJzCV1NTNyyFdBSof(|7fvS{5%E{#;&)Y|=fh(c`qs7F{$J#r+ ziyTp}RIT2F)EFMtXvEp`S|Xb>QK6}^5hxIVXK|?mh$Rmf4HES5eK=e=bI7I6&&S8d z-+%DHj};7%y5*{yh`4xDeLYx2pxh*l1jsSbtXo|`J|iRJ{zxc34SLo2iQMKUfYH$t z2d7^&b6)%;t{gNa1+f}}3xqf-X(QJIT`(D;r;@D82$pNv{K{RM#4nXG;LlaW@B$)n zKEBP6Y$0n14dfl=ymw-i?N5pq3d$I9>f!NmEjH44&IWau^{=*D z4)!m~r#Q-Q;In3gIcFrxtNI?$RKux4N)le;#>t6SKQ4|_^@MJ`)!>-cxZ22SKAn(q zOPwAz=sTpHS@KP#2^dn882^q-F&nanL@2e=A2*+GH_T^GP4>-C7s}*0J>KMPZ@cR+q2VbAMu-EjBDm zPXO!k02#-6|KcJ;jsYxQ2Ew>QI^AYQl&+M z@NXZ&oExMwt6E^eEM;8;xTCEDZ=Sr$u%>p99to@R$7xWl|H*&EXD5=76N~*-wrsuO>Q-JN7zz}A%msl6YfmPV-VQwIt@+@ zLAs{MCFKx|{F@iQYTE(ATY7JGH6(RRL6~i{&bR zv5!PcW8?QD#gEUmO0_{TJBzeD^A#JOwXX@7&VZ`1B|-}|s7fafuyoNZS9u`0=zwQU z6<%`r{!~mtV#1a`dzeXQ2n?G24HKwqR5@bZx%@h2S-1Fu5$gCj{12ed_LYZ*he0d@ zharcK7&RabbEok^Hp7hQ$^oQn8*4v3ur!cF%V3Ax_HEr48$P%|B1`*Mu|hjQZ~=sr zrK>F;Gi3n?R?r}{H={OvmPN7j3z~nOY{0*F>Lw=}blU!vcc^0MSmj~4=Ru`?DVIKd zbwfkRq-M3AmX=9mkuIwYW4L3vE|>USNXoN<1O7CH{FIB}s)_`b;}sX-nm=P8lw!E^ zk*|6i&3x$1l{}vGl`A9}@qwB$^EHh46lApBipJ4i8cnX;Xj}TFuS07rH{WohtK-h* zzbO$Z2u1kO4m<(Yp!e_k+vwX5{K`x@eV_A6xuU~3u0dV)ZBnIFJN`NqP(i6tlbeb2 zzY%U}VPe#(Y6^59S;E?;-t|XUg0xpz>FVO*;^tOWUf#x-to#0+0BnDE_k%+IR8Ns= zwgi7(RSlK5n-r(0Mx7EhzJpVILP9$tPdz+GjfW+alT1z`y9HRg@lsjxn??dW%sp;# zkpRjTrbr*>6QM z8f4U9*ACke(RogT2O3bQJ zue48xn%8>{O8>bSwZ9KMpJ8%|y;mUa6v;YMK8Tj-G2sFgQA}^M3_!M^NT>52x7Ff} zr}n*F2(v-09~`*ykw-)6L4kgm<|xo52VME`O#*E=vUlaDheZug;2VuZaXSpF}?geWa_;<`L$r+F1hFZxQ?=yTJTSnEqE<0p2<;e{>wWEZ>4=AG96XQu6xcR znU4^63ccG>em)HJ_KvH{N+}$(7l0x7B4P3SQY2V+y-AAz9>0B^p;E{|4IJn1)5r`PjEI z4+Fj}+7^aUojRLy{(Z~YYD)6)s;)a!A2+f!)k>sZM#6piio5HR_%KDObh;mlguOlz z3Ww4+g#dYBjkkz*-d-SeqAubEGegrzrb;2uV4aRGE(Y3J8;#10`s3u#cr_tG^4x8c zfBO5eBVm9`SAX^S1ucE;EPGk6wqS1)n_<>}l>*ZA+PnB+PXezH!Euq*Bmd)~9Aq_) z!1I1$ahTf%LYeQ#OSCD#um_vGelsS1d{~1LmrN%XsF}E{;#`u>l*w`oK**zy3xm?L z(SbY-R%z3|KOx|EZfbhKF*`o4V|w@(5N*{i1Yn1Da3pX3`ST@K28?0K5Sq@=uGp}) zO8_^}0>q!QP;yMCdmk^c6jR#6`zk~g}M}Y;4Il|PcqtG~Th)DSNwWi>hk^a$n zcAvCNj8n@?wTbf!#nt!I1NqwG^szdry|z=|S}qLW^eKUh5^uZ#?**zoz>I*ygzJks zFGzOPddgY65n+I~TUaPmxnd>(+ZCf_mQko0poobDy1Q35H-AG|1JK8u^3_qF_Wt*2 zdvM8ql^2a<05RIq;^Nb9#%Xd4XY$ZF_{a=-NQa?A6WowBQSON?3=S$GS}Jg5gTdWV0QmoaM_*r=)he4fff^x7t248NQc-SS3f^L;0&*=eGuD|npRgF zP%;jLD1c)0w7T3bfbaqKrd(Yex9FEnc!@QG{H4AJ>U@Nf!H+r1O2G32E~igY43O|o zX?NkC!Hm+sU+d{VvKh)=XCcpj_Ud!a(OGoahI@T|PLsILbr#4Yf5LonDeMJ+1O4*c zI<%z7tiS#+HE1Msuq$QT0~nk+x51{Nxz6PP+1a>0V{{#og}igNC*)im`5jNik4D^a zElHG@_OGcL9zvAJ{?cqfT5Y+$@+A%Kd7Ux54jb4==`|;he(&eky1xNtIS`DKG%r^< z1BHc!f!BKTs2KuTM1oxhHE+G&LUYxU1SXLliY4+y;m{TbY8u4iQ;EQ55;R?=*gVT) zvD%T_+kaq8^$i-7G{U6V!kLFhlPhi&k34*RW@<-(aS?h7%#-xW7zmQAU$E&GcWs>1 zPO!c4m#deT)Xlb5@&T9yqwmrl&Rp`6=-Gv0j@aeZI+3>~dokmb(hm6mUBom~az8(d zD1?lOvWJR>1{8Ugm8t!!fcDiWO89gnV^xw5=5;<{jUy{zxZE8~t)Czg3WOU`X)(K zg*+4qL~LX03zZAIrO@avCE#CuGIEK#q)X8uGxeD?DR`J6kj(hRz^D!}v`8py?sJ}r z#U`xRNYDD#vUe%Aq(lLEWb>`|qa%AcFdfgXwG{mc_r#mSPO@S*LNHpmp7fOY2&>Du z(M4xlR`$NmU^NaMwQzdKtt`yk^Awme`j7J=Q90cZJ zoo~wYbo+if2^q_s)|z}-__jk{0i^N0#Bt1+Sfw6`j=szcYc7}iPv*z3%1`HEh5}mp{SWO=Z9#;!yhhmI4>Ik75l?nZVr%9$M zb7ztUOSv1FoJvMY(*oB(r` z0!XUPr%#d8KeK$Xr9RWj|cD z(JTz4RBQR3o(cb-7r;9A^BmK}?~=FSeD&|otH^HZL^a1>o#o+F{oLZURocNamD08S zT1RX2%12Xwvi2-B1}p(0aTAe_v1^eu|JF6|s$BOBx?TQQ-Cj8X2CS-t06Hp_X{W`0 zB^!8uPg!I zIuD2AhCEZ3cUsA!#T>NcO;nI)^<&Ebd`fr@p!1$WC9+kCy8wq{z%nQb^m7K8!`Co0 zth?@2S+nA>g`YTWrU$p*1eAMgmyltGA*%MK8sC`w!XdkHmGfaHdlHFZ@CWLY$l_^6 zbLR{e8OzeW6sA=^T3xj}HvOhin;8DbDKPiIHF|*@7b_G|QuY&(7vlo|N{e~BpNb`} z*BrQG03S1z4fL30A;#eCgHvFlVT?cB>!G>%+I_QhpoC6RVg&kNtmGB*q&pB;z_o~* z?N!R5&UI-r!OhoME3AHRpN69izP@_jBU|5)YaH;oM;3`Crs^o@e?(FTe`h5GIp}|j zoorVp?a-?r?26os3VRylBCO8pLqxz&ZaA%-M8g&T*~g!dF)avK%})LH!wZ07wuL#e zFV+Hh;ddj`lnFpSnYQ2a^0TrEy_ZHqO|3Am(`2+THRW}EbqVD22G1Q8RaKCf7(74* zJ#+C_wzD%_2w!F<&arjJ^Doqk9vZf>3Y~AtjRu3k@5j`TnWN_8^(py*LO%2TKS!CQ zPT)T($lwwJ+j|buM1Lpx@)BW_wLiV$%b7pr^k=Mi0E>Xhdi;13`?MhUPDYdkPp-;D{N6_!YI-VtTi`oZzKGTz$)9ARFHheJk+`;KLt=p>l*vAZX8Sc#^>4O7YVp> zuH7z4#JcMuG8?$>cix{dSn%y72kcZBi3GMsKooO5inQ!`0*?w{TSk73}ERkq=;=p3*KJ`2hWckG!d&!R)2aEl6aPhEIgb z2kprAS3n&-Q+fNehwaJrI4h$y)J9?dF+1HNK;D2=<3vq>^;j$ zcI(X}4{T$jPB%TAkg@(4t!p%?L!T~PB{t&j#s^Mx>4V@)0F?D1wNxDmyluc^pqKwq zj^P;)o|5mSJ-`C0XqFP=bQxHhq>I7 zziB?8-rKR3EV_A*%DnHy78=aQ<@(=lA=Y>OgTw6b_)$IJKpbgQJ%}&xvA53N(^ZP< zsuHvo=rZ_L>NMYz`1=RS&fZq~%NZdiTA186-o3Xbaq0Y zhFI~=S{AB9r-eYG-q~uoHE8k7@g_8@1}8t@P9(f@Ys3^$nEn7KV*2aL{Y}7-b6KO~ z+-w%I4e6Iw{6aQ&tPe(_P7lzb*PtPuM^^A!+|Nq>2spQAAKBc~EWMSaC{LXt^EkB~bu6O}(fy zNs;8RL;6Pb_$vz~DoE4Exrx9t2m%QqCLiuaB~`pUT2bN>y2RJz&sP@}P~ApDb*~M| z`3a#91_7$^H(PjxCLvHrhlxSMkstge1A{bHb8|^*?@W$u=Q#^5yuwsuKCIUE0{r zG`M@%K1wYqPUXgxCD4DvaSyih?%rEd<$n6Y-S9Q9KOD@2i#&@*d~H`kAjy1RAOxXbWt)_+Fltk6Vxs6OU~kiDnv9Yk{q1eZ7$UA!s_)ipPzS-dS;N zI`IK*3?3|s=-o4~BagXT$)at!24Tc~r=dGZNZp5o*3~qm`LS3rY=gI50_=z3O`EkH zIo-Cl&c7eNdjUK66({ef=MNV-2h-S3x99j1Se`KO2n+$KC_5ecQsiJI@ZxU2*{oUG z^4jT;@7lIJH-P{KG9oC^#?_acENJo-?(Df;UhK3&t5^KLCjA==tPJntWb%i($|0LH zOCTMAzC1LTL166T18S{KHHmV4%j)U#bC2xdj|ygY5KI#>x<1g<-HO2iRZq5=x(o@Y zhVp|Pl5K3)Yk#jDCve1uI}-m7i@PWsqY&N~1#2nrq)ACj1h& zYW}JqD@TJtI`g)Agzgj!mnxkU4%9Y+r055c@I;}(ad5y+EhAh}UJhNXq`qY!x=Ymf zd3X$v^W4&-#3^F3p?p>?9UaE#Rq3CyihCt%UPX!`Xn-Ym)Zjvbo7zK_l81!)9)x2Y zw(~dfH~u_iEC(#DuRKhozm6?F>op?PVr*!pq%|p-jZb+;9K3HLBQWIIJTFTH{Gh9w z8;G`m0vjI2!0#^h?h>&`sr$IkKxK(pc|a19!Yw;Teb=>N6$$b`HMVzsKZtliy{dDTJ4W@}rj z!GIYJ!aIrVZToe_I|$)M`(o94`F2TPzcx^+(NkioU~H(Bx>Bbcwm6o*^7p;$__F)W zjz_0>94?=>;1sL}V>14)b-GP&il zk+XLXK^DhUNY#k-rG!HyR{qlq7cTny0av8oaKrE)hSSt%+#Uw=ho-M}!>haz+Jb)) z40NBD-r&q zKr1eygGlHGLQ61zv_IaE31$pMR*}`xuoc%-QN9inwaaDh+tnFIzE8M!pK>3AEBkP@ z#1Ri}h5WOdoo0z4mt~A|$L=M=EiR{i^ln>h+y*aOY47hF0bJk%&2>SAT^!l{IyDwV zL195F11NtT41^BcyO%xIQo@o5jIj6kfsNqheY3Ij|Sp4i77-Yey|kPkR`t5Lj0?C@(tXKH{~?q#Yd~ z3VQ<*bI_35)WROTx3si$eEiF>9J*Z?&fFQLFA;DNwo=u%Wg^~AA^pwnd&hcXme!T# z)_f)Oxx%)f{ZH__BcL?YigCjNSI?lS3fC~jfEDynfvg-`0fd!_eZartHYG~uO6Ou0 z16liRV^<)`of=^!R8)kdWYr~#?}_}dCkG!n*U&1Fm=$TZR!Na*0-y%+hyQLg3l0vx zixQN7!S*9C*`3bEV7&=27o@X)fDwJu{bG)&^>0y8L{;sZt)mf@MhC1D{+tYw>r*)s z8X^vjFYJ1BAtCSU8tJtd;EATn{a0wt#@~lt*1bQhcST-3$1LLOHCA4u!C=>y`4^6p zV5oV!qRE?ic|g)ra5kvyO_!U98e|K8YR;t%HJC1virL#05_A z-sdj(vab1xG{IR(vQ!~7$+9hTbO>#;NGIlT;gjALp0847sv1exgv>oOBTr`p3c3Ur z$1Suwhb*>MrCBjrjYk+TTK^+OKtZR}ZPW9W!iwK%+GVnco@GQtv z4h^x7#1eaI@1!sBzZ$yTXGpNPS`f!JoghS9bQw)*iSIiKDB3wDp1;nHj2r~Y76U|r zmHkKv{j3k?i71~rWzgxiN;(pW4LEx-NSbvQIy{SS>hjl`WoHTsIlUJU@bc2DWiRZM zGgS_E9fTloO?;nL-1VNk$5UBE)x<+Uz~M@@F3=7^6;hR_m{!mX z5}b|c#R$3R72CnjRbGcXxt_FdoEt&K2~%dG$*2+-lBpneY4mp5Uxwfc0||e-vq^&J z3)T9)zWfA;S1EaH_pWMSlRMw!BMg!UN2(zgzeZ=&>I{XCQFNMNaeCb#opnOc#4M8? zCBo<4vfA!H=L328j|!U;oz9P_ER;*2JolRvIDSHObwZBoktm<9*-0YP55OKY1dhoX z0_jVIKUPzoYwWULSalK-4`V6{pn_o*4z@!33{`r&!-PMFswxvBM;ac)p+vqHw!H-Q zr@8t#S8tt0OU6nQ(plqwM0kna$i3|I9yvDRtCUBBpC^_LNm_q+vent^@22CwV4BcV z8nC}=qRm$c7w^=ud9TC`xm1RQs&wI|UjpdwAjo}a=DhzfF@My8AXV`@M;9S(>Vz=W zlqps~yFFbdbYCjnj3^d(zN*r(nuWyeqcdcxz|L~3aCaci=ZmqD4&^lfyb%m1Ia{(9 z%LNfG=?B0FD*uGm8OD^N{=~;JvF&8n(spde>d%{c(#tu96Nm*w4BO1@aBmAqwd8)i z7`uM@)eiAW(DSG3Cikg=n*yr8Jw~hITPF&iXNc;E2q{S}mT}S+=KT4iX>Xf@9sowh z^JI9q#hGR#+ca~l_0xZj*}Lq(l^U_gW9|^bsHYrwASf*CNNiR+GnKJlPjz1=j=ChX zVrJ`KAng#f%_BGb|E2n=lpjm&V;MUNqg8K`yOYcX^2J9wk`t|?uM71OeNn|Gk?JDs zcH(k*J30Fs|7QX4DMK1|ZE2n)e@Tsn8bTY03$1Qo7)l@w_Dztc zT=A2VNl!wJT31n^_ysDXO4$;-`W53K54+!c>SIP8N7w^Dw__V#mfRmRx$2ldA0JJf zTz7lDQl}u8o|#ZwDBQ!*AHyie@|MdVIpj1MS0kfIEq(iR z?e|Ge3g@;E)Umcl|FO(b_<(B%!H=qAo^bAbyogV0$i{boQJ94*$~%Q%k>LayVoZrD z^{lvIFH`spS?&dEFi;&EJ9@aeeI~Vk_+J&1D-8Yau%C$AOyzi^3H&Ndpbrm`0yx%@f z$ywa)C2W*_E3mv37kT*XyE%`{w!Dk)0LOjTh1hHEEg_$q11U>-mgZdn_h#&{;SMCu z)VKlV=c4lY4O-3e6BABO;+va?+a&G+;B<+K!eYTkFyJe}{ggg3O*l7SBjc8iiR|G< z9zcKy6ohd8mi75R_UXybu~f?v;*wCHEPohtMEEi1WIHkN3snF6lGppADdIU(G+p?x_nGYHZyu8Rk9nkWP;>&P= z0fEY*#~y%dVjo}+5W8AiS+SsRklma$KeIf!=ZRWqndYntemG$$e|?1)_Prf3&hOq@AWC#?X72|V%GQ}z zFB7sE5iL-ZnGjzg<0h0pf8nf5jU$qSfK1huOfcA!%Z*Mk#;y`hTnar>q_O0Hgz(M3ak=+W>UR4$!;=lxb0do#aZ^`d2Cg)+`AXG zwJ_&AJ>z=qT5!q8Mz@&+z3IH2eXdf_(0lhiSrFRr0C-iJAwo7Hg>^{R+S2rP$odU{d=(oTJ>afxEeydPq1UrS@u#4wdQaE7|HtMQ~b}2!K(c`Ki zvEwdGb``jG|Bl|p^st#Q+bPOG8`H0Q&-m>{D9MMh_WLRezkSWpHjrAVaI=*|z{Iv6 zGdNVJm#-74rgqpRIP^ zsxS>tPEH)_XQ!vNc!=SkEZ6u4pRk2Hk+RotuZcIOWH;H<9kjS%ATm@dzTNFXa0!yS z7L|dd@^4mGdZ26RGPHWMd9*nJnoe;iSJ&Fs)}fV(CO$rpHD#uABuClRvlH-Jei8_n z{G`bn;Pk#Ej%-MRo#2Hh2?~4QLxuPgSwdE)$E~Y9nB_kW9lP7ZlVgJQ3pu9kd6sbZ zmZb3|e;6;!n&3L~*7k5zPdn}H|7osxV<<>SKRIpdJf~tUKl7E(zM=j!`p#8}y?4n_ zGm=7gF61&@qBqDt)r(01vZ$Keo)6sy$qfec4KP^ z_f^ zq5Ic2)1olwVKOWWQP^%-(QYX%GpY&ex z@(+CFmP#Xaoy@!b^?g}~^-p9XPikvRwil{7?JfI?#b?0TqF2g} z_p0aDuLKG`S5HqO)cek&?xl{PHCJuk-lI+sUqC>*ndY61&=5#z?*N zSy#6VTm5mCk&2A_Y-FF34-5XjJzJ(Cal;_pLuubC;dm%RRiaa<_^RKyQ#$bANb89N zsVa@};pY_>O4(6wheqnzd|LL@LMlewkkL;BS@oQJB(%@Ae6LCuHYZZzsxzNB76-o) z5XL(>?u>XWSEMsnk}?o_)G%dLrk!;1?fth98e%jsE8q@44_$!NuGD8BG5x`06$T1< zsPlZ(;jU^bYHDyF1v()vB+F9aqteZT>7hNe3C-Qoa&tsk<_e-LgSD_spBz*Ezq=OF zXzKaN6u=^fIBr`klgya#Qx(_DmPf3Ds_�-5Ejhosh|RaN(4^;ce0wMP3K&X5aZ ztIj2Sryz@DuRd0{PUh#IA~l$_9}iAGWKPEJGf~of@94otxD_bMhljF_HJiWA?s?Ly zX(1>hQQN&$vR*W8rFKbn6HqeHSasS~-ZFU8z@X}qIdyru^r+*xFlILW$@S)ZAPxu9# zkg)*)0UpgZS6c}U-x@5kf!Db0%n+S(wN3*LLUwTtEF3SUH%Dq1?$XJ(2G8JEi zkQYY358c9=T%cLe>3R~b0Tm=a}jA>2btQ?uMxmJxfY z%W^mtPH3I}ZRTwkpocu|y05x>dwWCG-VNb*SpPVy*C-8}`tsVU!RCYX@#lY~cOUf0 zMu@%HmQP_VeuF>b%F6n=!~dd_nz59(-S6HN z)_s8&OF0jopU@65Z?w@mYzY-2J+!_tvOLgYEd8|-k~L{j4b{4<9!=^%46z8v*h8py z+YAQdF)ceuIU|Kezk|OA%y_rv7C8RnrMs+(EbO1wDIlB@RbGTOl5At`lBU_~w+o?z zi;f-SYKI)eXvK*?>I`_WwHfz>uc-IPZiY<@CM-hGzTWLBWEKC2|6U7~j;+E5#SHI? z#f5@bO8Z30<^HJyXZO1eP4x7Fumv3&$u%3~v|(4LyvD^QBWv_G#On_OrsQWF$VvWI zJQ%w-cbBtXqk?9RaC7rmZ?yY^MxjPXoh-uW(Ta~O(Cy-#Y9(d7xe*bMZ78jdbivK; z%QpT%gcIel`0bUa@6F}AcMJJbBAR(I-QHi{^2f9;N?^0PxUBG(mfxCsYO^<8T(oi@ zeE#?K?zY{i@f!Wj08wzN8^;&JfUp%zeuXxxeyi^i1~mopWUq`;@ZZP=3~Y?@#>?~l zT7O#Sl2JGM5^bi!HG}vVfw?_UDiycq&%Y*&=u_q!!wt5pMqla#=`3u?EDwQ5jMgCzS2=)BCUYKu6sj3Gx#9agpVxhtjLm|&& z5Cd_?_JUjh?DfDN0$czfR!+$(d~H^x92yN{9GokMx9ye6r%k}#u&GQktEU(7jujHuFtL!G9 zFXSf6n>fjgDL;l^wi(VO`7LzVZ9q%udM)YQ5#z5+Xe&vwx&I_hOG8FnMle+UVuO86 zR~yaqMY|na?)%k*hk9R9v0f|gzP{lb`Dd8C@{$mNXj z%%$Sy`uaDNJKNilQBe_;Q&=k!J`B%edqK_RTCd#9el`H;5 zDg-}U!0w(W+jE11gOJZqtX`Tfi#HGB<}~UM{l-9L#rMXR4{C8*Y})H2YKjd`nf15iPaZzU zw2%yyym5>QUid9eGC4*6a&&+cW0=gBk46Z0pG?f^M;w4)GO5Jv4m4o?18+Ei@71RM4aAFJ7~ZV#X@O~1{7~WM zP~qQ@0SnMkpm3UW@x28^s&q%7q!si&KkSXAMkf_WS_{KO_>=ArL7TWAU>Lx0(du!u z0ofJ`xymqX(5W`cke@31@RIGxa939s3=<8u2aNH+z+;(PdH!UlYQ2u0rlvdmTate8 zO`mV(&4sU|?{%^7OW&K5G{cJveXC+=P7Xpd!QNNc>IL9O(vC>1e-8>;7`Q}J} z#aGWkT*W~MKCgA<%Bj@0Jv*c!N;|ef!?qbQ{4t5j02Q0QO46UK1(b;Ercn#yJ`=`2 z#@=g$JMaQnln)Y*29LRKMoleka!zu85X<#`V(Z6$u%;YUTA>$)QBqnOB>L2*y!C3! zR=jiU0Kb1CW#G#ozK*W0p!@z(Um`Q~{{=BizkWqSN6(+8x%Jo499Jp;xMr`ohhWe< zHI;1hx)&O$D=SnOtdeheh}i<^YtkUgAC6;EQc}p-6LQ-%aCScG3c~{kDtxng)9<3M ztt~?pYh`F*W|ps9_ypr5wo=e4t*S!w=KA+&>lycQs7hCyPA;WgdZ`o|wQ$z1)C=U{tu z$L)I8PVV`Q#!*_oCA=k6M@PrX#s;DuOxTh&81k%!mK^{&!gjy$YsMaKY-J#IU|;}` zS&ydW_us#N;b$;j!h0X0IyW~h^W0bkSz5I2-Y500L6W(5veLC6h;Z2jzZXlbKq~Ch zuNMF1>(`3U?;sQb499>%oAT^<7#@nU;2STdE7AbyK7q*zIRjutdJoh)EZ{--3RuM1 zl2P+b?j0$0_4Q{nzpuM1s_SZYRz6&xWq>o1iD}LETH##(CQQZDD1Z(p@km0s%P@Ne zC;rLh%G06Wf0=6+ux_XbpJt7rkMqd&`Nym<6Ne8xsLn`vPK)ByI46;<#E_>Py)JHC z$g;yaki|t!vbp|rl41Iwj4?>?Pl5;|h8(vi_E4=L`h(P`<={?0OC4zbQc^-&JPns{ zlN=0s2PP(_`BvXn2wH7uINw|Bk)`T*PJ^wnkhea)<#)348|D=Riokut@`B~J(1k)_ zc+Ll%9i9YUe*VVcKqn@i0Dnaz$6Cx|lRC_u#qM%R#6`Cjn@rpd&(7e~;- zy`qn81Bl$x(qfuTz;y=_5Z<-_xxQ}UU%V^QZ^~!~X;scZEM#JYO5UNa)|@9G!HZ|-Qg z{0EpIe`Tkgpf(q1{5~*DeewCtp8H3ZD%+~Qx%qKW2R%J~)<2=g)dcLxjpOT1U>Fa1 zYi+%y<)SOjySEHIWtvb3sertfdIi9rgX~(N9hn-1b`C4|0}Pp{E8114*r(lmzW%dt zrCeiw96~`o^HF!6TF-}K&~754sOrAFF0)Gsf~L0 zgzj$2#|{N9mvy>pJIvu0Cd?iAHD7RCk3U~54l>Rk9Ts%QhkTZt5hlEsK(>{9`4T5h zd6VN@G_eU5d0*d*k`@(GzyBNyMHxX1NP0ZPrfBi|PfW|uWk>nHY9c2_jr@E)<6Yfa zIx9GO{F#S)2@ydbxekjdqYF#G_z4DLpBx0Wv^!US27emMC;dQJS3clii|8`^k@FJ< zKc>f=hxpf~GX-e$Hl`;fTx{8IAW5WJi&5lBOz(5KBySU6{n^Ps&vP~P@iv`JLZ!Z_ zN(h?^8^mt)&2z+b30Qxfl6T<^=>EiH_widn>BTG^r|P);=iPxw^%*oQsR&D!nQm)s zZnd&4jr<^kDf6bm1&*~kM!CQ*QZ|IN7o>I@LQ^FE0Z;MIdc84U-a5sCYieqeTHz<% z(upaKqe42P(rKb(ei)~IE3WLpb3J!as#vMxzW^_*lncvZ#KHXTM3#wf^;Pf0?}*4H zF+y{NZEk4v2!qPoZ{W7yI%hPcuV9CeK*W_=Ra4Wg)&w}uv{ExWh@BV>YG@XG)Id?$ zA<&waE994J$Ts^#4KUMY1VM1r^fVz6B`os@UThv=yxN*hJB=OAK+%O?2_6no*e{iy zNZhNbb>`&tz(1OK*87kvtHgqB)Y(~tI7$u%FX zxLobFOD=M3XMXl&D<_a_?mlU<%OI|$49&8rVg8LfFc@u(&f}DkM&`%6G~(@`JY-*x7|G55mg|7*|kq_4O+ybN4yvVtdQ#sVEGKPbXF4u70GKZ%{wiZeLqn#Ia^Z zstoLWCc7fXSu42HVs_D0?Cq_zrQ2E0xoqrWQ4ZEY27>aQ$)7V&s7YLxWg zPTA+v0dK>9TU+Hv&46&f8a>PJ0GW2Pp1MvWfORe;7Y7H?>E0|@l@PIGvV|1p^ux4r zpP{fd!dTr{1JKc;9cZm!6HzeAQzAaL37zD}5Djyhn3G5aXbZ z!aMa0d5${5U;2AqFXjVxTfFVqAn)95mO6!Nziz!Ivl?oIHeM@?huR+|VEYWqVDx)a zsgS8yph`z;xvgE2z?RvWmV3LU@Cpl4k9)kT#N09amX|3#4Q#Bfn2Wvwpnz&6s{YnD!877svDj&y^ou^VDq&z~siv*H^#!vyHd6AZ{3~ub#es zapE)?G4YyVMv`l%T0Dz>!RR{8a=g{^AKa?Hm}0}8EbmeuG0E3AVM9?}%{l0#!bQ)A zn%UBf!%w1A{Gh-OUK^wHM~L@nvMkiLM+dRFSq;t2bH9I62aF)4#wZKnuEGTi{!!I{WfU3+U)&4o`*J`BVL!J(1WMSMvgFl@A za9ZMSzu)+`|BG9cH`nO8k&%RW_afHhAE*SOU0@1L!Yyv+*Fblu()wwas6j*SU}ZpE z-y7%QU2sJ35N|v2wRd^w$zjlP>q5CSU!h8+VBBwpcXQ2eEke8ViT`~E6-HOFa8A|C zvo5l&Z;!0cjx&F?sfuC0RM@W=$S?J?9j;UO*T;>}mZDy&cbgTF*az7sV4{G}EtCaJ z5A{+oUHlKg=>X*8MYiDkZ}En+R<|8bT3lfPTR-G<#7XA@61k<8;V(8eibmI=vifWH z9k;m2rr5e*OT@SIc74TO*0mps#?kA{EYeoFg!#%pbj zk;8Tef&K64=_%9`KvF~7AmW8yvq!F1C?C)5$Dk`+(DQh0_*u;rn01U|FTrfDBCHO{ zLQ^+W-HJ4wLP~IeOXoU(;o8GvV_PQH_0+-3B%M1Y!%}M}Ej(~3Xm=w=3U0!1k>7>{Pv1QS~jTl{E+G>sK0Y37SGXT_U^BI&I@)LiYDqr7LpKauT7|gZ!NAFYk~98>MeZRx z^1fQ1)%x7hA7mtiL{B$M_!Cz?l22805b?sNJ!i)=Rv1bj<58{=E@+Uf7fBP^Um4nE z_)iI>?|`mT+g9@s^bi@CQ&|l&WMfo_d>x{drd{^tUnLLDlh=lwxK&%=aC6paHgU(p zoqQWNIwMQt(}!>mAm-ue7~Vv78OrZRk&u!CfHYvyC{%??L$ApV%ez9So{O!L9v5sZgW%2Y!BC~2S1SIC1zv#2b)QNm_Pq~EdF2ZTT3vzO% zf9K7Wm6b3F%Y&X{z}qswtbJ?((L!{p5Pj-%Ah+_@b$G3Gs3*xUi}wg;_gPApClDl# zY)A;q0LR^71;S;iB!l(6vhQML#njAf6{@|V+Zp+93aX3Y;bEvyxVX8YivWuja&9L! zVeEr~g2X##%b;2*Z8_h7!GcQgHoi?kUOs7s^x_EmG16G@d%zX^IBx*|Ks`A6#6SYvupgfl%W~a;`R{QUJl{NeDnG@rwKKX*`I>I`6BuYeFj}?L z*Yoo5z(EU16tJWH)07qu6#Wa=$-pJmJeFMYyRo5xkB<*LOQAbXE-u|ZhUK3b!jQBx zxrx!};~#nUS2&Ng7~WqjzAbW;N)LZg+>PlXISMXeSY+mZR-skI#j1?@QAiEqY$Lya zKE?{G+z2zQoq^tFmmwVvL63E+jQ$<{wpRC^^jgHW+Op&{V>Xz;P=&R(-$@<%n-|^O z(n6JWbmUAa`CJ<-tAzwwpaJclE6yXAnq)TuX~5G3n(7kKH_R9R(VQTrhT4$@KkcQc zga}JKd8w*6ugOw>+p~KJOg6R=fpzin^750^`IfH{7nvH!SLgDC@BOWl-802Q$ML3}$G_!6tok*b1m zgAG(`*pJHbZo0cASn$W1o06kCue~AqL2ZvU>HB-U2WH=vb2SQs>FGU6Y4NcgdF}7p zq$0cJAhenE&O+vDjBOu5Xw{;tYkjzYLx!7sMx0vpfQDJH!@j^+yibT26`wrO0dH95_jAQSzj zzcpt*>pcUz?Z)wO!c~#ukP|^h-nZ+PLMrj*K{*qCnY7MScQhv?{~IODH_UecSy9%) zfsXfb4gskj@PAKPumUb;9TGGfo)L_4}OGJBYg6#re zN@xBrgppID>-0GzN5~vC7daOO!qx$8nCua;kOR@Dwj3z>w5DHduOC8|;tcz}9je{3 zN7p~PeEZ>o;%QdN@|=t3yJ=;mr*%d~*vyO}&zF-F(Wmy7GHDyKi9_|xI7a2`=E#V4 z8PKHbI3FF%|94|Xya8<43@dYE!4Wx#|JwXAU)dQECa8Ij(V z^J{j`*lYQ;YkH@)SgX0-O+eo|b-?p&*E$cSple1_M7G+Zl}AY9q`V`8vPghehS+j* zoj^nvZRtM$fwg00^A3HTf>8T^%x$He)gPfbu{`^cWUrDK(R4@@oJ`el|5Uk5oT(Tb zNLu(;+COaiC)H7cF`Ie$^5LPArDa$yeez44SQ?p+rKOH}sa#y0S67;oe;kjG#VM4Q z<&h8s{OhGcr>RqQFkePX#Z>raq^GOV;k@J@vl?a#Q#6c~59Q!}mMq(_|7jbiPbh^@ z%##FR$j;dpa*R~oG{yROcucQ5CCvwH=K~|-MZK+;qsvs++G?xA^o=F;nPH|}17o{^ zqV8m!iA!2qaD5v7BYTdgKTPbWW$xky&S;xUFcEj(#nzx&*#}wp=D$TiIi@$J^l9Kr z8jqEM5zkb73%5~H2>rP!s~R|;hclt30n{Jb=nOM!z!Y|ob5Gna$R6H~-1?wS3=wHvd#@B2<`q{U2iOj%u><)}@ znd+xp`eo4pI+|!fIC9jS3{_HB5}@)LGOc9SiZ>H~(rJ~j$XQZyCW7@Xibh4@pRnu; ze@erI(qU-la)spdWNRN=cB~+%q zx1r2yZ31*_BmVAhTzu_oJK%xC#i@IdF2)Vo@fhpVPi4R+EpE&xN%SZ%?&##peVcNq zwrm8uck|C!h(l*)h>;!gkXeP1_wRut^*u68nNI&crw3FkLguvEA3C1))+gaNX#CV* zz(u`}7ltX*(9}Q{79Q{3^7ze*0yidz0wlFJ2tvtIHN@{V^j>KP+v% zhQ@8VYh@%r{je~U+!*+mlw2*g;tk-=fVlp03FIH>7J#E-GW!mEG@OaGH8mQ~<0C=y zQ1+VA@y~W78v1(213tcyo2nN1Ku9aZMjh;^xc7HEQcZn*L%NccIPdS1tNVW1lZ%OG zudMn24Fd(P5o0ew7taT1T?PrhL%DDa!qKo2cz}efuZNbA>;s&Sl1NX(^WaTaw>8zp z@4_3!RRsit`v8!EoP?{LI|fhy|Ha+ugjxsAfAxmF@=z!NmgQQjt8q~8L+=3MJ8f-j zTD;C64&!j4D-4KC7~2|-uJ2x6`ONxj%Q7Cjeq7v~Eh;>+Gcz2-BfZGW4!d`(+)m_o z_%VjZahg53(Jc`)tR^c@00sO=09iZ~LlF6Hax31L05FoB{fq*DCU7G#HwE9r>p1Lq z-tXkxhuA_~?CSykcx09bqk0DQ_HHA|)Y*f{ZqRxaPoDe|_tiL8`R}iemC~`|eKa&Q zCoOF8xW47ftbb14jK4Mw8M-Il``xYA-f%A0!R=dC;;s;WUHI`10@|CuvKtzTMsxzl zV{_BfDFNOmIR6dP*X>eG*}KfAP6q}rqQ5sqXz;)z25<o-t`fNbSn+g`+sYTROCMBtIJ^T5I|!^PG0lZS3)&cr6?=7rB>|h;{!Pd(2XDy^vKb(fUHS~N1mFR3V47H zU=>1@p~9*Lwi#IY+wiW`)95HNbH`XxfzK1AQY6dOE%HZvx_ZjRFE=+G*&($CwLmNt zAK)dV*>v~%{<)hGS&D$*VrM(w%5IZFb~%O5o2i~BK5pR*{y!k)#x2gabA9YZO7&$@o{$Mg z)&z-GRli(ag>ZFk?IrHYI|zP|mSzM5-<6K8rsm$95iWwAK0fM-wLhVLy@D4-p@bj(t)CzB% z5`J1P1bj{%3lI<&zLbsdbIbfD@oaVIWTdc4_SkW-&ZGE66dpmV6PMJv@tyrjNv~+!Wx0CmwZ2MBcMDye@Hw@L8y`oSyq_4S$mt6lcrgU2+L$lR0V)f59V;^UyIO0kw| zGKhJL+uJ<-@$zTqKar$vL2*K{Rg(yIvNZ4Qfz6vPPiSkr%7Lpq3wLKmvlx;Qq#z7A zJenEjIfCe@TCd8f9Jkjh3Bf7CQk7!ShU(NGdjtdeeMfktVPQlIB+ak3*c1`8}PIgIwOK@bM4~D6%h< zmL3?KlfOmm54&C^#pr518{8oXu&O?z3ZlYhGVA30{pxV!w`}yxF3HP6x5I!YsnU5y zYjst#5 z%O;0fdoegf_j43BgaPZ6i(qY87YHmZ+32^5)mlcSy)5N01U1QOzM4<9TfS zQF0$EGBAycTdC=T%FNM$scDCxd)wNvP7>EYtDJv4-NtWbsr6A3B|~+8MGYRJg94-S zd3UB2~?l4XNRgeHPUZ=s{};x3K8pLM4SKYj3Of}40cKD#~${`EqL0) z)E7+~A!7Wus^DcdS~1(_lME-ad|fq5>uf=rsBgda?B<=D*ixcDa~v*n79M1nj+!r~ z+xwP%{hqQj z@&UX=Iri}!L$5E)D{=+HP=**shD?T+&?w5SeF51(%ff>q@CY)6t~eUe=K}N7BRMazaeXm~SEkIL*5J(!)?Zu2SH@Hyc`8 z>={0`ORA|^yG)apr%B9KeCtC6;cOaiUVJTV26!BQ-z2s1ye@o4Stm2sRBfjv$;yg0 zp~agqnmnMyU=bd2^=}mLcDR+jWX`F7qEdo(-h`}7Y{2l_!l^LzVwZ+TxLeYde7Oa4 z*pXEpu^g`ZYbtH0XtFtzCWt)EFchUti}q-0=79OhnM$5@Yg;Rkgi<=D^2=-J3r!90qW)R89~i!bgErKWz_QqvD6b>FaurL?ESqvkVhCwoHJmas7pDZ zTG;f>sbW1tHM>}jqg%Pe*?H(?P}erEnc3k!C6L#!820wwUi^6UnvR1whFp=0pZfqV z$B(z;af%&*oLzw?BS!(HYB4f(2#>+_=&C-iqXIjc@orPSRD--$Zvlg!1Mvu3s=RhL zKGsptqm)FuGwkH(*{45QCt_{_0M_HGN%N^;X^> zT=piEdsruom-lJKE^ey~$MWw!t=SxFV{6?EXDR?fhR6F)Mn@m)n9HAbd1Ky%FAflC zUaYF2`n9=mbkwwkq__Cfn@uJGMyt3G{^-Li-dYPzEh!Kr z^tB{So3=RR%|+GwX#JXsiw^mXd$u_>Zc3xV`9G-|9`nJM4Z~6mOkZt34|xvtK4ok; z)Le8;(M2p*A{k^Nwc+1*maMm-%vRr8$GyYQU1xgVy?4!qFhZq{_fxx7QkPUMNCD|_ z>`h+&UmMlUgHK_mO*Q$a_ku9%IaQQ*C{fFYJ|F8L__78kyd3m9ci&* zWx=eXelk%}r+`as=MhQAVn#*%spq<-t~~Q3CAiaA*{Zs8X68)ep6LgolMr^@xnKGI zc=31^K=GW6>znPLzr-nG*e_ClS7CsNhK-+EFR0|7(Pjd#ng#xZ@ts}$Gl0tW1E?~o zkN?(twk0yhP<5_Qk&r~x1a*KdpyR1CALJ6T@CakIBR-L09oLIjMh*KOp?)zZp%gF4 z7DLCS5sLlViF5SbkJ`qrv9&_15Nsl{B73nHEC_$D%f3S)x6K(wud^NZs%Ub}1!tmc zW{YsdG+_Ci)JI`=(J0d4Mpr`QeXE53=Pg9=6hq}4* z&i(SY-E-U1YbC7JL-;~ZUOL~WK2CpSh02vxg4kWUX%m4p7ZJD^Za+ggj;jNP;`Uzt6^ZUaW%j)c(kn*ZewmKeS#QHyc zdy;6G(Q=s1fQwJ-a*@*XwAqxlggAb=RP?FV21eI`yLm!zs8cr-h8jhTsr!1phhoNgCgFsw3jSDnqKEhy zYV4Sd$$mmhf@D&^bA;0sMYL-9FwV;ww9=F)%P(wKuX(I6muC!Xhu>mDZn${1HsRHW zMTBGF6JjD$YaE2W+c$nQ(DX6u2pPQ>g*lA<@kbYyjm_E|zsKRL81mNo=$Z!s@X8AE zpLVZiWDy+lmc#Qc_wu6+a>#%!_^v@Si5SEWe@Iy7`p!m zyl2PA{qGz30eno9N@~NKNCt?sbRoDIir-tjL?f=P4KAeBRj9W!f9m|ZcY?c(3hx!z zsx77?5tNE-n)#VOY9bHURg@8v(82%8^0%Z0K3b&eU^NZO11XWKhr zL`1~M`~SD8@+PAuAO=+`v|**Kp&=rW>$J!o4&HtIXU`~so@o0S zkZdO_N3l+ww>5W&AJE!QoRqq(?s#W$8N5W2R+9VdUn3N@5gsTjGi*R!V9iduyhelV z%p_vNqom<*RfxyDwySu4GMZmiUpV~!VUW3J>Ibn6CxAc(c1&D|2n=r&n8uN;$+2M$ zV&7ah29Nt7_|-?1wk?ojtBU0F-S@rzTNe4YVT_pe;>Cs&<|+4%lP<3kHi-{2YY5{{ zo-uD)PL$e$ZIptS*O-kGk69mGHtf4EO5UTEY{!(dKr=)(E0dsZ)>)C|D8H%D^x?op zFbbH;FZ4gn11RefMYrc}!H*HT2UrRrL+`y9C(2mg?=677b4+(QpSD&a&wZ zj!6BUS#*=5r#H-{(9;{7kthpq^G=~?I;CX6VzJS4Ds!`SPl~z7iKStatF%eY|74lY zaoBmngmT*u8`wly7Oa#}YHhY%5SE#dOm)ZEsO@cuyk;BIH#Ai*{&#P^q*Cxv<%dKR z3QTRr>l_sZF5AtveZ&)FhG+QP%zWu-?Olzis2Mt^PkCzeO=SgfJDx-^?iLoS1yZ zH9L~pk;2LU(+|Tx1 z;>Y*b+c@ARnylZB&$=UcOZ#|aT%_#RL_R2Hxt4SK!ZvKXkS#&U95#_N=7T@h)7F^bhpx-l0zfXAxM`XND4TlbVx|2bSVweB_+}&E#2w2hv$9Y>-k;Rcm9N# zbN1P@T zAg|Xgx>Faw%3OYB)%P*7Lj7(EYMpQ^2nhisXM6jI9}P4q3Fpkgo9@e8;qB*h)< z`!2E%EfQs%D}dx$=aif#8fa^WV&`j|#_@vj?&`u#8)6_$m3pFX=@(EV=y&}FZf}9D=tQj^k-?l@fL@@PWPig(`@J^ft$3! zoiAA9rnmm(bchSDuN?27+gEQo_ zUiRqkFV2+Z+c7JX&ozd|gn<1zIFa5zb2x=FPW)h;JE4{9qjF#53~yf_;OLWDv6;R| zLz8tHJ~*gw$_9Ad++12Tn?6iT9>;s+`^MOJ#AZT&l=+awHZT4XH2|NlKxxjIg#3XG zia@PeaufN4)<-*1Fc$1IME-dc(h-T#U?L(E4rzDSdyk!l!6W zDPD7_Z9+Z#Ea2c-~~N=vmCq4k!+O<{aQ-xQv4t+ zhvH{qtdibgTy~YT2$vpv;@}!9gFhj=Du2@BR98;Q4>^AU0QnSTGU^u)74r`B!lnr0 zSrw%(YD?qP!(TK+suU`J(uK<##aIWCCN2^Wa80*!{gcZGs~GVyIJzvtKHthZEtlfl z?byEm73;ZKoK%f>Oji8Bho@30s&+JGI$+EMh&|G!{ivkYr`TJT=|X(ZW-%W0riiq{MGS>iR$*qIv)*bsEV+IT=z1@z zvy1PALBNqh9|Z!kJ=>O9d_Xh%pNN z1AfCd+2srOg#wFGG0jb?M}d3PNa{6NZvkOOGM(b@mq*}8*{T5LS>E^nGHzjTQ1FGu zBCeOcr9tTJStKI4d(DCh5*x^{m9^4)j**B28SD6S3%D>~jegm_m8J2G$EjmM%5k)f zwf<`+fH-y|O}PX`=(y`uhto%vsBuO%LG2}%N?bpMHaxcxfVnMmL+;Y_W_NTOp%7hN zNoovK_=lmP0{w})9E8DsZEcR0r;g6?(Qx+81an#%4o;Bddj?X7aVer0S%B#SZvoiN{!_4x00g3xrWmyMB-sx5Xc8k_`Z4%o{GIjbV+$?>pOj80BBpE&HzwexC9IG7w>@${;49}hxou;Bo|O` zY>^TKPM-ne(Aqb*>AQ=g-psaT{TRQGY#g;!^7DtJkd8+zP{=tHQOQvt(4VNrF{q!K zyuuHBgT`iO2Q5UICe#=2B!?fQ^}J2{@X7%@6m;(2#fF1;d;?=i1P7A-Kt!Y*hYKa0 zTf5+cz%ED5fokz55vb&sj~|*(mN|veBAv1w2=}l+_Ce;>zGQ^gI!UO2DBGU^g>lpr zEci4a3cI8wF0{rXr_9W$#xc-mV2$L^fVXn7H#r-0bD3yC;=FTz)P)yz>y9k3t}mbf zf&a^HY6j1qh9rFeY~Ksvmm+Juv6IsNgM(8wXpL)t06uEAd?!csD5(y8QFLVcBxRG4 zjEIxkrQsuL%dMu(Y2GhCG0P0p8fo4yqCX7F^c3Z^njhlepre>oxbkw1SYKT8M<=}g zGtz-JO!hMz&NU5tSQ`DW9o|2&s_VT+^Yrc;QYM#$4{UQ+370kunqYQ+b{@TW6AOuz1P`%{I0s_#Y!ZvYYokdL#zB`yOp=6K-(klXgoplZkb zcou_FCj`T1WgbSjWCustI<6s~XDQ5^L*?rohU?@y-}vxRGHmgUy`Ah5XtJzg(D}9Z z6ei7EAi_~NvqUT)mrxS~RhWH77R*AdCFnCnHVU@M6Xrj%BR2J5WM-35KHC0bG zWqJRzzaMuA6k;L96CP*T!Gs6mw3iWK{g4X@rOQ%)JqHLpNuDD1Nc?<_8wui0Ianw5 zx7!4R5|5gNc)6=+`HB&{b%nj@`X`1rR9cTsG*nw|+r0(;y_+Y$q)q7R=`Kpyh3AC6 z9GMAnu|0%`m(rgo4tKlrA$D3vjt|1u2_H71#7?MjBijju;eKjzX29abJY4LT{ws=x zHtdx0u37>2$M9)!O5gSp?hS^ zLolw?Aey0~K3utZdyLUwlWfKOg{F$VBbnShQm%2jj;Vl!!Qn?DuYNo-3Qb3^LJuM-=wQ<=!67T3(*7e?4@se-i92Iz*~) z2!-h%OW{JbtZjLTvo=DsR9I~R=aa6J80Ygw1m9&em6v~dPxcE2OlT{}pu2$=)x)&B$^Me@|{R{xvHAWk5%4taAZu_Y;UyfO|K z8oUWI|7FGtH#IAAQ?)^@Q(2Qd28q>xLe=;s)48(zI~XXNWY?dj>%3Ft+=1?>VlIjv zuw(>XnZFbGSJNQ%9-glqTh2&PO}Z5D$H3B>&6&Rt^QCzC0jyezKV*XWHegkLm?D4h z#IxgS#GU8ONZQV&07X?>iLjrW7rPQ^`n4o?@}UOv+PR*)$mW-;@158c0RH|51gKaj z)jo16?0-85)2uQbDMwAjPkujT=Cq=>4L=q=v$6oiMg2O#GHaaoedWTvWkCzuQrFm{ z@iNfI5AS04>KW60UI8EBZ1%h{eHY#MbRewO$GS(TlK!`%0OREw!<{;8hL}O;nN;e; zaD4n61bOl6qmJlroD!Ef*<5iivrCe~*^zFcqC$`r8l+*PiCxkvUBv$|6|{Q_?oSQ0g*J72cGQ0fQVcaj z>d5kN#|OtX(!1Tp>ZGk*OO7thY6hX-7*3vR)z5;UNuc@AXyD-0t>)Nv<@Go%w|m~a zRCNCo&C{HC-SO#Hmf=CX;m8ey&!)X&%0DygV@qt_hxWQ68n#HRL20Cr;zVMA5gCE} z{?ldw2hUn1SDf%Loi&veA-(TMtNm-}(1U?S(S#@`>Wj;UW}~2fI>~?g6E;fX31y`W*Te0v=pbw?WRCB}JMp=2Gp-yTe1VzohL5-6 zh!uMz1DmG|nhWBsE%a%F?&8VhG%7a1^pi!x^KzBG^}#`mxzm`Z%c~y)n{?Nr@Nd+w zoQ!)NmiN5Lqh^QdTZBX82w@}_NGlzz2-XpLuEodAp>K1#JW*s4>706f|C^NBiGQ4P zeakb?^tKy`lzBdClaw*Z`Inz6Xb{Q0K`ES$HL5fwG4G{9)E@7ZrsA%>cAHDQcPoS6 z2~HN*%0){PJx?c$R}AMQi9<{y|(tOIPi+m6=gw*?0)Mb|TFH2(0$Vk&go zX6ZM|t%w38!-Xymz}j}A&5@&1krlo6@=4}=Uc6*ZFRP89wk{0LtMmXH=9@6~H53b% zILl?vK(>LTq9(qsX$>rOm&XImAwxSZ;yJ%2_;82ouCj8ipnhVTCvOK`$A#StsYsL) zQ<~B(6D^s@BT_8T@iEXlL`7;#;|Jn{^g8*mg`~I6!wd<#;h_jQ%q5BF}k@08lFA0^=AJV;un@! z7d)69m`yU+`;0bJ(Udaqx|W$En#(J?s_2|QlH&Us&Gb(~!Cti$kMMniy(-QTS@1bv))lns7N8cn@h~gIU`_+iipoJPKg4)V7Ib-rbXd>Cwzzs ziLA_Uf*HT6s=Vrc;eX{SCY}Lt%G-@qh)k>HlFH}ZUEL|_Ttu1DwlK|Jty+Kwt?kB6 zk+$M941RrltUBuE)B%+>jDZPgN}utQw~Wmi$)}3chuHB>D61A>&u8W8hsjkG7rCMToG$+ca!E2je0lgqr@shuD;L9$K069=tSvb~X=jrUU*X3^PS|a694!8b>BijK(J)rr{e>U#;14%k0tcYM@9#X$%Us-hx9E3Q1*oDIsv zdXi|AJ8T$Q>N{?ju3DN!?M~Vm=QS5E!AAYs(1xh+?3sQk2z&DNz1hn=>j>FW&{SV& zjtanylT{J%maBV)7J<)h=`eEnE9wr~tWzmpesdd^6keqv{Ud9}dVcpTk>Bv$r7-;@1c* z0LJQj@~Vy_!qvwnG|yBa1#RaT5Io&H*caEJJr?~i0oQl%{xbYk7OT+%q zv5xGx=O0XsOL1NyL-v`TEIBp(ko?`Sw_@HiG$ixPcJx(piZaECd=d2*F&DKe9uFt! z(aL5zb2TsaRd^k4AFK<};=hEY23@(n| zJA+L5+vM>*Kc`I&FzlsKv;Hi9#<+zQGh-oInK*GM>}Y2$LfsU`@YU7jgBuCu4Oxo! zgK4|rWbF&=Li{lQl&lTl-vr_0uv`LyFeBCUK@3(xAb;bjuWoG;f0(}{q&ChXbN|}| z6`)aKp}nUb=^ABICY@zGtI)@}3SX>^!C)%txxhlLX?N)@p(K>hGx_a6XfD$pomGNr zm&HKWl)#k?eS9AWDEuIcq*MkE0jX5kpPkVI$8U%cUtkQ>05k=17SLCz5L$fPh0CYl zk8ksN3UwaYmF2+XnDWdee!kMQ?|30YZQoZS?w1()gRU~ku#D+-pX^w!VIwok6UB0A z)gsofPY7I|sX-8D->iFJ$hMkhg)g0i?a~xxrM4@Gq(pTeO}MvkxRWxa$KqB@_nK#L zDe!%}sg;f5GqQUft9y~ADK)0$v=(ba_|&=TcOSzbzc`lPD)de(TI%Qtc@DG!8g!3Z zT~O;GMBzBc=u`%%q7tD+gLN`jd&ZK~AMFKM{?CyX3t-m+V1gnhEKYctpHxn-H#;Z^ zt2=?3iiDU{AYRi8JRopvZMAh*2%u}~sl#%9Ia^5AFzv^)Mi08`?pow|gaI$8se5AK z|0YJKL&DA&7cuQ2kY-dI4r6K)0a|lhctC1LTV7K0_~(R07C1%_;4jrI{^DVbE(92u zWqrObvJM#=DEMf{G#`0iqA9!AXTbF4UkA@B&5%aa+v`A0y~RN%P0}PZkTs5Ywo>%f zvu2WUT<3@AvSpL3xmd|VK>-!If+)SJhSRtGIPJj2#KA3 zlNk@WGXBG~8P?*;lq*@=&H1`<9U*^|=E}l%cCAbXOU@}K^jeVCcgVxUix>u+5J$a| z7g8ywJ#|;3!Of{`Dg+Hu@scdNECN+XHFD>0vO>UwuMZSKXa*(Fel^%$_wCU+Rp;_G|0=v(xWqfSg4s9dQ)wcEf0XS5T;an$B(GFWAJ@ayx2vn_gOq;M&0b z8yU=$Vq723Q~iVFA|YlFxT@A}Bg*dZT4_K-lJnt28XqwU(+TumT+ULKIlYTt!`kdW zRvht5e^qE@5&nB}LztiD@TYG~V^irmK!pE$ALGj$lABtxZs|%#WVt_n>u*4Anb5oY zBAwBx=bA}BCXmgL&d?#8FC{ZSF1@CJXajd0#<9xqnS$MuEQ1dGkH9EiS1Vh78K8OxHNSI-GhTa@WRgx7qc%D^2e zMs`9&-=^kF8jCtCo7bdarYiji7lA(+j8mS%Slx_0>+BG+}(>SMSDGM<|f{G z&i&w@&_3tI5QFt1al*-_2>#bpHfO025|?WJ6ylEF!Qwy}N~dvBS`!J?MaqCt=);)J z04|`$?TSEva1h9O3IyO)rqmY-gRYXfL|l)6=+XwgaU5GKZsLEZ@GGDRwHEqou6fndD4{$(!r~EuhEj+fz8qxSSCFU# z#Nrnv6NqN}p;xP2!2EGkyL2$!iIeg?C)OP8);&9yFQv=w5Yguq6u9u-f30|q@LI~o!NpNc-PGBZ3U6s0j0v}4rdKALSo1?+597|jKJm{V5VzU$2OBVW4#@xjApLw1k|A)l;)AW<55>a1 zeKm?wOccOS?kufh-%TsV#>PBfAnwnK{o&m`q2E$>_-c^eWvoAmq5Iac3zVOe+E;t&DokwT`Hr~y$Z4$2M0nw}noY+N z2S>T(9Z|?aSy#R}o{(;AN-m{ap4QbEOBY+VRISz)e)`U+sw}BD*4+;rqVcOYU4t8q zmF3wAqPZRg?0`#@Q02Jqxlanhup$ZjmW2eLq?yGx^t-W?4_m~XwFh243e}l;S6E+} zEB3{7fF?i0ep#F?@5tQepTw5=KpwCzQ3QklU|Z;{_pNBBvx@oj04NT1wRBeFV$_v) zPDsLfRGakt48AR{5YL`^1nd<8?mBw$wKVuO9q#be>raellK?u92ITj*9s;`pH5&CF z(BblriPCn9oMcvQ4)jsMI{&vShA@qELa$Jz@YCzG&m`9pXB>@PB$`79?efIxtv!ee8~Gma)j9~&iJ^Nga99*TUoHn8PGSrO`Bh! z4n?4MZ-FR0NwUI8o^LwzKA*12I{Y6n)7{#Uy25>!hahnC(RVrCH0%2#vBS+sFmivZ+74SZ7yQ zYwVm>^0o!3(8-YDY(3_aLoFs(Mg6XyN^)b$B;+x!zxAPXcQ|L^wzPDh*k8^Ix=Uqm z{mw4)-{LZfBc3!{u7aswVp;KA5y#M5Br7rqL>L)ci)u*R6I3->FAkl|?gH&c81&XU{9T`$99B~S*W z`Uu-LJ_%!~yq6{aJ9)(1aUDPAsV19%s5hSL&*$Ae3xX2fBQ%^TozC-rF+2VbDTtWu zkhA*>V72=P3{(Ge1~O9kD6NVI-=^r&5ekj5$Y2R*PTgw+V)#7m8LsN;)Nmb@b+NCu z(@I$F$W|c^_x>^_w)%2rNZ4$o>C(`U0L9I3T@D#(Q%{e}<3guwvADC;RTua46VG6# z;=9FZEi{Kczio~YRBq1+?Ub!6F0grR7N6($+{mhEU}>MtxJuw{nd|#;mw7@`Jb@2v z3lwm9CAGPLMQpHhf{PwOT^qKivW;!V%NHH^E3l9iLE8yU*sk@^g$AICrA7%2x>8D&LK+MK%sYH7apHGj#^Z6c$F6 z(YgtQL<}y%s5S3@f>N1^&`=hGW_cjes!)y8(02hH_=Ku-;y}b3%Z014-I+E?jEO!gX(4X9C?$c6wv5(N4fCz;6&5BNdL(q zg9i@~+ygR}ag4+Ab2$P3s5pi~ozNoQP1FEQ$J9+sx}(uov;2=4*+?>SWjD`O zhCkI;78_zohp?{_BVlSFhxv2@6#OvP!|U{y`$FYuRn|%FL;UEvZuv0QdNvD_ltQJm{{rD#ES?); zA2&2YouwXs#h9z=XU_dG)J4{!s{)VXL@guHg3<5`2@kb^^|bKU=<)D*Mxu~m0L-ZV z{4E?5+o?i`N@8aJ2c>eis5nil~L=keIf7DdI!~0i7XTG3ig0e_!rfspkCB%Fm6#))%8& zv*VIu?AY6a-rkPJEjbT}I|cRgr4uTzUnRV&Ss4@+P|>r4{rHGHDkr$o7mjz^ z;d_q#cS-E}4fbEmpzn$@jZG)!-h8zYPxgoQQGo>hiFEb z_RNmY0?ZY~ zh^^iGmt%m0-`Id39w-)M%ye-Krx3}~DU(HasnR2P2=rG061n4&5g@zl3BtLNlt{OJ z)~Rm`q~AD=W}rLxw&^$PwWl&RN`iK?VgWmm3!0lxOi6otQTPKEgs;6(AZm*ki5!Q^ zBHc{I@DK3es8Ov+47e-s`Ul^DbcJ{-W*a z3|WRei@g{{lq_H>NK{r^?Bq-$3R(>rfF^h$pGU{yZMnXBmIJe% z&x1fLzb|7X;zf_eO#s2s3q~-YI_R{d;Ptl3$FCFrJxAA+RcNU1N9Yv{Fm@mr*Kz7p?;dUZm)9XDI-h zQXjjJm84E#=i5<4vSLNZP4BM$R&hq;fi#B9M{Fk_;5l$awFx8GM|KgNud;z8&lmB^ z6g%s4Tg?%KJkauCA>W7SI-^QbQdWn~Z+5AOlT{b;)udSG6#jP5MMpNuh5j{NPIqy@ca}4YqZm1_7$*BM7`vkIC z<7)By{X&&Q%vuT9LtGKTF$jmhMy(V}uw{m|E(I^5-EqB3Fnfu9a8m!fFi+0H5NV49 ziT~?&aUbdtP@^ghZ9(vpHh22S74 zMDoVee6`^?EFwd_vlE0m#-Yv4bBV<#1VkfOK8&e7Z^whzvyuRT@2}crbtOUMH{|v{|&Te!RJQ44vZ!hqN3BTkw z;SWS=D1(g;{1KBUk_B*UyQAVPXb<>W7y1ej9V8 zVMKuO8M$-(Q%A4D%;_jsmtr$&t#kCbAv1dF`o%D3=)5y*J^$>5&I1ZGX6Vs6WfV7dtVpUmPEGv7Fd;VHIho#v$YwrL*c zwiM#0y%lvU6rR;6?CefxOIFdK8N*<7m7v&{=v_#E#0zeqt~X{*dgP88%iy0I&K8=5 zdYHe1t20jdJN}y_PDJ)I*-Mae2~+6>ekSb;1g&s+KK6VU)L3&t3j2q%tcTJ?KhQbw z`h+TFp)U`;?cK}e(BtZTnCvCJnf8QLk{HBSoDsdcc3C9$Sb5Dlg?{Y7C`yrK+k2`Xm5vBAc-;E4u{gG~5~a z)+ymDj793qg;g`V1Y3VlX1!XB(<^vCp{!x!PG{HM7+BP)rzO_y7HgMzz`IrnlwI=1P>*Tn3@{ZgJ4Z)KE=R3Q*7!LKJ1ZwY))Dt>U7UVQYu8vTZ1=wlDM zvLd^|@%FSzb84NS1lm*0rkcWMs7|2U#>)AN#uf@DRiO&oI?O zfev3PVZL%mruD&T4(~a+;=!{k?U{D}TwDDOWQ}L3qaE)9ry}WFew;ecFP(RF9FBV% zUYs(&AxSNN(s($#|3%cLB#d|N<`yGz20$LI5+`y;=9lB#G@)6H6p{G~h0qRTZq>X_ zy#q&K<+W8=EKkaolj>&_DzO(E1XkHUmuxBMDYQ*{1BhG5luxz-6~4KV>Ur;Nck9T} zH7+V^+Vi!*59?kZpjugHl5b5-{fq)?q7jLoI)v6gQeW>1h*#Qy#HIZN(A8pRM>C1`t?<@#{#npT>Kss`_<=oC3vpv}GykvS z#nn{{{%4;CA5ggLUtbH8f`aY5zmAQ+HJLy47-$1Y@q>%N{XnrBIJejvb}xp#-cN1= zh9aIMSo|WozEi$5fxx;-k;S$PZ0`k~pn(uSebB)WNR2$=IA;@$fR)E-5ZhkCs_&lU Wy!ywVebR`nML|YIx>V9Q;Qs+^>FVJC literal 0 HcmV?d00001 diff --git a/doc/source_id_02.png b/doc/source_id_02.png new file mode 100644 index 0000000000000000000000000000000000000000..843eb85ebec18b01902a9911ae30467070344b96 GIT binary patch literal 71207 zcma&OV{|25*DhSK)nUg*$F@6GcgMDEqmxcLX2-T|qhnh;wrzg7@8@~X`<;Jh{;0i2 z)fju!nrqdXbz$z1Z}JjI@VM{*03b<8e*FOekcuDQ?_t3|jyk`>=>dQkkoqdDcT$P;1Zw z6v2iH1sIXfAi}QU7lcdjCIPHozi=J8IJkCBpT0o5X!7%Hkt}|0hC0 zdhE&09&zf0^|DW2b+y&(I?8m+GYr}-nayFG22rv%WV`-Ize3Q043v&1lXu1Hy(#*{ zpaK(RDx7i3?n^>0TXsf#y*b^mxug4oo)~t?Wj^v}d4(XYi6NA7R7$ZMvB2D#PF$PQ zm{+Al$+`G8*NE-a{9N^PxAeVTqp;&vcXR06Rrj!_kC!D(aq{w+!ib{6wJ& z&-jP^;C%W!30j*PtxgZsj>ik7UvfGX0f zY!Xe<-Yi1=KdGZl^vNpRTzSl>0J(fLc{KS?bn<8+gJ6;DDm6HuYwU@n`4bG#Wg9{P z<|l+98Xyjm{zHC?8@TohBKoQ0iT~LFWb*|v;j&Z-oK=&K+CPaN762@8Vrjp90)R%1 zAn2evXiyH3YUz$ceg@F>eP(hpdfBW7j_E+jA%5IU2mm;XVdBwMt+*^I=($}ljGDFb z#lDqd5-?!b8j$;m75<2DOTsGGs$iBg<5(#>J&JDNR5|1Ik}de0+k{#Fi3^A(57`C) zkKL@{;H58-nuwy(_2nhO^4wY9G|PZI<)~`W?HouBv?P1IZ$A-BWe$|TAhC4Vm-QFK z#_^(@ymr)i8rXuHr7-?!q|PN>0jm-)pZgg{#T%q8W27f!BOdgMlP=DkH>n{-TxQbj zC7I6(04B34y5qdD3y^?NmPQ&8Ay$7b7;2Jub~J6g2Ld=i`7zPoY$yTAvPO>kZ+B=* z(YV#0lGG<0FT*aJYcTbdzF;itQ-umez~`F`i`D9sLA= zpMKHdWTyh#9gUL-EudD8m9J$k3QB6_Fi=1X6+u^I3f!nicr8Xv zeZl0wP6WE>paZo66zuk4OZ$7nKS5pN0OUXjO}un1J(|=JJA67C1b{yv1;i5jRUJJq z%i}-hw8><%MmqXR0%1epBt=68)x}(FSvY4xD><UMz0$B;f-#Zxec30F+Y+dYjA?;-5g z8@msnWLQ|4wf~7xUDt?vzpeHUIRr*|cC$pn&;UTAUZj|C9-f^VuL5HSQwa?ylH%pc z!?WS;;p3uSI6?zF9&-HlQWWXGc$N4RB*AVo`aX^X%>Vp%m)Y9<)#kEyGnHmwZmKDG zmcSyYF^K!twdi>J75lyOZ5zoxZ7`&OhNs$feKYMz{xz)#RaAS*wY3&r!$ahgs(6jY z-HD)*($wG`{FS3~R>Yt+?|WaTOZt~4jqhm-=%~l`?OVOwao8ZwA*S!&d~ZY2CE$-* zM$t$!BTLdo`Kc<+n;f@aM_3pp172V%bh!mLP$_L+p2EsTCi-k$GZ{wP)%a0y@l?Dm?n8PkwfWN# zCtzb5|CSFY5Ih~cBV%L9R3u>28pQIIG7@q-+&MI6U~OzOa6hiP7LJtTS0;U17=NkN zB^=Xu>uuV-vrsV;~ zjc4^KIf3FvQc_kP*`a5wBW&-nR=hW*B@9LTNH!GNy2T^=`{9Yd(z$?LQJu;j8eu_u z%C)nLkA62MKjF^i?DgC}FJt5I>mIpBHFV_3V+WKmT~cZn+b{~ziX(Yrk@7$Y;+_^? z6)kP!PFo%?56yD&2o6JlxGC?`(*?bEUZUC#^O`Ij_Qd={URmfRCU^vGXap%@0C=aG zZOhqK_iL-d4yRKpsX+jJ1V!e_imtsJb|+UtzRj!2!sc|Sc!uX!HMehGb)LG6$*9K& zPiL#1$S%=qGFv@|PithKpQFR)CtQ!+NPU;H+hG_~8%LIJe%ep{ zs&i6J=rxr8kymM#_4v}LOGIB*vi&U1ib>Dgxvc$7iJYwM)8Dp(#&DD}g8D>(b@!?q z1UYGVGdjN8)9hN+e9@mdlX%Uab@z2>+E#YZF_wLd*JEBh4uw$8zFalT`rKH%Sla8S z`%_&RYV%bcUo81Y3h$+HlYSS$&z^63fb`(8_YyJSn-uSL)UQG}tSWiAh=~h~Pq)dL z>@K*@BxsrZ=2o1#he@zCgfsPv359UoJxhMS#v(hId$HmCIlQbVw#CKE#(!d|vXfWy zkE$9KO5}x2n+M!=a&DZ~0h=ZsEd${gZDPZaxmM=Ex5gM;wB2S;f%l`q-K(0dd93x| zq@Qi9F!Fl~x7#^-`!!(__e2xtqKSQD`e^!DAOm5qj%r zvR;#sIvvW$a<65fBu3e*hRa~R9;ZxdzW?9CstYJ5M*m*$?J znhnstSZ#b}P|A`$KVWjDT#qO`DLFUl74rypVd-OIBB}$&_%~2!^X6D7?c-wtTT|6Z zM)=%wGmAW0y}rUV^o2>!ui5{-Cdzzk<9|*KT^>0lShVzgNv&?p(v$Sry?CRn&kQT5 zsAJIo-ZW8uVv$SXA}m7Gk42NVTr;6n+)jyzV$-J7;UEeRL=Dx>%*tFTVo_4J8i!cwsPi+T0v`D?QO>Eek)BhNQ!2iAxq^F z=$5&Tk;#*Ah;&3W+bXT;209&6_@vIwsI4r#(=VrEmfl7OAcaa4R}#O?=evnDE+2sf zSU;Jt9f8t@PRvB_EhR?+OW57chiBJ%i96>TbN@8H-y>Pf>Dntxew$3@?ouTh=}j{2 z;y+T5u)_6ffzM^l{(W9g=Qp%43Uk^mC7ej@O}DvbD7b(bT@rxfoerTac8ZXT_4$U< zzaJd1LtK428)*%zC}qBIf%n)B&=u1yatf29EH?=t%!er7{joWAOZ4&-QRuC~j+e1G z3I$XStk2Tyt7kL7hNV(F7z#OQrH<&3VBA7U}i*=(1 zXIm+3eBR+))hm5YG>LfD_v_a?+mD|q(SeZ_TGQsYO-4=lcb7KRrOMO%_NxWoBgTw! zUfqdHVSAn`)LeM<3g0_rXb|q@j_qF@LrAa+&dIG$`(R_e_pY`yoqv1__^5mGTRJ?( zQn**!HO`x66BEUwg<6-^P*EAznm95b^q5kaaS4c8RF>O@p`@#e+!d}MO4Tn#k+_o+ z^Dn2$Xm{rn%94-WO5>!!>p$i7Wkr|LOPAFRT&?K}?hG;*W7qdNBEF4exSMjHdt{oF zX&^@W{X{w8{mx8vstzOCjP@PO&C{OCgCCq2U;Y>M2yH0gbKh^847RRkfnq`reb73o zY`teBMrnZa_4>mF=U%~9WVe5h;S$nSFi@9OX73&Q5G2d)yQ)~a7r1ET#^p8%{mc|> z0?|kCfAESqF=C<&V_NIxy`3=khbJN-)|IpaGGt!mkoy^Gx*USw?>AHe}+9Fh=t2=4PA4TPcn zNcG;hU*86u?;Ykyy*8tf$)HHCRr%W;Is$TQOCcC{RDEp*-`{lCmEWHd&l$X*%O?|# zAc)?b4?R1Hh6Q&!_tNdw+ykIsbj5e4X3h{2ZDf$oJ4nKHW1eonV*+YRXWSIJOE}G7 zlmGy6-&o%f{%F{1zwE*_Zzf&TD}8Z!@0iU7LmP)!Ub}^-=kL;7JUavDV5xKp?7FpZ zkG;a7d9Z2P*Cv!gkeI?)ylBo-raKZ;#c6d$jPPmFrw z#UW=#I3z}&oj>tUaZ^+k+70Lc`Q5YK<4*@?y~fE8PF5mILOIl-25}9TQ;<45X_Kj4 zVJHCkPeUA&`k}sZNImF)nC-2SMx1(B@GdCgiZpIIwVUBMLSttvT419Iv(JniKmxvD z{I%BXm`oV{R4&mAuA5!`=%f?%6tT~lF5pJ^*RRUJB7XcUkcj-3`vcG)AcEItiMNk` zo%VCOadysjWa4pr@kks?XN;HAcak3nqA9_A_zSIXvxWu**n zgiV-V-BBHMI#!o+n%vLHf%JY<2Sjn?Vov6OeTJo%n=N{9DpgbA+2eCIRh@^-_mcIe z%L$dvS7Ei&$I6bEo%-^3?^7>0!diR7jeLjNnBBbvZM&hZ)R#NP91PXe?Syi7Zu3u_GGBZOd+Bla~BRu>e9KLh2Ka#hkelPDFpz5focqd$qiUlcTGH zW*f(&lzmlP7((WV$8BY2@fd&Ib}4P=LzJ#3bGP3ot)Kf}E%TG$EgJEl{)s-eNq3T; z0s=pWO7|%$rDZ<1T5PvGaF=Sjobowz7*p$;!%Jx2J#tDw|Eg9fthjAaPqMFC9Cb#N zkyj@**dgHdYA%~#W$RgRcKV!8aPrmtOa*#eev*d_e5K3J zR9}NSv#PC!vlWen=psx6gS4b{UX-0-G@r#4cSjsbs2;em8%Us0Z(y$n!8Ek=_9Y8d z0;0#EFUiZ5jNVQ-2h~#0{l&`@g^Yvy+e|ic5?&Dwt`RrXuU2kc4M*0f%z;(1{fBU+ zFmjC7^t=ER`TZ6=5`!@>QO&8Lm1&Y(O)HH38|>CAP)xAdWt-%CkmCUIj`B2k&H{tH zQ`b%*V?0@&qpVTV+%n^WeVTq&NkB6Xd-37cWt+dHN`tM^LDMdArkv8Ak7t_;6CKHr zpx+?3JG;}6Az0*m%Qe*<5ie~nOxyKriJpRqzKe>!RAHR0T6ChGtc{G6SiA1amD#%e zc_|V zzC0c8Dd|`f?(dl!392|5LW#jHs>zfR(+)PzQB^>{Klsa`)dbZBfImC zRk7XBq(1u$#M5MdgLGvaekv77%aMm8v-UD$KkV3ztcMrS>u!7mgo(IQlj-%7JDso;pnIGr=FnMA-S3O;y)IYxVLpdjy?d;6TrPXD?Wf zu@RM!=wAqE5Rvs8?$qOYUX~j9Y%9pt%eb13K|Lzu?vDn-w(9-kWh%7`jtY!@K|Jol zLuo&Szi!}Soao0UdizihoP0t%^uHsKANt7vY;5$|mX5A^A0W~j{C$EVH0>A~WUMSB zViF7XPjTp2)FqDNK!K#7*F7p*^W9RC14VQVLUMd*tn$uncVi-yrGGxF~aI^-tW@_ft+U14jL z^c+ksB9NuWw8+Ph-oFhgL3a_WyXt*pK-8mvc-`h^aDNy&-n9s|^~>*y3??!`$Mrg+ z(JEswIlsf9L&@3zhJ2v)OOOX0F*!SZx<$2HavSBon@@G*HYWBF|GYKlmzHN#`EPnm zai@c^oM&tGl?Fmpk4tk_+MVjC_(%Q8--N{s&p0Jy!h;K}yYM$eczti|oMqN?_A?dk zTnRBpcDQG%(bs+53&b&F>dY8&eHSvc#heT3&uv0COI^IZ9}41+siY;-@qQ%xUWu4f z9AdH$jCrvcF6=URn_cxZ=MZxgU57F}(0S1<#(V5KnwpVIrFTjGm&_xFt2=a=AQOj> zHiUoB;)xb-|GB-<1^Gd{iT|O((b-q07q5-)-?di{KUBaZh0E>!YH0tUh2=MARCfib zg&U1yP@TmkL9I7q2Iw)TF7d5l{3uIW^RN0yW-9X=M2`_$3>#L|MDia5PTWyhhRnZh z5h_XDeoSik42eH+#&D#tVcnc?^@5><%Vjg7M<4;F)Nr~CKe#=Avh}@LGyEpDiOD(J z_L!bpQjgmBzD>I&bk3ycroP~4C+~p@^u)uQc-!*O&FQ({_ZUG8T3C!%Rbum~MMJ^B z?*Zeendn|HoVfecB?}o;rzbmuQLCyAM8eDweDn=}O|)7l!zyk*4g}cJ&)sHDlv1dC zgfOs5wlzGkR6I(C)j3$tD8LRR8e`;LJ^J@G2fe86n$ln9G5EToW zkRm_j5JnBY+CgVdFFdd z!rwuL(0@>`#1j@EZP-Zh!J>k4i{kU9B=zi?=y)txG?MY(@;EX93yv)Eu!;T2pG=?S zKGMSS`22DUEg`6syWkMSv_m`P6aUc)EfWrVX zVq`nw)c?}Kt`^Fe$s9+1-+n2#xav)mNGGG!S~MvvS{MSDHfRX1_p0p{GIXQ@&8ba6 zw}*@yTyxQ3Fz4b7IifOweXIRk{YfjsukV9vl%w3ZSVGJ(xaXu=e)1b}f|q+)3QJu{ zPFnM0;>IU@<~aW@88!vr!<^k{pf<$=LiAXARS#Oo790jnk$$XV(6k0@nxDM{5``gp zt;i4f2!A63MN40|udFYvnlPEwnK*t==>P09>X+ov?J@+WQW91D-P@b(2@PwsLZ!ZC zp!{3*p!(?azN0h@dwdHrl%2-^N$^2Im=}o`goK1_d~l-+=3{&?B*zk-2Xr>~lYf(?`YIP;b{|)$j96e% zd?%$p!~|Igb`hF?MFSs)m8JBAp(~fXu)aFY;J!oND^t(13|IVe;qTH$c}AA)kGy`Qx+vc#*j#`1Wo!sQVFx? zO8@nc40gV;H1MOrY9d~G2raJ})R+hO8KoZhFy0%TMgV|j14?2>3~opL?A?Gjz3aTY z*<8j-4~jN<`u8Go7v0(pOuUpuwu#ce}J^2lU<&N1=%nQv;K_-Dc1CT zG7yRU2&CVi)9LB(@?t}d-rt2bW7P3Bjpeat=Rs)ZwUEG%oQ3aCpk98o94{A)k_X^n@r!@X$kyXlJm} znNsYQzXeEDqq-mdecz8Lq9R1{ZT6mwv-+JRj&2>W+>OQp#N{M5vFK z^C)}9Xa89|f`kQ&e??-OHGz*wmMMI3atavDv!YS_6U}0i8-8lK`-fhUs$DrpF2LSu zh+v4{=6LKPH^kUxiA7)&gS)WU@+?6L9(g~d#mCS=VZJZHF|^0Dy1ZZ~@~Y5$vpBgX zhU!?)H~*}htl-SC^-r@LMd5;-M!IcoJAwaszVGR@MeGmOV#%`vkZHB(-YBg=&e+}1 zJP%oGip?+i{L{N3l?Dn`oshVac}~3Mar;B+v+wixj{79{lcL1d zs@Js+jLtOl-g4M$zMHQKo%}x*?E=W9aAMYNMk9eLu7?`F`%4#LKgOXbv8JZxYSy_w&CW|cy&Q_dJ0Ij@Z- z54x+b!^TLX@0kA?RSvoAd+~lM;P|+;8;a~tE;apwo`y?v3{=rD6-I><+N^SE#uaZh^T}g{^BErPJYJHZVP^#j`VqYOD@Y-j^e?{|r zw!6Q$H0>F737%o00HSO7T^CWR#K0sAg2AJWOr*upW2d!1*oOxKsk4X4n7VR}}I$Q}Dlp#X)9463~L}vUXeuKQO!J`ky;cWKz zq+xD!2L$Q?40XVyhwP=pXErOo7;`E*^_B||x$_0GDBjH5)p&m2;|R_@F)9slj$4XyDWGZwLHEn3b z45xpGr`ID91VV9RLOk8oAV@e4Go-IJzKWnn*qoY`jR-n(2o{zXwzDvHDoaG;XFxdA zK6VYw>xI-C0*2>i2uCQ%gJc!}o-o|(|IzGx@aXlt~v z&+UB*{B1i%J+=z2$Y9b>`RihK)0$&)(MPp(dP>{%MMZMGDv~{>(b{?9({6I^3Dt@mJaRU1iLcCMKDm)T#lYy{|VCN5{f;h=9fv-q?s& zVEEUi3$q2zeP1DLR4`PN<#RnVuc3ZIQ&{Mrkvng1L%E^m8`EvWBFGUNGt(n@eXOA^ z*(|Zz`C&gj#@lb()Gwwm7ZGYy_kX+qJ~`e&rW1ZOwv$WTG)w#n;~8&J7|0^`y-8}m zBJQ_!m9G*{j&I{9%o^(Hs|G&LYYE0-5YSH;NbJT~9THWUi4bw#wYh!a*V>CK zKldUlz|4CPZ1dl*9_<8e2I`+0@PadSvr^GBzrs~!H8tvb=pUc!qCdhC3UU5Z)<&Ug zo%zoON%Z5ego;xe09l>UJU&j6A|JPIXV-8ah$vsej$0JPlgMUX%8tvLS08SYK`~pao4WZIiRO>>J8qmHMh!CP@<%gVTsochs@{0$u!_GF{N8E zwGw9DMhlr1*C8K0F!g?>6*xuhjH05IowQMFEY6I?`IG+dL{UYw$HlH*@6a8+OLn`! zYs7t8iS@nP3X}&v^;PWeV%Fc3aLemJ5U?A^I_@*n&m`sQ7O;JyI#gj5|NC93lD+jQ zh%v&ktx2%8`Vg9PQH*tR()bGD+NF^B;hGTLaC(Fa0e(zK%QE_rK5Q4*P{G)5g@S>4 zZu%+cP=7Ow0qh8sgJf8$DS&W4q#t^C7_o3^lH2o)bYg-K9U?kze8|OpWOj4(V=`dT z#g?x{rV~tdHiGQKZmnZKHqXe>-U?G=x>1fh>iAd#-pdZBpi=EtT7e-k@FvsN7BWRk zSI_iQHa<`2Km6wX4yjT@Z|)9Qx4wCk_l@b}GzJp=g4F`Jew02w89zLfr#XmWrPa5? z{xssu^VJLZ{Z^;L3WKUvqk|ow)xp5T#>D?jgqDb!f7Ir}(n)DG7VADV?rp(8)0bFY z{C*c!Yf*bOyre}#_7XxhulbCJ$2^fIqzdS9!&F9G!T<}w8%4Va8A*6c+73rMhp{BJ z$8ol!=fz+2pXg8}VEV}!T<}WTyF+w3={SD0(IsUIxV$)-8!|4;2$~0)!7uze#OdTo zkz&dH%IxUX7OP6%Z<9bUA^_qu`(*1D=vdo8z^76nn}*josQukH9j)13In8&cEk9$h zc)JjOWZ6z4s;T)BS!1F=Gr&5tU=tjmYXR1SOl?gK5c8>3rdqG$JUKnN7ooXXM|S^atWeBxKZQiXumxq z7m#W?5RK_x6QO<-qi5*!)wt=h@whvA*eF<=oW9P-)h*3;p5F{FQTN!(Z}Lkw4b~%i z=W}H5Tp*!IZXA(cloc|*`fE5~IY~PM9}cK()?bLVX?B~8Iv8W<&}}cr;?emiy!tB$+y1q*xwXl<&Vy@DQMN*wr^Vtjl*h}SE;n(Z}MuJ9L-p4 zL83iJI6!b{Fa+S&wJ_Zn>4kH-#zUaA`$J1Jng4N>WE-{UX4s@Jw8)WT z748p-cfuOG^G^5W=y#erS&_g5)w2eQIC>dv^EDxQT3l0N2tMw?<@yDsH zI;qn1n9{w*c7eSwcLc7ULc%7?2iAKZD$e0w&PCaw8&9ZnSIx1S7iOCaGmKg~TcdbB zufde|z%@sS@Vm!y2g)Oscov|hP5*CFJ0~s+$P7n-~bUzb4)%(p~g0263xrYE+DgPOg`u_}R)2Ib$m0T*eA&k0^#JB`BT_`OO zS2|zl$tHGId`?N!apT>yx}!)@r`^qYIQ}H%xmt*P@OenEA+LIOu~#4huk&6 zHZcpNd3T^o@xi*eLvmlTCz8*F_uT#949fo z%5oiwA}A@9><}$eILyyHMc$fX@oP;U1Zw#EXJ$Sf=^sEMf%{CA-YD)Fv)>ZQ=| zU+Y`yic6#Y!+iLUVm4Pczqvc4q#9$-ia%*v)S%h$ALeI^y)>E)`{NIzn!Ir98ea%B zEu@DNw9F6ZgNJAoS^MXVxw6~!!8bJrR2e9YWh(yAt)}ppqkCKQ7maY8COkf`s?^d7 zdRZQR<*ichc5`>Z@~|af7Ejmg%d<+(3zJJeyi@Y@0npDestPj^s2%C5V{h% zfA>dvfNrp`IDOT{cmXz@`3@(8A7VI??M^}3m0e*x@-2$tsN(75df|e%;4fPHlo3Uc zEfYHt~qh?*=Vf<=9j94tpgB`iLBN=)lv1V|L; z2D%n1mE9cx^iC|BzA2fs<$lAT!y9X~LXUmVO&YTc9WSZxONdbe?U zyIsv&Oyb?EYkIx49TWQo<*xlC3`tS;z`l);K zLP}pptsS|jp)vNt^6JDUy}XWF>7nGP8~gpmXDJvE|IsaHCY;Ous`NTBcP^Zp!C`Md z7+_XW!33AHF9u&oj~H+2efQcok7ak|{nFgX$%xo|8=~d0o2g5XUc1>&U%Izq7*Ph@ zH{`vpn^3ZiUG90^jL|@#9=&!I2A}C1BHXADbgP0-gSU7wDo(ZBv=1?cow|ge8psRy z39n_kZs^5#U)IxC_PIIONZ-A^2A{pZZYOqwFVFr%F#&oh&t5)kvd`_-tzl`)4)Vgn zmvJBYI*;)&7waUZ%qX`wYJ_}du93%R?z7SZ2MXGpK5!;z5Szcl9`3ld61gsWd^bnA z@|Cpw*yuBv*^(`%m|JsoS;_o$Yy&`K3&A2^R=2ab@Yz(7>OIi%$NF*-i`(f|h)e{U z3@3jAM$OJrrlrvmWjt8hV#3e!WW2B_kBddz5$&7{9oMY+c@3=-T=Un$^rB+FUA4iU`ms6HpNw9z z`j|hw3Q(eiHW10{_}{1a_bWAS=dUeM%`Z1sq&pvrkFmufGD-&S+|FD(cTHb@sI#;{PbIsXB^eEY|hzZrr6O*7*k=JWjM-dNqv{ zK`bs!8*K&kHr*xOR%1WRbn@y9hPsXZgvJW^;lR)-KL5GnWC@Beg|YG6##F~5iPmQ~ zzMepAVCZ1LmsM~P6c{kVE5G2}{3x*njR<+yr1wD)Y5T00T1MiFu`$oOkSnD=iF^=u z55=NmarePFh1GI4lyz70{VFY!GJJyK>T5rN=qJ2B)s!t20dYhur)mETjr2CR$E&f_ zA1gRVM}$ieEh_}NCp5=rv^=W2aV_r3X(PY9bp)oa6N39niF_SSd#FV%h4;=3y)|B^ z6zHvZD@^Ge^ttrwZ1OcLzzn~ei0+y;jSu-#X1CaasY0#uxvS>BDz z18y`br5Ok&2Q_zVf}l4`jKiAPaFMc#Uqr~r-Xg{vX=O(8rYjPT`ElSlH8g_$wC6Y9 zUdk*S?Ks~;XF3;e1&*lLt~ISl4C3U{E`jEzrcASwJ&uhQ>@z^cyfK%#XR1S>1JwhsVhCN~ucSj&B(4J9A==E2hpP#87>? zLs8G^D0v;7{1lF6!cq1yrDv3WR{8%@7M=q{zaY^?LKtFZRvn4bzpIlZi5JT;wuZG_)o zP2FWA5Vhs$x#_WKfC2U{r~;ZS9j$$@I`G9=KAQm%*l>J|j1;LtEDnDW8<~f^Sb+Zh z#Q7(qv?cABR^$Fi%h&n4sYscwm79nams28<)zoDogJelP#~J~m#WC1 zrf3yy-^A+z`b!4D?+3SmR( z$d>z-TTRK6f$mny&L^pD_R>PP@BRU-AkbgXs;f;Ak;3=6;G7)gD0*i%5v~E-9_1=> z;b_Q7FgAK}!VWjFw9YQtZ;*fpNfeb6q+d5f+$6L8(z09jBx~24gGUj2;~?$b5a%m_ zy@%e1eYFYlo{Ko>?oGk_pbbMqGeTUU_c#4sFI#eR_Lw+FWN`~j#5HLeSXY@MOrLdR za)7e(PLiC{27Dl5Pw*B47wsgK`{7G-djP*m3o-fNOgcIVeClErn?EJS#m}lOEa-qC zgyd9=oa0YG60?obV$aS_u*?tkfOGtV^QrSR3|w+xL=I{5;;GV?zGUR_X*7m#3F+Xd zRc9TIQ}TIiLgn(jx|N!m(A;My1Lc=3J;lQA>BB=V9Y}5uh>nf@^!%IueBvbG`#&H; z0?8tyjS62|YsA%esb|_=G~wu(cj9E(wOFMz%+>o#vhWs;z8EvDyxPyb&xk$t1MbD0mY4;j@u3odqW52V9h94Y{OQ|cny8WhlZ9(@isVqkgjMk{ zHD&|HTuAL{{j;cpa&X4=BC#Y5J%cC?U0xm)*PDt8Im(0W@(Et@_u;O?m1zef^rRmRw`P<=Vsr_j;@=}9vY9}{W7$pJi6#qd81o}8%P zzf4~|{IX1!`w_)0C3O;VNl*SWjthFDg_)8?b$(9N6(uyi@U(2P`P?Z&`e4|@@bE+X zeiKQqV`b_VOwbq6end`EX3m>F`sEZW^bOn(88YDKF}tV*PlQ}y0Hzqw_bsK*$OYXt zc-8YNOu@omWIK^6%wU}8dEwn22P>+nZgQ|^_4k{OZo&7i5m{)PK3E|pTKO&Vvki*p zyA9Ry%i|19BDSZquro&TdsAGMyJxJPmRLY}N_PF(xs-byL z8j2KAJq_P1E_hkcCC1N)eYn?S9}Cm^pRj*K`Q7mDNLV z{5~!QaM_C5mS(Og=52PV{557hoga(*1Py+;^^_3l$Ad=KZriR)WJhl`rAU!z_CwhM zhM9Pn{BsM-pKaa{&`CX0D-u+&S{XgAFC{qvKx)xy^!6WERuxcO8E5@G60X?jIJ##Sw9NTOa$ytuFIDZ%Bgh7hBYdKCR;c0lg zAds4u+_+|ySq3l4A8VvrToxYkuD(FiKbl(J1eg{`Vf$OX`M2|`^(E#Z2yrU|9FW9 z7h+Q+Y#%yV?(}s!{t~)XxWB&v-~Ti_U0#T?X*1B-9-Fj!mZ`OpbZw4HxUDv+xNS+} z#SL|#ve20?wHSXF9G}$5J2`n1j>1gE3R>-CkyLzdPRp@j$Nki<7ta+dMi4D7d>Jg_ zF7RJz_n(g_0l{%1zyEDWqozKC9=^{0w^;sraJ$L=Z=>0NmaGKPzn33Eh~rkdk^U=$ zlZ^yic^UnK71KbF4nTgZ~BY48cez(Eo71f!TM4#Wk?!rS)A&LmgncAlpaX#byp!Rw(Z~vE6F>{K| zEA4p^zpj(>q#p#JHivYYPI=r*=TScX3z3NB*AQOE+cUOy+^#%AvC1LSmd%{69?mVS z!8h}pBe*XgYmRpRns(Wfl8@626W8bnJxSK1ea#7!vRyzKvJ;wjB|R0tmx>ECd6_Ag z$d|q@#|FzAe?3v~)ik#8dJ^P44w?*^fKw`sS#Pn#Qg+e#GH8o8xjfwI(|#H>%|`;0 zbIRE6&|EFS-W=T%w|?F+&CUxCiYQPpu8uq=I~^MzdCb>#*hVRXg9?1*L!F>v)TaBC zZ{6x#NC^0S{Z~`Z2_Z_!pN7~`F+9m?BMN=)A04&gnu)SX8+H&_PM~RaV48gFo?R=iTBzQGMS6iV|)t^ zwyM#o7%>j|%i^VGHiiN|voCnUBc~PHs78%V|A*t6h%CKq+nD%Fr z{Vk;bDD0x#`idp zVuJBVva9TQ^vvD6WIG_t%T6+v6~a%fl$tl*bI**x*@CH06ybVY%H;DBvb{zDB(br~ z*&;%(aZOv=!c2n{d9wMI*$3H^Io`LW=`a*NYp-C$l67w}MFT8aRJUX%f+I6Zt!nEK+3?nu6PBYH(cKWfl1yb+$i|m7VY#|9(_{2A zLbsN{Gh%3w|3YeCmOC`ROdQWB6JFV8QTen=@tzvP3eaT-Quyr6K}J>l9YA3IJ-M&z zmEzlO<$0&159 zEp1)P{5~4howGUf3Vsh1MpB{8@(%ryc$ebi%t6*FBZ8X5h zvA-w2&bT&i|f^Xnf4JQ|DSTnU?!cW=*pbA8%vc!LE5ueqs%X7b{Co# z(~eP|T*zTi3D-x7y2hfM)mzvjuSxCf+*DDCjP3&P0Powx#0XnEAK?Uk%?qPK-<%eY zeerifjMTfGl%i0GR)(9T#7ghGYOb4|kda;S?2hgJcZ$lpdN&qzX zm6JJ%u277zW83-qxhGVBJ)!L(aG&#Q#2=*jx0LO%!6!@v%bJM?!H$OKm*g!6;pvoJ zA!_+kUai&axtajM2eG60p0Is{V+-C6-@WEB`LCvldvgl><8~Pj zAhz*O1?^WaDP|HPRIgjt{HtG}74<^YUbk>7uD-e)#;R@sT}92+wi9m!BzLv89juv4 zZ>LlK0+9CiYL`!OZ`hFpW#^)X3D#~d#v*^4|1OD5M=Kw%X$UqJwmft-!}n0^^zC!F z>1ijo);tY$Wxl@1MP-ND){K9q8;@$g7LP4{04bh2lr!j`f+{PVsQE6vg}pmXh#%kz z@}17R(NC{>-OU+orLRJDF3wuhdPw=ih;;u%kY;}hG`4k zZiL4?YEf~7aM-_OXbvZ2cKW%LuT4;`ilyqNmF-=Xi1I%ep!0cHH_ zr5YlXFA4ht$2oCt#+=)81d2|^<}Wccz`ZeTPyv{w5j+2Q0 z6dPmgB&)+ep}pW`em_pC@1^7^W&E5nmz#kC0Qz-$zjP2b_A=Yf%5PU1e31NVp&WJp z4E8Rr=$HzduLZV+jg4=1)Ca02mcySND=|uXTbRdYc7>$AU5~w$OeQ9N1=~o6jqA@E zc{+l(SnQ0_mBjJJJrF4olS=fp%F!d-Ab_C*g!qp`6m zc2P>&f4e3cnRq{@Ghx=TJ&uxdCzZoDS5zuw-C`R)&USNq>~?LHO8xNLe43>cJ6<@t*vRnvAu!{dHbxczle-}5e<=DB}$hik}u zT28-C5vFh~;Vp`^2y@{e;x)aTz#{GcW9plOBm07XC)i-4jcwbW*tWGBZp_WZ+}O6g zv8|20v2ELW^ZmW|t9t#%RNbjtefpf+_nyY5`@s8wuc)N~kVnx(q)Y?>gO1Q>$`~qT zE?~H=+eT(CC%%!Jx!K-Co8sTBSq+s`Ep4C1re9tdDE`Bocu97JIMDwUV^Cxr5S?vr zVI1ubH|76kA@S)uz~1;grB)hx?yvAYoG8j0>Uy&_goOkg_#{c%LjsQXP1qE-BJh*z z(ln_ej?Z`h-ru;ILk1^glL?Wc6Q9+7)kbvt9(zuSJvOYqnFzdkd#<%KiDyl`^PqhwprD(9d79Ac2G|0VE+~Br<^VFA|J>5TZQ2NVl#9 zP*38oEmt@+;om|f*?*^|A>$jp-Lped}F$(#nO6D0C#SqzRu{wkc5csB9-RYZtoRTt&-0uP0n>rwU?IQ3n2& zKYW(Q-2r;iTg%kDoY;@gA;wdTTxa|QV^8xNYBTOA>4ErSN4|M;$66;(UrY(~auVkgH1HB}hPgMP|F9;Tn_pdiG@I5?0?d;cVmJl4*?j z;;?I|1eoPt_F3_ryEEKy>kl{MK85)XA;ib;=AbD9bs)93SB`~UyVh(Q`#FDqe#5w9 zR%SN!m|V`COTgg6QnrA}XqO{*S%c-wvVB8+(I>fV4b8*gw7nqx1w8z{mXZDVo0F3N z+1sL2HJObRiWZZ|3}KeO8{jWZZEf9Fppeg|iIcB~!CWoMXU)6%P&y;?#|gHc@8|2M z*X3b#_jN-mzak4i?M&^{u+*m@6|2=NiudPznp_ra*JPInpC?>UbhJKG&ZPjgrAz>* zw~M)Z6j7Nlb60tne-8QW0$w0M1O8GrB*PEi=lkE+}aCqrcm` z{hb}nWEZ_C=lrpG`O)6zK7Aq`13Tvf5YB1#*loAB_px7P_WdZIATlu=uQ3oCKp^;d zY`)A{gsspa;N*&l70G_N3-ryhRnYDD-RE#c=Fv880}=%M+c|LKGJ5Jp0UccBqs5C( zUxK`9Z{=GZXX0QLFMJe%Sb&B-i%VY57xnAwU9+r<-bo-VNN{R8Xg{_?59N7yC;VDf=T^5fX(c=8|a(zS97j zp(gwJCCB&a%y{l31#(b5d>eCjR_}9KE2OgO!;WEMd8&KFw)^fpo1rZ8&h^)i*dAxs zU3PFWBHUI@^XEffX89ZL;4AT=+_gdPT0aK>|)46J70uM4zwC504lVx$LanJWzB%IizPPpGM zRfX%D#AvxN!#I!cK6fFV{I3U{X*wKA?6(`Yb@bhx_q{0YZz{oANbB)`+!y$*Mx^a# zx&=4FJSyR86ZW&7&!w&I38K-*lIrRH9lYiBcSU_YU_8ofPSeMxU7M#q&Ea=PlDcOA-gcjW;9YU=9x z$(LA(BVTdmI4owtz{3|gLH7Ruw=Vo{`g zltYa8=%pGzD)O(#ELRZP*cwrsO=bu8qOfPnjOoN&3Kjm`s-vWZjeM|ovp2?Mu*_c%iOgrCio+kWHl2hDVA`M|W)1~)$PEK)RV;YMxRmzx|lXg@-&7b&)e%0Zh z6r^Cbah4xtv2x;MVNMllrmA7ue+b*Gr0L>^6Rj{LRHT{Wh7$+VOOs;FxAH=DNfW~R zRVf4VX;#z>oR#o)+((Is(R`qGFWTS!3{C6}d7^qI{98 zKYhn$t;NEMq2<}!+5hx2e40vT$ArE54NQJpszrJJIAcunKV%P!YrYV| zXG5PFI?5XnAkJLQ7egb5d>4r-+te7{yU zTW%~S+Fq}?OaAr<(x{+39a-!9hmG#w}}h z&fHW-003%tVRxhBcJ&6aVfMuQMVs7XwusAP%odO8Wg}j&w)To{+@)0u5N+Mgt{*a* z{nk#?L+&5pIyOVvsj>IwFD#fro=3U_+VAxRAPS5;n(!O9j)tcvZ6<60AUxvUHCl-X zMdVciIFEZ;#)857YwOE8+khj%?(uj1>vI}*MwqT1LJJ$$!jU!O7lzw{Sx#NzDRt`c zrTf-Z0V}Knnt^#cRmSvfn?;*G1)lU~frjFN23NIHn}a3x!z{LvNG2~qAprpa@5P7n zxVV*X$h*zsL=E+&pHQM2m`A4>e|lE!q4K`jtU%MzLxc+gb27L^^fMQP5fKq1rN9xB zXZap;u;gdbG<0~IRfYs5Iacd)i;wS5_|InrS>0=V&G_3Sd?FwPI|k1py9!RE7{x{T za}R+fdA4zRTVpypI@u-GxL|}nuW|R1anH-aokmBV%v3P7hvpY z35Npf@4waKFEf^y2mtgMBX@0lIob~<89COz!thr{ zrtLI;jI@UIo&D&osI{2n=k!jyJ2$yrY0FLe+oSM($FL_-p1W)DzI+38``*|}puxM{@`7V(L!{LHp zshe0^FEBFF63f>`ITHB}Uedn#fj>-@Z)TRgv~AG}_!SPe{fqIDp|!uiKdacqP5PAf z*Z!6iYMlp}PbNi>UBUYY*Jxeo`wRDrFO-urwP219-?dJy@s8NEjJ=u$=k|90kdm8h z26x6oA|w=b)#rURdUkx(5a+Ucww56Tw|&62oa~TkgFTMOKasnHK3bi zL>lL7d-igfeLjNmY`-sLou#N|2~V@`XzgRMj4X4(92`9=oJpl3xn>k^%r2z8AdxOyo7AA}c%Hn-AkOt6vUuUAXHOs4|pr zc5ck6?v@mKSAW&%CNiiMea%xgCz|CY`7Sz1U;Q%(7W(I zaS>bW@O-wi{Ci0mSu58VX~yHj_nUdC&!?y6h5$Cwijz~DE|s|VjY)6r;M}Hs`c_Jb zu+5rxZ9Zl1O1b zFv2FK2_LP(GR^E%22x0=sOzR@rRj}x{{)K9_#VH7HRSUt>?D0O{ZWJU`S^Zl?-i!P zkFNs);n*;~?i5^hdmXNWx?j2^3R8$BDXm`IhcbL$uQTl4BY79=d^f$>PK_n6W7U_} zX9Y>5RKypi=Vs?s@4J-*-9Ed!EetDFa!XbJdC=~ADWv%D7toO5wxp+dQB|v!f-My{ zUUo{#a><~4G?7O?^&+&GJEX7kvN9H0Y8ycf9r){D)8Th#T1i4()ux{^1}5mBIEQ&3 z2`BV?TZ=%@@xVNX%gWi>?Bm18=i{W)IegiM5&X^N9~O8*D9s`J2e%IGjTbrd8JWb+ zV4knsanQaTd3m+dO1=jg^R(4r~C4S`d5|3!E^3G6nOuqWgkst zVl!t?ZIVm~bZxrp&QRA>bd%)=fqyc%6x?_g7Mc$TD~)0v9`IgaX8Z>?eV?vQ3ym=( zGMuJ-pJJGOU!U8jl#DQ47cbtXUimj(uf=u!0ixSoqXI@gSKAkJK4n}HCNJCeY;I%* zDh3iV_T8V`{`C^?s)Zp&FY`+9-5<4&rwPwd`?y0>#OMVlg-VJ|2rx14mwi*8JTJ4{ zVMUzhobI%nA2o+DeQDlo5+mE>Io+Sjo4bO`T66jInv5rc?T53U6co|@C+e6^wO)%T%`CxIb^bh=w)O73tWW?Dxld5Q@>Mgi1pRo%dsQ zj?ahS$Lf?C2?lr{?A^-lcQv`h89OX^)!;*AT4WKC7e!@OXlCH%5}e?vsN%Z&r_IX5 z%@w89u#2S#T?4{6{`4A+QrN}K4hd7FVf(k%z||boL|d%1;y8q3jgW=BGdPIPIRrK` z&W@nfr_`g6eCkPF7QpwWpS`yxu{vLdEUN>ZYeGxdNpt%7>O(YL{`Ln9oe{&aTl|k1 zr4rmJ_L()?fgr)3AEopF9`V{`%!!)tKOcYH^kOZ{z}e9ey?uQ$D`Uxwn~e>1wzbY_ z=OtTUr4rOOy_%WXV-f>lZN2;FC$djhK9{{G(^`}`;CoGDWYYB%6Ez4+4ZwZDyJ>D z6Q`Ig8f&|X&Q#Szjp?GtZ_8{a`->ZHCRwU%d=~yF44saFQrayHYh%8>ZTB&@9v93? zm4Y9lp4F3&~EK(gd zB}1*&EMGrh^f`~h{`?q})4V|@0#aYtSKAwM5hJ=L>D$-38uRn7pod|#$+|;3ecq^3 zO#B5esJErV^$Yi=$EyS}n}|Dg1_~6E30803(fUeokr!e;`Xp?_ z3DMG)*~GQl`bfTCnh1Qp&$cCJ-dbYLXecouT{)t1LpNhGXKiZj&N5PCop=%B6p}VADG>jl-KhG{!-LBhAK3D9=4U>x zSVX9XopA(UQl1N}*<;uBFHQ*caJ@@^^%tP-pIw;f%K~@MD>Vyvp&zjr%`nMc-DYU* z>PFN#B$c5f@VZ?m6ojFrjH+m-&t+^4LB^iD%h!y~KHYS;ti@FE6k}aeQC+9GIM`R$ zla2UDk=a*t;<~Lw=ZfWLx{Tl~!vLj?4 zc{0YQ9`5lhdjHI+nDchYd$ayi2E3Q7?h6hd27;fcKWn)>T08*Yb5dpu5I!rGS~!xZGiX-yT4h_iw03ufKa!I3id;Z~`% z$LoNXAZVbi6(L{r-1d}TO3Qw|Ctqa=_4bUD9*Jl0fH6h|+~~4RpH$qY$tH7ACG8g% zV~H7@>fcyVDCm(8{_5KhxSp!6ws}F*c}P_YGa-}N0}U={wTCq*2f>H}qvzQs-_GYn zZlhEOPXGWzF9wr-QLy&BsQIJLJ1}|`3UGDxHFk5jGM0U@pFxBE2SJ&Xf}) zTae#>c_VKtF4l?<3Tz^UDol@p| zPjGsXM$H+G;m1yTdI{L&HpLLt9EVAW`}zA{fA_0={?9~I`fe>)A5e@7u{BsixR$pr zGOo0F?-WUuxLMG)b9++0!mTMZstiAfz zOn#%e{TGAO@N93RBRAkvIndM7BET{QyF2~ehKz?X<}CBd2jbSt9QM453mrIW`}(lD z)gLC~O@yRQr%cl`96G`-^oUfdTS@f!Fo+)Nww5?BG_C!Z>wQUXg_-TgSPqtS9CGQB z8V5`$#Ak#Or9YM+73loI8U^v6m*(MFvat#S3GO6qZqCyQ+Jb}L;W=m%prjPeYv~r? zoBeKw0s}K>aOvR^zhwDrL5C;+gt16ImMUHt$2P*13) zga1)uf7U_zYQHRgVy3{J+rI-S0jFb2B|{wE_2&VkeYcf**aIV7OS(ky+jg>8VYa=LSw z3Y*@{1#jb`-m}(imAZb$AZHph1{&x-0+H#DXZfsiyxGbpZG_U9_i5nzFDSKV%z)&0 zCBdgfLw56`UFj7)rko0}3X*g>J&Ud%-Nm>pnjJRDDy;ROO9W)A3^2MuDaYI3 z7Q@yr8gL~YRuVRK_v_%IgcmA6cy80t#^Oz@JJSxGRQ!(_XnXlDU*7WySX2BwVPEo& zC6h~EUp64SHYnXMYjXtO_ewg&npx-uQf6c&=K+9!-sf%)6Xp{d;(}|_^JZ(KbTXh5 zd-qrwneZ<9R%*Mlv7$hQu){GtJC|L8gJ+h}Df1Ex!{M^CuZYN{vI4qfb=q|_nKG)22A$b)P86Mm zF#_9%v^$a${pQ zv^eV*Mh!%vOTX0Lc_sq(`i;kd!qxpuhB+%JkPOG)~?<;vA-&-K!69Nn#(;7)hP=NZsQRy7Ln^J^e6OnNs2Zy61L5$He%;WZ?>BwbNUDmbtEmv;3^GO z&DKr}oCwyqv8JLcUDcbkHY!6y?~D?mkblnaJ^m&Wsv6HS)mwl2-oVSclQ_j4}u!~Z2 zUQpA5DP@j~Vx=n_Tw?)Z&b!&>b;Dho2;~v;>g&)*d80;U=s5u_P05v&qohdZs83Z) zXBAOR4Lg6O<37F8N`m8C_?=2I_vj%vsQhRDLc!4O8ss4?SgIGRnHguLtg-mzC$&{3 zuh)1%t&so40-TP_tk4PC@Ghn-QIQUGSU*gel9raIkL#!YGY@FqiCxR0@l|F zkfbUs`0i@tXX97WQG5QG#;2O%>nc(INqDj=s_v30z2x0gIKWO3NmVMl)JYvfeUq_k zL3;`Ice;dBoy;miIsK8%S`R;3v}Nm@L5`*q2oCrc<+VtW4U~RO=^dNV7H~2Q#MGki zjbk#@vvqDep~}qeuZ>xrF{Y*%G7PCu^M{WF@|A5WC_1lgz4toL8bPf^PM$(ae3_sF z>CQE#;aL$aUU6DFnNj+m^kp_Gu(gb1vf*V+g3uxc=4Q?cBBLK_$7b{IZfzyiN@(E@D6=aKW*+WxIJ~bh53!li=q9gUV2ZY98rHjbn__>a6OK_nkKXf+CBr*e zbuLsOHx`IEl|)TdU76~vGmL9JF?@}GbfIT}@;)0f3)d@;c}vFsSgVigtx8UI0ifu> zRJZ}zma?h%z0WG%!xet;h|8FIJh$96Cyo#vIG%+rsy%YBVlmXJH#YT-b`3HGT>?`U zBxz0d19BaG2Lghz(LyI5J|LJ#l#ezaf4a|!G{KDzFIZKu$Ta3nRIkG2qRVXhc)slI1ufN; zt-9N36@>0{y2(9wWk9Q#rpVg2P3(KDZ0SBDsW-P?G*lT0 zz8ByN?`tHvU4GMlFY@>`torydszR?TwbGO+$OZ1bsQeh!1w4kXTjUp)szk!#BfC!8O@-E8{nMqw%w-uO~h~x71K{9UelCFmW;m`>|7COE<-1a6ybvgbdZ{ zZp5grzBkkvmD6MXgoYL}p_1%Wr3f5`mOb{(QVv>D3-{s9HP+yp)&gTb+SXeEHOa%w zJi;N59$h^XMZG2vv(Tyn5670yn$%sK0lpYHZp~Y~s69Fad3i;0X4UCb|Wq72`YmxQwJ@--} z%MD=g%J%Upi-0P)`x}NeHlQ?Ff+z;JI;KVT^Ac-y{JzUw`#T!#9CYt=Y9%)x8cj0Tl&rqCvS>S# z9eD6*lge)Gpmp&uI6VJJ>NP~vqpoiCVM2s~03?ds8r8Zu3g_}y3{Lx(o;kS+jai%? zw6+Q1#C-kY@2hbEz+T7f@O3T7Pu@vl=5E+Rq$AHbO_qt~7 ztB1SgI+ecVDq`g{8{y>S^aml_{(;5;9UTR-&sL--GrD|{f+6M0k7Sv{DmGE_K*ABW zT1ahv=n119WP=VL8JzV1R4mrTiNSO@zfi4Ab(l(h-WcSOLe*hz4mbB2p$rL4NNB*< zBv}&{27g^H5|VMfwwE%k4=nU;i(I5YMR1b`fZvBEZWilf?Js;oZ|6>^v^~5Uo9h5& zY^~(4A=G1h?5fWCM0$;MOG*1jXFEsuXSIa@-Vx4^vP zo98vQ_@c^?_CPu1mY5K7TnM5I5jk?m7Nsggwo0(+{)f|hoMagqf0**)**(O*`dY(<{T(ogRc)37BC$U4GTx6HX`{_hPAfe+r_1> z4WVX}dP-!($vlp!d4E(I8eeu+8X7Ah2N~#X@Vk>dUgdJ1ez6m+nQ?AC?e%6h=8KB+ zBta|f-;ipLkNtfv>M0{Dg2dz^Oxa^+tl-)`HeN!MMh*Q|F39W{gS?+ukX~0SoTnde z5A24B0Gv!AThHmS(bCoJUNvf^Wk;jz%Zg@6f0E%2v$(uGR4(=5EW!gzdWMSQAI{t! ztNd-eY{0<3UL6GRJAy>B(d|y_4~xx}@c*2jLikSv#16hZzw)usu+^rbqoQJ#= zKc{CTP(LUTAW@6BG_lu@n%#Gg_qiS>8H!D|GJ^yesFdlwv81Z>>-^3Y)p70i{%#Le zZ!t2IVU@}v?m|olpw^PCtq{0e47HJz|0;ay$T<81ZyD|I095WKQ%ufUE|No<*m zoE$)%Eb~0WH|7;Y(OHoX^97JglWiwMb!400hYm+U7AH&+AL_yFzytIb7M`QygapL? z;!?(D(mT4`wF{#wteJ@a=l4u1Sa)%uOX=Rb!t3*pT&hZmduHkpA|WO8UTs0_Oa=v> z=kzcl&<~bh8GowL+QhY^WndHU2lNxO4jR|u6rNO1p6QQ~eR)dH+vG0{{M6X6){E{4 zkeR6%&@tek$MR0A^BF31iA-(eRw%Rpl7{S7e|k3qLug-qU+n!%kx$ky%FYHbP};_V z8rH(%^$V$BG?%G}QMKn${yo0Y+I7Eicr?iP$Kmtc>1yYIRTY;HYB+`3<2tU7OB&DZ zIMi7I(wmcEa&sd-7mv!+A9CP}Y0hRIR;FO~tolM`5-QaGVoLE%_;c`5=e!toeze@C z{$b@KWyGQw{N9BEGgvTiB&=oNP1xP2!`ZU+ z-CT}G@6NGCAAxtn2q3}HEJOVrprxx?`VBb4%9BgKFgX%9lXbt3B1DNj-!^qma02`^ zc|%z?$liuPHM}1YdXIP8*KKdi06DZM5qIYm$SIKPrK(?w0ElsbkF`bq2*eS(9hOCn zhMKBgKWn__8wud?zRM|>(|#}1DhyzRgZ3k{qO1@gCfm}YzF5vl1Rdy;qDU1$5KtWX zhlwMg1bsEZPho-1<{;LyEG3{iriq5?^m*bbGJT|K&{Mq($+lyd1 z^f^p(_{sq9+?;aj&PWco9RFL5?niF0x>ciUSp!u$m}hH8y_vR5UEZUM!Q0MbVX)zs zAV1-6$~|-#^BGBWk}!By_6yAoUrh_>01S+{T0X0-LS^5z6?*dMq^(2pIbQcROmJmF z9=N}LMuI%afrzsv#|AbI#uc;wAXh$en~5WK z%^L28$@I>e6BD|W2Rf8tK~Ml01fFL>*PdhRPz%eap`za~p?g^>66HwwiCv%2JoFf= z)nJZHH9*#$3MTl~zTZkz;rZ}%Pw-&)+Y{+RL$zc>UJ}1$n~L=0)i6dCs?)BlJUH3^m z7NWZhZ7CVShrvy*j2`H}O}^uPk)>a8urS!E_NCa*Qed*vM2EA&(G;tZjVgt3xQiuR zf9w{jv-$=|Da_`{@I1asE0nD5Gf^2=>;7n{7Tvo%41^L^UzAtXThcvIoOayEi}PLo zIQ)DaJ7q2Zd)#K?KdIaJoCMIBk2_=g@;#VI>cRKpy;>@v-EkqiDL?1)@pdsJ+yIJf z0nPLC=_SRxWX#MeQ%*TCMb{x=F@Rj>8-+JE%7@R1*LGeZy;b!9LfX^I0amN1Vu7kU z3t}%o^^d=7knSw4xH?q;pT}>2vdzH!rf)radlRt|2^}d;z;_HK@x6C252i<*M~^$N zED1qj5_FFY=k8ZC&|vILgo%=KHg#16Ua!tdEP#Y9F0a?Vdr8a9gvRB=skpSDtTl_H zRu^2qWp&Kb-L`AK{_o#6L{dM|dbC8MH^d254H%eQADLhtUY`lT8+RR`cg&;L z3aZsX=9=`Gd{>Apm_P(812`czhHjH=?rmi2P*$L_aGum?FOxN4*;>7B07V)bs_2_H~@mwh0yNhB6WPa3DlToaP|j zf)3r%yiyK6D-{GKfA0?pIzPTOQ(&J{l(P(AdDhRA7MAT0n9Y;v-%~RmBk&)U&cqiq}US zC#l`TSM7-gkjt-z!Gy|pC{Z9mCF9*eIZfI&n^59}DNB}t0f7xwvNuf=(SxQu%ou25 z7j@>L?IxVgKjD=BL5K@w1?}yG1H=EWpsmKr>Z7RnfBW%$YKYZl? z+I?~WG9<&C zg!h@Q06?}psDZts6qk0R7xjY66mMcC3EfypbhrsQJKNC5#up9Ioyo8hn0P*DuCrB& zYE7hvw_{~8=Hy5=lIZ41ttCYz5giXD+M50FKqM&GwILrSKH&1bm8adarEOVP^*qyn zpfYwm;FJvq&vHNJkN)37w^x|9_$!L!@{$rIzYM4dMT@rAc4fveuIyd}$WFw0s+ml$ zGdPS4GZlJBf~}W2dO~9f={+lIJfc_z0fA*x;Ks=8`r_1Lbe<+80<49WCp{s%N|Kwp z{4XTK=FC%RYP3p%PA?ok)AQqtgYAobW4V%VV6Db1%;on84)WmTYkhHh27|O2aTgf0 z4tpO?0!|>v4CmCBiCf&V8I!Jt4{x_G!}t0z1D7~lj7P}4`I)Ft9d_L%_=)ZYvXA9i z%|4dYg0&R#QNJsWtoAe{gW_eZfgS&hcVV2Un*ID6mQWox;{kYI{98@$Pe?!q=W~lg%o6L^ya^@D?sAb0 znuYphaggQDD&>dnI=dESGU?TZ47hb(Ct(^?CAT1S5fjJ3c@NfUbHllnXClOUq{Kya zS2q}^)I^yELQt*-x%PsfaqpV_vWXr!Z}LbEgEnZ zan#q}k-z7t!rd>jOy&>Y9gp@OwEvT}hfF=}u-!MeTUHWI{mUyH9X$eq+i=QQ?EI;n z%mgh0B9&%ncVNf~f`-Um_#v7su&8Y0h5Ws}#TekHVsz9zbZ5Y25QVoWHANq(nEL-O zk~Pbe#lcTaps$(4no&G0KT0;K2jhQ>1_Jb)wmAMa zDBMKb8U6etFHe+UYM!DHu%a?*JTD}_xSN~#; z9IXX;nR=BD%X35^K0YPBbND1o>&6b6qzbq1V7$iV;ZA25L$rK>MFy}m$!ZWh*4c59 zffrzX0LQs~yy6el8!b4Y`acv23mCsmV@(h9btD)%dW$o+&u~={=I`ciWXsRm-X!w+ z|6s%E;g@J?I55Q>tb=>m2@4UeMH)%0Qg#1%N`Zab4snCHIumDgmgQ^?+bk?BL{7R0 zF;tlo+{nNG#D+^z(t)jqKTR2CmMLFXUMK+oaaQnwELxMq>9!JyBc6|h-80~93V;w7 zi*`sg5^>)2t?sn{$Yzl{LVDmE1uj;&6k>fo01)Fk-|SL;$1E!u@;ml;sh$noA(b7= z1dC1Nbw6Oo)qlL7F-)65&H6JCPU+&kt5l4)Ue^xcXG_bGtio6iBGhI6RjGsUZ0b#% z%65%0mIl5Qr~2!vR=eJ|o;wU49aD?G_NMJWXS6u!Kf(}zQe$-%<5bL}DsYfB(G*kt z2BR7O7Uz6-vn5lFi$+C3MS5*$YJ}MepN$oR^@1k#&>58KCABQSU1A>-*}v^TfJ{vV zCMFf;C4YDM!yn^a3xlanvE~Q5;?ze$uJj8p!f~sY$}9nTdI^7fdfbFX5}k$v_7C?V z0m2Z%-;ZO3Lm_j6%?6gsWXdqb$jLARA`$OFzvj*bl4j^sUG*7hE6ae+UZ3}hVbK)o zR7vDC;8PlsPL!&Y0pE(g|NLnqi1PS|BD)U<&aD4Y5&85}4glmPhE=Qsm#Po}e)4l( zJJL>;28X4HFrli!^~SLEoOzMpNpZ6PlkE)!=>A>DUZB=^(VQClxXvs)r}2^{^>(Pb zT)bX>g5GL`KW`@L8YV7$drGa;dDetTlp%68L!H%_GpDL>(ZW>#retMV zQn3h7DBp@8CBUj7f=c-n@D1e=MGmp#jRp{^N{U0EX^EjR3i|@vKp5H+_zp!*#`_hl zWpTYeadA>1rMYo={{E=6;1Tw0lXOC6m=OMh7--6Pyh5AkaA^F^`w^!5`gHW~UyXx0 z@^OnrsYgTO&E3f6C|?N0S2I0FcM+?`?`|02b8-P1p)ar@NYuNbs&qkMezHs&H20Uo zU&P+U`q%&fiWE^A03bcS(R#H+@5s{2H zE(e}6=FOQplvQSEK*By}IXNhBg-S4#>u1^sIkP+xzlW6QT{Lu$(q>Y+*Gb|aHUk)q z4-m?_g3{(9`p@wYp3(CJ@~&Gx)6+v7l`;u9b9oCx)SDQt?#-mcWluBJ6Md8Ds22vE!$ty_2f}x0v}=1yV6upiv%`3?su)d47+oDra?b%(stC?$ud1 zDx?mCJ5CIvj(8+Vl8&sgH!~$&e(lJ05o@_R%53Ls7Z{jH1jRBMAy6F}v(d*KRzqjd zK{wNA6bR@}Gp>}Lmc|)beuP=I(ZyNU$n*S`WKO>r#0Vw1d%#?Rj1o9c7aU;Rifmx?|d9;ms` zpJ1+b=yJMt_)y5xTbjWpHrh!2wb$R+`z*I$zxr)S-<6iOguwpr@os@pu<7o4NaJsG zgp?x3sI8{0hlg42DMEGkZ*%TmfG~NdMKnSC3fY5Em*eW!m1pu}1p#uakRalZU$&c# zd+fMKQGw_FF`w_7_sdj zf3A{%U->LmQPz>&Ut zcqyiaUb^&w%dG>L_Hu9yL*mvYMTxHKUm$8KL8%EdE@w8~yN)vF;DFo#v;U>M;~!so+aK zl+pAUE{|lvN3P`LG`+fpQ|w|aICH*UV*b*psKdOUDk>_XqFP?D^8bqk_!~_)J$aEK#sbp|WZoF@o>VHjFUa8@*9Wo>vM-7&Bem=s?weL}jsZ?gdV4qd+0Xd?D^2 z5)-BX04$}bCn#UKb8L5;Z!37^jC}6*ZGAr$U+ryv6+>!M;l-97LCtKV(hh_J-N-qu zd-z6;K!V~rjnBBU+l$wfVpBrIMHyDAl&2WVXF{KM^^}SDK}iFxXqQ=^ug0C!Wq%4A zoxjH()t)t`!XW^FDZox!cj!5OL_qZG9Q~Ay`$JYtmm6z%poK@r{YriIo**xvv++6H zuTseSzACDwvaCwZZ>8({ID{3E)ad(L!kYn9qwB+-U=z@4|0T7Q8uEPT9i7CAQ6PP8 z8}*2HZDXD__mLgQAOXeQ@iH&8_;A<2qoWoSIRBQ=67WrKkERC-Fh|!I z1W8FUJg+w3nrChJF`Hxfe(HJoW(oBrMz865N)MYKF|rhpKq$Spd4z{c&?56lS#l}# zH$g{6uL^VC^~j2z81HX=vd`N@H=}8m7Blt;A=dllDKq&`Ml-_v?WSPA;bEjP-q4!& zr7(2}t97+3tqsa~Zvqt>62HDE4h(g!TmT?UJq$pH+Q6CY+77(Fot)CnvgIDj2w~KB z_4?Rm6ZLHtcdaj*VSX7YiokyHP_nbml^w*OZpq^I%oeJjmp zMA*AG=r-sax-q|k#abFf75!0ZU)6})KV}*IAJV=lI+8a0vy)70PV9+oV}gmDj&0kT*w(}o+nRV{ z+qP{d+w<-I_i}HxPG5ANu2c1*>c#WJGneu;$B*RUlIYWBR7qO2!t~|sy#5gavM&1} zT~AIIP3z~u!Oe|phkq`%wMC6_J)WSiCV|i0_UgadSF%aO-P9%*{300mcKEl zr;xS&MiSS4Y)$Ki4z$yfEp(s3<&upK0qv%AaJ#M;tReeAdl$x^`h}X&zX8NBv-1ln zLQw8`kZ?bhsBj5TEJxIr95@7S69^m%^nzlXlis{LO-=6L8B{tduF9_+-;E=Sa@iFvkQamcPEB3RmkY&tNS1dR;h|r69ZUsyPG=I zg52+9rV1r8DmW0*m8Sw;C_#e?{(wWcSzRm2bEkr{p)2pTUN$@ES4yV?S zI}S6Fg@uTlvx>2v^qCjkbu$>CF*IjUgA)cODnve3yeF^i(6s@W0O0o(X!jri15hZH z*dU3Y6zn>`eez>`C^+V;{9bu}R#E!X_;mM3!qr)?-r;oh^X;nF>;M9wLi4RcB^ThF zs#}sYo$YhN427u(uENbigO4jn1KBH;jH?PJgrGTL)0QwV60zkuHNTMQf|v90N-5Y` z%kW)Ii+y>ee;$3v3qy)ITnbnY5)u<$s1b{nyQ~Vv)S16HTncQ!r1gg{y^X-x0RnXb9O{pEg} z73+TCFp!s_(>4z(6%RJ71;w*fnE3xLgF;Rae1u@mf)^``hMO;M9d15Dp7JozKh885 z*q&=t!Zq7M+us&47%TL|q3sW9wbLh8DD&SWUt#aUNV#M@~{}a9tw*O+*gib5x)?k!G(g>{K;sh&$Yj> zj7k53Jkkz{I**stIzR5-D{t{#h-#46pYE+j;U_8a$878B9Jd&BKBdlh1v_ffC4Xv6 zaJch@hviW%n_8_M=H{#UayhqZN!9}_Aprqk5|us6Q|B7a@Od49p|M#P_P1JpT$j^J z*tK%>@OuKjaWSUwqXK|6lvUhhYGGa%Y39=KKjUB?bYl>Tiun<%6-v*}xMJ-*Ufz)f zUI$l(O=&IBx~GTJM;z;F0Y8TdR$6#8R{v;em8d?te;$(|9z2g_9=SC<8*;^?|2Td= zUL`X^^S=lPZ_+lD*?Z9O?i6O`Z@9hN`IFjQ9Q$>RU1KYt@7Foc{KZPuc(jvrREq#} zyiwiLaa#ivcBs(oVUwDI3>$Gym(}a2Ls8&17*lW}yFr+oI)v{FLv&58cIAQV@*KM* zzP$A?Gz5tBT_f=L3US-PKWWp?-W~dUnA9v1X9+{-;H?q_k@`q@#n8QSPXTO&s4UGlk?2kd-OIoD8B#fi{e0fo} z>wn+W`*@h^lj8*Zvc6~|>Ui8}vwPP&t6v44yr+v&{yuc;{Iro0c}gfW4#0#zHc!@C zngtF03VwqxW0ze^sZxjt@Q?AGJuTV9 zMxWcgsjoWthn|007_OS-o_7y}d^AKn58JP{;R7+*Qyt6pv%v^QIzx22ayk>TJ0H~} zl($%7JNKGhy=nKKLW8`R>4pHr&Um~m3e=bg$nq(FNIu_^Gdzn}`Pb;_L5n6omJ!}c z?Q^C}zXGab0@bBJXSe$OH3nd@8r&{U8hmkfaA0gE3+UsH z?BJ0~9DRZr9BnGSLmRfb-_*O4ZF6oZuHN1A*JIQ@Alme5k|!PF`@gOht>s^hW9hBm zvKa*=#?EwaWT*g!aM2Y>r`&I#-MfSnM5XkE_w)KNEep$N%!DYIK9}Z7Yp@+GDS^yd zJtK9cykBEo7YFZlGa1@1Hp;1Ww`oU1uZM{o-(jnx#u^6`rBXm>vzyaj;Xvwezf1;I z_xb?-Wos{w#UBor+VSochz~XT>hbmzevk?Z5*YBw7@$mn4Go4<>vZD`blkKFNH(C{k35_r844@UQx7Q3V|X@e@Y#`HwnDuRvo^_+>=|sr37t&0 zt=18^(c@EC98K8&WPLv>gUDHezcVC?)LiRe(xH!HSbp)}Lj$>3w3MinCBe0*(3OwI!68UEq>Hf3mPz_O=kCPxz8NLr?&cmHW^p7S~ z94bgBsZg?{RRm3$jZzGWBbYTZMG9n=!7`xxB^U7sQDBa4AHNa+B?=tT`Kgk_zA3f% zO6OY^eka9}-kh-8&68Q!SQ#tIseDZU$>+_{+?#)1=&J=^q5u@5Y%$P=*=T;8Rg95hWe*Em&}`ekA3>H(bWCTD8?q(UmQU z{T^@P099b%k)0FF^#6R@qORdEt7qHhRu9M(v;*$iVwAa-u!vDx@roZqW20HMHcA-zQ zV|Hxke&gq!jv`a|r*--7cqI4*`d_QY%^SmtMRP?YoZ>7~QGx&ehM-@G#%{a+$mXHX z7!t*s&V*VBz6b~vb1je7yXMt=)5EgB`Kf86>hC7Zibl=yg{JR1>KI}eq~$?kO+h}J=)|wG7niX? zC<#9e6ic%%2L*e^*I3Oa#-g1r#xeteYIE=*`|!9olUZ^&nHwub$uSgien#wVEkM>_ zBWZ(`;Ze@#d`6DNweoHAuk*`mOKbF5nYcdp9?(bxoxp{vXH_+6W#z>h^{6NDnaRf$ z^7MW}p1|nAuGfRZhCIoIXr%cCj3K88SKyq==4FQXe3JgNtRKGMDxI&rv8i}TO^tLTCtmtr~OezKZAR756Rqu zeA3gu-PNqre!4kb*MMsIGv3ye(@Jx~)h}ka_~HJla~j zW^F~!m&bv=SuSKyeR&xtK1v%OM$JjehR?h39x;Sr;{DOi73bMg9ThX6z#C`l8T>6wt}BFrL{%5)e!uOm$}TnVi5+&fe6_k>IFVXSYswoYcal;dlyH z-Zmxn;Y2^=+4xw6&+l8>nFuk2^$?QB8;p6daoa&aUkhkZ-PawjVry{bV8?iL=Gfn) zHjl$?RmbM1cm)Z-yEkw{Y{onPi)qMH&i;xVgkisY4*hWY$p?e0OJw zT&5yB;$GI8PiE3YIqkpY8XR5l# zD#bM5YAWvO<1*Hu)e=^l-^lDgJ1p0gJxfN;wUllcqFK+v%4=eZbU?29DgniFb79P! z0m<>e0p*UbIF+*4m$rW@-Qy2*6_yfD%MH$_#yPgM8tTxQipl3n!;ymay3ih_E4M<~ ziMEyrEgW`-Tx7`R`t*ALNwPd7GiLgAjoymzj3RwG9p&1m@tG5@46#C6=I#eVG(rRC zJ(5CHR45n0y-!$hy#EcYgPw@%L{^z+ZGDEz4;v3?Dds_^(GgAAam2{mn?hIJ+YWqK z0D`khp~>FE4NQzH#=Lfs&{}eeYkeogA8sxEpKPy>_;t;jc^V8@1EMCia=?x2T{HM{ zO=Hoz;D&uUMOPzQyD)w0A0%J~hvN;Igv`qu5ukjt;TLA>6QvcD8r*5v`llC%rYu@E znfPG|xeG5587+lePF_wT-fq(Sji(+ECAopg%v~Kk{A7{kc1CtmdySl_8)jH_JT~|Q z2;yCDlapr7sC>OxUg;+W+?9=PH*j9Y#?Vf^Bi`b+lI$C6!w9Q-y1E*hAZN6t2mgseD5q`yaAE1`JyqZySZX>2* z?9by$DgqYRJI5(^LtB+sP(+ED7_uvr&`@jO^rCXI^JTRa$7psM@_88oy}Aiq#@)Um?MMs&b^LL3u|FfS42vM5eRmog5v| zAV(QeDAhOr$@pCXCu9+*vA~QX^BB*zmoq`dPGT@wyzWUd$8g+7#DW*PaR&A3*Cooj z=y$h}7}y(u3J2AYk@g#lYk3IIMP;NdP2=o&tiH1cs$+Uq;rM4sVXNe1yP&MR;o5?K zF={V?dTC1!W@I#qXawK`Api5OmQm*^Z5c_F(^AjZt+={l`)Xa{K(A}#ob8(Ird|Wc zFs@3CVA`dwO}+6j0eAWLxgIy;8bto=cjl#B!cN(SY9?_X5m~@+l^^Yiy;x`X`Yp*);slb zvmM+$ou=}{apm&R%e!&Y+^&ThK5#D0@%Sw(-IqME+t0?0YhKBNmk(o#z51{>ze zq)Q`i3i&R)m=aFPBmqhUsuL)GZPmi;?-ui^tMOn@v&1Ubd-z-0au-Z)?s7rs{M)e5Tw;yni#zCLAk%j z`U^>8dRP(z4|*}YY9`Xr_5-nwUJ4iYdb2eBESXym#Hh@bBYY_ilha22ErF4tQq-d4 zLIq(eLwGxp_E-fAUeP`(My9^iK6fk!lYR$}u8o_951ltFG(=AO^!$(2-`@JQQN9lv zI3Qw1v370ZCLmzk8Erb+2xd>Pv2q&JI`HZ}O7q?-e_Ot^umhPq+|106YG-@r)pK!;r)OrUkX(*clz&hF-OEbS<4y-%;SV-`dfbKC7PL zRh_<00-x_FuQ!y6qL?s5x5LiTR>}3PIGu9XBB}kOt}EYici40y65KQm`{(GPZ=0@~ zjnMQV_r!gY<0&2w3V#}Pjjq*Y`_RV3=45jx>O?OQyZt!yfA1jkG+ElK2R1tb+QFYC z*W}u(g$+$->>qL=pDBlh7Vf zV~4e0cmp3sHiS__w=mfz(?u10$xh152edk$&p0|#k}Uljzz;iKgJDiTVpd!$Io#UNw#N z_2zwuQ;=}dx~_KWO>IoTq2-}>2ltu_+jpt=jULbT)T|1P$+@|; zDAAs<1V4GomNAZbXry{9Uge~6T61Lw!u%MKZYQ4Frd%iO+Ptbd;07P^4__lpI~l7i<}15fJcNejC6zJG_hu3xu;;o>*5)1xb13&PS58N73L#@0~(g@>2E zsu44`^L#Iu4DZ_YLAQ>T>Q(4J^*C!1RORyOCMR&%E+5k zjy*N1>7wp0pxd+vnqqLb@S;kRmpxjW)yF4O5%0}O*kb{kD2$clr-_<1CF=>InFi!G z3OM}N14`(vG^Npr=9M? zO8L|dU}02=p4DxE3Uh9p8ADjwf2zd^MdzIAsJ>{MiW@iNLm&dYI7rd$RFO`P&1eK$ zNlw-ZV|S=yqfqCXOgAZREutwIDr;2VvM?pK(SMjsH#=q-4KcnL+KzbZ4a^){?>M`= z0>&T}g@~N1CI{|4U$`cElo2OFX5WIQN6?Z~CTI<5AnUDeXJ;jbuvUdAQUbt2l>pM{ zX!zM#9AKKdBq{_rv(=>YyacCUM8MXvy$^~|+tgQ7^0bDih^38dROxASlb-NuMXme| z>_r##phW<&hB*fgRjg9d}{Rl~WPbZiK6G!lT2-lliwY6YY(JQ>-d4bnA= z!^&;srCJikqKo6pskD~;UX6laf&dMmq@p;VYFCN64KjXs1y9QEFgZCH^AXOt>NcgR z@IzDbA;-kPdb>^kLAwj{R9BbTO~nxcpK#Ekis8@e*RT5PeAcVwaR0moHh0t0uzAL` zj2LYNbG$pGzdPvF4B6#=t|0P)>&U2Fh)Y?jleYatvEyu)ph35%O*46v9{uG)KM(@^ zedg*b3=EerH#UK(VF4rEl}5z@gt*u903pRU2WFLAGKc_%7HURLBjYm*y4eU@_lh_| zAt6s;!S$i1+Fdn;v`rPhD^Q##NQ^HPH+%S`yJ^0Vlpto+vPj?koxJ)ufq00ObG%yozlS6SyobuPCn zLSohfZae1tQL01RM;v5PUv?y`;KY+=D1#3dE>4p`xUs;5E9Di)oL*_ml)y zV|}`_KRG%INfYMH94z2UX);j&z@20nBRJE*0S5*=x|5d~e1yLW`MgLWAK<5e@QmUN z48r%Guc$D9_=rLPY6LTkozQRjv~xDQ?f|jV#Y(-y;^S8R8g)8=5KW(i72v?u|71{ewT2O zC2w9d()h4%XkX$o7E+AerjN*+T31q|>~z1GYMiuO6jHENwp zbDWevvUVmI1c2Y`9NZe&nu`!j5BFfGvsDZ~8}Sc*$B~Oif%l}KoY)nuoxf zLI(1wCuPk_H|Vt)d_%?LRMoj;zAbJ`2m4vuG-H;!S%ynYkA%dA=~h%^x^N34pv&-* zzp=k#O;=GlrdGdd zLod-ErDekx5fplTRcBbFGi;a2p!;!WXvP|)1V}lvr5^s{5NWn`zjo^{N*tf-PHW|q z(76KdRuTQJDIjf`xHfbD*iwR}wyvfdY_5ATRBHRfW#3aLb}IOw(9q&<>F6sNd#dp+ z4i4(cf#s}*%d4gwbB$v$xB5vUeWfh5JHH667vJvWo|liffi#dV{j_TGygkKZk<@Bz<|M3|lW8L97;NngTTD`wQSt2v2V02BnC^GqV=C&oWiKG89aYMC|YDS(%#~ zndw^_wu*`LJ-ENCTLD_FSi|R?^!78#RV?bAmtkZ~CEmaV8DJi_!9FvPzFf#$Cv^_u0MaEXs{5D6c9IlFCV*`Cx1 zRk5gRd|n5d7Oc8NjJ-GvzfMhet-rD{ZaI{5v7+km`urKO-#*35A)T1>p&4iIr;9nC z>F0TCGd8Wy@{Rd!;4q$Ky0@_P)BUdteV{n2w^$gW*-*OLg+D z=2L++EJo1J&*!ajN@jR*ta(lDrNYpE+jDYN^f!lUzMf4qdt760I$!zJRZ zQ0D>BK?_UtrhCxsqHy|pFTVn<=feJ$s4rEr!U3hMF?1SVNtA^{h|%_ml)l6xkoiPO zy%WThEg|NKlEzCIE2oeqk|=Qjiit!6h6c_F(o`aZdIgb8PhJyoQrr(WIdPOlV}E2Dd)r zi{o@ywBI6-0Q!AX9|i-zgk|KrYOF@U6f{o!(+o-e8&&z(ejl=WluTdx@0B+M1qID- zO*yv+o|S*a2K+2Z$_#>;ue?{W6m>>QM}q`i2mi&a`c0@)NB_h)~I5kjzf zLEG~_iNg1t0P$F@T$I^ph39?TK6AF@<4z~}C;73NwDRE~eO|tb3C+cfXI)m6E2&N!3r}Vo z;Vt>Qd$Xmvpf0njWCZOlQ|EwD=FQ?bu3veThx>b8A##YxiD7eXC9^A;A^SN-a?gxX zM*2zXFS%5b+|?SKe2!?x6)%2}A+kubq)SK9Qwhet$#^Hh`eCnMzop02(aF8s%MXx- zM$vEasG>@dy{w@EI zDk5))cy}QAgwPnbEXi3%cEWl~P9zTMSpRhV^w{QYSXziYz@Oy92)VSolu=IJ=q-An zL52nwdnd9`8JUV?|JFTE()Fjx-$U5`S!RmQWuZy4ks3qx9mQIuygUj#ZyD~*xWQr1 zxTyG@-uv35+By|eO7u+KayXR|Chhne$B3PPGMWDIJJdm0jWgkk;R4eo9*pS;41OZS zPn8Vz?5HY_q4&K0A2ZXoMjA%=KA>rW1~_h+U)eKbh@K@=JQ_D;v1Gmw67yuL8Il@t zK}{oztClw*U)YpAckxovBu0C=l_G5*4O%@N7FFV1H= za&xL4HMT0&l1>QNJ*;-?r+A3&R8Mz0c1={zr;Ertdhclu80j7^omNe}zx?$n{YSCz zS=B_*SGWJ~mEK#!X3W*f6c7Y1ar9pkw|UWQj}yGwB{`eF zx8B^Gx3?cKU#2*}-@H>!`rP@5UCt5I__0mhra?7436vNX5ME~t;Qz7M?4lQpPQhAy;$(G*;baBav`>*>n6x7qC1BC=Jo(`-`zs8z31DdeyQ{@Z;j{U7(=6$UuR#<@r?2 zEK+>@(=q1V^=Q`a<8j`>v<)COop3gqL->3RRE-s-`Qv-P=5J?MjX5uAVt)C4*83{B z(O{*=<5hFFU`OPar9MqBrl`@s{x&P<{VaB7C;PorX3gjN4wRJM{j>XNw1f47-d1)E!TGL$aZV%mLQ)9>%3E;Uad&teSo;H~vEzI{ZMwRn;k@zDXtD^lpze&8@^SEU z=C6pN?Ro#0(igEdjkBILje=I8h}FJ&y^-V&A7r&Oute0nC-!H{UDmH^8-SOrqq-o z&gZq(X^z+H?NbiT3YVMj`&MK%I?{)IlLoN}>O`ZSU&Q-^p-oQf>a<4k?Q?O?!23j8 z?#u}9*U$RTNae**RE+b|PM4>@gS;FcoT2>C=_kwH; zvEab*Qpv;Ex69E@RvOjD9ZpQbFpu|^;?0*!w?mD}b2Wwmzw77b975>}jNeov!|hK- z);pzT4Dn^q#3E33Iq&=RlgPS^mr27@3tk!yps4Y;V&Q;0%=Jz*x2+73uh=l8=OrW0 zJEMVvzT^1c6&;9P-QQA)2D8fXlHhoyKilm;ral6@Ow>vT;J)5M-Bi8d`0ZJ0ajKDG z>+62fe!MPKqb0ruB~(T5ZVnR4Nwo4(?HKF6pT9ok$h~FSKe(16#2>tQ99(TXJ+6j` zzfvVMh#c0#uY&BP8<`oiUmk{z_0VIp$14d?T-RSOPUT&#UziGi<6%B(zZ^eJ2bG_H z|AJ#F@YvfOE3o0WrM(b`kUZSF<)Nfw?tHUc!2?vuyFpvF!GOq7b?y3pHJ%00nP(%&d%H0f8p^|MC=sv zofMqO@l)Fo_#gQ1ue9gpwT_gPOpAnXNsHyAGbx;c%f0&AFpkaYi$NpsLi(;Xn2+dvd`%T5}Mp zQKef~>wdBEl5B2z?2~y-Es%gIx9N{TveCI{EI2nKrd@rj4&K~NNc{fDN) z>>)yewpZlJ`DOjn+z)-^Sd#-$O(FC3cszKdNgiPaT6E4~B&`OaIe8`ophfbx5s6OLJhz_U~(z)-mgl z)ywV?Bd3&R*{IS^A{-dNy*)ddFOz9vN`ds)%I@v7&Dn=?vnDQX%EW3RWQx%hKbii#>AaN3;v|LX{B3!4&eOekd|A_@Q+4w0L3_J}urE@6W6L+% zwx0OTflY|nCE9yfI5JKb7Y7t#^S9@_>c_Sq?yrWkWiLzLjtPu4O9-ergU?ZG0y=+n zy1vhTuu1=%AB2a@a$%?TE5QEq%%~@%*J?dJE4<;(H!Wx%-&s>@0Rxacj2>-)Z?e@1 zJMGL$>^0s)P=A7Mb>1{A6JV}e!)xZbg4bQ+VfrR@QrC@rz${iL}4Q5aK>f4p1v#R8Fd+M~zlB^ZiStsa33%+2jEAoiJ zwjpbp%gEO(yrARCPWCAWRK1#Ithl@7_|7xw_b9Dv^V-oSIjBUVY7m!Rl8XVa!mbKrQHCC|u^|DS= z3eH!+RrNP1a7NerL6_ZS7}u|iySnsh^=Z_neIc>yT~}Sv?NAQVWm%~{Jt1Pke`hYz zTUv8Z86I)kpO(`OZ%m`vB;LRgs=lR+yo<2S)CgNlX;Rg~#?8gyMvq#fpYub8elPM5 zXFYsYis+YLcrJ}dI4BAq`kU`k7S zfWODv*Y5ZL{gTSMyq1=hj>;z4sf75f1YI`2d#6)~!*nC=RKFMY{DPJuy8F;QFR{lu zt@D81bLt+`S}-VmChP!0LTJ_rxoDhEuV*(Q=Eu1pxmYQKTv*h^FfFk{aZ$>>-z9uN z`!jn@WhgQVrEi8;OV=nE^%ZanedSP^qA^77!i{5B2KS0``UpleBYbh;W4^_K+sB1` zUeON_M>SRyi;U(3HK;fU`GS6`;}A+glJ99Za4rtxG>93lkFXQ)(P*3^w!fQkHn@PQvto!flIa5;f; zpsoAk^SpRvvm*^}U_jt7_OZU7ReAKI_NE2~9nJTjwJq;E%T*Ku#sCGDX)-#hzg{W% zDhOBP4JjU{z_#a*ars2k7a0j)dRn^E?m%?HYSah^iK+1pvw~j2=un&Yh4xO`Y1d|j zQb(x1DefNu^O$DZ5X!X2BqAOKT^cxs) ztOsC|EupXN0}vEPt}l9i=E8};2W;@^2cNztI1(BX9azoGk!E~taGsU^Z1#+AE^B%d zj=4SitswwkSpeSsd&s+KbLV-ZdlWcc%goe#n|*#_ZW#qF5-4Jb?zt3UQ{CAy6dyo_ z4j~eFpj=8`J2tnl9AS9bJT#i}-I_tBbv{%NiwS!B_D!&ilul@7~JI!kbL zeIg72K)QFo8vNuw?GxSdMxoEc$i?*6ju25_h0;YLRKlEHaB9$uxiEegtI6^(V^weI z!%tBwAe<)H{>AtQv==X)e0oM=y#LtLwCC{3*78FPxvgHKsD79G@QUo}M#Qgj8nw0M zAQD`Ltiyd%GYY~Z=7z_chr4W((oMxx(&QJ0n=2;vxM8SPnrqKaVd@ASW+68bFCIjf2uUx2rlixkaKZ4>Nwp_;gGE^!V6PekKtm%OZF5?W?;c>K*qu zCRZ7!&w0wBp1XiTBgvOGNJU-_xK%hg6BT%|bsZ#IgL2@Ywce>w1Z&Q&v>w;wVl-9H z5v277;WnEy`@Xeumr97?0rd0J%j^|Del3`V+>v4RawIUQl4USDtTBVA?lvnm$Lk{c z)60PxHomoWBJb5R$Xfg4IOHuQ$&8P8Xi>^fU%~Jc9gD|p;^yb`!k2=O#UE)ze=N@z zj*1}=*a)F8#J~VlP+d&=RiRy7oA~lmo9s)MSV#K?V&M8U&6*Jk5Z^iZA9tGcX@tir z|72){D`oo_z{>fumXV;c2!p~1CQA;C{pLIZcO^?0K)H#6_U!3@@rR?MpiKOIU%&gX z?v(?<2+l=$t_awzK1ES4ywGciZZYzbs$noODEaXt!_TRzH0LgaTh4|I29fX02CVqi z(c<}H;^N{1(f7rYkQle;$})fixxP~;Scr7Q)!=C?0DAFJu( zM|%(HwT{X>kw;ED?b#kycQt?<0;WX_3mx<(e7Tj}U;uq-ly$z_WBF9au!}ivCs>z9 z4V&-!5(@X9Oe{F0Sdk$0=da4!`yICh&PEq(>ixCh1}_(P2sHVnMarGi zV{~$W`e|hSgs<<8Qj8EO^&f|izLthf`JA$oWUkg%x6P-HkR2lvnd^tg^YZF48w{MS zALAD1IwhErdOkknRT??g23F));i5MqCV?7VSv+pE&r8G7<6lC#Z?#vJ=IPIW%Jk*4 zh|-}&_8H>PKmzP|)NjW9$rhzo?-9e?QJcl6x>2uS01Gh*1@)omN*AymnWui4TwdEJ z)m?A%!K`lgmOS=PtJMisS@>V^0!VTd=+LCal1>JX+&QCORg9j<>Qmay0Qzi)c^U9RrM6)mt1qCBA}SuF;F4GVT21TJp_lFLfA382)JAdYoVtHrNl@507T{%dxa0pBL21yDSx|GKh-;WbJD6w$>%`t`B|&WVr?~^*ftYO;{AB)dD&_Dg5sN<3UyAj8LH2*R3K3r^PRvs|8r_6&@N$&1j?Q;p%7eA-E+n(eUU3CZ} zKL0Sav?@b;PjTajc=^9rUW_baE111Ek@jw^87FgeBPv~^;+wyP6RV4PI{GY zZG@saMNd2v;3=q!hM62S`cObj42-zS-6T@cp|XW~dc@&9GH(s5;y6UYN(2z4CT`79 zf5OSsyA9i9>&w{5BtQB0FTf6?b^DvQD|7dNj>g{S>WSK)s(HG@nwQP+|qsuDhcxlhUz)+X0xm<(E;0 zC_>6f-CNFtsV(jpMZcYxH&Za5G_B zX4mHCy};H@QX;8QgDM74;9Kvtd%r4zZCXapp_um$TgA6z5CQ;ZhV{-mL5AU&R!!$E z<1PI*z&U*@TB9V!UV{PvEqd-3=?IePFIt=3AV+M%Zve9G=FQT+HzpL19u*0wF3-bW6NaL zab!Dd)(_vhqv7xL;@Cc<(NG$9Wq+vZCUCot=cGWLPtL*-NYl=y@{1XsnQEuW&Bft59|KY3bH9vFvKuXrSiqIjV{fW0y#_Z4*U~WIZ2-X!9y|#N6#`?Ksuk3w$%YteynuW zlY}e6`Rw*Y!i>D^j9vd#^SP;|{XA7SM4N$xs_|01RV^@m8)pJ}p+&wi zUz~c`)}`}!4*{bSR!tI}kRT+JhOan;h?+_fmPt|b*7F59BhyC8UJpw26e_ri7hf$( zN@f{<$(;!QL#bFuK#NOBr3N#sERMa)Nma@(&YmjPBiJ4%8q{SbgPK9O-;@X)v{-4k z|DcadU*-&6z0R>MI!IcRvYuVb`K2dHq+IYFXrl)%-heh4ueHhupD} zBHA`3FG7|1x`@0LE%ugTG*C$16s>FHQ_%fi5MLa*mLC$D%DNU z-x&D3ekLK62&u5{&|p5S!lp7pltQ%s7=D8gQT71P>3*yOFsZ*~%K60m{Ex*5Ctl)J zApg;fh8h6;L?8g}IfEG=ot}k?K^5mcDvL(%(t~^hhS$Z+m=tig^!R%h0(5d*7vj`E zZc*^=83oVFaKvmm9J7kUmPvtD&l>Zto`j9=0Sz_I);M6C{-RW= ztTbOJH$|t_9B^e{V+6g_MRc}_976!nZ0oPpETlR=H}?=ptv%x;S{L!H~9KPTb#fEp!w*_m#CM2U4sI%cL@MhlNHy} z8435@z07nm2?UO+(9x3MzVNYrvB^SXE<{a8DtNL#P1zCAB}4(m*@!v6!UX^9#d)UT z_K@K=Fo-|~0~6BIyYBuA0uv9$AuvWTRQ^x7_=P5+!KabR1Hb^kUn@dvC&vt4c*Txu zsRYe?jA<5vlZeX7g@1sOW~r!B3s7~C?L*5ZF~p^Qt!V;!*VKYm`Cq?o?XV0}{8vlx zX+-x4Gm0L$Xi$qerhuViG_W$b%+*3Z$A|ysYHB}|kh~A*-Cr)H0fDfV^lTB#^3vwM z%$n=Ovd5*om~I6~<+yC#=HjyN%(!K~9HP4n_qddnL^d{2G9a<9I09n+oPK7=(eGp_ zt))`l#=DS*a&*zf?)?4sXz@k4si=H7i(}0Bg#3_Q6&|t0SrKIX!d)giLKt`m0|R0T zaR>aPHSV}HSQb`cFJ2+VpLxGKbshHiBx~%5mYR{MNcXzq)w6Ah`OjUH^0xKI$oe` z0Cw4|qREQGydvbNXx?7SkUfI{1kI9efkl+L^)Gc?3uVNR*pr&h35=+WA}rz+TC6(^ zYzOj)<+E#!<;_z0e7SqfPfIg5rASW-x>ybU_gM}M3C=YzFc$*A{jB;#K)`UT)GUmv zx6AqNXi7nY!nXqaZ|u5h2J;kPMd-haAxvgrc~_BJ6{oPInU(Q8vsVO4Rfu=T!|sL+ z#XIiGeKfQRSk6kxx+M3g7G;lcgA!@crHq)+KU%V>cnB}so78JmEKx<{QtIb0PoJop z+l0kvmQrD2mirza5zaK^GQi1MUmcx29~lmyMq`FdpN&9Ec-07&sfy|F5v_|Kj|m_5 zQgz_ACF)g5{%A=TXH`^^>#M*S2 z@7ormX`yDhR=(S6o<3@aj?0IB?{*)GB&R5* z5EU(vihPkE1V;MYgM$beXI`k5oJwkTxr0pD`|Q>zxk}ZSM>SJyL_7cl@iA%M?jM(8 zv~V#*qc&W1i$6}f7cl-8V{aW*Ro8`&9u$=j2?+_2?(W6_q`N_o7LZ1yLq(*!q$HIR zN$HgC?vh42rR2`@e)ryS?|(nWH{QXA`<%VkT64|$%sHQD?Lw8J{ic&dd@HQPFPc`e zjOs()8g);WxSECW_`n_<5M*orj61PZ0Z2P3~uK^BDT{{c) z9|+~d{fiLAx~HN47?|j|a5?ZysP3B}5YFx+ak!79Nn0Y}4Mvp=Gv5Yz#U{j}pVs|D zx5|EzyP=^Gj~vX1&1+0~si`BbCY5uV#T8yWeIu3_Hk^RWPhT2Wn8eWhDfqSaNADAk z3$tSVYW4HFXp?I%vnE=wZ~Tb$a$d}T=?*e*J%6S_AT5n3E`B-AwtgmZ_CxJ${n6xz zMSkA80PU#6&N;(eQ0bBw>B?XEluxLdLH+6d#&|2CW*m6Lk%64P+7oe9eal2unTr$qj!u61$NO(DO)}B)u^JPuYZzWotlU97){Oi8-dtc8 zz4ci0;4XXKFP56=!r>pW?srikagoWQvMaw*3mIA|^V5(S1iU zp`R2#eNsdKQzpNYh^=F7E9BP$lD!8WdHFUzQN|8`IJs_?xih?9>wGDjd6X9B*VN(O zm#1Mu7)|f3aiy%9k$OjlIKhK#x1&v}Sl!IzriduYgSuH;-8e&IV_#)7u}d5>0Yp^v z6V<4=R?e#Cfo;FX<|0&)>zkwbqDd>z7r z*ZG*Ws>SmCJ}zZ?1xzj>1JK-eajh@Jeo zBK#sL=@0FQh6eF_0dSFlg~ivx!flangw{I&-pQWaf69)4R*5t&S zw1>T@b3Z;<>F#1K{O`wVb#r^Wx2vmpY2TD!_(wgRr>wGcQ5;nWwjrkr5nIDJgj?P$EM$7oI3zv#{EEBP#eKb~pvv z`=&3$8?GYch{l&3BBG*jy_VMayIYt!86U%Vcz9ys;yx!Ou^ZHCD=8_Rk_LSIxHDVx z{OhosoE#&5P*T$LXucM|%~Z_i&(&6cN97$Hic?cli;8xSHbn#kI!w9VzkAo_P+VP8 z&`|Nc!Y7w7!;?RtFF4CVR+Na+Pb0Ye zMX21Q{hnAFI}Y0C&z}?I>C*b|z#F=T4&cYJwL2>;>|UfaD&m!;B?{u`^prcX=lt9q zfp|yJ+uO_g-;Zjpy28JOg_mAlUY3@*m&}pUzf8H9nVDDSU0hsBv;s z<+bd>MME7gGQ>tlCnh6{$v?e1owu8-)zSGFS)W!LPCOvhWhZ~Lxv!7QFrIb5;J+a(kIhwL~QZhrd)~g zIr`aSW187j@Ci6LSAt5#!$UYIV|#lW{%z7KS3Pe^{tRCe#D*lKq@kgq)YR0mT1?E$ z;{X0Gt)=-G6wT5n>9-gwFKi~ct zD@^nGCm7zIUs&jMzVS6Q1W4-7o;^E0KBlFmMSF)pl$4gj|BsG}Vq#)a#>c|IsCHPA zdiu2aGp{udt%RU@i8<^o1ufzfBpJ=ZnL1E0M_qbz)i$D6d3>fd4`i! zSg0Vzk(ZYj^WHEPEMZ_^0Nw?7{Ac`;xc4ROQ1CSWmcqsB|NaiXINiO8NRVHRqLo{I zudq!Sg-H}Bk(ZfKU+)bADI{czpPrp%wR6G4VKJ=Nr@?#k_N^AIwU(B3 z9z7f#nx7ADXT>Y)1P28oJxPMRxsFca6uYlF6Du<_CKlH5{(fY)rKKe!Bjd)-&TYh= ztH|hl^4y$3b``j+a_jM@&z=nr4dsPK6G#gW%fvt6 ze@dbJVNOv&qaU4=kgs?mmyM0VKjW`_`WJ8&c@c)hQdE)2B5p(d{Y51uc#?x3KA;K< z*My7z6QH5Vs;@Vo!Fwp~?RmO0o5XKNh~W>b3=8V>r|>6uJr(@I@8841!?7_jg`HOA zy}auD{Us$NegzRQSG=BVUbI(FD)%_u(J3{DV`V(7$G>lb@$Bw~hlkG>o3u~cHH1=p zijUWN^=f^p+&Z4!(0i>fr8kM+=ik|yTpUYhM+Z3JOQVFTsi~Nl7&yBtwS8%Ow&rI; zgU@XBn@65|PYeuF%gcG+QNX|bgQd_c)GasdjPmnC;pQ%VQR8y!&Yf#mtLfM^VEA<&r`45}Gj$$Bl7si@6(^>qyf63L z;Xy3z?B?MgXR4g8uXcUxW-3)EaQa;9~69iCrNhoxv*K3l(6sK^}N119WT&nS=x_-(<&R_+rUJ^!or@WM@VHp6n1$H z!(!I@zP#@W59hU8ce?KE4qZA3Ef7%_TLLzm-66o~vVybF|7kl5lNOs&^5)N2M~Aey zxOn0F{a=Cic}Nsk2=iYwIIeVE>^9iJ8~TWd0y5Uqp9R1+g>C3}^UjED#m}GpsiH}; z+1>}8^xzvT`csdOj_}b?`S|#5-MR%UoF?jVQnOoM<9+4s_t<`YAYCDeukLI$X>f2* zHTP)T&?olP!`<0@nb znyYo=784Vrpm;3C0l~-b@%rZGQFVm9?96tr9fpHLU+a5F7rn8*uC1)>OM#Zw{~TvI(IR!S!X`=o&e^l0 zgKqZc&!1DH!J|1|{@vFAnDU|~u6?Ocr*st-_4MTA-(Cy$Xv{VIH=gaq)bzBqvGLHr zfc^Q=hFN!9-N}?S0JEp*_I=5M(-k&)0HNXyy>ln+#nO~0a2%bSR($frB<6jtufP?; zfR}#%{s1o~d2z#UVWH_g3=-l5bx_9H*%_=kY@6fLQ+75sF^`jiOG*rMba-&rrBHsP znHw4^r7H`N^+i%Y|DnAF%X9(Hm(MsnHb#htSK@R1kNSC-sf9&+T-+InT z@J${kTRL^_Z#+C|0t02V{aRXElRkJbQS;VL zNvVIb)S^E{n7-i(hSnAEt)v7T%XW>X$=4~6eV4g+ zq=xsszoT(%&Wouyi&gVXu$J$(L`{ zYifFW*0#3Z|1RCm(hPmBcw=RODH`0GlarId@Hr*r>UiAnCZbZ`_T|e3fQ!2`RV~KF z%J^Vq@(K!ASXdBMU%!4`R#qnB`F9WO)a=!(4)aotW3QE1Eh=j2m0jZ%Lo-v;E!YOX zen~Lk!&?uwCQH`>9(nJ91ueYC4habX3xUa~iP94L|$sDPDX@6BCn_e|Y5K{k^?j;IsMc=4Pg+F_B^X@bFL=1^|G;(#Xg! zW4+30ZEI_*tP2Lo%gtTmc~;`d)Zle-veF&jZMgmO=g$Ctf3Ks#=lr%aUz8c1rVqgD zAGo-<#KjwOa|3(LZz5o;0WQ*oW4EKD9R&1MRq+sy|43Yeoc{FaD8`46i>uo6?4UE6 zzOJ^GNABRv6M*tcl=~pJpumZc&YGE-c{}H3(ee@Nz&{cK zIot{^^8C9P;3{H36$v0vYi_qa?BOu}^w7||rkCJ0l<}{|8~zcHlS9y5$qepZ!9)Ad z*4B1slh1OQ`7Yp~>7RCn=4m05}ColvwnWyK(!RZ_xJ!$;!&=>+8cD0A~~p)m21HRP@E! zHeetVW8>w_=B_TQtMg;CRL+GX=$$uV3#3xAO7x2YmPd z_VKm0R-dhXY>ZD-^lE)Dv#+o3^Lbf$`Np3=Ybz_A*XmxM=DaVq{V|DhvamOJyTg+Q9&5o>L`$0T`dGgwc^No z3$U=ZwlOYoGWJh-pIhJTl!sJaN!$?9wNl4mrq^8y-8^{cG!=CN1wn=9sLfc+)Qlp^#OEKIDaXKO zRd!x?kklT&L=ed_C3XMX9wpQSJ~u7|N>Q?wq2tq=_^{D3siu09?nFg3#v5A6g3p#yRGb5wv9e-9Al^51DA55? zPfcz3{T=N3i=7&L3`uVob=r1288{MiICpPz$Dzy6;Ju@OBk>Q!(cuWa{!u_R242Ub z$W%Z?#Is;}<)Q$AfDDBJe{*AF(Ov-Hf%}4A`w~1LS0alR+!m_Bg+l5fX@MFKVDskiZHxPf1hLv9E z>$go((xokg9T!Hyem#q0LilR4#C4j&a2SH9(B8E#jrIlD3nW9f02|Sycp@SK$E_j! z&0mc7O$=E66dlk&9&v_ z4q9f|6bL#YdtTbl{Xhi9_T4!M2jPWz?;NvP(F z7dCcw4c=Ghu+}Tr(=~^Cba}@P3wG66q_Z1ssyb0O%Bd<*(DSLHD3rfzjpU;R(fP{0 zS0>cK@H`9D^}{E6wReL6r;uXiY4i;$G@ckq7lw!*v4xnd&Pwsl-ag5l&Lw;sw?CX7 z9xciYCBm6jiHwJp$gxv|-`d*GOIe+0V^Ds;anG8q zlj}4+W))uz_SZZAzCV!u3=XRXSf}0K?FAqecJ>`Cl9;r#2DigixFa|i)LXY=V`9L> z4hlgo0vwfI{`rvb@JB+<>wou`pe)ne-24x!Fc49}E&xN84qq=vD@lcudjVkc@wvXd zyaaGLnE4#s?pHv_`FVMpL)qQnWZoXF4+5^s%F3#R{Nix6_u_0VjZ|bDYC;W{2i>Z< zJX~B+8{2%2%N-D?%PT740fTm_3=UmkLrw5e-q zdIN+21m<}<`!+K(lQBrhX|+d=z0S1wr=E+;NeN&@K>y8{?D|!XX4n6&vVKm(q<3|9 z`#@-e=R9t~7Kao-Lqh{5|KCcyVMiDM1iHG}4^J22!!A2BmInGhkea~c3%hJpzMkX? z%7ALyai8#R2)U>(1x|t;3t=$5e8S7jJ?QptKu$WQd8~{tsiIf$n$jXAHulZIa_7IR z3wB6RgoMsdwx@@`DnTwnTJtkWnnt(Ek=Bx_c=2~@u-aEe0Cs`F!8Nd)u(n8m{qEfj zWU`^Dr>TjYSn&VyZ1Lj|xe{91VETQat~TfXrx36J)X~87y)L$YrU<>!t#Pq|(YHVH znaNQ|f|M}wVEmH!>d3*ZjF09dXnI&M6XYMsJ z*{WO^4SGLqVJ0eC=WL-+1UabPa89T?QyqX3@Dr2#gWq4&L`6kO3zJ)t8%507f-O)* zGEh@5L7W3<09g{!Rrp+A%(LoMfKhYS&AMz&3^w>&TMp+y33aaKZPAx6FCkUpHt*rs z-PTlA-UCxF(62gxX_^0N_bBn@`;F}iyZL&UmDcw5i?cIGR(8wB4U#xbZci3}|8CnA z!wBn)teV8c;2-J=IIj;>IxJmYU4hp#R97#94U*be7l zIh95?6bIaUnBg~>ua)4B$tE&s5zz~)5V)HGi{6<7Xz+dh?6pC<3g0!}!<#yqZ9~|Q1^Yil! zKYsjxOal1`TjzfoxKP$IdCcP zydOV&h_HVJNU~q#@NVZ>wp{#?yQrXo>OEx15DksuMPP!doUCj|*&Q$=+Ex#6d|+AY z>#q*pR7z#$e*aFlvAnu^esK{!g@ULv@cDOn=IaY5xJx4#n3;#I%IoXv;e%$na8z;2 z;_~vcx`u|Et1Hy5qdJ?Q<|as{2ohjrWgKB~Ha0eYe}8y+vuC(%)IGuS+FB7iJG+zC zm%UKoCkwBxdLA?2Dpt!%F+6)>c{}q3R~NZ-anno;`iq@#g#R z27ozy92^{6TooN1w?AX7j&JtQJON6Q^4mhSB_iol%c6e0XH`Z9gl(PVJov$T2nYy(rS$fORs}*??*04s$Py{G_~pRm@1k$tD&3E*l$8enV?jRE zxs1}I00G5kcTN;?)+mh=UNtSP_>>fd>WcHfeol3z4(Vt0J^_UyTq(5f2bZ8N|FLEy{Cpn@CZ zgc9BLVXl7j=Qd&s^Y&dVVMODi{lVcOtc}dyk<91V*x2DvzJ>4_v4spqu$?i9*m%-P zcObj%j%T0$VRX|i394FJT12?GC?B&>SS}yhQiXWpJVg`b^u8jPa|2c?A0+ApY&fQe zJ~L2QxjLB!lw-*n)2c6dLqeMupat97akYItHU zTMrIhrpheAfzlLpcXvail*>t*Q&SQpAR-$7bO|jbR)bmr*!es>&QO^~{CG8(QCnO4 z$mg;cH&>Jr(yTBtK`MNV#9iF2#L;Tlo}8S6qoW#`gMcV1YtAwZ#=x(<-WTI{vS`0FS%N2k{IrRWP~^vL>PO((zR5TXY1ff_#QyoioiQn%Xx-WV zS_~DnOtX(%jO!=f;TRNY`yK*foK!o4{ttim=O_s5TkNf!uL5%DyQNg{J$z9ES~!Ur zjH$)9hMgH6PQ%c^d64P;zRi0>&FsW*jga@8iI-T!+@Vs1x@@5LRmPwXGug9$_e_@G z!*Z4v%+)Q9FlrayFf9p4Apm%EU~2ZH!5aq$5jQq#h4J5-Q=0r4Z@KdbfpB#nqJD?` zRG2Tq72YxZnC?9R^JjjW z6+kHr@~VDn8P(NvUsHxP#)x|;FDmP)w{iEw##HKxBN-~>_X-k)c#_{?Vl>QA9&ZT$ zEm~V!CK4ONZl3mCm-7B0DMnn#eH`Y;8S;eX5<3V)*@j%mX6A~HPzHkzBZ~h6lm9(( z&CBJ(2LlFTVCs?9AhKr2TOr?gBxVz(47rG(zD%EHW(+30Sc}xoVkv+J|r`)O0nX)H_0= za51vu?sPt|k+PGNS{!-Q*!6|ly5&tsc+Vo*L-KSJG*9DD($^CEjwp!anwgizc@l|J zWlaIe{v0yaYkw)D3qvrKlW3Oh|8nsne4oxJdnM4CEqxlx>p8)d+;{ZTQI^iT(~kIW zv5JkBhXsyGvx}cE$f(g09JF%ze07IRS_=VsYP6&tT){} zdngN%tq5Ns-a5ZT+^9GP1gZ%uU)T$2{3%ZF4ttWVXq-d;&|KYTl%>%n4!>^a^^nYc zD!%dhWE=d(xbcC-j`KpOYOt>tQ<~I~nJok{h+_F-X=HhnwSy|}m z-ol}(Y>0CC9C)``Z@9c=3?7PaUEK)6mw3PwMO^n~`_4wLRlZ-iZo2Y#I5`)7h{H~q z%+unhSX(MmBvlfKFXk8#MDa2zBqc=>mic1pfm}ll{aI`w-I|CZxlQ;^OBCet^WJ1W>(8LP7e9%5(iy+%tN!L6wPU+bH%y#Bsv*s zWQ5&waX+FccrrI=84gTLB<(N}nb@of`{}oYkl#pU=wo^7T+loh)*dY9Vw#{L`YiHS z>7RFGs>QPrQ7Ibcq_Y&}rLX@pC>$v<#rL-R9BCsVJQy5Gf1O>8DjpKE&I@EkQXVcU zG7mhSF&!h6p!(?kk@2X<{5ejmEP@Pe0ns=hn;jQw5x%|HYF0vOvQ@}cb5G-u(*O1# zCdYvT$#T;?2lfrpjcF-F)^z$MK z;`l5+zRGe-Iuw&tqLULdyy#M5q0gW{z##f{YLYfMjP3Iw$~=d%A;q||y1BWzqobpKvh*(}&ynzQ zTxJ>zO>-M-wlT~f>4`)n&G!L$SeUE!kl7p&^W_kwyuor=dxkVm_Y9-uC7$(&w&pIj zwm)G}gCc}<_cFioaa)kk5}OB@40P`$C}Mq)m4EXi`y=_J9m)BCVCmH>JL;^`!v#%@ z0sHEEl7yOse%VSt{HS&Hn8v1xrS&H;UZCJ2Jt4UX(#BLo>J080YKzAh}iD#sgW=F zy-ZqW%Qoi3sjL`nG979T+5RaPyue>w#R{s?(XD)coJ`#whZ_lN2Du~$m6wr-d4$S* z54q37dZRnBSl>5irJao+U$9iDt5bmUBCn?nw^!-?+{9(bf1^u%IkCE=FVUGuVs`b) z9f2dgEUS>SfkQLAjfz+GQ8uhR=F7gzjX>3CVvDJwAfotOm69+f9O)PmCT_)%Pvoy^ zE9El<2iLiOm=sbB^<^k3*fo<`WSA~-7wdaxm|{gg%MX?Rc;Dz2-;F^1Tux$abHi92 zajK0!=Jgo=-5-amIh|qCXbq}w>Z)PdD0nMN!e0|)yKtFN9cymTuI>FDCq}M<@}EY& zN6YfyKmD>NNt5HOYMR3+mH(S0H0npo`mPR#G=vs%PO_#`f?FFOk+y4kC&V)%8kd%t zR!O=voJl3;b|BtG)qfjf5(PfvEYT^8&hRV8dP9ITR=uFH^1o2nVIa_gg1jSmmouXz z2%-P?um449_}$U_!5IboEBrnAk<|az35{|sAoBlzX`#}E1WQFQTqi0E`x-AVi$()e zOvbW2k0w{S!wAj)sbw(vzR@rpx*!1fat55Mz+2(kMgy_5JYDHLGG_ZKdbBI{0%S%} znN@aM-mH;SlkmgZNo;|0_=rMGEB?j=)v2_=oF40;+g#66)MXjrvFf! z>px8yf6sdD9Oe8!;%fP$7>Nn}xI!21=_fBSGHJ<^A7*IC_>)zaXqVrjc_04t-Xm6I zkbX&^j$gzZmZxB7?5vI)WBEP!(p&6olH}ZcaYd1`N#$2hlHg>+5d_#oX8HpXq_;y<9AT&M~T8nt*r*q z>L?HdIy?((;kQqKRjlPtzV_&UWagk@+HKUdOT|6m~&^wFG;;VEtQeEwZV zj6cs!9z1Nlw}>Ej^L?AM?5ahYLX&wj0z=7Fixc0iDckjDiCcul-Q>Um?mZO zyKNm&XX&-C`*6=xOtBy`y(-R2AZ*)nGVg6{Ov~aY0(cQU@qCsTNnha=(GQuNs1IcK z40CS7OC1XhZ<(*yWooDWAjN{ovAQvwD!k75HReZ+iDisq;IGQG&zYTY4wHnX4@TBn zJfoiqJLk}2nS_y0DLWaeLiK8>6qmP{$eNa^K!sO(amgGxL%hMTCd zUfT+!N>P7(6r_zUcTX&$_!XBw+o(Vh9zP#VjW&ulaCfNHI2FOZMNEXoW~?gz21w6`!m~2x!q%9Lj7o3nAEK4 z>1uCLTl=*XG6?A6LPYL(y7g?ZS3DHMr>DLT+9-Hctyy=K9_O_4+pO6C_3Po0ltWMO zHs7XjX+;kW^4zjHvb0qYDA@RZGDdO#V}k!=RzgC5;c~BY=|`pJsa-5VONqMa`#IWu zHkeXkgrzU5gAZq3!OfJJn;payKk-uu#rAWy5_LoRlF;u^c~Qq8SnBPwZ1Xr`);MI1luy1Er#m$y7zuKY?>k4@pdPpmqu01nw_$vaNo@bL zBKfJHe|Pm2)@Qp8B>Y6Yu@ah8jgeQuH}g7*tW%#RKu|oe<|9Q(;g*WttgCXIM!kH+ zrP1bkGC@9UO=|bw;^2bEd3rP)BUaJ=7eh@txPvOhXyE4@nn7k^YzWHmpcHM|V7@pTzeO zQ*%D1P0lvhy$%kYka8l>hTWoAMNPkmU1U=R#KYe%sR=Znds0D zJZ@XRNi6P4%0B&yl^cuCjQ3t?+_%YZhhvY6GV|j0ZBpXmIoQtk*QfpXMm_j^paarFdH*@XaQXY;wWj9N8^%#RR zwdQGqS?Wx6b>f145|16?N-vY--0SU1_wKVClV!(yZZ)-asXZR@F;<;=b9OU>4{L2~ z2XmsWU@T5)bgL_e<;9Gm(|=D<2q?fJJrXly-0<~kRw1W&mZ)5}T3q`S=JIlG*Y`D} z?ny4ekl5^%UPlwwH*!x>j!S+V68Ad~#;%$iCEKq23O#(4>$#o##9cfvTOm}nRR8tI z&*lX09tPuCvKWG&({Y&6+SPm?_0h@t^ww*WD)qzWl34U%HRq`Rt%)R{MD*;HSjnVN znS2xknsm#%mBQF9n?l~F#I!QzGdXD`TQ=w%|DMjt&R9e_2`Bv`3-o+V;7`j+bT%Mp z79PyMJkVvSr&nE?PEs%*UYENf#336p`Rjlr4@)Y%El?(gq$M?{)$)0ro&nFu_nFTR zo2G8PwlPy(Z7z2uPMEXR{H{x1IS3msUGrBuL)WFuJ>=>jQ3`sWz3+d&{hwkN_|X5s zrB$L^cPT!kitN_jtg3>B=Iy~WSNEs$^@Il0$Q$$CzbC1JEsTwpP9K6SsJPe=;~?tX z2a8%-()IYy-+WaZ$i076?eP{3+isN%iC{W5UINIndUJ6)%!7oVieOiJFCjx493oZ>jkjMR zDMXLxe+#;xZn!4CQ&grJr)d`~^T1S-5j4Jqw*0y0Ig_4d;ZnRDI*!{``m z+@JBq^Ec}ZbX6aBpyF1k3mrKEJn@e}gv0sxwh2&@)j=oV^53m6nA=bL#_P7qxpv6Cxm zl6&f_I3`JnR?%N%f}b9G+Z&}kjt+N z$@{k|=$IQg=FsVO#OIEdNN6NKyei}&8bMHeBKI@u&s^%vi_x@J?&`3opr5UIrv2b* z%5)iT_`d;CK374T{1S-?Z_$<|P1Bx}q!^!&*J0$Wc|a@MvUa2DqpB?GvWZ`o7-Oia z?cWCo)Ej|Ae;Ep9EMt!K#_TN4hHpDsy0bxkN%gJ&HZmqVsA|e}vOFot2FxPLKTN}l z|M>kH`zs3G?kbqB($Zpm7P=MV)EfG}a_fTUMHxfoKIlcxWH}0F-p1TbHI~A zoWm!%fwN+%DZaXtt7%TIG4(oZh!HD)-2!QwE?=J$^x?$lL|RLsnh#T(#INHW@wd{2 z;0;y@)ruwR$z3kT&WR_tjzeR~o(`{`)mi5Io1fq@s1u*TB0c#`E&d z4%!?C^cS^gSLdUrt`caJBSMZ&l>9^|y8$-S6nqtD!*=PPFa!go%FZUr(R-gxqYQ6R ze9>d%A#uq#PE#WZO+U*NLosJY1kN}saadhOChb^j-QL(LPU7B7irnm<8034j#GT0_ zTcs0KKsJ2KWTK;)FHX(++rvIt!fne#PIjU@;X!1vDKF-0ON}MHO8fT~k9(hl{_85V zn?ILGh`Eoq8SeUb52l)Kx;9a_ylc}g0Q)QA+l2OOp=aQ8Vp9}4P4N-10CF_pHe%n- z_A`tTBlbHbgk(vJpCu`j(!aK^!dp6^qQmPuDA6TipzmmoZ~qJ95DqUH+w(Ng4-$!G zSG$R}%-Bg4tu#u+gK$|>Eq{U1wt+wvZw{P1b%y&UUP+0hc0{b5)09IU2@wI%TcVAW zu_8Z8l1fr0*S;hB71x z@qFa9l2W+ud^Ze;!PoxT*DP{B3stkAQLq>H={JoxyZ4wi8#hOfuW5OiLp%pE8QWaF zty?@z4&~FPA!kr#kT<#4q@B5V=FDJzrWVjl0M#*CVMp>4u1?Zu;g6Jifo1_XkQ@g` zf9FlmJ*0BG-?607LW(S^CF;&*J$S%-M@cDj{ae$&n_HGUiYa-!M{ky;uc~F_CBQ~n zxMz!bE2mh>x|SFIj5P`GKGq~W+QC9c=kTZ)wCiLvnK(pcW@UvQrMsCKEdtU+u{3dL zBn6}}daSIj_CfdlcypAz=W4VX%FsDVX$JcGTZ@au(B1Vh$3l!00DaTEFIh%K{ne{i z#>P|uEtYYn*pI|6fo6TnlWoXdHTbTy{`% zpPkwAGOvWzDzKyBEtc11@?*LYieE2)TL%&eZS92SSCz|4G{8@R9tw0NcAxifiez2+{MhIy%Hz_R=N5g*#JpA`(6gK1oNK9;Q3$hkyfdi@Y%^%2L&F_afNPEm zdd9T0t;PCN>4r$U#c`?6MWNnL7igos-JM%)fckUQ@8Z=1iOVyo!VudpmfmsX>uxHX ztWF%(WlXus()B3705nd_*f3JchiGG-l^2l0e3U?iCA&<|M@Yz)<)c~n&g)`5&3fE7 zV?Awa>%3p9!1n{{xy9eTbLR)9j`jzoUcxN864&yncb|P65Kj@l8Sw1-XkF#{tjzK_ zv9sfwQUERv;?J0$?5)K`=cRrv!%2a`%S+E#*yT8DcT?f9dxZA-pFea_7tXOOh zJL%I3w2PZvgrFry2JB!@PZ0#NJM$ks9=NGvsUrFf-lDv`ql3ve8$Y1m*ZnQi=MA(f zxV{J8h9t(w%uEV23z!LHOPL)yJAOLlRXwMq3bj-SbfIzFgl%UkfkaO(=III@ZhT2zPWlr8uk$150|sD` zx09ry(!#^P0rnCkVfo4ZGd#JhjDWapl{}H#jyxdF{&?lfZ zR9e>yyyPs^4Pd;1b_iwR=e)PaTFToT#S|;0bDpjaojowzZWsP{wty0M!=y$-pB9 zb_=jACw>?`^Y;Gt{E-(v0RgY&5Y3}UkM0EwLl2UF&ea4&RzMWNm+VazEQMY&J$(Sp z0rWtjF<^vh zlfAtJKAX=)MeG+b^B%i((Bi!Y@&aPv_irSLp-As1vdf83*3c*i!pY2x{@b^w(Ei6J z;rUdz1pEmgL%JWWKbd3GEn|S5{p_q4P&%M#oXBGt1>`lwuSsHFLh;=xyw;kIjtAEl zKG#YN_%6_VhR&R@uwLe%e6m2X(^}t_DK@!C!spK<|IrAjVr7Bt4qvR2qR4MORsebc zprZgS+Z_7vRFNICv%r+~0!j;v638pr4Gq`8lGxbXoPt?qRLda~^ZW~f281toi@Ogv ze7!yaGX?0~Z?-0iq0tIQ{iq)SQv;gzNOeJN?IrM1pqmZP1kQuDkg(SnoD?t|OU--T zR}(FyLP>bdx?*5@d9BAJq@;j8^LA&Z>P5A)!`rvOD=Es$)2(*S1wjr-A%O1!eR?%@ zbyQ#i{sj60d}Sdl3yAdC*uH=Jrd{o92@V~&0SM$4Zw(?qF2m7LGM~*9F#cm@v-9)+ zq>6f&_opJM)F4z!QH<|CaboC^hI&#(MnN7(5GEt>L>;~Zs24gq zI%Z~O$frJ;w3r7@4sicBorMs%f z>FHr2z^>t8t36KHBvpWyjxPz_Teubs(PpwFyP`s~Xxs-xN?=X*(NGcg(3=Jy0YsQx zP!%HQQi4k7$IB)#yXkUkQ0ehh>3hSs!|Vs%r@u$c^&#a9oDvsAfxU&MVBi>n?*?
9IDUz53urhO za9^Nh17U;xMKupNH&|b!%7B7mAy&(PQ!o+&6`Ni~i2hAr_zYN;XWd->18xp<14!l; z5ZDTo1%94VY8dInYiY8X5v__@hT@uxILly0%p@ z4`CFj)=pJ3F56R)?n;V^pjnx&eq#;mi1PB+CtTQNKy^C;PQISH`ZDkt^z=M{AGdn% zGx)u4Dw&n~J0Zl};J>ecKLgfYDfs=#A6?@q)MXJ}ThT{B8LxY`%`4u8jb@VA*_jEK zM6M{=n2(s=w_YA3IEux^Mc__Dr5lI{_>w8&K4L%s7#>FYA1*G(fiF*hihP`>knQ1H=ko z$^gR{m|&sd;lMZ<2HgaZ0b#%0L4Z6^$aQbQ^yY!GftJ>D6@0g*6-Urnal%$KsB;IB z3`!$Fst&bTkT}fF%m7_!WofC@?a=)2HMnHfh{ASbn z>iiAxoeBzAT$=b?X{YRf3+e6c4PKLpjg3x$2g1k$0s94uG_MMuYwvpjPKT=shK7dO zs%HSm4$m%u=IDd?GHM0l$mdL6pt*6cOHJXgGe}EH`U9>X;;b5eY*f_mogHuZB-{xg zMO=LRo!hsgzWLT^ai?m@$e<(01Ra+%!^Pb9TZtHhz{6?ej{+kI1XR#2f(Q?kEt(Kw zxCYpc9g@f3&0wKGjr%|PoTipmf3je7@+xeXo>C->90*Vmi% zlu9t4h&`Z2|C_(QN|Vj*>gjQIaHxXS1I`cxX6q<75XTrbe}LIQ02p!I%>5b_9o=xg znJ?yb9uXG=F&K-4=T-9u^i}$L(6#~}$?;khpBI4UTB=7_?LBPl>#fp$2-+HIY9=LG z8XBV@v_T+QpZJmrpLufO8J1ORJx*=s>%EZ60#TF|%(LJ^T#_-xA}l82|3BTvj_igvb1BPQkz zdkySrw$dRpEo~mSg7K_+aY;$SfDz*j+$~{^k$k-tF$qu~g2=kYWgB1~CcLmfN59U! z9G)^OgE7b*=$AlQmLdK}Rh%DwsY5ZD$&mNu3k4OGF>na+B@-`kZKWnw-+zwhv#gcJ zid&_6h3EdE-dIMp_EQRnXs)(3)@#Z_9rLvuS^4sr1(PXhvkqJ82eOT>B;W3cX$6eo%aFW)H9&C#dqIA0K*C*74UNJBfyu@$tM7X&ko3iL_|bDC4@}? zG+e+2hnz@d7=$QDvK&AT@#YOOxl&LFH7Eie*P6Wm@StH6=(CM?cjv z%Q{RYOqsJYkIb)@miHSP{fqVtK|qbe{O|qAMuQO2Ocmy=@-gIk{T&ugg^AHn( zUIxs*XeH^BN`0h|2ja55y*;SJdbu;znZR9+1DpWXBLG6!--oWXK);086v(n}_CC4g2H9(K0*P*@jlxtyi6?kYv5LUtY!bKqPhAb1J9Au+kVPcUN9xDcY zUJkkhH-JY-NciA^bPl0C%oGL&1|}wu;By$drl)Hlp#c74Q&ZCxw^iHWZ+ijA;s8Ox zG4cNX1Ox?o?lgoi7E>ZrzfLsdsdMkNN! zp~?)zupob62m;AEp6st`SRfjbN|HlW%?D}MbmQEUR~kj%@r6-ODNEY8W%(Ko>B zMDkG)-$t$2;z4->{vk~bUjsyh`ud)`b9Df66Xi9Z{Nn)~YjnTN=@ig#ovQTf43sJ; zDcOFoaU5g-IURWVV0d67%ZFe?K){~M!m65F6nHeEUj{s<7z0bSjMqDN98_xck!?)F zgsh>VJMvLsU)QSnk~9iv8Goq?VIttlv#uOdRc?fGcN=$-l?L6P2%%4GDE^i82=$K~ z+$WU%#5U_sF?*!6 zGvpUQl7(Cc==jm}e_^wO4glV;12`K6;pRdw3@#tYqf_(qX(D_OHepSXxfpoEf`Sk( zaNXYS>|P<#u#LSS;k9sqc?0isV3Gl3ot^qr|dbyvblus~~r z;{$%ao_t!5c6x9S6d0&eZWSw)2`&Q6AFL5L!)h;IQl!~UiMzopw}(G!fYkz2@dpkf z00;>16a?>pw?HWc;#pAO|AX5A#^s*ehlma!fSrkHs?x#a&6{$AB6_85)4iMV-B&== zM=l_EuJiMA@E%w2RnQw+MsetfpuBUBOj<^UbJs0<@YP>WF-fFk0)a?Zu7qL*;5W!h zz+S(=j)%0a-s_?wKcAWLG2Tf851^owgoM94HM=ld*bg`wTR`*@&$b$^xw5u~RH8zb z41qwm@C4+4p!HFN++kMKF6b4GTE>xF6eHagHR8E!6^i60Jr8A7GQ%ZieJb7 zbi(11H*epafUg5|qpztshDX1$yl(;f$a%rFA!j~LaxwDokscWBj{Gm zhjSE6HN)ZVZs2zzM{$8liGu?OqF{=EWI!xn|D`hwW(TR=m67R$GZ8?W3=KXgvU$Q3 z1LT324y6_6jUmae!zqGJZKmyDiI9ipfVvLiIApv)e!u$KI6Zv^Xr;toh&K6x?^78y2VWMlxx8fsoiG#*f+0>}UN{5(~}t)!yD1@e7lJOJjev=9^l z;Ld;;fYl363#jZU_@-|{!UOQ0P!O?%Yr#Bs<{KKoDFI4Fn)WIwRz^j|2_T^w*mB71 z{Gkv))wZ=m0PS7?-=gY*f`X7-+PL}v-HO+V@$vEMOt*X?$AU5eu!325dCObZmR|*a zq*)dzIB_X$@{48O-r1JA?ixzJwWX-ZIy2qdHHo<_d$`0USE4)d1GjFr;L&W@q21z~ z?U4l``(2b1zh~h&1kB&|?5m$i78#6G*hn>$4-NhXTnl@`G;Xe}j3;O5&KcinM6r%&O6jpK93CU+ok!`6WfJFwvlEN%D!`{JJ8hr$yS1&|2= zJh99c^7svKc97%%H{8|D4HAP3$PTGU0VR6CCt!I@Fl=CC@C6VSSN+p~^9)(5>OC-> zjg1Wu-P1RK&o|fAoq_@cL|BN$@?0(u8DUYNvK5fQ0IvUD(^0XJ))-_-kN|v9XOdY- z6?y|;dmEe{jj9c$Zed(*FXWd{JOFDL#+L+Wf4yWc0G8U@*GH#E4hzi68tP`P;N~VM z7ztuza5;oTMA5bdHWsk}TlD@S7J9NomAdN?=;e%#&9!M#C}`^0Jy zDL#6;qnH?w|E?62KFfVL4bYV9PWChj$s@V8SDXBWG-xH4D(Nu`Ry# zJb)@T1d`4_Q2v2B#0WNyM@{py?gdA2^A->7%O!Mhna_`F-yPqwgb9{;#&qJf!J34CB8Brg>nBN0`jS@F*2^WvR^D@D|CuP}6D4^4Po* zlakCVGsRr#Y+6pmflM8Q*i3W_n^~i!QuBbBk*PT>yoQL{v-wX!|Bdn87>xJ(KJW2) ze&6%i?gpYy{oP`%TKx)tYXZVY1+WSLoODsiC__do*>Z-SM5os!L_9irU;hogx{7Pp zb#i@dKqxe@@^0SFLDyzX&&_@qQmRGC`7jIFOf8DXrM~<-;Pxh1wh@Vh|{Pbp}UnpciuFcg!V>{g(N~Gc8zDEdw^U=h){AMRqulpf1ACHUq8ia1>rtc zrMB@PL?*9!JiDEr*R7@VB7WO+k#^-ydD=wTL?sG3$;gO{e2VRwj%HGbJi^?(QJzv- zGhI)OSVxxxhEhwbtKM*xV>KUDy6Yk>b@EYIfCyKBcbL##gIR-3`XV8c$rvCaI>=Qi zQezqYTCQTSNk7sCO)l}?X(JPpKxg_|TpQA{jHgr_41#h_va#>d2~u zviVZ)%j_(trFQIc2Uw*}LnlG#FVJdgExRs^cO<)KA1fV&uwnIZ0x?}d9Hr(ZJGjwm zzUB+NnSREWU6<%C7+hA6O?i>xW{(q36KhHa2Yq>WcU0oXeP_v8NIDrYo_?M)(?SMH ze9A=@ER;gZ*pl&;O=X@*l5^vu*31-$st!Z){K`t!KFQIE3(1W~Qgcm{pEKinlAyjm zw*^%zhm#JqBESpRvuM$9rf_Rdco$6ZDh;ZCNLRSa@5zme+o}*o=mGuc20jzk-4M2? z)9+hXuG!Me;1@H_7wN|GiKc~x66~S&J>lc2=Y}MbNNoB-dFS9z_U=t+Qi6zz5}aAa z5-QgWGnb5@xF&szM5fS)nR`yXvoKY0L_pK3q+((_!xmg!o@fXr&#L(x_4dU_!@pi? vKoh(T0OKF(LUU5b!{>nT(0uB@NB4ZbZCr^T$l$cYxQz%2iVW=WPc8og9>3#! literal 0 HcmV?d00001 diff --git a/include/sick_lidar_localization/fifo_buffer.h b/include/sick_lidar_localization/fifo_buffer.h index 23e7bdf..cf1e82a 100644 --- a/include/sick_lidar_localization/fifo_buffer.h +++ b/include/sick_lidar_localization/fifo_buffer.h @@ -1,5 +1,5 @@ /* - * @brief sim_loc_fifo implements a threadsafe fifo-buffer ("first in, first out"). + * @brief lls_loc_fifo implements a threadsafe fifo-buffer ("first in, first out"). * * Copyright (C) 2019 Ing.-Buero Dr. Michael Lehning, Hildesheim * Copyright (C) 2019 SICK AG, Waldkirch diff --git a/include/sick_lidar_localization/pointcloud_converter.h b/include/sick_lidar_localization/lls_transform.h similarity index 79% rename from include/sick_lidar_localization/pointcloud_converter.h rename to include/sick_lidar_localization/lls_transform.h index d9dd18d..1ee75ed 100644 --- a/include/sick_lidar_localization/pointcloud_converter.h +++ b/include/sick_lidar_localization/lls_transform.h @@ -1,5 +1,5 @@ /* - * @brief sim_loc_pointcloud_converts sim_loc_driver messages (type sick_lidar_localization::LocResultPortTelegramMsg), + * @brief lls_loc_pointcloud_converts lls_loc_driver messages (type sick_lidar_localization::LocResultPortTelegramMsg), * to PointCloud2 messages and publishes PointCloud2 messages on topic "/cloud". * * The vehicle poses (PoseX, PoseY, PoseYaw of result port telegrams) are transformed and published @@ -78,11 +78,11 @@ namespace sick_lidar_localization { using namespace msg; } namespace sick_lidar_localization { /*! - * class PointCloudConverter implements a thread to converts lidar_loc_driver messages + * class LLSTransformer implements a thread to converts lidar_loc_driver messages * (type sick_lidar_localization::LocResultPortTelegramMsg) to PointCloud2 messages * and publishes them on topic "/cloud". */ - class PointCloudConverter + class LLSTransformer { public: @@ -90,12 +90,12 @@ namespace sick_lidar_localization * Constructor * @param[in] nh ros node handle */ - PointCloudConverter(rosNodePtr nh = 0); + LLSTransformer(rosNodePtr nh = 0); /*! * Destructor */ - virtual ~PointCloudConverter(); + virtual ~LLSTransformer(); /*! * Starts the converter thread, converts telegrams and publishes PointCloud2 messages. @@ -131,7 +131,7 @@ namespace sick_lidar_localization * @param[in] triangle_height heigt of the virtual triangle in meter * @return list of 3D points */ - std::vector poseToDemoPoints(double posx, double posy, double yaw, double triangle_height); + // std::vector poseToDemoPoints(double posx, double posy, double yaw, double triangle_height); /*! * Converts the vehicle position from a result port telegram to PointCloud2 message with 4 points @@ -139,8 +139,15 @@ namespace sick_lidar_localization * @param[in] msg result telegram message (LocResultPortTelegramMsg) * @return PointCloud2 message */ - ros_sensor_msgs::PointCloud2 convertToPointCloud(const sick_lidar_localization::LocalizationControllerResultMessage0502 & msg); + // ros_sensor_msgs::PointCloud2 convertToPointCloud(const sick_lidar_localization::LocalizationControllerResultMessage0502 & msg); + /*! + * Converts the vehicle pose from a result port telegram to a marker array. + * @param[in] msg result telegram message (LocResultPortTelegramMsg) + * @return marker array + */ + // ros_visualization_msgs::MarkerArray convertToMarker(const sick_lidar_localization::LocalizationControllerResultMessage0502 & msg); + /*! * Converts the vehicle pose from a result port telegram to a tf transform. * @param[in] msg result telegram message (LocResultPortTelegramMsg) @@ -153,7 +160,7 @@ namespace sick_lidar_localization * converts the telegrams from type LocResultPortTelegramMsg to PointCloud2 and publishes * PointCloud2 messages. The vehicle pose is converted to a tf transform and broadcasted. */ - virtual void runPointCloudConverterThreadCb(void); + virtual void runLLSTransformerThreadCb(void); /* * member data @@ -161,14 +168,22 @@ namespace sick_lidar_localization rosNodePtr m_nh; ///< ROS node handle sick_lidar_localization::FifoBuffer m_result_port_telegram_fifo; ///< fifo buffer for result port telegrams from lidar_loc_driver - std::string m_point_cloud_frame_id; ///< ros frame id of PointCloud2 messages, default: "sick_lidar_localization" std::string m_tf_parent_frame_id; ///< parent frame of tf messages of of vehicles pose (typically frame of the loaded map) std::string m_tf_child_frame_id; ///< child frame of tf messages of of vehicles pose - rosPublisher m_point_cloud_publisher; ///< ros publisher for PointCloud2 messages + // std::string m_marker_frame_id; ///< ros frame id marker arrays + // double m_marker_arrow_length; ///< arrow length of lls marker messages --> + // double m_marker_arrow_width; ///< arrow width of lls marker messages --> + // double m_marker_arrow_height; ///< arrow length of lls marker messages --> + // double m_marker_color_r; ///< color of lls marker messages (RGBA) --> + // double m_marker_color_g; ///< color of lls marker messages (RGBA) --> + // double m_marker_color_b; ///< color of lls marker messages (RGBA) --> + // double m_marker_color_a; ///< color of lls marker messages (RGBA) --> + // rosPublisher m_marker_publisher; ///< ros publisher for marker arrays + // rosPublisher m_point_cloud_publisher; ///< ros publisher for PointCloud2 messages bool m_converter_thread_running; ///< true: m_verification_thread is running, otherwise false std::thread* m_converter_thread; ///< thread to verify lidar_loc_driver - }; // class PointCloudConverter + }; // class LLSTransformer } // namespace sick_lidar_localization #endif // __LIDAR_LOC_POINT_CLOUD_CONVERTER_H_INCLUDED diff --git a/include/sick_lidar_localization/sick_lidar_localization.h b/include/sick_lidar_localization/sick_lidar_localization.h index 2e1bcbc..0fba84a 100644 --- a/include/sick_lidar_localization/sick_lidar_localization.h +++ b/include/sick_lidar_localization/sick_lidar_localization.h @@ -69,18 +69,19 @@ namespace sick_lidar_localization class Config { public: - std::string hostname = "192.168.0.1"; // IP adress of the localization controller + std::string hostname = "192.168.0.1"; // IP address of the localization controller std::string serverpath = "api"; // Relative path to the rest api, i.e. url of rest requests is "http://// int verbose = 0; // If verbose>0: print informational messages, otherwise silent except for error messages - std::string udp_ip_sim_output = ""; // IP address for output UDP messages, or "" for broadcast (INADDR_ANY), default: "", use IP address of your local machine - std::string udp_ip_sim_input = "192.168.0.1"; // IP address for input UDP messages, or "" for broadcast, default: "192.168.0.1", (IP adress of the localization controller) - int udp_port_sim_input = 5009; // UDP port of input messages - int udp_sim_input_source_id = 1; // Source_id of input messages - int udp_port_sim_output = 5010; // UDP port of output messages - std::string udp_sim_output_logfile = ""; // Optional logfile for human readable UDP output messages, default: "" (no outputlogfile) + std::string udp_ip_lls_output = ""; // IP address for output UDP messages, or "" for broadcast (INADDR_ANY), default: "", use IP address of your local machine + std::string udp_ip_lls_input = "192.168.0.1"; // IP address for input UDP messages, or "" for broadcast, default: "192.168.0.1", (IP address of the localization controller) + int udp_port_lls_input = 5009; // UDP port of input messages + int udp_lls_input_source_id = 1; // Default source_id of UDP input messages (used if source_id not set otherwise) + std::map> msgtype_version_sourceid_map; // msgtype_version_sourceid_map[msgtype][msgversion] := default source_id for UDP input messages of type and version + int udp_port_lls_output = 5010; // UDP port of output messages + std::string udp_lls_output_logfile = ""; // Optional logfile for human readable UDP output messages, default: "" (no outputlogfile) int software_pll_fifo_length = 7; // Length of fifo in SoftwarePLL std::string odom_topic = "/odom"; // Topic of ros odom messages - int ros_odom_to_udp_msg = 0; // Convert ros odom message to upd: 0 = map velocity to OdometryPayload0101 (Type 1, Version 1, LidarLoc 1), + int ros_odom_to_udp_msg = 0; // Convert ros odom message to udp: // 1 = map velocity to OdometryPayload0104 (Type 1, Version 4, LidarLoc 2), // 2 = map position to OdometryPayload0105 (Type 1, Version 5, LidarLoc 2), // 3 = map velocity to OdometryPayload0104 and position to OdometryPayload0105 @@ -121,7 +122,7 @@ namespace sick_lidar_localization void close(); /* - ** @brief Register a listener for upd messages. The callback functions of the listener will be called after receiving a new udp message. + ** @brief Register a listener for udp messages. The callback functions of the listener will be called after receiving a new udp message. ** Overwrite the functions defined in sick_lidar_localization::UDPMessage::Listener with customized code to handle udp messages. */ bool registerListener(sick_lidar_localization::UDPMessage::Listener* listener); @@ -134,12 +135,13 @@ namespace sick_lidar_localization /* ** @brief Send udp messages to the localization controller */ - bool sendUDPMessage(const sick_lidar_localization::UDPMessage::OdometryPayload0104& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id); - bool sendUDPMessage(const sick_lidar_localization::UDPMessage::OdometryPayload0105& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id); - bool sendUDPMessage(const sick_lidar_localization::UDPMessage::EncoderMeasurementPayload0202& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id); - bool sendUDPMessage(const sick_lidar_localization::UDPMessage::CodeMeasurementPayload0303& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id); - bool sendUDPMessage(const sick_lidar_localization::UDPMessage::LineMeasurementPayload0403& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id); - bool sendUDPMessage(const sick_lidar_localization::UDPMessage::LineMeasurementPayload0404& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id); + bool sendUDPMessage(const sick_lidar_localization::UDPMessage::OdometryPayload0104& payload, bool encode_header_big_endian, bool encode_payload_big_endian); + bool sendUDPMessage(const sick_lidar_localization::UDPMessage::OdometryPayload0105& payload, bool encode_header_big_endian, bool encode_payload_big_endian); + bool sendUDPMessage(const sick_lidar_localization::UDPMessage::EncoderMeasurementPayload0202& payload, bool encode_header_big_endian, bool encode_payload_big_endian); + bool sendUDPMessage(const sick_lidar_localization::UDPMessage::CodeMeasurementPayload0303& payload, bool encode_header_big_endian, bool encode_payload_big_endian); + bool sendUDPMessage(const sick_lidar_localization::UDPMessage::CodeMeasurementPayload0701& payload, bool encode_header_big_endian, bool encode_payload_big_endian); + bool sendUDPMessage(const sick_lidar_localization::UDPMessage::LineMeasurementPayload0403& payload, bool encode_header_big_endian, bool encode_payload_big_endian); + bool sendUDPMessage(const sick_lidar_localization::UDPMessage::LineMeasurementPayload0404& payload, bool encode_header_big_endian, bool encode_payload_big_endian); /* ** @brief Parses commandline arguments, reads a launchfile and sets parameters for sick_lidar_localization. diff --git a/include/sick_lidar_localization/sick_ros_wrapper.h b/include/sick_lidar_localization/sick_ros_wrapper.h index 3eeefd2..b90150c 100644 --- a/include/sick_lidar_localization/sick_ros_wrapper.h +++ b/include/sick_lidar_localization/sick_ros_wrapper.h @@ -140,8 +140,8 @@ inline bool rosOk(void) { return true; } #include #include #include -#include -#include +// #include +// #include typedef ros::NodeHandle* rosNodePtr; @@ -234,8 +234,8 @@ template class rosServiceServer : public ros::ServiceServer #include #include #include -#include -#include +// #include +// #include typedef rclcpp::Node::SharedPtr rosNodePtr; diff --git a/include/sick_lidar_localization/sick_services.h b/include/sick_lidar_localization/sick_services.h index 3974859..de21a0d 100644 --- a/include/sick_lidar_localization/sick_services.h +++ b/include/sick_lidar_localization/sick_services.h @@ -83,7 +83,7 @@ #include "sick_lidar_localization/LocSetOdometryActiveSrv.h" #include "sick_lidar_localization/LocSetRecordingActiveSrv.h" #include "sick_lidar_localization/LocSetRingBufferRecordingActiveSrv.h" -#include "sick_lidar_localization/LocStartLocalizingSrv.h" +#include "sick_lidar_localization/LocStartSrv.h" #include "sick_lidar_localization/LocStopSrv.h" #include "sick_lidar_localization/LocSwitchMapSrv.h" #include "sick_lidar_localization/LocGetLocalizationStatusSrv.h" @@ -109,7 +109,7 @@ #include "sick_lidar_localization/srv/loc_set_odometry_active_srv.hpp" #include "sick_lidar_localization/srv/loc_set_recording_active_srv.hpp" #include "sick_lidar_localization/srv/loc_set_ring_buffer_recording_active_srv.hpp" -#include "sick_lidar_localization/srv/loc_start_localizing_srv.hpp" +#include "sick_lidar_localization/srv/loc_start_srv.hpp" #include "sick_lidar_localization/srv/loc_stop_srv.hpp" #include "sick_lidar_localization/srv/loc_switch_map_srv.hpp" #include "sick_lidar_localization/srv/loc_get_localization_status_srv.hpp" @@ -282,9 +282,9 @@ namespace sick_lidar_localization bool serviceCbLocSetRingBufferRecordingActiveSrvROS2(std::shared_ptr service_request, std::shared_ptr service_response); rosServiceServer m_srv_server_LocSetRingBufferRecordingActiveSrv; - bool serviceCbLocStartLocalizingSrvROS1(sick_lidar_localization::LocStartLocalizingSrv::Request &service_request, sick_lidar_localization::LocStartLocalizingSrv::Response &service_response); - bool serviceCbLocStartLocalizingSrvROS2(std::shared_ptr service_request, std::shared_ptr service_response); - rosServiceServer m_srv_server_LocStartLocalizingSrv; + bool serviceCbLocStartSrvROS1(sick_lidar_localization::LocStartSrv::Request &service_request, sick_lidar_localization::LocStartSrv::Response &service_response); + bool serviceCbLocStartSrvROS2(std::shared_ptr service_request, std::shared_ptr service_response); + rosServiceServer m_srv_server_LocStartSrv; bool serviceCbLocStopSrvROS1(sick_lidar_localization::LocStopSrv::Request &service_request, sick_lidar_localization::LocStopSrv::Response &service_response); bool serviceCbLocStopSrvROS2(std::shared_ptr service_request, std::shared_ptr service_response); diff --git a/include/sick_lidar_localization/udp_message_parser.h b/include/sick_lidar_localization/udp_message_parser.h index 0481481..d626777 100644 --- a/include/sick_lidar_localization/udp_message_parser.h +++ b/include/sick_lidar_localization/udp_message_parser.h @@ -82,18 +82,6 @@ namespace sick_lidar_localization uint16_t sourceid; // 2 byte source id }; - /* - ** @brief Container for the odometry payload message type 1 version 1 (UDP input) - */ - struct OdometryPayload0101 - { - uint64_t telegram_count; // 8 byte TelegramCount uint64 - uint64_t timestamp; // 8 byte Timestamp uint64 [microseconds] - int32_t x_velocity; // 4 byte X - velocity int16 [mm/s] - int32_t y_velocity; // 4 byte Y - velocity int16 [mm/s] - int64_t angular_velocity; // 8 byte angular velocity int32 [mdeg/s] - }; - /* ** @brief Container for the odometry payload message type 1 version 4 (24 byte payload, UDP input and output) */ @@ -101,6 +89,7 @@ namespace sick_lidar_localization { uint64_t telegram_count; // 8 byte TelegramCount uint64 uint64_t timestamp; // 8 byte Timestamp uint64 [microseconds] + int32_t source_id; // 4 byte source id int16_t x_velocity; // 2 byte X - velocity int16 [mm/s] int16_t y_velocity; // 2 byte Y - velocity int16 [mm/s] int32_t angular_velocity; // 4 byte angular velocity int32 [mdeg/s] @@ -116,6 +105,7 @@ namespace sick_lidar_localization { uint64_t telegram_count; // 8 byte TelegramCount uint64 uint64_t timestamp; // 8 byte Timestamp uint64 [microseconds] + int32_t source_id; // 4 byte source id int64_t x_position; // 8 byte X-position int64 [mm] int64_t y_position; // 8 byte Y-position int64 [mm] int64_t heading; // 8 byte heading int32 [mdeg] @@ -131,6 +121,7 @@ namespace sick_lidar_localization { uint64_t telegram_count; // 8 byte TelegramCount uint64 uint64_t timestamp; // 8 byte Timestamp uint64 [microseconds] + int32_t source_id; // 4 byte source id int64_t encoder_value; // 8 byte EncoderValue int64 in tics }; @@ -141,9 +132,24 @@ namespace sick_lidar_localization { uint64_t telegram_count; // 8 byte TelegramCount uint64 uint64_t timestamp; // 8 byte Timestamp uint64 [microseconds] + int32_t source_id; // 4 byte source id int64_t code; // 8 byte Code int32 }; + /* + ** @brief Container for the code measurement payload message type 7 version 1 (variable length payload, UDP input message) + */ + struct CodeMeasurementPayload0701 + { + uint64_t telegram_count; // 8 byte TelegramCount uint64 + uint64_t timestamp; // 8 byte Timestamp uint64 [microseconds] + int32_t source_id; // 4 byte source id + std::string code; // variable length string => udp message: 2 byte codelength (uint16) + byte string + int32_t x_position; // 4 byte relative pose along the x-axis of the sensor frame [mm] + int32_t y_position; // 4 byte relative pose along the y-axis of the sensor frame [mm] + int32_t heading; // 4 byte relative orientation of the code in the sensor frame [mdeg] + }; + /* ** @brief Container for the code measurement payload message type 3 version 4 (24 byte payload, UDP output message) */ @@ -151,6 +157,7 @@ namespace sick_lidar_localization { uint64_t telegram_count; // 8 byte TelegramCount uint64 uint64_t timestamp; // 8 byte Timestamp uint64 [microseconds] + int32_t source_id; // 4 byte source id int32_t code; // 4 byte Code int32 int32_t distance; // 4 byte Distance int32 [mm] uint32_t sync_timestamp_sec; // seconds part of synchronized timestamp in system time calculated by Software-PLL @@ -165,6 +172,7 @@ namespace sick_lidar_localization { uint64_t telegram_count; // 8 byte TelegramCount uint64 uint64_t timestamp; // 8 byte Timestamp uint64 [microseconds] + int32_t source_id; // 4 byte source id uint8_t num_lanes; // 1 byte NumOfLanes uint8 std::vector lanes; // Lanes: num_lanes * 2 byte, each lane encoded by int16 uint32_t sync_timestamp_sec; // seconds part of synchronized timestamp in system time calculated by Software-PLL @@ -179,6 +187,7 @@ namespace sick_lidar_localization { uint64_t telegram_count; // 8 byte TelegramCount uint64 uint64_t timestamp; // 8 byte Timestamp uint64 [microseconds] + int32_t source_id; // 4 byte source id int16_t lcp1; // 2 byte lcp1 int16 [mm] int16_t lcp2; // 2 byte lcp2 int16 [mm] int16_t lcp3; // 2 byte lcp3 int16 [mm] @@ -196,6 +205,7 @@ namespace sick_lidar_localization { uint64_t telegram_count; // 8 byte TelegramCount uint64 uint64_t timestamp; // 8 byte Timestamp uint64 [microseconds] + int32_t source_id; // 4 byte source id int64_t x; // 8 byte X int64 [mm] int64_t y; // 8 byte Y int64 [mm] int32_t heading; // 4 byte Heading int32 [mdeg] @@ -294,6 +304,10 @@ namespace sick_lidar_localization ** @brief Sets the synchronized timestamp calculated by software pll */ virtual void setSyncTimestamp(uint32_t sec, uint32_t nsec) = 0; + /* + ** @brief Get/set the source id + */ + virtual int32_t& sourceID(void) = 0; }; /* @@ -347,6 +361,13 @@ namespace sick_lidar_localization m_payload_data.sync_timestamp_nsec = nsec; m_payload_data.sync_timestamp_valid = 1; } + /* + ** @brief Get/set the source id + */ + virtual int32_t& sourceID(void) + { + return m_payload_data.source_id; + } protected: /* @@ -389,7 +410,7 @@ namespace sick_lidar_localization /* ** @brief Encodes the payload of a udp message ** @param[in] message_payload payload of a udp message, can be OdometryPayload0104, OdometryPayload0105, EncoderMeasurementPayload0202, - ** CodeMeasurementPayload0303, LineMeasurementPayload0403 or LineMeasurementPayload0404 + ** CodeMeasurementPayload0303, CodeMeasurementPayload0701, LineMeasurementPayload0403 or LineMeasurementPayload0404 ** @param[in] encode_big_endian encode in big or little endiang ** @param[out] encoded vector of bytes */ @@ -398,7 +419,7 @@ namespace sick_lidar_localization /* ** @brief Encodes a UDP input message ** @param[in] message_payload payload of a udp message, can be OdometryPayload0104, OdometryPayload0105, EncoderMeasurementPayload0202, - ** CodeMeasurementPayload0303, LineMeasurementPayload0403 or LineMeasurementPayload0404 + ** CodeMeasurementPayload0303, CodeMeasurementPayload0701, LineMeasurementPayload0403 or LineMeasurementPayload0404 ** @param[in] encode_big_endian encode in big or little endiang ** @param[out] encoded vector of bytes */ diff --git a/include/sick_lidar_localization/udp_message_publisher.h b/include/sick_lidar_localization/udp_message_publisher.h index bf7ba4a..74f5e55 100644 --- a/include/sick_lidar_localization/udp_message_publisher.h +++ b/include/sick_lidar_localization/udp_message_publisher.h @@ -110,6 +110,7 @@ namespace sick_lidar_localization ros_msg.header.stamp = rosTimeNow(); ros_msg.telegram_count = message.telegram_count; ros_msg.timestamp = message.timestamp; + ros_msg.source_id = message.source_id; ros_msg.x_velocity = message.x_velocity; ros_msg.y_velocity = message.y_velocity; ros_msg.angular_velocity = message.angular_velocity; @@ -127,6 +128,7 @@ namespace sick_lidar_localization ros_msg.header.stamp = rosTimeNow(); ros_msg.telegram_count = message.telegram_count; ros_msg.timestamp = message.timestamp; + ros_msg.source_id = message.source_id; ros_msg.x_position = message.x_position; ros_msg.y_position = message.y_position; ros_msg.heading = message.heading; @@ -144,6 +146,7 @@ namespace sick_lidar_localization ros_msg.header.stamp = rosTimeNow(); ros_msg.telegram_count = message.telegram_count; ros_msg.timestamp = message.timestamp; + ros_msg.source_id = message.source_id; ros_msg.code = message.code; ros_msg.distance = message.distance; ros_msg.sync_timestamp_sec = message.sync_timestamp_sec; @@ -160,6 +163,7 @@ namespace sick_lidar_localization ros_msg.header.stamp = rosTimeNow(); ros_msg.telegram_count = message.telegram_count; ros_msg.timestamp = message.timestamp; + ros_msg.source_id = message.source_id; ros_msg.num_lanes = message.num_lanes; ros_msg.lanes = message.lanes; ros_msg.sync_timestamp_sec = message.sync_timestamp_sec; @@ -176,6 +180,7 @@ namespace sick_lidar_localization ros_msg.header.stamp = rosTimeNow(); ros_msg.telegram_count = message.telegram_count; ros_msg.timestamp = message.timestamp; + ros_msg.source_id = message.source_id; ros_msg.lcp1 = message.lcp1; ros_msg.lcp2 = message.lcp2; ros_msg.lcp3 = message.lcp3; @@ -194,6 +199,7 @@ namespace sick_lidar_localization ros_msg.header.stamp = rosTimeNow(); ros_msg.telegram_count = message.telegram_count; ros_msg.timestamp = message.timestamp; + ros_msg.source_id = message.source_id; ros_msg.x = message.x; ros_msg.y = message.y; ros_msg.heading = message.heading; diff --git a/include/sick_lidar_localization/udp_receiver_thread.h b/include/sick_lidar_localization/udp_receiver_thread.h index 391b0a9..c1ad762 100644 --- a/include/sick_lidar_localization/udp_receiver_thread.h +++ b/include/sick_lidar_localization/udp_receiver_thread.h @@ -73,11 +73,11 @@ namespace sick_lidar_localization /* ** @brief Default constructor ** @param[in] services time sync services - ** @param[in] udp_ip_sim_output IP address for output UDP messages, or "" for broadcast (INADDR_ANY), default: "", use IP address of your local machine - ** @param[in] udp_port_sim_output UDP port of output messages, default: 5010 - ** @param[in] udp_sim_output_logfile Optional logfile for human readable UDP output messages, default: "" (no outputlogfile) + ** @param[in] udp_ip_lls_output IP address for output UDP messages, or "" for broadcast (INADDR_ANY), default: "", use IP address of your local machine + ** @param[in] udp_port_lls_output UDP port of output messages, default: 5010 + ** @param[in] udp_lls_output_logfile Optional logfile for human readable UDP output messages, default: "" (no outputlogfile) */ - UDPReceiverThread(sick_lidar_localization::SickServices* services = 0, const std::string& udp_ip_sim_output = "", int udp_port_sim_output = 5010, const std::string& udp_sim_output_logfile = ""); + UDPReceiverThread(sick_lidar_localization::SickServices* services = 0, const std::string& udp_ip_lls_output = "", int udp_port_lls_output = 5010, const std::string& udp_lls_output_logfile = ""); /* ** @brief Default destructor, exits running threads @@ -99,7 +99,7 @@ namespace sick_lidar_localization void stop(); /* - ** @brief Register a listener for upd messages. The callback functions of the listener will be called after receiving a new udp message. + ** @brief Register a listener for udp messages. The callback functions of the listener will be called after receiving a new udp message. ** Overwrite the functions defined in sick_lidar_localization::UDPMessage::Listener with customized code to handle udp messages. */ void registerListener(sick_lidar_localization::UDPMessage::Listener* listener); @@ -127,9 +127,9 @@ namespace sick_lidar_localization bool runReceiver(void); sick_lidar_localization::SickServices* m_services; // time sync services - std::string m_udp_ip_sim_output; // IP address for output UDP messages, or "" for broadcast (INADDR_ANY), default: "", use IP address of your local machine - int m_udp_port_sim_output; // UDP port of UDP output messages, default: 5010 - std::string m_udp_sim_output_logfile; // Optional logfile for human readable UDP output messages, default: "" (no outputlogfile) + std::string m_udp_ip_lls_output; // IP address for output UDP messages, or "" for broadcast (INADDR_ANY), default: "", use IP address of your local machine + int m_udp_port_lls_output; // UDP port of UDP output messages, default: 5010 + std::string m_udp_lls_output_logfile; // Optional logfile for human readable UDP output messages, default: "" (no outputlogfile) bool m_run_receiver_thread; // Flag to start and stop m_receiver_thread std::thread* m_receiver_thread; // Background thread to receive udp data, parsing, conversion and publishing std::list m_udp_message_listener; diff --git a/include/sick_lidar_localization/udp_sender.h b/include/sick_lidar_localization/udp_sender.h index 8137bbb..e23ffcd 100644 --- a/include/sick_lidar_localization/udp_sender.h +++ b/include/sick_lidar_localization/udp_sender.h @@ -59,19 +59,19 @@ #include "sick_lidar_localization/udp_message_parser.h" #if __ROS_VERSION == 1 -#include "sick_lidar_localization/OdometryMessage0101.h" #include "sick_lidar_localization/OdometryMessage0104.h" #include "sick_lidar_localization/OdometryMessage0105.h" #include "sick_lidar_localization/EncoderMeasurementMessage0202.h" #include "sick_lidar_localization/CodeMeasurementMessage0303.h" +#include "sick_lidar_localization/CodeMeasurementMessage0701.h" #include "sick_lidar_localization/LineMeasurementMessage0403.h" #include "sick_lidar_localization/LineMeasurementMessage0404.h" #elif __ROS_VERSION == 2 -#include "sick_lidar_localization/msg/odometry_message0101.hpp" #include "sick_lidar_localization/msg/odometry_message0104.hpp" #include "sick_lidar_localization/msg/odometry_message0105.hpp" #include "sick_lidar_localization/msg/encoder_measurement_message0202.hpp" #include "sick_lidar_localization/msg/code_measurement_message0303.hpp" +#include "sick_lidar_localization/msg/code_measurement_message0701.hpp" #include "sick_lidar_localization/msg/line_measurement_message0403.hpp" #include "sick_lidar_localization/msg/line_measurement_message0404.hpp" namespace sick_lidar_localization { using namespace msg; } @@ -84,6 +84,27 @@ namespace sick_lidar_localization */ class UDPSenderImpl; + /* + ** @brief class UDPDefaultInputSourceId provides default source ids for UDP input messages. + ** If the source id of a UDP input message is not set (source_id = 0, e.g. in case of ROS odometry messages), + ** the source id is taken from configuration file (launch file). + */ + class UDPDefaultInputSourceId + { + public: + /** default constructor */ + UDPDefaultInputSourceId(int default_source_id = 1, const std::map>& sourceid_map = std::map>()) + : m_default_source_id(default_source_id), m_msgtype_version_sourceid_map(sourceid_map) {} + + /** returns the default source id from configuration file */ + virtual int getSourceId(int msgtype, int msgversion); + + protected: + + int m_default_source_id; // default source id, if not otherwise set in a message or by configuration + std::map> m_msgtype_version_sourceid_map; // msgtype_version_sourceid_map[msgtype][msgversion] := default source_id for UDP input messages of type and version + }; + /* ** @brief class UDPSender implements a UDP sender for UDP input messages. */ @@ -94,17 +115,18 @@ namespace sick_lidar_localization /* ** @brief Default constructor ** @param[in] nh ros node handle (always 0 for native linus or windows) - ** @param[in] sim_ip_address UDP IP address, or "" for broadcast - ** @param[in] udp_port_sim_input UDP port of UDP input messages, default: 5009 - ** @param[in] udp_sim_input_source_id source_id of UDP input messages, default: 1 + ** @param[in] lls_ip_address UDP IP address, or "" for broadcast + ** @param[in] udp_port_lls_input UDP port of UDP input messages, default: 5009 + ** @param[in] source_id_cfg source_id map of UDP input messages, default source id: 1 ** @param[in] verbose print informational messages if verbose > 0, otherwise silent mode (error messages only) - ** @param[in] ros_odom_to_udp_msg Convert ros odom message to upd: 0 = map velocity to OdometryPayload0101 (Type 1, Version 1, LidarLoc 1), + ** @param[in] ros_odom_to_udp_msg Convert ros odom message to udp: ** 1 = map velocity to OdometryPayload0104 (Type 1, Version 4, LidarLoc 2), ** 2 = map position to OdometryPayload0105 (Type 1, Version 5, LidarLoc 2), ** 3 = map velocity to OdometryPayload0104 and position to OdometryPayload0105 */ - UDPSender(rosNodePtr nh = 0, const std::string& sim_ip_address = "192.168.0.1", int udp_port_sim_input = 5009, int udp_sim_input_source_id = 1, int verbose = 0, - const std::string& odom_topic = "/odom", int ros_odom_to_udp_msg = 3); + UDPSender(rosNodePtr nh = 0, const std::string& lls_ip_address = "192.168.0.1", int udp_port_lls_input = 5009, + const sick_lidar_localization::UDPDefaultInputSourceId& source_id_cfg = UDPDefaultInputSourceId(1), + int verbose = 0, const std::string& odom_topic = "/odom", int ros_odom_to_udp_msg = 3); /* ** @brief Default destructor, exits running threads @@ -114,18 +136,18 @@ namespace sick_lidar_localization /* ** @brief Sends a UDP input message. ** payload can be OdometryPayload0104, OdometryPayload0105, EncoderMeasurementPayload0202, - ** CodeMeasurementPayload0303, LineMeasurementPayload0403 or LineMeasurementPayload0404 + ** CodeMeasurementPayload0303, CodeMeasurementPayload0701, LineMeasurementPayload0403 or LineMeasurementPayload0404 ** @param[in] payload UDP message payload data ** @return true on success or false on error */ - template bool sendUDPPayload(const T& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id) + template bool sendUDPPayload(const T& payload, bool encode_header_big_endian, bool encode_payload_big_endian) { - std::vector message = sick_lidar_localization::UDPMessage::encodeMessage(payload, encode_header_big_endian, encode_payload_big_endian, source_id); + std::vector message = sick_lidar_localization::UDPMessage::encodeMessage(payload, encode_header_big_endian, encode_payload_big_endian, (uint16_t)(payload.source_id & 0xFFFF)); bool ok = sendData(message); if (!ok) - ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::sendUDPPayload(" << m_sim_ip_address << ":" << m_udp_port_sim_input << ", payload=" << sick_lidar_localization::UDPMessage::printPayload(payload) << ", header_big_endian=" << encode_header_big_endian << ", payload_big_endian=" << encode_payload_big_endian << ", source_id=" << source_id << ") failed"); + ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::sendUDPPayload(" << m_lls_ip_address << ":" << m_udp_port_lls_input << ", payload=" << sick_lidar_localization::UDPMessage::printPayload(payload) << ", header_big_endian=" << encode_header_big_endian << ", payload_big_endian=" << encode_payload_big_endian << ", source_id=" << payload.source_id << ") failed"); else if (ok && m_verbose) - ROS_INFO_STREAM("sick_lidar_localization::UDPSender: udp payload " << sick_lidar_localization::UDPMessage::printPayload(payload, false) << " sent to " << m_sim_ip_address << ":" << m_udp_port_sim_input); + ROS_INFO_STREAM("sick_lidar_localization::UDPSender: udp payload " << sick_lidar_localization::UDPMessage::printPayload(payload, false) << " sent to " << m_lls_ip_address << ":" << m_udp_port_lls_input); return ok; } @@ -149,11 +171,11 @@ namespace sick_lidar_localization */ bool sendData(const std::vector& udp_data); - std::string m_sim_ip_address; // UDP IP address, or "" for broadcast - int m_udp_port_sim_input; // UDP port of UDP input messages, default: 5009 - int m_source_id; // source_id of UDP input messages, default: 1 + std::string m_lls_ip_address; // UDP IP address, or "" for broadcast + int m_udp_port_lls_input; // UDP port of UDP input messages, default: 5009 + sick_lidar_localization::UDPDefaultInputSourceId m_source_id_cfg; // source_id map of UDP input messages, default source id: 1 int m_verbose; // Print informational messages if verbose > 0, otherwise silent mode (error messages only) - int m_ros_odom_to_udp_msg; // Convert ros odom message to upd + int m_ros_odom_to_udp_msg; // Convert ros odom message to udp UDPSenderImpl* m_udp_sender_impl; // UDP sender implementation hiding the udp socket details #if __ROS_VERSION > 0 @@ -161,9 +183,6 @@ namespace sick_lidar_localization void messageCbOdomROS(const ros_nav_msgs::Odometry& msg); void messageCbOdomROS2(const std::shared_ptr msg) { messageCbOdomROS(*msg); } - void messageCbOdometryMessage0101(const sick_lidar_localization::OdometryMessage0101 & msg); - void messageCbOdometryMessage0101ROS2(const std::shared_ptr msg) { messageCbOdometryMessage0101(*msg); } - void messageCbOdometryMessage0104(const sick_lidar_localization::OdometryMessage0104 & msg); void messageCbOdometryMessage0104ROS2(const std::shared_ptr msg) { messageCbOdometryMessage0104(*msg); } @@ -176,6 +195,9 @@ namespace sick_lidar_localization void messageCbCodeMeasurementMessage0303(const sick_lidar_localization::CodeMeasurementMessage0303 & msg); void messageCbCodeMeasurementMessage0303ROS2(const std::shared_ptr msg) { messageCbCodeMeasurementMessage0303(*msg); } + void messageCbCodeMeasurementMessage0701(const sick_lidar_localization::CodeMeasurementMessage0701 & msg); + void messageCbCodeMeasurementMessage0701ROS2(const std::shared_ptr msg) { messageCbCodeMeasurementMessage0701(*msg); } + void messageCbLineMeasurementMessage0403(const sick_lidar_localization::LineMeasurementMessage0403 & msg); void messageCbLineMeasurementMessage0403ROS2(const std::shared_ptr msg) { messageCbLineMeasurementMessage0403(*msg); } @@ -184,11 +206,11 @@ namespace sick_lidar_localization /** subscriber for ros messages, converted to udp messages and send to localization server */ rosSubscriber m_subOdomROS; - rosSubscriber m_subOdometryMessage0101; rosSubscriber m_subOdometryMessage0104; rosSubscriber m_subOdometryMessage0105; rosSubscriber m_subEncoderMeasurementMessage0202; rosSubscriber m_subCodeMeasurementMessage0303; + rosSubscriber m_subCodeMeasurementMessage0701; rosSubscriber m_subLineMeasurementMessage0403; rosSubscriber m_subLineMeasurementMessage0404; #endif diff --git a/launch/lls_transform.launch b/launch/lls_transform.launch new file mode 100644 index 0000000..c4c0f2a --- /dev/null +++ b/launch/lls_transform.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + + \ No newline at end of file diff --git a/launch/pointcloud_converter.launch b/launch/pointcloud_converter.launch deleted file mode 100644 index 500b156..0000000 --- a/launch/pointcloud_converter.launch +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - - \ No newline at end of file diff --git a/launch/sick_lidar_localization.launch b/launch/sick_lidar_localization.launch index 0cc3546..f81cd59 100644 --- a/launch/sick_lidar_localization.launch +++ b/launch/sick_lidar_localization.launch @@ -2,35 +2,44 @@ - + - - - - - - + + + + + + - - - - + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + diff --git a/msg/CodeMeasurementMessage0303.msg b/msg/CodeMeasurementMessage0303.msg index 2f25ebb..fb702e7 100644 --- a/msg/CodeMeasurementMessage0303.msg +++ b/msg/CodeMeasurementMessage0303.msg @@ -2,4 +2,5 @@ std_msgs/Header header uint64 telegram_count # 8 byte TelegramCount uint64 uint64 timestamp # 8 byte Timestamp uint64 [microseconds] +int32 source_id # 4 byte source id int64 code # 8 byte Code int32 diff --git a/msg/CodeMeasurementMessage0304.msg b/msg/CodeMeasurementMessage0304.msg index 70fb92c..ef2d19f 100644 --- a/msg/CodeMeasurementMessage0304.msg +++ b/msg/CodeMeasurementMessage0304.msg @@ -2,6 +2,7 @@ std_msgs/Header header uint64 telegram_count # 8 byte TelegramCount uint64 uint64 timestamp # 8 byte Timestamp uint64 [microseconds] +int32 source_id # 4 byte source id int32 code # 4 byte Code int32 int32 distance # 4 byte Distance int32 [mm] diff --git a/msg/CodeMeasurementMessage0701.msg b/msg/CodeMeasurementMessage0701.msg new file mode 100644 index 0000000..b20f7e1 --- /dev/null +++ b/msg/CodeMeasurementMessage0701.msg @@ -0,0 +1,9 @@ +# Code measurement message type 7 version 1 (localization controller input message for 2D codes) +std_msgs/Header header +uint64 telegram_count # 8 byte TelegramCount uint64 +uint64 timestamp # 8 byte Timestamp uint64 [microseconds] +int32 source_id # 4 byte source id +string code # variable length string # udp message: 2 byte codelength (uint16) + byte string +int32 x_position # 4 byte relative pose along the x-axis of the sensor frame [mm] +int32 y_position # 4 byte relative pose along the y-axis of the sensor frame [mm] +int32 heading # 4 byte relative orientation of the code in the sensor frame [mdeg] diff --git a/msg/EncoderMeasurementMessage0202.msg b/msg/EncoderMeasurementMessage0202.msg index 8f025dc..48a84fc 100644 --- a/msg/EncoderMeasurementMessage0202.msg +++ b/msg/EncoderMeasurementMessage0202.msg @@ -2,4 +2,5 @@ std_msgs/Header header uint64 telegram_count # 8 byte TelegramCount uint64 uint64 timestamp # 8 byte Timestamp uint64 [microseconds] +int32 source_id # 4 byte source id int64 encoder_value # 8 byte EncoderValue int64 in tics diff --git a/msg/LineMeasurementMessage0403.msg b/msg/LineMeasurementMessage0403.msg index 59b8c3c..472220b 100644 --- a/msg/LineMeasurementMessage0403.msg +++ b/msg/LineMeasurementMessage0403.msg @@ -2,6 +2,7 @@ std_msgs/Header header uint64 telegram_count # 8 byte TelegramCount uint64 uint64 timestamp # 8 byte Timestamp uint64 [microseconds] +int32 source_id # 4 byte source id uint8 num_lanes # 1 byte NumOfLanes uint8 int16[] lanes # Lanes: num_lanes * 2 byte, each lane encoded by int16 diff --git a/msg/LineMeasurementMessage0404.msg b/msg/LineMeasurementMessage0404.msg index bfb6d54..f06c6dc 100644 --- a/msg/LineMeasurementMessage0404.msg +++ b/msg/LineMeasurementMessage0404.msg @@ -2,6 +2,7 @@ std_msgs/Header header uint64 telegram_count # 8 byte TelegramCount uint64 uint64 timestamp # 8 byte Timestamp uint64 [microseconds] +int32 source_id # 4 byte source id int16 lcp1 # 2 byte lcp1 int16 [mm] int16 lcp2 # 2 byte lcp2 int16 [mm] int16 lcp3 # 2 byte lcp3 int16 [mm] diff --git a/msg/LocalizationControllerResultMessage0502.msg b/msg/LocalizationControllerResultMessage0502.msg index cb408da..6d2eae8 100644 --- a/msg/LocalizationControllerResultMessage0502.msg +++ b/msg/LocalizationControllerResultMessage0502.msg @@ -2,6 +2,7 @@ std_msgs/Header header uint64 telegram_count # 8 byte TelegramCount uint64 uint64 timestamp # 8 byte Timestamp uint64 [microseconds] +int32 source_id # 4 byte source id int64 x # 8 byte X int64 [mm] int64 y # 8 byte Y int64 [mm] int32 heading # 4 byte Heading int32 [mdeg] diff --git a/msg/OdometryMessage0101.msg b/msg/OdometryMessage0101.msg deleted file mode 100644 index 23a660e..0000000 --- a/msg/OdometryMessage0101.msg +++ /dev/null @@ -1,7 +0,0 @@ -# Odometry message type 1 version 1 (localization controller input message) -std_msgs/Header header -uint64 telegram_count # 8 byte TelegramCount uint64 -uint64 timestamp # 8 byte Timestamp uint64 [milliseconds] -int32 x_velocity # 4 byte X - velocity int16 [mm/s] -int32 y_velocity # 4 byte Y - velocity int16 [mm/s] -int64 angular_velocity # 8 byte angular velocity int32 [mdeg/s] diff --git a/msg/OdometryMessage0104.msg b/msg/OdometryMessage0104.msg index 04ddff9..45210fb 100644 --- a/msg/OdometryMessage0104.msg +++ b/msg/OdometryMessage0104.msg @@ -2,6 +2,7 @@ std_msgs/Header header uint64 telegram_count # 8 byte TelegramCount uint64 uint64 timestamp # 8 byte Timestamp uint64 [microseconds] +int32 source_id # 4 byte source id int16 x_velocity # 2 byte X - velocity int16 [mm/s] int16 y_velocity # 2 byte Y - velocity int16 [mm/s] int32 angular_velocity # 4 byte angular velocity int32 [mdeg/s] diff --git a/msg/OdometryMessage0105.msg b/msg/OdometryMessage0105.msg index f7042a3..7d4f4b5 100644 --- a/msg/OdometryMessage0105.msg +++ b/msg/OdometryMessage0105.msg @@ -2,6 +2,7 @@ std_msgs/Header header uint64 telegram_count # 8 byte TelegramCount uint64 uint64 timestamp # 8 byte Timestamp uint64 [microseconds] +int32 source_id # 4 byte source id int64 x_position # 8 byte X-position int64 [mm] int64 y_position # 8 byte Y-position int64 [mm] int64 heading # 8 byte heading int32 [mdeg] diff --git a/src/gen_service_call.cpp b/src/gen_service_call.cpp index cd77966..3a657e0 100644 --- a/src/gen_service_call.cpp +++ b/src/gen_service_call.cpp @@ -76,7 +76,7 @@ static void printUsage(void) { std::cout << "gen_service_call sends requests to the localization server via http REST API and returns its response." << std::endl; std::cout << "Usage: gen_service_call [--hostname=] [--verbose=<0|1>] [--output=] [--append=] [-d=<0|1|2>" << std::endl; - std::cout << " : name of command (service request), f.e. LocIsSystemReady or LocStartLocalizing" << std::endl; + std::cout << " : name of command (service request), f.e. LocIsSystemReady or LocStart" << std::endl; std::cout << " : GET or POST" << std::endl; std::cout << " : parameter as json string, f.e. {}" << std::endl; std::cout << " --hostname=: ip address of the localization server, default: 192.168.0.1" << std::endl; @@ -225,14 +225,14 @@ int main(int argc, char** argv) response = sick_curl.send("LocSaveRingBufferRecording", "POST", "{\"data\":{\"reason\":\"YYYY-MM-DD_HH-MM-SS pose quality low\"}}"); // LocSaveRingBufferRecordingSrv.srv // "sMN LocSaveRingBufferRecording" // response: { "header": std_header_ok, "data": { "success": True } } response = sick_curl.send("LocSetKinematicVehicleModelActive", "POST", "{\"data\":{\"active\":true}}"); // LocSetKinematicVehicleModelActiveSrv.srv // "sMN LocSetKinematicVehicleModelActive" // response: { "header": std_header_ok, "data": { "success": True } } response = sick_curl.send("LocSetLinesForSupportActive", "POST", "{\"data\":{\"active\":true}}"); // LocSetLinesForSupportActiveSrv.srv // "sMN LocSetLinesForSupportActive" // response: { "header": std_header_ok, "data": { "success": True } } - response = sick_curl.send("LocSetMap", "POST", "{\"data\":{\"mappath\":\"test.vmap\"}}"); // LocSetMapSrv.srv // "sMN LocSetMap" // response: { "header": std_header_ok, "data": { "success": True } } + response = sick_curl.send("LocSetMap", "POST", "{\"data\":{\"mappath\":\"test.vmap\"}}"); // LocSetMapSrv.srv // "sMN LocSetMap" // response: { "header": std_header_ok, "data": { "success": True } } response = sick_curl.send("LocSetMappingActive", "POST", "{\"data\":{\"active\":true}}"); // LocSetMappingActiveSrv.srv // "sMN LocSetMappingActive" // response: { "header": std_header_ok, "data": { "success": True } } response = sick_curl.send("LocSetOdometryActive", "POST", "{\"data\":{\"active\":true}}"); // LocSetOdometryActiveSrv.srv // "sMN LocSetOdometryActive" // response: { "header": std_header_ok, "data": { "success": True } } response = sick_curl.send("LocSetRecordingActive", "POST", "{\"data\":{\"active\":true}}"); // LocSetRecordingActiveSrv.srv // "sMN LocSetRecordingActive" // response: { "header": std_header_ok, "data": { "success": True } } response = sick_curl.send("LocSetRingBufferRecordingActive", "POST", "{\"data\":{\"active\":true}}"); // LocSetRingBufferRecordingActiveSrv.srv // "sMN LocSetRingBufferRecordingActive" // response: { "header": std_header_ok, "data": { "success": True } } - response = sick_curl.send("LocStartLocalizing", "POST", "{}"); // LocStartLocalizingSrv.srv // "sMN LocStartLocalizing" // json response: { "header": { "status": 0, "message": "Ok" }, "data": { "success": True } } + response = sick_curl.send("LocStart", "POST", "{}"); // LocStartSrv.srv // "sMN LocStart" // json response: { "header": { "status": 0, "message": "Ok" }, "data": { "success": True } } response = sick_curl.send("LocStop", "POST", "{}"); // LocStopSrv.srv // "sMN LocStop" // json response: { "header": { "status": 0, "message": "Ok" }, "data": { "success": True } } - response = sick_curl.send("LocSwitchMap", "POST", "{\"data\":{\"submapname\":\"test.vmap\"}}"); // LocSwitchMapSrv.srv // "sMN LocSwitchMap" // response: { "header": std_header_ok, "data": { "success": True } } + response = sick_curl.send("LocSwitchMap", "POST", "{\"data\":{\"submapname\":\"test.vmap\"}}"); // LocSwitchMapSrv.srv // "sMN LocSwitchMap" // response: { "header": std_header_ok, "data": { "success": True } } */ return EXIT_SUCCESS; diff --git a/src/pointcloud_converter.cpp b/src/lls_transform.cpp similarity index 75% rename from src/pointcloud_converter.cpp rename to src/lls_transform.cpp index efd417e..b2f74a3 100644 --- a/src/pointcloud_converter.cpp +++ b/src/lls_transform.cpp @@ -1,5 +1,5 @@ /* - * @brief pointcloud_converter subscribes to sim_loc_driver messages (type sick_lidar_localization::LocResultPortTelegramMsg), + * @brief lls_transform subscribes to lls_loc_driver messages (type sick_lidar_localization::LocResultPortTelegramMsg), * converts them to PointCloud2 and publishes PointCloud2 messages on topic "/cloud". * * It also serves as an usage example for sick_lidar_localization and shows how to subscribe and use the @@ -57,14 +57,16 @@ * */ #include "sick_lidar_localization/sick_common.h" - -#include "sick_lidar_localization/pointcloud_converter.h" +#include "sick_lidar_localization/lls_transform.h" +#if __ROS_VERSION == 2 +#include "launchparser/launchparser.h" +#endif int main(int argc, char** argv) { // Ros configuration and initialization #if __ROS_VERSION == 1 - ros::init(argc, argv, "pointcloud_converter", ros::init_options::NoSigintHandler); + ros::init(argc, argv, "lls_transform", ros::init_options::NoSigintHandler); ros::NodeHandle node("~"); rosNodePtr nh = &node; #elif __ROS_VERSION == 2 @@ -72,44 +74,48 @@ int main(int argc, char** argv) rclcpp::NodeOptions node_options; node_options.allow_undeclared_parameters(true); //node_options.automatically_declare_initial_parameters(true); - rosNodePtr nh = rclcpp::Node::make_shared("pointcloud_converter", "", node_options); - //parseLaunchfileSetParameter(nh, argc, argv); + rosNodePtr nh = rclcpp::Node::make_shared("lls_transform", "", node_options); + if (!LaunchParser::parseLaunchfileSetParameter(nh, argc, argv)) + { + ROS_ERROR_STREAM("## ERROR sick_lidar_localization: parseLaunchfileSetParameter() failed, aborting... "); + return false; + } #else #error __ROS_VERSION not defined, define __ROS_VERSION 1 or 2 #endif - ROS_INFO_STREAM("pointcloud_converter started."); + ROS_INFO_STREAM("lls_transform started."); std::string result_telegrams_topic = "/localizationcontroller/out/localizationcontroller_result_message_0502"; // default topic to publish result port telegram messages (type LocResultPortTelegramMsg) //rosGetParam(nh, "result_telegrams_topic", result_telegrams_topic); - // Init verifier to compare and check sim_loc_driver and sim_loc_test_server messages - sick_lidar_localization::PointCloudConverter pointcloud_converter(nh); + // Init verifier to compare and check lls_loc_driver and lls_loc_test_server messages + sick_lidar_localization::LLSTransformer lls_transform(nh); - // Subscribe to sim_loc_driver messages + // Subscribe to lls_loc_driver messages #if __ROS_VERSION == 1 rosSubscriber result_telegram_subscriber = rosSubscribe(nh, - result_telegrams_topic, &sick_lidar_localization::PointCloudConverter::messageCbResultPortTelegrams, &pointcloud_converter); + result_telegrams_topic, &sick_lidar_localization::LLSTransformer::messageCbResultPortTelegrams, &lls_transform); #elif __ROS_VERSION == 2 # ifdef _MSC_VER - auto subscriber = nh->create_subscription(result_telegrams_topic, 10, std::bind(&sick_lidar_localization::PointCloudConverter::messageCbResultPortTelegramsROS2, &pointcloud_converter, std::placeholders::_1)); + auto subscriber = nh->create_subscription(result_telegrams_topic, 10, std::bind(&sick_lidar_localization::LLSTransformer::messageCbResultPortTelegramsROS2, &lls_transform, std::placeholders::_1)); rosSubscriber result_telegram_subscriber = rosSubscriber(subscriber); # else rosSubscriber result_telegram_subscriber = rosSubscribe(nh, - result_telegrams_topic, &sick_lidar_localization::PointCloudConverter::messageCbResultPortTelegramsROS2, &pointcloud_converter); + result_telegrams_topic, &sick_lidar_localization::LLSTransformer::messageCbResultPortTelegramsROS2, &lls_transform); #endif #endif // Start pointcloud converter thread - pointcloud_converter.start(); + lls_transform.start(); // Run ros event loop rosSpin(nh); - std::cout << "pointcloud_converter finished." << std::endl; - ROS_INFO_STREAM("pointcloud_converter finished."); - pointcloud_converter.stop(); - std::cout << "pointcloud_converter exits." << std::endl; - ROS_INFO_STREAM("pointcloud_converter exits."); + std::cout << "lls_transform finished." << std::endl; + ROS_INFO_STREAM("lls_transform finished."); + lls_transform.stop(); + std::cout << "lls_transform exits." << std::endl; + ROS_INFO_STREAM("lls_transform exits."); return 0; } diff --git a/src/lls_transform_thread.cpp b/src/lls_transform_thread.cpp new file mode 100644 index 0000000..c2f9dc0 --- /dev/null +++ b/src/lls_transform_thread.cpp @@ -0,0 +1,354 @@ +/* + * @brief lls_loc_pointcloud_converts lls_loc_driver messages (type sick_lidar_localization::LocResultPortTelegramMsg), + * to PointCloud2 messages and publishes PointCloud2 messages on topic "/cloud". + * + * The vehicle poses (PoseX, PoseY, PoseYaw of result port telegrams) are transformed and published + * by tf-messages with configurable parent and child frame id. + * + * It also serves as an usage example for sick_lidar_localization and shows how to use sick_lidar_localization + * in a custumized application. + * + * Copyright (C) 2019 Ing.-Buero Dr. Michael Lehning, Hildesheim + * Copyright (C) 2019 SICK AG, Waldkirch + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of SICK AG nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission + * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Authors: + * Michael Lehning + * + * Copyright 2019 SICK AG + * Copyright 2019 Ing.-Buero Dr. Michael Lehning + * + */ +#include + +#include "sick_lidar_localization/sick_common.h" +#include "sick_lidar_localization/lls_transform.h" + +/*! + * Constructor + * @param[in] nh ros node handle + */ +sick_lidar_localization::LLSTransformer::LLSTransformer(rosNodePtr nh) +: m_nh(nh), m_converter_thread_running(false), m_converter_thread(0) +{ + if(nh) + { + m_tf_parent_frame_id = "map"; + m_tf_child_frame_id = "lls"; + rosGetParam(nh, "tf_parent_frame_id", m_tf_parent_frame_id); + rosGetParam(nh, "tf_child_frame_id", m_tf_child_frame_id); + // m_marker_frame_id = "map"; + // std::string marker_topic = "lls/marker"; + // rosGetParam(nh, "marker_topic", marker_topic); + // rosGetParam(nh, "marker_frame_id", m_marker_frame_id); + // m_marker_arrow_length = 1.0; + // m_marker_arrow_width = 0.1; + // m_marker_arrow_height = 0.1; + // m_marker_color_r = 1.0; + // m_marker_color_g = 1.0; + // m_marker_color_b = 1.0; + // m_marker_color_a = 0.5; + // rosGetParam(nh, "marker_arrow_length", m_marker_arrow_length); + // rosGetParam(nh, "marker_arrow_width", m_marker_arrow_width); + // rosGetParam(nh, "marker_arrow_height", m_marker_arrow_height); + // rosGetParam(nh, "marker_color_r", m_marker_color_r); + // rosGetParam(nh, "marker_color_g", m_marker_color_g); + // rosGetParam(nh, "marker_color_b", m_marker_color_b); + // rosGetParam(nh, "marker_color_a", m_marker_color_a); + // m_marker_publisher = rosAdvertise(nh, marker_topic); + // m_point_cloud_publisher = rosAdvertise(nh, "/map"); + } +} + +/*! + * Destructor + */ +sick_lidar_localization::LLSTransformer::~LLSTransformer() +{ + stop(); +} + +/*! + * Starts the converter thread, converts telegrams and publishes PointCloud2 messages. + * @return true on success, false on failure. + */ +bool sick_lidar_localization::LLSTransformer::start(void) +{ + m_converter_thread_running = true; + m_converter_thread = new std::thread(&sick_lidar_localization::LLSTransformer::runLLSTransformerThreadCb, this); + return true; +} + +/*! + * Stops the converter thread. + * @return true on success, false on failure. + */ +bool sick_lidar_localization::LLSTransformer::stop(void) +{ + m_converter_thread_running = false; + if(m_converter_thread) + { + sick_lidar_localization::LocalizationControllerResultMessage0502 empty_msg; + m_result_port_telegram_fifo.push(empty_msg); // push empty telegram to interrupt converter thread waiting for notification + m_converter_thread->join(); + delete(m_converter_thread); + m_converter_thread = 0; + } + return true; +} + +/*! + * Callback for result telegram messages (LocResultPortTelegramMsg) from lls_loc_driver. + * The received message is buffered by fifo m_result_port_telegram_fifo. + * Message handling and evaluation is done in the converter thread. + * @param[in] msg result telegram message (LocResultPortTelegramMsg) + */ +void sick_lidar_localization::LLSTransformer::messageCbResultPortTelegrams(const sick_lidar_localization::LocalizationControllerResultMessage0502 & msg) +{ + m_result_port_telegram_fifo.push(msg); +} + +/*! + * Creates and returns a list of 4 points from position and orientaion of a sensor: + * the center point (PoseX,PoseY) and 3 corner points of a triangle showing the orientation (PoseYaw) + * Note: This is just an example to show the position and orientation of a sensor by a list of points. + * @param[in] posx x-position of sensor in meter + * @param[in] posy y-position of sensor in meter + * @param[in] yaw orientation (yaw) of sensor in radians + * @param[in] triangle_height heigt of the virtual triangle in meter + * @return list of 3D points + */ +// std::vector sick_lidar_localization::LLSTransformer::poseToDemoPoints(double posx, double posy, double yaw, double triangle_height) +// { +// // Center point at (posx, posy) +// std::vector points; +// ros_geometry_msgs::Point centerpoint; +// centerpoint.x = posx; +// centerpoint.y = posy; +// centerpoint.z = 0; +// points.push_back(centerpoint); +// ros_geometry_msgs::Point cornerpoint = centerpoint; +// // Add triangle corner points at (posx + dx, posy + dy) +// cornerpoint.x = centerpoint.x + triangle_height * std::cos(yaw); +// cornerpoint.y = centerpoint.y + triangle_height * std::sin(yaw); +// points.push_back(cornerpoint); +// cornerpoint.x = centerpoint.x + 0.5 * triangle_height * std::cos(yaw + M_PI_2); +// cornerpoint.y = centerpoint.y + 0.5 * triangle_height * std::sin(yaw + M_PI_2); +// points.push_back(cornerpoint); +// cornerpoint.x = centerpoint.x + 0.5 * triangle_height * std::cos(yaw - M_PI_2); +// cornerpoint.y = centerpoint.y + 0.5 * triangle_height * std::sin(yaw - M_PI_2); +// points.push_back(cornerpoint); +// return points; +// } + +/*! + * Converts the vehicle position from a result port telegram to PointCloud2 message with 4 points + * (centerpoint plus 3 demo corner points showing a triangle). + * @param[in] msg result telegram message (LocResultPortTelegramMsg) + * @return PointCloud2 message + */ +// ros_sensor_msgs::PointCloud2 sick_lidar_localization::LLSTransformer::convertToPointCloud(const sick_lidar_localization::LocalizationControllerResultMessage0502 & msg) +// { +// ros_sensor_msgs::PointCloud2 pointcloud_msg; +// // Create center point (PoseX,PoseY) and 3 corner points of a triangle showing the orientation (PoseYaw) +// // Note: This is just an example to demonstrate use of sick_lidar_localization and PointCloud2 messages! +// std::vector points = poseToDemoPoints( +// 1.0e-3 * msg.x, // x-position in meter +// 1.0e-3 * msg.y, // y-position in meter +// 1.0e-3 * msg.heading * M_PI / 180.0, // yaw angle in radians +// 0.6); // triangle_height in meter (demo only) +// // set pointcloud header +// pointcloud_msg.header.stamp = msg.header.stamp; // telegram timestamp +// if(msg.sync_timestamp_valid) // software pll initialized: use system time of vehicle pose calculated from lidar ticks by software pll +// { +// pointcloud_msg.header.stamp.sec = msg.sync_timestamp_sec; +// pointcloud_msg.header.stamp.NSEC = msg.sync_timestamp_nsec; +// } +// pointcloud_msg.header.frame_id = "map"; +// // pointcloud_msg.header.seq = 0; // no seq field in ROS2 +// // clear cloud data +// pointcloud_msg.height = 0; +// pointcloud_msg.width = 0; +// pointcloud_msg.data.clear(); +// // set pointcloud field properties +// int numChannels = 3; // "x", "y", "z" +// std::string channelId[] = { "x", "y", "z" }; +// pointcloud_msg.height = 1; +// pointcloud_msg.width = points.size(); // normally we have 4 points (center point and 3 corner points) +// pointcloud_msg.is_bigendian = false; +// pointcloud_msg.is_dense = true; +// pointcloud_msg.point_step = numChannels * sizeof(float); +// pointcloud_msg.row_step = pointcloud_msg.point_step * pointcloud_msg.width; +// pointcloud_msg.fields.resize(numChannels); +// for (int i = 0; i < numChannels; i++) +// { +// pointcloud_msg.fields[i].name = channelId[i]; +// pointcloud_msg.fields[i].offset = i * sizeof(float); +// pointcloud_msg.fields[i].count = 1; +// pointcloud_msg.fields[i].datatype = ros_sensor_msgs::PointField::FLOAT32; +// } +// // set pointcloud data values +// pointcloud_msg.data.resize(pointcloud_msg.row_step * pointcloud_msg.height); +// float* pfdata = reinterpret_cast(&pointcloud_msg.data[0]); +// for(size_t data_cnt = 0, point_cnt = 0; point_cnt < points.size(); point_cnt++) +// { +// pfdata[data_cnt++] = static_cast(points[point_cnt].x); +// pfdata[data_cnt++] = static_cast(points[point_cnt].y); +// pfdata[data_cnt++] = static_cast(points[point_cnt].z); +// } +// return pointcloud_msg; +// } + +/*! + * Converts the vehicle pose from a result port telegram to a marker array. + * @param[in] msg result telegram message (LocResultPortTelegramMsg) + * @return marker array + */ +// ros_visualization_msgs::MarkerArray sick_lidar_localization::LLSTransformer::convertToMarker(const sick_lidar_localization::LocalizationControllerResultMessage0502 & msg) +// { +// double posx = 1.0e-3 * msg.x; // x-position in meter +// double posy = 1.0e-3 * msg.y; // y-position in meter +// double yaw = 1.0e-3 * msg.heading * M_PI / 180.0; // yaw angle in radians +// ros_visualization_msgs::Marker marker_msg; +// marker_msg.header.stamp = msg.header.stamp; // telegram timestamp +// if(msg.sync_timestamp_valid) // software pll initialized: use system time of vehicle pose calculated from lidar ticks by software pll +// { +// marker_msg.header.stamp.sec = msg.sync_timestamp_sec; +// marker_msg.header.stamp.NSEC = msg.sync_timestamp_nsec; +// } +// marker_msg.header.frame_id = m_marker_frame_id; +// marker_msg.ns = "lls"; +// marker_msg.id = 1; +// marker_msg.type = ros_visualization_msgs::Marker::ARROW; +// marker_msg.scale.x = m_marker_arrow_length; // arrow length +// marker_msg.scale.y = m_marker_arrow_width; // arrow width +// marker_msg.scale.z = m_marker_arrow_height; // arrow height +// marker_msg.pose.position.x = posx; +// marker_msg.pose.position.y = posy; +// marker_msg.pose.position.z = 0.0; +// tf2::Quaternion q; +// q.setRPY(0, 0, yaw); +// marker_msg.pose.orientation.x = q.x(); +// marker_msg.pose.orientation.y = q.y(); +// marker_msg.pose.orientation.z = q.z(); +// marker_msg.pose.orientation.w = q.w(); +// marker_msg.action = ros_visualization_msgs::Marker::ADD; // note: ADD == MODIFY +// marker_msg.color.r = m_marker_color_r; +// marker_msg.color.g = m_marker_color_g; +// marker_msg.color.b = m_marker_color_b; +// marker_msg.color.a = m_marker_color_a; +// marker_msg.lifetime = rosDurationFromSec(0); // lifetime 0 indicates forever +// ros_visualization_msgs::MarkerArray marker_array; +// marker_array.markers.push_back(marker_msg); +// return marker_array; +// } + +/*! + * Converts the vehicle pose from a result port telegram to a tf transform. + * @param[in] msg result telegram message (LocResultPortTelegramMsg) + * @return tf transform + */ +ros_geometry_msgs::TransformStamped sick_lidar_localization::LLSTransformer::convertToTransform(const sick_lidar_localization::LocalizationControllerResultMessage0502 & msg) +{ + double posx = 1.0e-3 * msg.x; // x-position in meter + double posy = 1.0e-3 * msg.y; // y-position in meter + double yaw = 1.0e-3 * msg.heading * M_PI / 180.0; // yaw angle in radians + ros_geometry_msgs::TransformStamped vehicle_transform; + vehicle_transform.header.stamp = msg.header.stamp; // telegram timestamp + if(msg.sync_timestamp_valid) // software pll initialized: use system time of vehicle pose calculated from lidar ticks by software pll + { + vehicle_transform.header.stamp.sec = msg.sync_timestamp_sec; + vehicle_transform.header.stamp.NSEC = msg.sync_timestamp_nsec; + } + vehicle_transform.header.frame_id = m_tf_parent_frame_id; + vehicle_transform.child_frame_id = m_tf_child_frame_id; + vehicle_transform.transform.translation.x = posx; + vehicle_transform.transform.translation.y = posy; + vehicle_transform.transform.translation.z = 0.0; + tf2::Quaternion q; + q.setRPY(0, 0, yaw); + vehicle_transform.transform.rotation.x = q.x(); + vehicle_transform.transform.rotation.y = q.y(); + vehicle_transform.transform.rotation.z = q.z(); + vehicle_transform.transform.rotation.w = q.w(); + return vehicle_transform; +} + +/*! + * Thread callback, pops received telegrams from the fifo buffer m_result_port_telegram_fifo, + * converts the telegrams from type LocResultPortTelegramMsg to PointCloud2 and publishes + * PointCloud2 messages. The vehicle pose is converted to a tf transform and broadcasted. + */ +void sick_lidar_localization::LLSTransformer::runLLSTransformerThreadCb(void) +{ + ROS_INFO_STREAM("LLSTransformer: converter thread for lls_loc_driver messages started"); +#if defined __ROS_VERSION && __ROS_VERSION == 1 + tf2_ros::TransformBroadcaster tf_broadcaster; +#elif defined __ROS_VERSION && __ROS_VERSION == 2 + tf2_ros::TransformBroadcaster tf_broadcaster(m_nh); +#endif + + while(rosOk() && m_converter_thread_running) + { + // Wait for next telegram + while(rosOk() && m_converter_thread_running && m_result_port_telegram_fifo.empty()) + { + rosSleep(0.0001); + m_result_port_telegram_fifo.waitForElement(); + } + if(rosOk() && m_converter_thread_running && !m_result_port_telegram_fifo.empty()) + { + sick_lidar_localization::LocalizationControllerResultMessage0502 telegram = m_result_port_telegram_fifo.pop(); + // Convert vehicle position from result telegram to PointCloud2 + // ros_sensor_msgs::PointCloud2 pointcloud_msg = convertToPointCloud(telegram); + // rosPublish(m_point_cloud_publisher, pointcloud_msg); + // Convert vehicle position from result telegram to marker + // ros_visualization_msgs::MarkerArray marker_msg = convertToMarker(telegram); + // rosPublish(m_marker_publisher, marker_msg); + // Convert vehicle pose from result telegram to tf transform + ros_geometry_msgs::TransformStamped tf2_vehicle_transform = convertToTransform(telegram); + tf_broadcaster.sendTransform(tf2_vehicle_transform); + } + } + ROS_INFO_STREAM("LLSTransformer: converter thread for lls_loc_driver messages finished"); +} diff --git a/src/pointcloud_converter_thread.cpp b/src/pointcloud_converter_thread.cpp deleted file mode 100644 index 2170525..0000000 --- a/src/pointcloud_converter_thread.cpp +++ /dev/null @@ -1,292 +0,0 @@ -/* - * @brief sim_loc_pointcloud_converts sim_loc_driver messages (type sick_lidar_localization::LocResultPortTelegramMsg), - * to PointCloud2 messages and publishes PointCloud2 messages on topic "/cloud". - * - * The vehicle poses (PoseX, PoseY, PoseYaw of result port telegrams) are transformed and published - * by tf-messages with configurable parent and child frame id. - * - * It also serves as an usage example for sick_lidar_localization and shows how to use sick_lidar_localization - * in a custumized application. - * - * Copyright (C) 2019 Ing.-Buero Dr. Michael Lehning, Hildesheim - * Copyright (C) 2019 SICK AG, Waldkirch - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of SICK AG nor the names of its - * contributors may be used to endorse or promote products derived from - * this software without specific prior written permission - * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its - * contributors may be used to endorse or promote products derived from - * this software without specific prior written permission - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * Authors: - * Michael Lehning - * - * Copyright 2019 SICK AG - * Copyright 2019 Ing.-Buero Dr. Michael Lehning - * - */ -#include - -#include "sick_lidar_localization/sick_common.h" -#include "sick_lidar_localization/pointcloud_converter.h" - -/*! - * Constructor - * @param[in] nh ros node handle - */ -sick_lidar_localization::PointCloudConverter::PointCloudConverter(rosNodePtr nh) -: m_nh(nh), m_point_cloud_frame_id("sick_lidar_localization"), m_converter_thread_running(false), m_converter_thread(0) -{ - if(nh) - { - std::string point_cloud_topic = "/cloud"; // default topic to publish result port telegram messages (type LocResultPortTelegramMsg) - m_point_cloud_frame_id = "cloud"; - m_tf_parent_frame_id = "cloud"; - m_tf_child_frame_id = "sick_lidar_localization"; - //rosGetParam(nh, "point_cloud_topic", point_cloud_topic); - //rosGetParam(nh, "point_cloud_frame_id", m_point_cloud_frame_id); - //rosGetParam(nh, "tf_parent_frame_id", m_tf_parent_frame_id); - //rosGetParam(nh, "tf_child_frame_id", m_tf_child_frame_id); - m_point_cloud_publisher = rosAdvertise(nh, point_cloud_topic); - } -} - -/*! - * Destructor - */ -sick_lidar_localization::PointCloudConverter::~PointCloudConverter() -{ - stop(); -} - -/*! - * Starts the converter thread, converts telegrams and publishes PointCloud2 messages. - * @return true on success, false on failure. - */ -bool sick_lidar_localization::PointCloudConverter::start(void) -{ - m_converter_thread_running = true; - m_converter_thread = new std::thread(&sick_lidar_localization::PointCloudConverter::runPointCloudConverterThreadCb, this); - return true; -} - -/*! - * Stops the converter thread. - * @return true on success, false on failure. - */ -bool sick_lidar_localization::PointCloudConverter::stop(void) -{ - m_converter_thread_running = false; - if(m_converter_thread) - { - sick_lidar_localization::LocalizationControllerResultMessage0502 empty_msg; - m_result_port_telegram_fifo.push(empty_msg); // push empty telegram to interrupt converter thread waiting for notification - m_converter_thread->join(); - delete(m_converter_thread); - m_converter_thread = 0; - } - return true; -} - -/*! - * Callback for result telegram messages (LocResultPortTelegramMsg) from sim_loc_driver. - * The received message is buffered by fifo m_result_port_telegram_fifo. - * Message handling and evaluation is done in the converter thread. - * @param[in] msg result telegram message (LocResultPortTelegramMsg) - */ -void sick_lidar_localization::PointCloudConverter::messageCbResultPortTelegrams(const sick_lidar_localization::LocalizationControllerResultMessage0502 & msg) -{ - m_result_port_telegram_fifo.push(msg); -} - -/*! - * Creates and returns a list of 4 points from position and orientaion of a sensor: - * the center point (PoseX,PoseY) and 3 corner points of a triangle showing the orientation (PoseYaw) - * Note: This is just an example to show the position and orientation of a sensor by a list of points. - * @param[in] posx x-position of sensor in meter - * @param[in] posy y-position of sensor in meter - * @param[in] yaw orientation (yaw) of sensor in radians - * @param[in] triangle_height heigt of the virtual triangle in meter - * @return list of 3D points - */ -std::vector sick_lidar_localization::PointCloudConverter::poseToDemoPoints(double posx, double posy, double yaw, double triangle_height) -{ - // Center point at (posx, posy) - std::vector points; - ros_geometry_msgs::Point centerpoint; - centerpoint.x = posx; - centerpoint.y = posy; - centerpoint.z = 0; - points.push_back(centerpoint); - ros_geometry_msgs::Point cornerpoint = centerpoint; - // Add triangle corner points at (posx + dx, posy + dy) - cornerpoint.x = centerpoint.x + triangle_height * std::cos(yaw); - cornerpoint.y = centerpoint.y + triangle_height * std::sin(yaw); - points.push_back(cornerpoint); - cornerpoint.x = centerpoint.x + 0.5 * triangle_height * std::cos(yaw + M_PI_2); - cornerpoint.y = centerpoint.y + 0.5 * triangle_height * std::sin(yaw + M_PI_2); - points.push_back(cornerpoint); - cornerpoint.x = centerpoint.x + 0.5 * triangle_height * std::cos(yaw - M_PI_2); - cornerpoint.y = centerpoint.y + 0.5 * triangle_height * std::sin(yaw - M_PI_2); - points.push_back(cornerpoint); - return points; -} - -/*! - * Converts the vehicle position from a result port telegram to PointCloud2 message with 4 points - * (centerpoint plus 3 demo corner points showing a triangle). - * @param[in] msg result telegram message (LocResultPortTelegramMsg) - * @return PointCloud2 message - */ -ros_sensor_msgs::PointCloud2 sick_lidar_localization::PointCloudConverter::convertToPointCloud(const sick_lidar_localization::LocalizationControllerResultMessage0502 & msg) -{ - ros_sensor_msgs::PointCloud2 pointcloud_msg; - // Create center point (PoseX,PoseY) and 3 corner points of a triangle showing the orientation (PoseYaw) - // Note: This is just an example to demonstrate use of sick_lidar_localization and PointCloud2 messages! - std::vector points = poseToDemoPoints( - 1.0e-3 * msg.x, // x-position in meter - 1.0e-3 * msg.y, // y-position in meter - 1.0e-3 * msg.heading * M_PI / 180.0, // yaw angle in radians - 0.6); // triangle_height in meter (demo only) - // set pointcloud header - pointcloud_msg.header.stamp = msg.header.stamp; // telegram timestamp - if(msg.sync_timestamp_valid) // software pll initialized: use system time of vehicle pose calculated from lidar ticks by software pll - { - pointcloud_msg.header.stamp.sec = msg.sync_timestamp_sec; - pointcloud_msg.header.stamp.NSEC = msg.sync_timestamp_nsec; - } - pointcloud_msg.header.frame_id = m_point_cloud_frame_id; - // pointcloud_msg.header.seq = 0; // no seq field in ROS2 - // clear cloud data - pointcloud_msg.height = 0; - pointcloud_msg.width = 0; - pointcloud_msg.data.clear(); - // set pointcloud field properties - int numChannels = 3; // "x", "y", "z" - std::string channelId[] = { "x", "y", "z" }; - pointcloud_msg.height = 1; - pointcloud_msg.width = points.size(); // normally we have 4 points (center point and 3 corner points) - pointcloud_msg.is_bigendian = false; - pointcloud_msg.is_dense = true; - pointcloud_msg.point_step = numChannels * sizeof(float); - pointcloud_msg.row_step = pointcloud_msg.point_step * pointcloud_msg.width; - pointcloud_msg.fields.resize(numChannels); - for (int i = 0; i < numChannels; i++) - { - pointcloud_msg.fields[i].name = channelId[i]; - pointcloud_msg.fields[i].offset = i * sizeof(float); - pointcloud_msg.fields[i].count = 1; - pointcloud_msg.fields[i].datatype = ros_sensor_msgs::PointField::FLOAT32; - } - // set pointcloud data values - pointcloud_msg.data.resize(pointcloud_msg.row_step * pointcloud_msg.height); - float* pfdata = reinterpret_cast(&pointcloud_msg.data[0]); - for(size_t data_cnt = 0, point_cnt = 0; point_cnt < points.size(); point_cnt++) - { - pfdata[data_cnt++] = static_cast(points[point_cnt].x); - pfdata[data_cnt++] = static_cast(points[point_cnt].y); - pfdata[data_cnt++] = static_cast(points[point_cnt].z); - } - return pointcloud_msg; -} - -/*! - * Converts the vehicle pose from a result port telegram to a tf transform. - * @param[in] msg result telegram message (LocResultPortTelegramMsg) - * @return tf transform - */ -ros_geometry_msgs::TransformStamped sick_lidar_localization::PointCloudConverter::convertToTransform(const sick_lidar_localization::LocalizationControllerResultMessage0502 & msg) -{ - double posx = 1.0e-3 * msg.x; // x-position in meter - double posy = 1.0e-3 * msg.y; // y-position in meter - double yaw = 1.0e-3 * msg.heading * M_PI / 180.0; // yaw angle in radians - ros_geometry_msgs::TransformStamped vehicle_transform; - vehicle_transform.header.stamp = msg.header.stamp; // telegram timestamp - if(msg.sync_timestamp_valid) // software pll initialized: use system time of vehicle pose calculated from lidar ticks by software pll - { - vehicle_transform.header.stamp.sec = msg.sync_timestamp_sec; - vehicle_transform.header.stamp.NSEC = msg.sync_timestamp_nsec; - } - vehicle_transform.header.frame_id = m_tf_parent_frame_id; - vehicle_transform.child_frame_id = m_tf_child_frame_id; - vehicle_transform.transform.translation.x = posx; - vehicle_transform.transform.translation.y = posy; - vehicle_transform.transform.translation.z = 0.0; - tf2::Quaternion q; - q.setRPY(0, 0, yaw); - vehicle_transform.transform.rotation.x = q.x(); - vehicle_transform.transform.rotation.y = q.y(); - vehicle_transform.transform.rotation.z = q.z(); - vehicle_transform.transform.rotation.w = q.w(); - return vehicle_transform; -} - -/*! - * Thread callback, pops received telegrams from the fifo buffer m_result_port_telegram_fifo, - * converts the telegrams from type LocResultPortTelegramMsg to PointCloud2 and publishes - * PointCloud2 messages. The vehicle pose is converted to a tf transform and broadcasted. - */ -void sick_lidar_localization::PointCloudConverter::runPointCloudConverterThreadCb(void) -{ - ROS_INFO_STREAM("PointCloudConverter: converter thread for sim_loc_driver messages started"); -#if defined __ROS_VERSION && __ROS_VERSION == 1 - tf2_ros::TransformBroadcaster tf_broadcaster; -#elif defined __ROS_VERSION && __ROS_VERSION == 2 - tf2_ros::TransformBroadcaster tf_broadcaster(m_nh); -#endif - - while(rosOk() && m_converter_thread_running) - { - // Wait for next telegram - while(rosOk() && m_converter_thread_running && m_result_port_telegram_fifo.empty()) - { - rosSleep(0.0001); - m_result_port_telegram_fifo.waitForElement(); - } - if(rosOk() && m_converter_thread_running && !m_result_port_telegram_fifo.empty()) - { - sick_lidar_localization::LocalizationControllerResultMessage0502 telegram = m_result_port_telegram_fifo.pop(); - // Convert vehicle position from result telegram to PointCloud2 - ros_sensor_msgs::PointCloud2 pointcloud_msg = convertToPointCloud(telegram); - rosPublish(m_point_cloud_publisher, pointcloud_msg); - // Convert vehicle pose from result telegram to tf transform - ros_geometry_msgs::TransformStamped tf2_vehicle_transform = convertToTransform(telegram); - tf_broadcaster.sendTransform(tf2_vehicle_transform); - } - } - ROS_INFO_STREAM("PointCloudConverter: converter thread for sim_loc_driver messages finished"); -} diff --git a/src/sick_lidar_localization.cpp b/src/sick_lidar_localization.cpp index 524521b..1d0c4b4 100644 --- a/src/sick_lidar_localization.cpp +++ b/src/sick_lidar_localization.cpp @@ -74,6 +74,15 @@ template static bool getRequiredParam(rosNodePtr nh, const std::str return true; } +template static bool getOptionalParam(rosNodePtr nh, const std::string& param_name, T& param_value, const T& default_value) +{ + bool ret_val = rosGetParam(nh, param_name, param_value); + if (!ret_val) + param_value = default_value; + return ret_val; +} + + /* ** @brief Parses commandline arguments, reads a launchfile and sets parameters for sick_lidar_localization */ @@ -96,12 +105,12 @@ bool sick_lidar_localization::API::getParams(rosNodePtr node, sick_lidar_localiz okay = getRequiredParam(node, "hostname", config.hostname) && okay; okay = getRequiredParam(node, "serverpath", config.serverpath) && okay; okay = getRequiredParam(node, "verbose", config.verbose) && okay; - okay = getRequiredParam(node, "udp_ip_sim_output", config.udp_ip_sim_output) && okay; - okay = getRequiredParam(node, "udp_ip_sim_input", config.udp_ip_sim_input) && okay; - okay = getRequiredParam(node, "udp_port_sim_input", config.udp_port_sim_input) && okay; - okay = getRequiredParam(node, "udp_sim_input_source_id", config.udp_sim_input_source_id) && okay; - okay = getRequiredParam(node, "udp_port_sim_output", config.udp_port_sim_output) && okay; - okay = getRequiredParam(node, "udp_sim_output_logfile", config.udp_sim_output_logfile) && okay; + okay = getRequiredParam(node, "udp_ip_lls_output", config.udp_ip_lls_output) && okay; + okay = getRequiredParam(node, "udp_ip_lls_input", config.udp_ip_lls_input) && okay; + okay = getRequiredParam(node, "udp_port_lls_input", config.udp_port_lls_input) && okay; + okay = getRequiredParam(node, "udp_lls_input_source_id", config.udp_lls_input_source_id) && okay; + okay = getRequiredParam(node, "udp_port_lls_output", config.udp_port_lls_output) && okay; + okay = getRequiredParam(node, "udp_lls_output_logfile", config.udp_lls_output_logfile) && okay; okay = getRequiredParam(node, "software_pll_fifo_length", config.software_pll_fifo_length) && okay; okay = getRequiredParam(node, "odom_topic", config.odom_topic) && okay; okay = getRequiredParam(node, "ros_odom_to_udp_msg", config.ros_odom_to_udp_msg) && okay; @@ -109,6 +118,32 @@ bool sick_lidar_localization::API::getParams(rosNodePtr node, sick_lidar_localiz { ROS_ERROR_STREAM("## ERROR sick_lidar_localization: getRequiredParam failed"); } + getOptionalParam(node, "udp_lls_input_source_id_1_1", config.msgtype_version_sourceid_map[1][1], config.udp_lls_input_source_id); + getOptionalParam(node, "udp_lls_input_source_id_1_4", config.msgtype_version_sourceid_map[1][4], config.udp_lls_input_source_id); + getOptionalParam(node, "udp_lls_input_source_id_1_5", config.msgtype_version_sourceid_map[1][5], config.udp_lls_input_source_id); + getOptionalParam(node, "udp_lls_input_source_id_3_3", config.msgtype_version_sourceid_map[3][3], config.udp_lls_input_source_id); + getOptionalParam(node, "udp_lls_input_source_id_4_3", config.msgtype_version_sourceid_map[4][3], config.udp_lls_input_source_id); + getOptionalParam(node, "udp_lls_input_source_id_4_4", config.msgtype_version_sourceid_map[4][4], config.udp_lls_input_source_id); + getOptionalParam(node, "udp_lls_input_source_id_7_1", config.msgtype_version_sourceid_map[7][1], config.udp_lls_input_source_id); + ROS_INFO_STREAM("sick_lidar_localization config: hostname = " << config.hostname); + ROS_INFO_STREAM("sick_lidar_localization config: serverpath = " << config.serverpath); + ROS_INFO_STREAM("sick_lidar_localization config: verbose = " << config.verbose); + ROS_INFO_STREAM("sick_lidar_localization config: udp_ip_lls_output = " << config.udp_ip_lls_output); + ROS_INFO_STREAM("sick_lidar_localization config: udp_ip_lls_input = " << config.udp_ip_lls_input); + ROS_INFO_STREAM("sick_lidar_localization config: udp_port_lls_input = " << config.udp_port_lls_input); + ROS_INFO_STREAM("sick_lidar_localization config: udp_lls_input_source_id = " << config.udp_lls_input_source_id); + ROS_INFO_STREAM("sick_lidar_localization config: msgtype_version_sourceid_map[1][1] = " << config.msgtype_version_sourceid_map[1][1]); + ROS_INFO_STREAM("sick_lidar_localization config: msgtype_version_sourceid_map[1][4] = " << config.msgtype_version_sourceid_map[1][4]); + ROS_INFO_STREAM("sick_lidar_localization config: msgtype_version_sourceid_map[1][5] = " << config.msgtype_version_sourceid_map[1][5]); + ROS_INFO_STREAM("sick_lidar_localization config: msgtype_version_sourceid_map[3][3] = " << config.msgtype_version_sourceid_map[3][3]); + ROS_INFO_STREAM("sick_lidar_localization config: msgtype_version_sourceid_map[4][3] = " << config.msgtype_version_sourceid_map[4][3]); + ROS_INFO_STREAM("sick_lidar_localization config: msgtype_version_sourceid_map[4][4] = " << config.msgtype_version_sourceid_map[4][4]); + ROS_INFO_STREAM("sick_lidar_localization config: msgtype_version_sourceid_map[7][1] = " << config.msgtype_version_sourceid_map[7][1]); + ROS_INFO_STREAM("sick_lidar_localization config: udp_port_lls_output = " << config.udp_port_lls_output); + ROS_INFO_STREAM("sick_lidar_localization config: udp_lls_output_logfile = " << config.udp_lls_output_logfile); + ROS_INFO_STREAM("sick_lidar_localization config: software_pll_fifo_length = " << config.software_pll_fifo_length); + ROS_INFO_STREAM("sick_lidar_localization config: odom_topic = " << config.odom_topic); + ROS_INFO_STREAM("sick_lidar_localization config: ros_odom_to_udp_msg = " << config.ros_odom_to_udp_msg); return okay; } @@ -148,7 +183,7 @@ bool sick_lidar_localization::API::init(rosNodePtr node, sick_lidar_localization m_services = new sick_lidar_localization::SickServices(node, m_config.hostname, m_config.serverpath, m_config.software_pll_fifo_length, m_config.verbose); // Start UDP receiver thread for UDP output messages - m_udp_receiver_thread = new sick_lidar_localization::UDPReceiverThread(m_services, m_config.udp_ip_sim_output, m_config.udp_port_sim_output, m_config.udp_sim_output_logfile); + m_udp_receiver_thread = new sick_lidar_localization::UDPReceiverThread(m_services, m_config.udp_ip_lls_output, m_config.udp_port_lls_output, m_config.udp_lls_output_logfile); m_udp_receiver_listener = new sick_lidar_localization::UDPMessage::InfoListener(); if (m_config.verbose) m_udp_receiver_thread->registerListener(m_udp_receiver_listener); @@ -166,8 +201,9 @@ bool sick_lidar_localization::API::init(rosNodePtr node, sick_lidar_localization } // Initialize UDP sender for UDP input messages - m_udp_sender = new sick_lidar_localization::UDPSender(node, m_config.udp_ip_sim_input, m_config.udp_port_sim_input, m_config.udp_sim_input_source_id, m_config.verbose, - m_config.odom_topic, m_config.ros_odom_to_udp_msg); + m_udp_sender = new sick_lidar_localization::UDPSender(node, m_config.udp_ip_lls_input, m_config.udp_port_lls_input, + sick_lidar_localization::UDPDefaultInputSourceId(m_config.udp_lls_input_source_id, m_config.msgtype_version_sourceid_map), + m_config.verbose, m_config.odom_topic, m_config.ros_odom_to_udp_msg); return true; } @@ -195,7 +231,7 @@ void sick_lidar_localization::API::close() } /* -** @brief Register a listener for upd messages. The callback functions of the listener will be called after receiving a new udp message. +** @brief Register a listener for udp messages. The callback functions of the listener will be called after receiving a new udp message. ** Overwrite the functions defined in sick_lidar_localization::UDPMessage::Listener with customized code to handle udp messages. */ bool sick_lidar_localization::API::registerListener(sick_lidar_localization::UDPMessage::Listener* listener) @@ -233,16 +269,16 @@ bool sick_lidar_localization::API::unregisterListener(sick_lidar_localization::U /* ** @brief Sends a UDP input message. ** payload can be OdometryPayload0104, OdometryPayload0105, EncoderMeasurementPayload0202, -** CodeMeasurementPayload0303, LineMeasurementPayload0403 or LineMeasurementPayload0404 +** CodeMeasurementPayload0303, odeMeasurementPayload0701, LineMeasurementPayload0403 or LineMeasurementPayload0404 ** @param[in] payload UDP message payload data ** @return true on success or false on error */ -template bool sendUDPPayload(sick_lidar_localization::UDPSender* udp_sender, const T& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id) +template bool sendUDPPayload(sick_lidar_localization::UDPSender* udp_sender, const T& payload, bool encode_header_big_endian, bool encode_payload_big_endian) { if (udp_sender) { - return udp_sender->sendUDPPayload(payload, encode_header_big_endian, encode_payload_big_endian, source_id); + return udp_sender->sendUDPPayload(payload, encode_header_big_endian, encode_payload_big_endian); } else { @@ -254,27 +290,31 @@ template bool sendUDPPayload(sick_lidar_localization::UDPSender* udp /* ** @brief Send udp messages to the localization controller */ -bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::OdometryPayload0104& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id) +bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::OdometryPayload0104& payload, bool encode_header_big_endian, bool encode_payload_big_endian) +{ + return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian); +} +bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::OdometryPayload0105& payload, bool encode_header_big_endian, bool encode_payload_big_endian) { - return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian, source_id); + return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian); } -bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::OdometryPayload0105& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id) +bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::EncoderMeasurementPayload0202& payload, bool encode_header_big_endian, bool encode_payload_big_endian) { - return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian, source_id); + return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian); } -bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::EncoderMeasurementPayload0202& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id) +bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::CodeMeasurementPayload0303& payload, bool encode_header_big_endian, bool encode_payload_big_endian) { - return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian, source_id); + return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian); } -bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::CodeMeasurementPayload0303& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id) +bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::CodeMeasurementPayload0701& payload, bool encode_header_big_endian, bool encode_payload_big_endian) { - return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian, source_id); + return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian); } -bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::LineMeasurementPayload0403& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id) +bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::LineMeasurementPayload0403& payload, bool encode_header_big_endian, bool encode_payload_big_endian) { - return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian, source_id); + return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian); } -bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::LineMeasurementPayload0404& payload, bool encode_header_big_endian, bool encode_payload_big_endian, uint16_t source_id) +bool sick_lidar_localization::API::sendUDPMessage(const sick_lidar_localization::UDPMessage::LineMeasurementPayload0404& payload, bool encode_header_big_endian, bool encode_payload_big_endian) { - return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian, source_id); + return sendUDPPayload(m_udp_sender, payload, encode_header_big_endian, encode_payload_big_endian); } diff --git a/src/sick_lidar_localization_main.cpp b/src/sick_lidar_localization_main.cpp index 696324b..f827925 100644 --- a/src/sick_lidar_localization_main.cpp +++ b/src/sick_lidar_localization_main.cpp @@ -65,41 +65,56 @@ static void sendUDPMessageExamples(sick_lidar_localization::API& lidar_loc_api) sick_lidar_localization::UDPMessage::OdometryPayload0105 odometry0105; sick_lidar_localization::UDPMessage::EncoderMeasurementPayload0202 encoder_measurement0202; sick_lidar_localization::UDPMessage::CodeMeasurementPayload0303 code_measurement0303; + sick_lidar_localization::UDPMessage::CodeMeasurementPayload0701 code_measurement0701; sick_lidar_localization::UDPMessage::LineMeasurementPayload0403 line_measurement0403; sick_lidar_localization::UDPMessage::LineMeasurementPayload0404 line_measurement0404; odometry0104.telegram_count = 1000001; odometry0104.timestamp = 123456789; + odometry0104.source_id = 1; odometry0104.x_velocity = -1234; odometry0104.y_velocity = -1234; odometry0104.angular_velocity = 1234; odometry0105.telegram_count = 1000002; odometry0105.timestamp = 123456780; + odometry0105.source_id = 1; odometry0105.x_position = -1234; odometry0105.y_position = -1234; odometry0105.heading = 1234; encoder_measurement0202.telegram_count = 1000003; encoder_measurement0202.timestamp = 123456781; + encoder_measurement0202.source_id = 1; encoder_measurement0202.encoder_value = 123456789; code_measurement0303.telegram_count = 1000004; code_measurement0303.timestamp = 123456782; + code_measurement0303.source_id = 1; code_measurement0303.code = 1234; + code_measurement0701.telegram_count = 1000004; + code_measurement0701.timestamp = 123456782; + code_measurement0701.source_id = 1; + code_measurement0701.code = "1234"; + code_measurement0701.x_position = -1234; + code_measurement0701.y_position = -1234; + code_measurement0701.heading = 1234; line_measurement0403.telegram_count = 1000005; line_measurement0403.timestamp = 123456783; + line_measurement0403.source_id = 1; line_measurement0403.num_lanes = 1; line_measurement0403.lanes.push_back(1234); line_measurement0404.telegram_count = 1000006; line_measurement0404.timestamp = 123456784; + line_measurement0404.source_id = 1; line_measurement0404.lcp1 = 12; line_measurement0404.lcp2 = 34; line_measurement0404.lcp3 = 56; line_measurement0404.cnt_lpc = 78; line_measurement0404.reserved = 0; - if (!lidar_loc_api.sendUDPMessage(odometry0104, false, false, 1) - || !lidar_loc_api.sendUDPMessage(odometry0105, false, false, 1) - || !lidar_loc_api.sendUDPMessage(encoder_measurement0202, false, false, 1) - || !lidar_loc_api.sendUDPMessage(code_measurement0303, false, false, 1) - || !lidar_loc_api.sendUDPMessage(line_measurement0403, false, false, 1) - || !lidar_loc_api.sendUDPMessage(line_measurement0404, false, false, 1)) + if (!lidar_loc_api.sendUDPMessage(odometry0104, false, false) + || !lidar_loc_api.sendUDPMessage(odometry0105, false, false) + || !lidar_loc_api.sendUDPMessage(encoder_measurement0202, false, false) + || !lidar_loc_api.sendUDPMessage(code_measurement0303, false, false) + || !lidar_loc_api.sendUDPMessage(code_measurement0701, false, false) + || !lidar_loc_api.sendUDPMessage(line_measurement0403, false, false) + || !lidar_loc_api.sendUDPMessage(line_measurement0404, false, false)) { ROS_ERROR_STREAM("## ERROR sick_lidar_localization: UDPSender::sendUDPPayload() failed"); } diff --git a/src/sick_services.cpp b/src/sick_services.cpp index a233281..28106ac 100644 --- a/src/sick_services.cpp +++ b/src/sick_services.cpp @@ -79,7 +79,7 @@ #define serviceCbLocSetOdometryActiveSrv sick_lidar_localization::SickServices::serviceCbLocSetOdometryActiveSrvROS1 #define serviceCbLocSetRecordingActiveSrv sick_lidar_localization::SickServices::serviceCbLocSetRecordingActiveSrvROS1 #define serviceCbLocSetRingBufferRecordingActiveSrv sick_lidar_localization::SickServices::serviceCbLocSetRingBufferRecordingActiveSrvROS1 -#define serviceCbLocStartLocalizingSrv sick_lidar_localization::SickServices::serviceCbLocStartLocalizingSrvROS1 +#define serviceCbLocStartSrv sick_lidar_localization::SickServices::serviceCbLocStartSrvROS1 #define serviceCbLocStateSrv sick_lidar_localization::SickServices::serviceCbLocStateSrvROS1 #define serviceCbLocStopSrv sick_lidar_localization::SickServices::serviceCbLocStopSrvROS1 #define serviceCbLocSwitchMapSrv sick_lidar_localization::SickServices::serviceCbLocSwitchMapSrvROS1 @@ -107,7 +107,7 @@ #define serviceCbLocSetOdometryActiveSrv sick_lidar_localization::SickServices::serviceCbLocSetOdometryActiveSrvROS2 #define serviceCbLocSetRecordingActiveSrv sick_lidar_localization::SickServices::serviceCbLocSetRecordingActiveSrvROS2 #define serviceCbLocSetRingBufferRecordingActiveSrv sick_lidar_localization::SickServices::serviceCbLocSetRingBufferRecordingActiveSrvROS2 -#define serviceCbLocStartLocalizingSrv sick_lidar_localization::SickServices::serviceCbLocStartLocalizingSrvROS2 +#define serviceCbLocStartSrv sick_lidar_localization::SickServices::serviceCbLocStartSrvROS2 #define serviceCbLocStateSrv sick_lidar_localization::SickServices::serviceCbLocStateSrvROS2 #define serviceCbLocStopSrv sick_lidar_localization::SickServices::serviceCbLocStopSrvROS2 #define serviceCbLocSwitchMapSrv sick_lidar_localization::SickServices::serviceCbLocSwitchMapSrvROS2 @@ -171,8 +171,8 @@ sick_lidar_localization::SickServices::SickServices(rosNodePtr nh, const std::st m_srv_server_LocSetRecordingActiveSrv = rosServiceServer(srv_LocSetRecordingActiveSrv); auto srv_LocSetRingBufferRecordingActiveSrv = ROS_CREATE_SRV_SERVER(nh, sick_lidar_localization::LocSetRingBufferRecordingActiveSrv, "/LocSetRingBufferRecordingActive", &serviceCbLocSetRingBufferRecordingActiveSrv, this); m_srv_server_LocSetRingBufferRecordingActiveSrv = rosServiceServer(srv_LocSetRingBufferRecordingActiveSrv); - auto srv_LocStartLocalizingSrv = ROS_CREATE_SRV_SERVER(nh, sick_lidar_localization::LocStartLocalizingSrv, "/LocStartLocalizing", &serviceCbLocStartLocalizingSrv, this); - m_srv_server_LocStartLocalizingSrv = rosServiceServer(srv_LocStartLocalizingSrv); + auto srv_LocStartSrv = ROS_CREATE_SRV_SERVER(nh, sick_lidar_localization::LocStartSrv, "/LocStart", &serviceCbLocStartSrv, this); + m_srv_server_LocStartSrv = rosServiceServer(srv_LocStartSrv); auto srv_LocStopSrv = ROS_CREATE_SRV_SERVER(nh, sick_lidar_localization::LocStopSrv, "/LocStop", &serviceCbLocStopSrv, this); m_srv_server_LocStopSrv = rosServiceServer(srv_LocStopSrv); auto srv_LocSwitchMapSrv = ROS_CREATE_SRV_SERVER(nh, sick_lidar_localization::LocSwitchMapSrv, "/LocSwitchMap", &serviceCbLocSwitchMapSrv, this); @@ -220,7 +220,7 @@ void sick_lidar_localization::SickServices::getDefaultCommand(const std::string& command_map["LocSetOdometryActive"] = {"LocSetOdometryActive", "POST"}; command_map["LocSetRecordingActive"] = {"LocSetRecordingActive", "POST"}; command_map["LocSetRingBufferRecordingActive"] = {"LocSetRingBufferRecordingActive", "POST"}; - command_map["LocStartLocalizing"] = {"LocStartLocalizing", "POST", "{}"}; + command_map["LocStart"] = {"LocStart", "POST", "{}"}; command_map["LocStop"] = {"LocStop", "POST", "{}"}; command_map["LocSwitchMap"] = {"LocSwitchMap", "POST"}; command_map["LocGetLocalizationStatus"] = {"LocGetLocalizationStatus", "POST"}; @@ -634,17 +634,17 @@ bool sick_lidar_localization::SickServices::serviceCbLocSetRingBufferRecordingAc return serviceCbLocSetRingBufferRecordingActiveSrvROS1(*service_request, *service_response); } -bool sick_lidar_localization::SickServices::serviceCbLocStartLocalizingSrvROS1(sick_lidar_localization::LocStartLocalizingSrv::Request &service_request, sick_lidar_localization::LocStartLocalizingSrv::Response &service_response) +bool sick_lidar_localization::SickServices::serviceCbLocStartSrvROS1(sick_lidar_localization::LocStartSrv::Request &service_request, sick_lidar_localization::LocStartSrv::Response &service_response) { - std::string command = "LocStartLocalizing", method = "POST", json_data = "{}"; + std::string command = "LocStart", method = "POST", json_data = "{}"; std::map response_data = sendJsonRequestGetResponse(command, method, json_data); service_response.success = response_data["/data/success"].toBool(); ROS_INFO_STREAM("SickServices::serviceCb(\"" << command << "\", \"" << method << "\", \"" << json_data << "\"): success=" << std::to_string(service_response.success)); return true; } -bool sick_lidar_localization::SickServices::serviceCbLocStartLocalizingSrvROS2(std::shared_ptr service_request, std::shared_ptr service_response) +bool sick_lidar_localization::SickServices::serviceCbLocStartSrvROS2(std::shared_ptr service_request, std::shared_ptr service_response) { - return serviceCbLocStartLocalizingSrvROS1(*service_request, *service_response); + return serviceCbLocStartSrvROS1(*service_request, *service_response); } bool sick_lidar_localization::SickServices::serviceCbLocStopSrvROS1(sick_lidar_localization::LocStopSrv::Request &service_request, sick_lidar_localization::LocStopSrv::Response &service_response) diff --git a/src/udp_message_parser.cpp b/src/udp_message_parser.cpp index 7ee58e3..6993a6c 100644 --- a/src/udp_message_parser.cpp +++ b/src/udp_message_parser.cpp @@ -194,75 +194,6 @@ std::vector sick_lidar_localization::UDPMessage::encodeHeader(size_t pa } } -#define OdometryPayload0101UdpInputMsgLidarLocVersion 1 // Note: odometry message type 1 version 1 (localization controller udp input message) in old lidar loc version 1 message format (NOT in lidar loc version 2) - -/** @brief Encodes the header of a OdometryPayload0101 message */ -template<> std::vector sick_lidar_localization::UDPMessage::encodeHeader(const sick_lidar_localization::UDPMessage::OdometryPayload0101& message_payload, size_t payload_size, bool header_big_endian, bool payload_big_endian, uint16_t source_id) -{ - int lidar_loc_version = OdometryPayload0101UdpInputMsgLidarLocVersion; // Note: odometry message type 1 version 1 in old lidar loc version 1 message format (NOT in lidar loc version 2) - return sick_lidar_localization::UDPMessage::encodeHeader(payload_size, header_big_endian, payload_big_endian, 1, 1, source_id, lidar_loc_version); -} - -/* -** @brief Encodes the payload of a OdometryPayload0101 udp message (odometry payload message type 1 version 1 -** @param[in] message_payload payload -** @param[in] encode_big_endian encode in big or little endiang -** @param[out] encoded vector of bytes -*/ -template<> std::vector sick_lidar_localization::UDPMessage::encodePayload(const sick_lidar_localization::UDPMessage::OdometryPayload0101& message_payload, bool encode_big_endian) -{ - int lidar_loc_version = OdometryPayload0101UdpInputMsgLidarLocVersion; // Note: odometry message type 1 version 1 in old lidar loc version 1 message format (NOT in lidar loc version 2) - if(lidar_loc_version == 2) - { - // Encode payload according to lidar localization specification version 2 (default) - std::vector buffer(32); - encode((uint64_t)message_payload.telegram_count, &buffer[0] + 0, 8, encode_big_endian); - encode((uint64_t)message_payload.timestamp, &buffer[0] + 8, 8, encode_big_endian); - encode((uint64_t)message_payload.x_velocity, &buffer[0] + 16, 4, encode_big_endian); - encode((uint64_t)message_payload.y_velocity, &buffer[0] + 20, 4, encode_big_endian); - encode((uint64_t)message_payload.angular_velocity, &buffer[0] + 24, 8, encode_big_endian); - return buffer; - } - else if(lidar_loc_version == 1) - { - // Encode payload according to lidar localization specification version 1 (for backward compatibility only) - std::vector buffer(16); - // Payload: 4 byte TelegramCount UInt32 - encode((uint64_t)message_payload.telegram_count, &buffer[0] + 0, 4, encode_big_endian); - // Payload: 4 byte Timestamp UInt32 in ms - encode((uint64_t)message_payload.timestamp, &buffer[0] + 4, 4, encode_big_endian); - // Payload: 2 byte vx Int16 in mm/s - encode((uint64_t)message_payload.x_velocity, &buffer[0] + 8, 2, encode_big_endian); - // Payload: 2 byte vy Int16 in mm/s - encode((uint64_t)message_payload.y_velocity, &buffer[0] + 10, 2, encode_big_endian); - // Payload: 4 byte omega Int32 in mdeg/s - encode((uint64_t)message_payload.angular_velocity, &buffer[0] + 12, 4, encode_big_endian); - return buffer; - } - else - { - ROS_ERROR_STREAM("## ERROR UDPMessage::encodePayload(OdometryPayload0101): lidar_loc_version = " << lidar_loc_version << " not supported, expected version 2 (default) or version 1 (backward compatibility)"); - return std::vector(); - } -} - -/* -** @brief Print the payload data. Implementation for odometry payload message type 1 version 1 -** @return payload data as human readable string -*/ -template<> std::string sick_lidar_localization::UDPMessage::printPayload(const sick_lidar_localization::UDPMessage::OdometryPayload0101& payload, bool print_sync_time) -{ - std::stringstream s; - s << "OdometryPayload0101:{" - << "telegram_count:" << payload.telegram_count - << ", timestamp:" << payload.timestamp - << ", x_velocity:" << payload.x_velocity - << ", y_velocity:" << payload.y_velocity - << ", angular_velocity:" << payload.angular_velocity - << "}"; - return s.str(); -} - /* ** @brief Decodes the payload of a udp message. Implementation for odometry payload message type 1 version 4 (24 byte payload) ** @param[in] udp_buffer payload bytes received by udp @@ -348,6 +279,7 @@ template<> std::string sick_lidar_localization::UDPMessage::printPayload(const s s << "OdometryPayload0104:{" << "telegram_count:" << payload.telegram_count << ", timestamp:" << payload.timestamp + << ", source_id:" << payload.source_id << ", x_velocity:" << payload.x_velocity << ", y_velocity:" << payload.y_velocity << ", angular_velocity:" << payload.angular_velocity @@ -412,6 +344,7 @@ template<> std::string sick_lidar_localization::UDPMessage::printPayload(const s s << "OdometryPayload0105:{" << "telegram_count:" << payload.telegram_count << ", timestamp:" << payload.timestamp + << ", source_id:" << payload.source_id << ", x_position:" << payload.x_position << ", y_position:" << payload.y_position << ", heading:" << payload.heading @@ -451,6 +384,7 @@ template<> std::string sick_lidar_localization::UDPMessage::printPayload(const s s << "EncoderMeasurementPayload0202:{" << "telegram_count:" << payload.telegram_count << ", timestamp:" << payload.timestamp + << ", source_id:" << payload.source_id << ", code:" << payload.encoder_value << "}"; return s.str(); @@ -487,11 +421,83 @@ template<> std::string sick_lidar_localization::UDPMessage::printPayload(const s s << "CodeMeasurementPayload0303:{" << "telegram_count:" << payload.telegram_count << ", timestamp:" << payload.timestamp + << ", source_id:" << payload.source_id << ", code:" << payload.code << "}"; return s.str(); } +/** @brief Encodes the header of a CodeMeasurementPayload0701 message */ +template<> std::vector sick_lidar_localization::UDPMessage::encodeHeader(const sick_lidar_localization::UDPMessage::CodeMeasurementPayload0701& message_payload, size_t payload_size, bool header_big_endian, bool payload_big_endian, uint16_t source_id) +{ + return sick_lidar_localization::UDPMessage::encodeHeader(payload_size, header_big_endian, payload_big_endian, 7, 1, source_id); +} + +/* +** @brief Encodes the payload of a CodeMeasurementPayload0701 udp message (code measurement payload message type 7 version 1 (variable length payload) +** @param[in] message_payload payload +** @param[in] encode_big_endian encode in big or little endiang +** @param[out] encoded vector of bytes +*/ +template<> std::vector sick_lidar_localization::UDPMessage::encodePayload(const sick_lidar_localization::UDPMessage::CodeMeasurementPayload0701& message_payload, bool encode_big_endian) +{ + int buffer_length = (int)(sizeof(message_payload.telegram_count) + sizeof(message_payload.timestamp) + 2 + message_payload.code.length() + + sizeof(message_payload.x_position) + sizeof(message_payload.y_position) + sizeof(message_payload.heading)); + std::vector buffer(buffer_length); + + uint8_t* p_data = &buffer[0]; + int len = sizeof(message_payload.telegram_count); + encode((uint64_t)message_payload.telegram_count, p_data, len, encode_big_endian); + p_data += len; + + len = sizeof(message_payload.timestamp); + encode((uint64_t)message_payload.timestamp, p_data, len, encode_big_endian); + p_data += len; + + uint16_t codelength = (uint16_t)message_payload.code.length(); + len = sizeof(codelength); + encode((uint16_t)codelength, p_data, len, encode_big_endian); + p_data += len; + + for(int n = 0; n < codelength; n++, p_data++) + { + *p_data = (uint8_t)message_payload.code[n]; + } + + len = sizeof(message_payload.x_position); + encode((uint64_t)message_payload.x_position, p_data, len, encode_big_endian); + p_data += len; + + len = sizeof(message_payload.y_position); + encode((uint64_t)message_payload.y_position, p_data, len, encode_big_endian); + p_data += len; + + len = sizeof(message_payload.heading); + encode((uint64_t)message_payload.heading, p_data, len, encode_big_endian); + p_data += len; + + return buffer; +} + +/* +** @brief Print the payload data. Implementation for code measurement payload message type 7 version 1 +** @return payload data as human readable string +*/ +template<> std::string sick_lidar_localization::UDPMessage::printPayload(const sick_lidar_localization::UDPMessage::CodeMeasurementPayload0701& payload, bool print_sync_time) +{ + std::stringstream s; + s << "CodeMeasurementPayload0701:{" + << "telegram_count:" << payload.telegram_count + << ", timestamp:" << payload.timestamp + << ", source_id:" << payload.source_id + << ", code:" << payload.code + << ", x_position:" << payload.x_position + << ", y_position:" << payload.y_position + << ", heading:" << payload.heading + << "}"; + return s.str(); +} + /* ** @brief Decodes the payload of a udp message. Implementation for code measurement payload message type 3 version 4 (24 byte payload) ** @param[in] udp_buffer payload bytes received by udp @@ -524,6 +530,7 @@ template<> std::string sick_lidar_localization::UDPMessage::printPayload(const s s << "CodeMeasurementPayload0304:{" << "telegram_count:" << payload.telegram_count << ", timestamp:" << payload.timestamp + << ", source_id:" << payload.source_id << ", code:" << payload.code << ", distance:" << payload.distance << printSyncTime(payload, print_sync_time) @@ -599,6 +606,7 @@ template<> std::string sick_lidar_localization::UDPMessage::printPayload(const s s << "LineMeasurementPayload0403:{" << "telegram_count:" << payload.telegram_count << ", timestamp:" << payload.timestamp + << ", source_id:" << payload.source_id << ", num_lanes:" << (int)payload.num_lanes << ", lanes:["; for (int n = 0; n < payload.num_lanes; n++) @@ -673,6 +681,7 @@ template<> std::string sick_lidar_localization::UDPMessage::printPayload(const s s << "LineMeasurementPayload0404:{" << "telegram_count:" << payload.telegram_count << ", timestamp:" << payload.timestamp + << ", source_id:" << payload.source_id << ", lcp1:" << (int)payload.lcp1 << ", lcp2:" << (int)payload.lcp2 << ", lcp3:" << (int)payload.lcp3 @@ -718,6 +727,7 @@ template<> std::string sick_lidar_localization::UDPMessage::printPayload(const s s << "LocalizationControllerResultPayload0502:{" << "telegram_count:" << payload.telegram_count << ", timestamp:" << payload.timestamp + << ", source_id:" << payload.source_id << ", x:" << payload.x << ", y:" << payload.y << ", heading:" << payload.heading diff --git a/src/udp_receiver_thread.cpp b/src/udp_receiver_thread.cpp index be34e6b..38825bc 100644 --- a/src/udp_receiver_thread.cpp +++ b/src/udp_receiver_thread.cpp @@ -86,12 +86,12 @@ static std::string getErrorMessage(void) { return std::to_string(errno) + " (" + /* ** @brief Default constructor ** @param[in] services time sync services -** @param[in] udp_ip_sim_output IP address for output UDP messages, or "" for broadcast (INADDR_ANY), default: "", use IP address of your local machine -** @param[in] udp_port_sim_output UDP port of output messages, default: 5010 -** @param[in] udp_sim_output_logfile Optional logfile for human readable output messages, default: "" (no outputlogfile) +** @param[in] udp_ip_lls_output IP address for output UDP messages, or "" for broadcast (INADDR_ANY), default: "", use IP address of your local machine +** @param[in] udp_port_lls_output UDP port of output messages, default: 5010 +** @param[in] udp_lls_output_logfile Optional logfile for human readable output messages, default: "" (no outputlogfile) */ -sick_lidar_localization::UDPReceiverThread::UDPReceiverThread(sick_lidar_localization::SickServices* services, const std::string& udp_ip_sim_output, int udp_port_sim_output, const std::string& udp_sim_output_logfile) - : m_services(services), m_udp_ip_sim_output(udp_ip_sim_output), m_udp_port_sim_output(udp_port_sim_output), m_udp_sim_output_logfile(udp_sim_output_logfile), m_run_receiver_thread(false), m_receiver_thread(0) +sick_lidar_localization::UDPReceiverThread::UDPReceiverThread(sick_lidar_localization::SickServices* services, const std::string& udp_ip_lls_output, int udp_port_lls_output, const std::string& udp_lls_output_logfile) + : m_services(services), m_udp_ip_lls_output(udp_ip_lls_output), m_udp_port_lls_output(udp_port_lls_output), m_udp_lls_output_logfile(udp_lls_output_logfile), m_run_receiver_thread(false), m_receiver_thread(0) { } @@ -131,7 +131,7 @@ void sick_lidar_localization::UDPReceiverThread::stop() } /* -** @brief Register a listener for upd messages. The callback functions of the listener will be called after receiving a new udp message. +** @brief Register a listener for udp messages. The callback functions of the listener will be called after receiving a new udp message. ** Overwrite the functions defined in sick_lidar_localization::UDPMessage::Listener with customized code to handle udp messages. */ void sick_lidar_localization::UDPReceiverThread::registerListener(sick_lidar_localization::UDPMessage::Listener* listener) @@ -165,8 +165,8 @@ void sick_lidar_localization::UDPReceiverThread::sleep(double seconds) */ bool sick_lidar_localization::UDPReceiverThread::runReceiver(void) { - if (!m_udp_sim_output_logfile.empty()) - UNLINK(m_udp_sim_output_logfile.c_str()); + if (!m_udp_lls_output_logfile.empty()) + UNLINK(m_udp_lls_output_logfile.c_str()); SOCKET udp_socket = INVALID_SOCKET; while (rosOk() && m_run_receiver_thread) { @@ -178,15 +178,15 @@ bool sick_lidar_localization::UDPReceiverThread::runReceiver(void) } // int broadcast_opt = 1; // setsockopt(udp_socket, SOL_SOCKET, SO_BROADCAST, &broadcast_opt, sizeof(broadcast_opt)); - struct sockaddr_in sim_servaddr = { 0 }; - if(m_udp_ip_sim_output.empty()) - sim_servaddr.sin_addr.s_addr = htonl(INADDR_ANY); + struct sockaddr_in lls_servaddr = { 0 }; + if(m_udp_ip_lls_output.empty()) + lls_servaddr.sin_addr.s_addr = htonl(INADDR_ANY); else - sim_servaddr.sin_addr.s_addr = inet_addr(m_udp_ip_sim_output.c_str()); - sim_servaddr.sin_family = AF_INET; - sim_servaddr.sin_port = htons(m_udp_port_sim_output); - ROS_INFO_STREAM("sick_lidar_localization::UDPReceiverThread: udp socket created, binding to port " << ntohs(sim_servaddr.sin_port) << " ... "); - while (rosOk() && m_run_receiver_thread && udp_socket != INVALID_SOCKET && bind(udp_socket, (SOCKADDR*)&sim_servaddr, sizeof(sim_servaddr)) < 0) + lls_servaddr.sin_addr.s_addr = inet_addr(m_udp_ip_lls_output.c_str()); + lls_servaddr.sin_family = AF_INET; + lls_servaddr.sin_port = htons(m_udp_port_lls_output); + ROS_INFO_STREAM("sick_lidar_localization::UDPReceiverThread: udp socket created, binding to port " << ntohs(lls_servaddr.sin_port) << " ... "); + while (rosOk() && m_run_receiver_thread && udp_socket != INVALID_SOCKET && bind(udp_socket, (SOCKADDR*)&lls_servaddr, sizeof(lls_servaddr)) < 0) { ROS_INFO_STREAM("sick_lidar_localization::UDPReceiverThread: socket bind failed, error " << getErrorMessage() << ", retrying..."); sleep(1.0); // Retry after 1 second @@ -205,8 +205,8 @@ bool sick_lidar_localization::UDPReceiverThread::runReceiver(void) while (rosOk() && m_run_receiver_thread && udp_socket != INVALID_SOCKET && bytes_received < bytes_required) { int n = recv(udp_socket, (char*)&udp_buffer[bytes_received], (int)sizeof(udp_buffer) - bytes_received, 0); - // socklen_t sim_servaddr_len = sizeof(sim_servaddr); - // int n = recvfrom(udp_socket, (char*)&udp_buffer[bytes_received], (int)sizeof(udp_buffer) - bytes_received, 0, (SOCKADDR*)&sim_servaddr, &sim_servaddr_len); + // socklen_t lls_servaddr_len = sizeof(lls_servaddr); + // int n = recvfrom(udp_socket, (char*)&udp_buffer[bytes_received], (int)sizeof(udp_buffer) - bytes_received, 0, (SOCKADDR*)&lls_servaddr, &lls_servaddr_len); if (n <= 0) { if (n < 0) @@ -269,6 +269,7 @@ bool sick_lidar_localization::UDPReceiverThread::runReceiver(void) } if (payload && payload->decodePayload(udp_payload_buffer, udp_payload_len, payload_is_big_endian)) { + payload->sourceID() = msg_header.sourceid; sick_lidar_localization::SyncTimeStamp sync_time_stamp = sick_lidar_localization::makeSyncTimeStamp(0, 0, false); if(m_services) { @@ -283,12 +284,12 @@ bool sick_lidar_localization::UDPReceiverThread::runReceiver(void) // Notify listener (and publish UDP output messages on ROS-1 or ROS-2) payload->notifyListener(m_udp_message_listener); // Log output messages - FILE* fp_udp_sim_output_logfile = 0; - if (!m_udp_sim_output_logfile.empty() && (fp_udp_sim_output_logfile = fopen(m_udp_sim_output_logfile.c_str(), "a")) != 0) + FILE* fp_udp_lls_output_logfile = 0; + if (!m_udp_lls_output_logfile.empty() && (fp_udp_lls_output_logfile = fopen(m_udp_lls_output_logfile.c_str(), "a")) != 0) { std::string payload_str = payload->toString(false); - fprintf(fp_udp_sim_output_logfile, "%s\n", payload_str.c_str()); - fclose(fp_udp_sim_output_logfile); + fprintf(fp_udp_lls_output_logfile, "%s\n", payload_str.c_str()); + fclose(fp_udp_lls_output_logfile); } } else diff --git a/src/udp_sender.cpp b/src/udp_sender.cpp index 9e84c71..8ed67e8 100644 --- a/src/udp_sender.cpp +++ b/src/udp_sender.cpp @@ -92,22 +92,22 @@ namespace sick_lidar_localization /* ** @brief Default constructor */ - UDPSenderImpl() : m_udp_socket(INVALID_SOCKET), m_sim_ip_address(), m_udp_port_sim_input(0) + UDPSenderImpl() : m_udp_socket(INVALID_SOCKET), m_lls_ip_address(), m_udp_port_lls_input(0) { } /* ** @brief Initializes the socket - ** @param[in] sim_ip_address IP address of localization controller, or "" for broadcast - ** @param[in] udp_port_sim_input UDP port of input messages, default: 5009 + ** @param[in] lls_ip_address IP address of localization controller, or "" for broadcast + ** @param[in] udp_port_lls_input UDP port of input messages, default: 5009 */ - bool initSocket(const std::string & sim_ip_address = "192.168.0.1", int udp_port_sim_input = 5009) + bool initSocket(const std::string & lls_ip_address = "192.168.0.1", int udp_port_lls_input = 5009) { - m_sim_ip_address = sim_ip_address; - m_udp_port_sim_input = udp_port_sim_input; + m_lls_ip_address = lls_ip_address; + m_udp_port_lls_input = udp_port_lls_input; if ((m_udp_socket = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == INVALID_SOCKET) { - ROS_ERROR_STREAM("## ERROR UDPSenderImpl::init(" << udp_port_sim_input << "): can't create socket"); + ROS_ERROR_STREAM("## ERROR UDPSenderImpl::init(" << udp_port_lls_input << "): can't create socket"); return false; } #if defined WIN32 || defined _MSC_VER @@ -116,7 +116,7 @@ namespace sick_lidar_localization int broadcast_opt = 1; #endif if (setsockopt(m_udp_socket, SOL_SOCKET, SO_BROADCAST, &broadcast_opt, sizeof(broadcast_opt)) < 0) - ROS_ERROR_STREAM("## ERROR UDPSenderImpl::init(" << udp_port_sim_input << "): setsockopt(SO_BROADCAST) failed, error: " << getErrorMessage()); + ROS_ERROR_STREAM("## ERROR UDPSenderImpl::init(" << udp_port_lls_input << "): setsockopt(SO_BROADCAST) failed, error: " << getErrorMessage()); return true; } @@ -134,34 +134,34 @@ namespace sick_lidar_localization { if (m_udp_socket != INVALID_SOCKET) { - struct sockaddr_in sim_servaddr = { 0 }; - if(m_sim_ip_address.empty()) + struct sockaddr_in lls_servaddr = { 0 }; + if(m_lls_ip_address.empty()) { - sim_servaddr.sin_addr.s_addr = htonl(INADDR_BROADCAST); + lls_servaddr.sin_addr.s_addr = htonl(INADDR_BROADCAST); } else { #if defined WIN32 || defined _MSC_VER - sim_servaddr.sin_addr.s_addr = inet_addr(m_sim_ip_address.c_str()); + lls_servaddr.sin_addr.s_addr = inet_addr(m_lls_ip_address.c_str()); #else - struct in_addr sim_in_addr; - if (inet_aton(m_sim_ip_address.c_str(), &sim_in_addr) != 0) + struct in_addr lls_in_addr; + if (inet_aton(m_lls_ip_address.c_str(), &lls_in_addr) != 0) { - sim_servaddr.sin_addr.s_addr = sim_in_addr.s_addr; + lls_servaddr.sin_addr.s_addr = lls_in_addr.s_addr; } else { - ROS_ERROR_STREAM("## ERROR UDPSenderImpl::sendData(): inet_aton(" << m_sim_ip_address << ") failed (invalid address)"); - sim_servaddr.sin_addr.s_addr = inet_addr(m_sim_ip_address.c_str()); + ROS_ERROR_STREAM("## ERROR UDPSenderImpl::sendData(): inet_aton(" << m_lls_ip_address << ") failed (invalid address)"); + lls_servaddr.sin_addr.s_addr = inet_addr(m_lls_ip_address.c_str()); } #endif } - sim_servaddr.sin_family = AF_INET; - sim_servaddr.sin_port = htons(m_udp_port_sim_input); - int bytes_send = sendto(m_udp_socket, (const char*)buffer, num_bytes, 0, (SOCKADDR*)&sim_servaddr, sizeof(sim_servaddr)); + lls_servaddr.sin_family = AF_INET; + lls_servaddr.sin_port = htons(m_udp_port_lls_input); + int bytes_send = sendto(m_udp_socket, (const char*)buffer, num_bytes, 0, (SOCKADDR*)&lls_servaddr, sizeof(lls_servaddr)); if (bytes_send != num_bytes) { - ROS_ERROR_STREAM("## ERROR UDPSenderImpl::sendData(): " << bytes_send << " of " << num_bytes << " bytes send to " << m_sim_ip_address << ":" << m_udp_port_sim_input << ", error: " << getErrorMessage()); + ROS_ERROR_STREAM("## ERROR UDPSenderImpl::sendData(): " << bytes_send << " of " << num_bytes << " bytes send to " << m_lls_ip_address << ":" << m_udp_port_lls_input << ", error: " << getErrorMessage()); return false; } return true; @@ -172,25 +172,25 @@ namespace sick_lidar_localization protected: SOCKET m_udp_socket; // OS socket descriptor - std::string m_sim_ip_address; // IP address of localization controller, or "" for broadcast - int m_udp_port_sim_input; // UDP port of input messages, default: 5009 + std::string m_lls_ip_address; // IP address of localization controller, or "" for broadcast + int m_udp_port_lls_input; // UDP port of input messages, default: 5009 }; } /* ** @brief Default constructor ** @param[in] nh ros node handle (always 0 for native linus or windows) -** @param[in] sim_ip_address IP address of localization controller, or "" for broadcast -** @param[in] udp_port_sim_input UDP port of input messages, default: 5009 -** @param[in] udp_sim_input_source_id source_id of UDP input messages, default: 1 +** @param[in] lls_ip_address IP address of localization controller, or "" for broadcast +** @param[in] udp_port_lls_input UDP port of input messages, default: 5009 +** @param[in] source_id_cfg source_id map of UDP input messages, default source id: 1 ** @param[in] verbose print informational messages if verbose > 0, otherwise silent mode (error messages only) -** @param[in] ros_odom_to_udp_msg Convert ros odom message to upd: 0 = map velocity to OdometryPayload0101 (Type 1, Version 1, LidarLoc 1), +** @param[in] ros_odom_to_udp_msg Convert ros odom message to udp: ** 1 = map velocity to OdometryPayload0104 (Type 1, Version 4, LidarLoc 2), ** 2 = map position to OdometryPayload0105 (Type 1, Version 5, LidarLoc 2), ** 3 = map velocity to OdometryPayload0104 and position to OdometryPayload0105 */ -sick_lidar_localization::UDPSender::UDPSender(rosNodePtr nh, const std::string& sim_ip_address, int udp_port_sim_input, int udp_sim_input_source_id, int verbose, const std::string& odom_topic, int ros_odom_to_udp_msg) -: m_sim_ip_address(sim_ip_address), m_udp_port_sim_input(udp_port_sim_input), m_source_id(udp_sim_input_source_id), m_verbose(verbose), m_ros_odom_to_udp_msg(ros_odom_to_udp_msg), m_udp_sender_impl(0) +sick_lidar_localization::UDPSender::UDPSender(rosNodePtr nh, const std::string& lls_ip_address, int udp_port_lls_input, const sick_lidar_localization::UDPDefaultInputSourceId& source_id_cfg, int verbose, const std::string& odom_topic, int ros_odom_to_udp_msg) +: m_lls_ip_address(lls_ip_address), m_udp_port_lls_input(udp_port_lls_input), m_source_id_cfg(source_id_cfg), m_verbose(verbose), m_ros_odom_to_udp_msg(ros_odom_to_udp_msg), m_udp_sender_impl(0) { #if __ROS_VERSION > 0 if(nh != 0) @@ -198,39 +198,39 @@ sick_lidar_localization::UDPSender::UDPSender(rosNodePtr nh, const std::string& // Subscribe to odometry messages #if __ROS_VERSION == 1 auto messageCbOdomROS = &sick_lidar_localization::UDPSender::messageCbOdomROS; - auto messageCbOdometryMessage0101 = &sick_lidar_localization::UDPSender::messageCbOdometryMessage0101; auto messageCbOdometryMessage0104 = &sick_lidar_localization::UDPSender::messageCbOdometryMessage0104; auto messageCbOdometryMessage0105 = &sick_lidar_localization::UDPSender::messageCbOdometryMessage0105; auto messageCbEncoderMeasurementMessage0202 = &sick_lidar_localization::UDPSender::messageCbEncoderMeasurementMessage0202; auto messageCbCodeMeasurementMessage0303 = &sick_lidar_localization::UDPSender::messageCbCodeMeasurementMessage0303; + auto messageCbCodeMeasurementMessage0701 = &sick_lidar_localization::UDPSender::messageCbCodeMeasurementMessage0701; auto messageCbLineMeasurementMessage0403 = &sick_lidar_localization::UDPSender::messageCbLineMeasurementMessage0403; auto messageCbLineMeasurementMessage0404 = &sick_lidar_localization::UDPSender::messageCbLineMeasurementMessage0404; #else auto messageCbOdomROS = &sick_lidar_localization::UDPSender::messageCbOdomROS2; - auto messageCbOdometryMessage0101 = &sick_lidar_localization::UDPSender::messageCbOdometryMessage0101ROS2; auto messageCbOdometryMessage0104 = &sick_lidar_localization::UDPSender::messageCbOdometryMessage0104ROS2; auto messageCbOdometryMessage0105 = &sick_lidar_localization::UDPSender::messageCbOdometryMessage0105ROS2; auto messageCbEncoderMeasurementMessage0202 = &sick_lidar_localization::UDPSender::messageCbEncoderMeasurementMessage0202ROS2; auto messageCbCodeMeasurementMessage0303 = &sick_lidar_localization::UDPSender::messageCbCodeMeasurementMessage0303ROS2; + auto messageCbCodeMeasurementMessage0701 = &sick_lidar_localization::UDPSender::messageCbCodeMeasurementMessage0701ROS2; auto messageCbLineMeasurementMessage0403 = &sick_lidar_localization::UDPSender::messageCbLineMeasurementMessage0403ROS2; auto messageCbLineMeasurementMessage0404 = &sick_lidar_localization::UDPSender::messageCbLineMeasurementMessage0404ROS2; #endif # ifdef _MSC_VER m_subOdomROS = rosSubscriber(nh->create_subscription(odom_topic, 10, std::bind(&sick_lidar_localization::UDPSender::messageCbOdomROS2, this, std::placeholders::_1))); - m_subOdometryMessage0101 = rosSubscriber(nh->create_subscription("/localizationcontroller/in/odometry_message_0101", 10, std::bind(&sick_lidar_localization::UDPSender::messageCbOdometryMessage0101ROS2, this, std::placeholders::_1))); m_subOdometryMessage0104 = rosSubscriber(nh->create_subscription("/localizationcontroller/in/odometry_message_0104", 10, std::bind(&sick_lidar_localization::UDPSender::messageCbOdometryMessage0104ROS2, this, std::placeholders::_1))); m_subOdometryMessage0105 = rosSubscriber(nh->create_subscription("/localizationcontroller/in/odometry_message_0105", 10, std::bind(&sick_lidar_localization::UDPSender::messageCbOdometryMessage0105ROS2, this, std::placeholders::_1))); m_subEncoderMeasurementMessage0202 = rosSubscriber(nh->create_subscription("/localizationcontroller/in/encoder_measurement_message_0202", 10, std::bind(&sick_lidar_localization::UDPSender::messageCbEncoderMeasurementMessage0202ROS2, this, std::placeholders::_1))); m_subCodeMeasurementMessage0303 = rosSubscriber(nh->create_subscription("/localizationcontroller/in/code_measurement_message_0303", 10, std::bind(&sick_lidar_localization::UDPSender::messageCbCodeMeasurementMessage0303ROS2, this, std::placeholders::_1))); + m_subCodeMeasurementMessage0701 = rosSubscriber(nh->create_subscription("/localizationcontroller/in/code_measurement_message_0701", 10, std::bind(&sick_lidar_localization::UDPSender::messageCbCodeMeasurementMessage0701ROS2, this, std::placeholders::_1))); m_subLineMeasurementMessage0403 = rosSubscriber(nh->create_subscription("/localizationcontroller/in/line_measurement_message_0403", 10, std::bind(&sick_lidar_localization::UDPSender::messageCbLineMeasurementMessage0403ROS2, this, std::placeholders::_1))); m_subLineMeasurementMessage0404 = rosSubscriber(nh->create_subscription("/localizationcontroller/in/line_measurement_message_0404", 10, std::bind(&sick_lidar_localization::UDPSender::messageCbLineMeasurementMessage0404ROS2, this, std::placeholders::_1))); #else m_subOdomROS = rosSubscribe(nh, odom_topic, messageCbOdomROS, this); - m_subOdometryMessage0101 = rosSubscribe(nh, "/localizationcontroller/in/odometry_message_0101", messageCbOdometryMessage0101, this); m_subOdometryMessage0104 = rosSubscribe(nh, "/localizationcontroller/in/odometry_message_0104", messageCbOdometryMessage0104, this); m_subOdometryMessage0105 = rosSubscribe(nh, "/localizationcontroller/in/odometry_message_0105", messageCbOdometryMessage0105, this); m_subEncoderMeasurementMessage0202 = rosSubscribe(nh, "/localizationcontroller/in/encoder_measurement_message_0202", messageCbEncoderMeasurementMessage0202, this); m_subCodeMeasurementMessage0303 = rosSubscribe(nh, "/localizationcontroller/in/code_measurement_message_0303", messageCbCodeMeasurementMessage0303, this); + m_subCodeMeasurementMessage0701 = rosSubscribe(nh, "/localizationcontroller/in/code_measurement_message_0701", messageCbCodeMeasurementMessage0701, this); m_subLineMeasurementMessage0403 = rosSubscribe(nh, "/localizationcontroller/in/line_measurement_message_0403", messageCbLineMeasurementMessage0403, this); m_subLineMeasurementMessage0404 = rosSubscribe(nh, "/localizationcontroller/in/line_measurement_message_0404", messageCbLineMeasurementMessage0404, this); #endif @@ -258,11 +258,11 @@ bool sick_lidar_localization::UDPSender::init(void) close(); } m_udp_sender_impl = new sick_lidar_localization::UDPSenderImpl(); - if (!m_udp_sender_impl->initSocket(m_sim_ip_address, m_udp_port_sim_input)) + if (!m_udp_sender_impl->initSocket(m_lls_ip_address, m_udp_port_lls_input)) { delete(m_udp_sender_impl); m_udp_sender_impl = 0; - ROS_ERROR_STREAM("## ERROR UDPSender::init(" << m_sim_ip_address << ", " << m_udp_port_sim_input << ") failed"); + ROS_ERROR_STREAM("## ERROR UDPSender::init(" << m_lls_ip_address << ", " << m_udp_port_lls_input << ") failed"); return false; } return true; @@ -294,7 +294,7 @@ bool sick_lidar_localization::UDPSender::sendData(const std::vector& ud } if (!m_udp_sender_impl) { - ROS_ERROR_STREAM("## ERROR UDPSender: can't init udp socket, UDPSender(" << m_sim_ip_address << ", " << m_udp_port_sim_input << ") failed"); + ROS_ERROR_STREAM("## ERROR UDPSender: can't init udp socket, UDPSender(" << m_lls_ip_address << ", " << m_udp_port_lls_input << ") failed"); return false; } bool ok = m_udp_sender_impl->sendData(udp_data.data(), (int)udp_data.size()); @@ -320,6 +320,17 @@ static double quaternionToYawAngle(double w, double x, double y, double z) return std::atan2(siny_cosp, cosy_cosp); } +/** returns the default source id from configuration file */ +int sick_lidar_localization::UDPDefaultInputSourceId::getSourceId(int msg_type, int msg_version) +{ + if (m_msgtype_version_sourceid_map.find(msg_type) == m_msgtype_version_sourceid_map.end() + || m_msgtype_version_sourceid_map[msg_type].find(msg_version) == m_msgtype_version_sourceid_map[msg_type].end()) + { + m_msgtype_version_sourceid_map[msg_type][msg_version] = m_default_source_id; + } + return m_msgtype_version_sourceid_map[msg_type][msg_version]; +} + #if __ROS_VERSION > 0 /** subscriber callback function for ros odom messages */ @@ -329,7 +340,6 @@ void sick_lidar_localization::UDPSender::messageCbOdomROS(const ros_nav_msgs::Od rosTime timestamp_msg = msg.header.stamp; uint64_t timestamp_sec = sec(timestamp_msg); uint64_t timestamp_nsec = nsec(timestamp_msg); - uint64_t timestamp_msec = 1000 * timestamp_sec + timestamp_nsec / 1000000;// message timestamp in milliseconds int64_t timestamp_mircrosec = 1000000 * timestamp_sec + timestamp_nsec / 1000;// message timestamp in microseconds double vx_ms = msg.twist.twist.linear.x; // vx in m/s double vy_ms = msg.twist.twist.linear.y; // vy in m/s @@ -344,21 +354,6 @@ void sick_lidar_localization::UDPSender::messageCbOdomROS(const ros_nav_msgs::Od static uint64_t s_telegram_count = 0; s_telegram_count++; - // Convert to OdometryPayload0101 message - if(m_ros_odom_to_udp_msg == 0) - { - sick_lidar_localization::UDPMessage::OdometryPayload0101 odometry0101; - odometry0101.telegram_count = s_telegram_count; - odometry0101.timestamp = timestamp_msec; - odometry0101.x_velocity = vx_mms; - odometry0101.y_velocity = vy_mms; - odometry0101.angular_velocity = omega_mdegs; - // Send OdometryMessage0101 - if (m_verbose) - ROS_INFO_STREAM("sick_lidar_localization::UDPSender: sending odom message (vx=" << vx_ms << ", vy=" << vy_ms << ", omega=" << omega_rs << ") converted to OdometryPayload0101"); - if (!sendUDPPayload(odometry0101, true, false, m_source_id)) - ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::messageCbOdomROS(): sendUDPPayload(" << sick_lidar_localization::UDPMessage::printPayload(odometry0101) << ") failed"); - } // Convert to OdometryPayload0104 message if(m_ros_odom_to_udp_msg == 1 || m_ros_odom_to_udp_msg == 3) { @@ -368,10 +363,11 @@ void sick_lidar_localization::UDPSender::messageCbOdomROS(const ros_nav_msgs::Od odometry0104.x_velocity = vx_mms; odometry0104.y_velocity = vy_mms; odometry0104.angular_velocity = omega_mdegs; + odometry0104.source_id = m_source_id_cfg.getSourceId(1, 4); // Send OdometryMessage0104 if (m_verbose) ROS_INFO_STREAM("sick_lidar_localization::UDPSender: sending odom message (vx=" << vx_ms << ", vy=" << vy_ms << ", omega=" << omega_rs << ") converted to OdometryPayload0104"); - if (!sendUDPPayload(odometry0104, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT, m_source_id)) + if (!sendUDPPayload(odometry0104, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT)) ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::messageCbOdometryMessage0104(): sendUDPPayload(" << sick_lidar_localization::UDPMessage::printPayload(odometry0104) << ") failed"); } // Convert to OdometryPayload0105 message @@ -383,10 +379,11 @@ void sick_lidar_localization::UDPSender::messageCbOdomROS(const ros_nav_msgs::Od odometry0105.x_position = x_pos_mm; odometry0105.y_position = y_pos_mm; odometry0105.heading = heading_mdeg; + odometry0105.source_id = m_source_id_cfg.getSourceId(1, 5); // Send OdometryMessage0105 if (m_verbose) ROS_INFO_STREAM("sick_lidar_localization::UDPSender: sending odom message (x=" << x_pos_mm << ", y=" << y_pos_mm << ", heading=" << heading_mdeg << ") converted to OdometryPayload0105"); - if (!sendUDPPayload(odometry0105, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT, m_source_id)) + if (!sendUDPPayload(odometry0105, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT)) ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::OdometryPayload0105(): sendUDPPayload(" << sick_lidar_localization::UDPMessage::printPayload(odometry0105) << ") failed"); } if(m_ros_odom_to_udp_msg < 0 || m_ros_odom_to_udp_msg > 3) @@ -395,19 +392,6 @@ void sick_lidar_localization::UDPSender::messageCbOdomROS(const ros_nav_msgs::Od } } -/** subscriber callback function for input udp messages type OdometryMessage0101 */ -void sick_lidar_localization::UDPSender::messageCbOdometryMessage0101(const sick_lidar_localization::OdometryMessage0101 & msg) -{ - sick_lidar_localization::UDPMessage::OdometryPayload0101 odometry0101; - odometry0101.telegram_count = msg.telegram_count; - odometry0101.timestamp = msg.timestamp; - odometry0101.x_velocity = msg.x_velocity; - odometry0101.y_velocity = msg.y_velocity; - odometry0101.angular_velocity = msg.angular_velocity; - if (!sendUDPPayload(odometry0101, true, false, m_source_id)) - ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::messageCbOdometryMessage0101(): sendUDPPayload(" << sick_lidar_localization::UDPMessage::printPayload(odometry0101) << ") failed"); -} - /** subscriber callback function for input udp messages type OdometryMessage0104 */ void sick_lidar_localization::UDPSender::messageCbOdometryMessage0104(const sick_lidar_localization::OdometryMessage0104 & msg) { @@ -417,7 +401,10 @@ void sick_lidar_localization::UDPSender::messageCbOdometryMessage0104(const sick odometry0104.x_velocity = msg.x_velocity; odometry0104.y_velocity = msg.y_velocity; odometry0104.angular_velocity = msg.angular_velocity; - if (!sendUDPPayload(odometry0104, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT, m_source_id)) + odometry0104.source_id = msg.source_id; + if (odometry0104.source_id <= 0) + odometry0104.source_id = m_source_id_cfg.getSourceId(1, 4); + if (!sendUDPPayload(odometry0104, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT)) ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::messageCbOdometryMessage0104(): sendUDPPayload(" << sick_lidar_localization::UDPMessage::printPayload(odometry0104) << ") failed"); } @@ -430,7 +417,10 @@ void sick_lidar_localization::UDPSender::messageCbOdometryMessage0105(const sick odometry0105.x_position = msg.x_position; odometry0105.y_position = msg.y_position; odometry0105.heading = msg.heading; - if (!sendUDPPayload(odometry0105, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT, m_source_id)) + odometry0105.source_id = msg.source_id; + if (odometry0105.source_id <= 0) + odometry0105.source_id = m_source_id_cfg.getSourceId(1, 5); + if (!sendUDPPayload(odometry0105, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT)) ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::OdometryPayload0105(): sendUDPPayload(" << sick_lidar_localization::UDPMessage::printPayload(odometry0105) << ") failed"); } @@ -441,7 +431,10 @@ void sick_lidar_localization::UDPSender::messageCbEncoderMeasurementMessage0202( encoder_measurement0202.telegram_count = msg.telegram_count; encoder_measurement0202.timestamp = msg.timestamp; encoder_measurement0202.encoder_value = msg.encoder_value; - if (!sendUDPPayload(encoder_measurement0202, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT, m_source_id)) + encoder_measurement0202.source_id = msg.source_id; + if (encoder_measurement0202.source_id <= 0) + encoder_measurement0202.source_id = m_source_id_cfg.getSourceId(2, 2); + if (!sendUDPPayload(encoder_measurement0202, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT)) ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::messageCbEncoderMeasurementMessage0202(): sendUDPPayload(" << sick_lidar_localization::UDPMessage::printPayload(encoder_measurement0202) << ") failed"); } @@ -452,10 +445,30 @@ void sick_lidar_localization::UDPSender::messageCbCodeMeasurementMessage0303(con code_measurement0303.telegram_count = msg.telegram_count; code_measurement0303.timestamp = msg.timestamp; code_measurement0303.code = msg.code; - if (!sendUDPPayload(code_measurement0303, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT, m_source_id)) + code_measurement0303.source_id = msg.source_id; + if (code_measurement0303.source_id <= 0) + code_measurement0303.source_id = m_source_id_cfg.getSourceId(3, 3); + if (!sendUDPPayload(code_measurement0303, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT)) ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::messageCbCodeMeasurementMessage0303(): sendUDPPayload(" << sick_lidar_localization::UDPMessage::printPayload(code_measurement0303) << ") failed"); } +/** subscriber callback function for input udp messages type messageCbCodeMeasurementMessage0701 */ +void sick_lidar_localization::UDPSender::messageCbCodeMeasurementMessage0701(const sick_lidar_localization::CodeMeasurementMessage0701 & msg) +{ + sick_lidar_localization::UDPMessage::CodeMeasurementPayload0701 code_measurement0701; + code_measurement0701.telegram_count = msg.telegram_count; + code_measurement0701.timestamp = msg.timestamp; + code_measurement0701.code = msg.code; + code_measurement0701.x_position = msg.x_position; + code_measurement0701.y_position = msg.y_position; + code_measurement0701.heading = msg.heading; + code_measurement0701.source_id = msg.source_id; + if (code_measurement0701.source_id <= 0) + code_measurement0701.source_id = m_source_id_cfg.getSourceId(7, 1); + if (!sendUDPPayload(code_measurement0701, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT)) + ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::messageCbCodeMeasurementMessage0701(): sendUDPPayload(" << sick_lidar_localization::UDPMessage::printPayload(code_measurement0701) << ") failed"); +} + /** subscriber callback function for input udp messages type messageCbLineMeasurementMessage0403 */ void sick_lidar_localization::UDPSender::messageCbLineMeasurementMessage0403(const sick_lidar_localization::LineMeasurementMessage0403 & msg) { @@ -464,7 +477,10 @@ void sick_lidar_localization::UDPSender::messageCbLineMeasurementMessage0403(con line_measurement0403.timestamp = msg.timestamp; line_measurement0403.num_lanes = msg.num_lanes; line_measurement0403.lanes = msg.lanes; - if (!sendUDPPayload(line_measurement0403, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT, m_source_id)) + line_measurement0403.source_id = msg.source_id; + if (line_measurement0403.source_id <= 0) + line_measurement0403.source_id = m_source_id_cfg.getSourceId(4, 3); + if (!sendUDPPayload(line_measurement0403, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT)) ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::messageCbLineMeasurementMessage0403(): sendUDPPayload(" << sick_lidar_localization::UDPMessage::printPayload(line_measurement0403) << ") failed"); } @@ -479,7 +495,10 @@ void sick_lidar_localization::UDPSender::messageCbLineMeasurementMessage0404(con line_measurement0404.lcp3 = msg.lcp3; line_measurement0404.cnt_lpc = msg.cnt_lpc; line_measurement0404.reserved = 0; - if (!sendUDPPayload(line_measurement0404, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT, m_source_id)) + line_measurement0404.source_id = msg.source_id; + if (line_measurement0404.source_id <= 0) + line_measurement0404.source_id = m_source_id_cfg.getSourceId(4, 4); + if (!sendUDPPayload(line_measurement0404, UDP_HEADER_BIG_ENDIAN_DEFAULT, UDP_PAYLOAD_BIG_ENDIAN_DEFAULT)) ROS_ERROR_STREAM("## ERROR sick_lidar_localization::UDPSender::messageCbLineMeasurementMessage0404(): sendUDPPayload(" << sick_lidar_localization::UDPMessage::printPayload(line_measurement0404) << ") failed"); } #endif // __ROS_VERSION > 0 diff --git a/srv/LocStartLocalizingSrv.srv b/srv/LocStartSrv.srv similarity index 64% rename from srv/LocStartLocalizingSrv.srv rename to srv/LocStartSrv.srv index e0e9e3d..9e15ea7 100644 --- a/srv/LocStartLocalizingSrv.srv +++ b/srv/LocStartSrv.srv @@ -1,7 +1,7 @@ -# Definition of ROS service LocStartLocalizing for sick localization. +# Definition of ROS service LocStart for sick localization. # -# ROS service LocStartLocalizing starts localization -# by sending cola command ("sMN LocStartLocalizing"). +# ROS service LocStart starts localization +# by sending cola command ("sMN LocStart"). # # See Telegram-Listing-v1.1.0.241R.pdf for further details about # Cola telegrams and this command. diff --git a/test/config/rviz2_sick_lidar_localization_pointcloud.rviz2 b/test/config/rviz2_sick_lidar_localization_pointcloud.rviz2 index a13734f..2bc6a93 100644 --- a/test/config/rviz2_sick_lidar_localization_pointcloud.rviz2 +++ b/test/config/rviz2_sick_lidar_localization_pointcloud.rviz2 @@ -6,8 +6,9 @@ Panels: Expanded: - /Global Options1 - /Status1 - - /PointCloud21 - /TF1 + - /TF1/Frames1 + - /TF1/Tree1 Splitter Ratio: 0.5 Tree Height: 617 - Class: rviz_common/Selection @@ -44,63 +45,42 @@ Visualization Manager: Plane Cell Count: 10 Reference Frame: Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: PointCloud2 - Position Transformer: XYZ - Selectable: true - Size (Pixels): 50 - Size (m): 0.10000000149011612 - Style: Flat Squares - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /cloud - Use Fixed Frame: true - Use rainbow: true - Value: true - Class: rviz_default_plugins/TF Enabled: true Frame Timeout: 15 Frames: All Enabled: true - cloud: + lls: Value: true - sick_lidar_localization: + map: Value: true Marker Scale: 5 Name: TF Show Arrows: true Show Axes: true - Show Names: false + Show Names: true Tree: - cloud: - sick_lidar_localization: + map: + lls: {} Update Interval: 0 Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: MarkerArray + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /lls/marker + Value: false Enabled: true Global Options: Background Color: 48; 48; 48 - Fixed Frame: cloud + Fixed Frame: map Frame Rate: 30 Name: root Tools: @@ -174,5 +154,5 @@ Window Geometry: Views: collapsed: true Width: 1200 - X: 344 - Y: 60 + X: 1284 + Y: 66 diff --git a/test/config/rviz2_win64_sick_lidar_localization_pointcloud.rviz b/test/config/rviz2_win64_sick_lidar_localization_pointcloud.rviz index a4f5d62..9bed1bd 100644 --- a/test/config/rviz2_win64_sick_lidar_localization_pointcloud.rviz +++ b/test/config/rviz2_win64_sick_lidar_localization_pointcloud.rviz @@ -6,8 +6,9 @@ Panels: Expanded: - /Global Options1 - /Status1 - - /PointCloud21 - /TF1 + - /TF1/Frames1 + - /MarkerArray1/Topic1 Splitter Ratio: 0.5 Tree Height: 757 - Class: rviz_common/Selection @@ -44,63 +45,42 @@ Visualization Manager: Plane Cell Count: 10 Reference Frame: Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: PointCloud2 - Position Transformer: XYZ - Selectable: true - Size (Pixels): 3 - Size (m): 0.05000000074505806 - Style: Flat Squares - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /cloud - Use Fixed Frame: true - Use rainbow: true - Value: true - Class: rviz_default_plugins/TF Enabled: true Frame Timeout: 15 Frames: All Enabled: true - cloud: + lls: Value: true - sick_lidar_localization: + map: Value: true Marker Scale: 5 Name: TF Show Arrows: true Show Axes: true - Show Names: false + Show Names: true Tree: - cloud: - sick_lidar_localization: + map: + lls: {} Update Interval: 0 Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: false + Name: MarkerArray + Namespaces: + {} + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /lls/marker + Value: false Enabled: true Global Options: Background Color: 48; 48; 48 - Fixed Frame: cloud + Fixed Frame: map Frame Rate: 30 Name: root Tools: @@ -174,5 +154,5 @@ Window Geometry: Views: collapsed: true Width: 1656 - X: 404 - Y: 121 + X: 641 + Y: 71 diff --git a/test/config/rviz_sick_lidar_localization_pointcloud.rviz b/test/config/rviz_sick_lidar_localization_pointcloud.rviz index e0bf245..8d35953 100644 --- a/test/config/rviz_sick_lidar_localization_pointcloud.rviz +++ b/test/config/rviz_sick_lidar_localization_pointcloud.rviz @@ -5,10 +5,9 @@ Panels: Property Tree Widget: Expanded: - /Global Options1 - - /PointCloud21 - /TF1 - /TF1/Frames1 - - /TF1/Tree1 + - /MarkerArray1/Namespaces1 Splitter Ratio: 0.5 Tree Height: 848 - Class: rviz/Selection @@ -26,10 +25,9 @@ Panels: Name: Views Splitter Ratio: 0.5 - Class: rviz/Time - Experimental: false Name: Time SyncMode: 0 - SyncSource: PointCloud2 + SyncSource: "" Preferences: PromptSaveOnExit: true Toolbars: @@ -55,61 +53,49 @@ Visualization Manager: Plane Cell Count: 10 Reference Frame: Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: PointCloud2 - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 10 - Size (m): 0.009999999776482582 - Style: Points - Topic: /cloud - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - Class: rviz/TF Enabled: true Frame Timeout: 15 Frames: All Enabled: true - cloud: + lls: Value: true - sick_lidar_localization: + map: Value: true + Marker Alpha: 1 Marker Scale: 5 Name: TF Show Arrows: true Show Axes: true Show Names: true Tree: - cloud: - sick_lidar_localization: + map: + lls: {} Update Interval: 0 Value: true + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /lls/marker + Name: MarkerArray + Namespaces: + {} + Queue Size: 100 + Value: false + - Alpha: 1 + Class: rviz/Axes + Enabled: false + Length: 1 + Name: Axes + Radius: 0.10000000149011612 + Reference Frame: + Show Trail: false + Value: false Enabled: true Global Options: Background Color: 48; 48; 48 Default Light: true - Fixed Frame: cloud + Fixed Frame: map Frame Rate: 30 Name: root Tools: @@ -133,12 +119,13 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 14.366720199584961 + Distance: 18.02161407470703 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false + Field of View: 0.7853981852531433 Focal Point: X: -4.796201705932617 Y: 4.4470672607421875 @@ -150,7 +137,6 @@ Visualization Manager: Near Clip Distance: 0.009999999776482582 Pitch: 0.7803980112075806 Target Frame: - Value: Orbit (rviz) Yaw: 0.7153980731964111 Saved: ~ Window Geometry: @@ -159,7 +145,7 @@ Window Geometry: Height: 1145 Hide Left Dock: false Hide Right Dock: true - QMainWindow State: 000000ff00000000fd000000040000000000000156000003dbfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003db000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006340000003efc0100000002fb0000000800540069006d0065010000000000000634000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004d8000003db00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd000000040000000000000156000003dbfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003db000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006340000003efc0100000002fb0000000800540069006d0065010000000000000634000003bc00fffffffb0000000800540069006d00650100000000000004500000000000000000000004d8000003db00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: @@ -169,5 +155,5 @@ Window Geometry: Views: collapsed: true Width: 1588 - X: 724 + X: 908 Y: 27 diff --git a/test/data/simu_unittests/linux_unittest_gen_sick_caller.txt b/test/data/simu_unittests/linux_unittest_gen_sick_caller.txt index 713dc56..ece34cd 100644 --- a/test/data/simu_unittests/linux_unittest_gen_sick_caller.txt +++ b/test/data/simu_unittests/linux_unittest_gen_sick_caller.txt @@ -16,7 +16,7 @@ { "request": "LocSetOdometryActive", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, { "request": "LocSetRecordingActive", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, { "request": "LocSetRingBufferRecordingActive", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, -{ "request": "LocStartLocalizing", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, +{ "request": "LocStart", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, { "request": "LocStop", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, { "request": "LocSwitchMap", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, { "request": "LocGetLocalizationStatus", "response": { "data": { "details": "LOCALIZING", "locStatus": 1 }, "header": { "message": "Ok", "status": 0 } } }, diff --git a/test/data/simu_unittests/win64_unittest_gen_sick_caller.txt b/test/data/simu_unittests/win64_unittest_gen_sick_caller.txt index 713dc56..ece34cd 100644 --- a/test/data/simu_unittests/win64_unittest_gen_sick_caller.txt +++ b/test/data/simu_unittests/win64_unittest_gen_sick_caller.txt @@ -16,7 +16,7 @@ { "request": "LocSetOdometryActive", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, { "request": "LocSetRecordingActive", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, { "request": "LocSetRingBufferRecordingActive", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, -{ "request": "LocStartLocalizing", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, +{ "request": "LocStart", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, { "request": "LocStop", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, { "request": "LocSwitchMap", "response": { "data": { "success": true }, "header": { "message": "Ok", "status": 0 } } }, { "request": "LocGetLocalizationStatus", "response": { "data": { "details": "LOCALIZING", "locStatus": 1 }, "header": { "message": "Ok", "status": 0 } } }, diff --git a/test/rest_server/python/README.md b/test/rest_server/python/README.md new file mode 100644 index 0000000..5a9a853 --- /dev/null +++ b/test/rest_server/python/README.md @@ -0,0 +1,61 @@ +# Test scripts for sick_lidar_localization + +Folder `test/rest_server/python` contains the following python test scripts for sick_lidar_localization: + +* [lls_pcapng_player.py](lls_pcapng_player.py): plays a pcapng-file recorded by Wireshark and broadcasts udp messages to simulate a localization controller.
+ Usage example: + ``` + python3 test/rest_server/python/lls_pcapng_player.py --pcap_filename test/data/wireshark/20210816_lidarloc2_2.0.0.14R_moving.pcapng + ``` + +* [lls_udp_receiver.py](lls_udp_receiver.py): receives udp messages from sick_lidar_localization, parses the messages and prints received localization data.
+ Usage example: + ``` + python3 test/rest_server/python/lls_udp_receiver.py --udp_port=5009 + ``` + +* [lls_udp_sender.py](lls_udp_sender.py): generates synthetical datagrams to emulate a local localization controller and sends corresponding UDP messages.
+ Usage example: + ``` + python3 test/rest_server/python/lls_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --max_message_count=300 + ``` + +* [send_odometry_message_0104.py](send_odometry_message_0104.py): creates and publishes odometry messages type 1 version 4 (ROS-1)
+ Usage example: + ``` + python test/rest_server/python/send_odometry_message_0104.py + ``` + Alternatively or on ROS-2, odometry messages can be published e.g. by + ``` + ros2 topic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 '{telegram_count: 1000001, timestamp: 123456789, source_id: 0, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' + ``` + +* [send_odometry_message_0105.py](send_odometry_message_0105.py): creates and publishes odometry messages type 1 version 5 (ROS-1)
+ Usage example: + ``` + python test/rest_server/python/send_odometry_message_0105.py + ``` + Alternatively or on ROS-2, odometry messages can be published e.g. by + ``` + ros2 topic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 '{telegram_count: 1000002, timestamp: 123456780, source_id: 0, x_position: -1234, y_position: -1234, heading: 1234}' + ``` + +* [send_ros_odom_messages.py](send_ros_odom_messages.py): creates and publishes ROS messages of type `nav_msgs.msg.Odometry` (ROS-1)
+ Usage example: + ``` + python test/rest_server/python/send_ros_odom_messages.py + ``` + +* [send_ros2_odom_messages.py](send_ros2_odom_messages.py): creates and publishes ROS messages of type `nav_msgs.msg.Odometry` (ROS-2)
+ Usage example: + ``` + python3 test/rest_server/python/send_ros2_odom_messages.py + ``` + +* [sick_rest_server.py](sick_rest_server.py): implements a tiny rest server, responds to http get- and post-request for local offline tests.
+ Usage example: + ``` + sudo python3 ../rest_server/python/sick_rest_server.py + ``` + +See the bash- and cmd-scripts in folder `test/scripts` for complete usage examples. diff --git a/test/rest_server/python/sim_pcapng_player.py b/test/rest_server/python/lls_pcapng_player.py similarity index 99% rename from test/rest_server/python/sim_pcapng_player.py rename to test/rest_server/python/lls_pcapng_player.py index 13fbf4a..eacd569 100644 --- a/test/rest_server/python/sim_pcapng_player.py +++ b/test/rest_server/python/lls_pcapng_player.py @@ -37,7 +37,7 @@ udp_port = cli_args.udp_port print("pcapng_player {} initializing, udp port {} ...".format(pcap_filename, udp_port)) - # Init upd sender + # Init udp sender udp_sender_socket = socket.socket(socket.AF_INET, socket.SOCK_DGRAM, socket.IPPROTO_UDP) # UDP socket udp_sender_socket.setsockopt(socket.SOL_SOCKET, socket.SO_BROADCAST, 1) # Enable broadcasting mode print("pcapng_player: sending on udp port {}".format(udp_port)) diff --git a/test/rest_server/python/sim_udp_receiver.py b/test/rest_server/python/lls_udp_receiver.py similarity index 85% rename from test/rest_server/python/sim_udp_receiver.py rename to test/rest_server/python/lls_udp_receiver.py index 855ee1f..7d0684f 100644 --- a/test/rest_server/python/sim_udp_receiver.py +++ b/test/rest_server/python/lls_udp_receiver.py @@ -29,12 +29,12 @@ def decode(payload, big_endian = True, signed_value = False): cli_args = arg_parser.parse_args() udp_port = cli_args.udp_port - # Init upd receiver + # Init udp receiver udp_socket = socket.socket(socket.AF_INET, socket.SOCK_DGRAM, socket.IPPROTO_UDP) # UDP socket udp_socket.bind(("", udp_port)) # Receive udp datagrams - print("sim_udp_receiver listening on port {} ...".format(udp_port)) + print("lls_udp_receiver listening on port {} ...".format(udp_port)) while True: data, addr = udp_socket.recvfrom(1024) # buffer size is 1024 bytes if len(data) >= 16 and data[0:4] == b"\x4d\x4f\x50\x53": # 4 byte Magic 0x4d 0x4f 0x50 0x53 ("MOPS") @@ -56,7 +56,7 @@ def decode(payload, big_endian = True, signed_value = False): header_is_big_endian = False payload_is_big_endian = True else: - print("## ERROR sim_udp_receiver: unknown message header encoding") + print("## ERROR lls_udp_receiver: unknown message header encoding") continue payloadlen = decode(data[6:8], header_is_big_endian) @@ -64,15 +64,7 @@ def decode(payload, big_endian = True, signed_value = False): msgtypeversion = decode(data[12:13], header_is_big_endian) # int(data[13]) print("{} byte udp message received, msgtype {}, msgtypeversion {}, {} byte payload".format(len(data), msgtype, msgtypeversion, payloadlen)) - if msgtype == 1 and msgtypeversion == 1 and payloadlen == 32: - telegram_count = decode(data[16:24], payload_is_big_endian) - timestamp = decode(data[24:32], payload_is_big_endian) - x_velocity = decode(data[32:36], payload_is_big_endian, True) - y_velocity = decode(data[36:40], payload_is_big_endian, True) - angular_velocity = decode(data[40:48], payload_is_big_endian, True) - print("OdometryMessage0101:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", x_velocity:" + str(x_velocity) + ", y_velocity:" + str(y_velocity) + ", angular_velocity:" + str(angular_velocity) + "}") - - elif msgtype == 1 and msgtypeversion == 4 and payloadlen == 24: + if msgtype == 1 and msgtypeversion == 4 and payloadlen == 24: telegram_count = decode(data[16:24], payload_is_big_endian) timestamp = decode(data[24:32], payload_is_big_endian) x_velocity = decode(data[32:34], payload_is_big_endian, True) @@ -121,8 +113,18 @@ def decode(payload, big_endian = True, signed_value = False): cnt_lpc = int(data[38]) # decode(data[38:39], payload_is_big_endian) print("LineMeasurementMessage0404:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", lcp1:" + str(lcp1) + ", lcp2:" + str(lcp2) + ", lcp3:" + str(lcp3) + ", cnt_lpc:" + str(cnt_lpc) + "}") + elif msgtype == 7 and msgtypeversion == 1 and payloadlen >= 30: + telegram_count = decode(data[16:24], payload_is_big_endian) + timestamp = decode(data[24:32], payload_is_big_endian) + codelength = decode(data[32:34], payload_is_big_endian, True) + code = data[34:(34+codelength)].decode("utf-8") + x_position = decode(data[(34+codelength):(34+codelength+4)], payload_is_big_endian, True) + y_position = decode(data[(34+codelength+4):(34+codelength+8)], payload_is_big_endian, True) + heading = decode(data[(34+codelength+8):(34+codelength+12)], payload_is_big_endian, True) + print("CodeMeasurementMessage0701:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", code:" + str(code) + ", x_position:" + str(x_position) + ", y_position:" + str(y_position) + ", heading:" + str(heading) + "}") + else: - print("## ERROR sim_udp_receiver: unknown message type or wrong payload length") + print("## ERROR lls_udp_receiver: unknown message type or wrong payload length") \ No newline at end of file diff --git a/test/rest_server/python/sim_udp_sender.py b/test/rest_server/python/lls_udp_sender.py similarity index 93% rename from test/rest_server/python/sim_udp_sender.py rename to test/rest_server/python/lls_udp_sender.py index 04fc14c..5aeb768 100644 --- a/test/rest_server/python/sim_udp_sender.py +++ b/test/rest_server/python/lls_udp_sender.py @@ -1,5 +1,5 @@ """ - sim_udp_sender generates synthetical datagrams to emulate a local localization server + lls_udp_sender generates synthetical datagrams to emulate a local localization server (specified by LocalizationController 2.0 UDP Data Format) and sends the UDP packages on port 5010. """ @@ -9,6 +9,8 @@ import socket import time +source_id = 0x0001 + # Encodes an integer to a bytearray of size in little or big endian. def encode(value, length, big_endian = False): payload = bytearray(length) @@ -45,7 +47,7 @@ def createHeader(msg_type, msg_type_version, payload_length, big_endian): payload[8:10] = encode(0x06c2, 2, True) # 2 byte PayloadType 0x06c2 for little endian payload[10:12] = encode(msg_type, 2, True) # 2 byte MsgType payload[12:14] = encode(msg_type_version, 2, True) # 2 byte MsgTypeVersion - payload[14:16] = encode(0x0001, 2, True) # 2 byte SourceID 0x0001 + payload[14:16] = encode(source_id, 2, True) # 2 byte SourceID 0x0001 return payload # Creates and returns an odometry message (type 1, version 4, 16 byte message header + 24 byte payload) @@ -57,7 +59,7 @@ def createOdometryMessage0104(telegram_count, timestamp, x_velocity, y_velocity, message[32:34] = encode(x_velocity, 2, big_endian) # 2 byte X-velocity int16 [mm/s] message[34:36] = encode(y_velocity, 2, big_endian) # 2 byte Y-velocity int16 [mm/s] message[36:40] = encode(angular_velocity, 4, big_endian) # 4 byte angular velocity int32 [mdeg/s] - message_str = "OdometryPayload0104:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", x_velocity:" + str(x_velocity) + ", y_velocity:" + str(y_velocity) + ", angular_velocity:" + str(angular_velocity) + "}" + message_str = "OdometryPayload0104:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", source_id:" + str(source_id) + ", x_velocity:" + str(x_velocity) + ", y_velocity:" + str(y_velocity) + ", angular_velocity:" + str(angular_velocity) + "}" return message, message_str # Creates and returns an odometry message (type 1, version 5, 16 byte message header + 40 byte payload) @@ -69,7 +71,7 @@ def createOdometryMessage0105(telegram_count, timestamp, x_position, y_position, message[32:40] = encode(x_position, 8, big_endian) # 8 byte X-position int64 [mm] message[40:48] = encode(y_position, 8, big_endian) # 8 byte Y-position int64 [mm] message[48:56] = encode(heading, 8, big_endian) # 8 byte heading int64 [mdeg] - message_str = "OdometryPayload0105:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", x_position:" + str(x_position) + ", y_position:" + str(y_position) + ", heading:" + str(heading) + "}" + message_str = "OdometryPayload0105:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", source_id:" + str(source_id) + ", x_position:" + str(x_position) + ", y_position:" + str(y_position) + ", heading:" + str(heading) + "}" return message, message_str # Creates and returns an code measurement message (type 3, version 4, 16 byte message header + 24 byte payload) @@ -80,7 +82,7 @@ def createCodeMeasurementMessage0304(telegram_count, timestamp, code, distance, message[24:32] = encode(timestamp, 8, big_endian) # 8 byte Timestamp uint64 [microseconds] message[32:36] = encode(code, 4, big_endian) # 4 byte Code int32 message[36:40] = encode(distance, 4, big_endian) # 4 byte Distance int32 [mm] - message_str = "CodeMeasurementPayload0304:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", code:" + str(code) + ", distance:" + str(distance) + "}" + message_str = "CodeMeasurementPayload0304:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", source_id:" + str(source_id) + ", code:" + str(code) + ", distance:" + str(distance) + "}" return message, message_str # Creates and returns a line measurement message (type 4, version 3, 16 byte message header + variable payload) @@ -93,7 +95,7 @@ def createLineMeasurementMessage0403(telegram_count, timestamp, lanes, big_endia message[32] = len(lanes) # 1 byte NumOfLanes uint8 for n, lane in enumerate(lanes): # variable number of lanes message[33+2*n+0:33+2*n+2] = encode(lane, 2, big_endian) # 2 byte lane int16 - message_str = "LineMeasurementPayload0403:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", num_lanes:" + str(len(lanes)) + ", lanes:[" + message_str = "LineMeasurementPayload0403:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", source_id:" + str(source_id) + ", num_lanes:" + str(len(lanes)) + ", lanes:[" for n, lane in enumerate(lanes): if n > 0: message_str = message_str + "," @@ -112,7 +114,7 @@ def createLineMeasurementMessage0404(telegram_count, timestamp, lcp1, lcp2, lcp3 message[36:38] = encode(lcp3, 2, big_endian) # 2 byte lcp3 int16 [mm] message[38] = cnt_lpc # 1 byte cnt_lpc uint8 message[39] = 0 # 1 byte memory alignment - message_str = "LineMeasurementPayload0404:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", lcp1:" + str(lcp1) + ", lcp2:" + str(lcp2) + ", lcp3:" + str(lcp3) + ", cnt_lpc:" + str(cnt_lpc) + "}" + message_str = "LineMeasurementPayload0404:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", source_id:" + str(source_id) + ", lcp1:" + str(lcp1) + ", lcp2:" + str(lcp2) + ", lcp3:" + str(lcp3) + ", cnt_lpc:" + str(cnt_lpc) + "}" return message, message_str # Creates and returns a LocalizationController result message (type 5, version 2, 16 byte message header + 40 byte payload) @@ -128,7 +130,7 @@ def createResultMessage0502(telegram_count, timestamp, x, y, heading, big_endian message[53] = 90 # 1 byte MapMatchingStatus [0...100, 90: Good] message[54] = 0 # 2 byte Reserved for memory alignment message[55] = 0 # 2 byte Reserved for memory alignment - message_str = "LocalizationControllerResultPayload0502:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", x:" + str(x) + ", y:" + str(y) + ", heading:" + str(heading) + ", loc_status:10, map_match_status:90}" + message_str = "LocalizationControllerResultPayload0502:{" + "telegram_count:" + str(telegram_count) + ", timestamp:" + str(timestamp) + ", source_id:" + str(source_id) + ", x:" + str(x) + ", y:" + str(y) + ", heading:" + str(heading) + ", loc_status:10, map_match_status:90}" return message, message_str if __name__ == "__main__": @@ -149,14 +151,14 @@ def createResultMessage0502(telegram_count, timestamp, x, y, heading, big_endian udp_send_rate = cli_args.udp_send_rate udp_output_logfile = cli_args.udp_output_logfile max_message_count = cli_args.max_message_count - print("sim_udp_sender --udp_port={} --udp_send_rate={} --udp_output_logfile={} --max_message_count={} initializing...".format(udp_port, udp_send_rate, udp_output_logfile, max_message_count)) + print("lls_udp_sender --udp_port={} --udp_send_rate={} --udp_output_logfile={} --max_message_count={} initializing...".format(udp_port, udp_send_rate, udp_output_logfile, max_message_count)) # Setup if udp_output_logfile != "" and os.path.exists(udp_output_logfile): os.remove(udp_output_logfile) unittestEncode() - # Init upd sender + # Init udp sender udp_sender_socket = socket.socket(socket.AF_INET, socket.SOCK_DGRAM, socket.IPPROTO_UDP) # UDP socket udp_sender_socket.setsockopt(socket.SOL_SOCKET, socket.SO_BROADCAST, 1) # Enable broadcasting mode print("udp_sender: sending on udp port {}".format(udp_port)) @@ -227,7 +229,7 @@ def createResultMessage0502(telegram_count, timestamp, x, y, heading, big_endian if message is None: telegram_idx = -1 msg_type_idx = msg_type_idx + 1 - if msg_type_idx > 5: + if msg_type_idx > 7: msg_type_idx = 0 continue; print("udp_sender: sending {} byte message = {}".format(len(message), message.hex())) diff --git a/test/rest_server/python/scripts_LLS1-OdometryUDPSender.py b/test/rest_server/python/scripts_LLS1-OdometryUDPSender.py deleted file mode 100644 index fe6dcc7..0000000 --- a/test/rest_server/python/scripts_LLS1-OdometryUDPSender.py +++ /dev/null @@ -1,182 +0,0 @@ -import socket -import math - -import time -starttime=time.time() - -# Network Socket -global sock - -# IP and Port for UDP Telegrams -UDP_IP = "192.168.0.1" # "192.168.1.1" -UDP_PORT = 5009 - -# Source ID from odom sender -> has to match the ID in the configuration file -SourceID = 21 # 31 - -global telegramCount -telegramCount = 0 - -#Found on https://stackoverflow.com/questions/25239423/crc-ccitt-16-bit-python-manual-calculation -#Using preset 0xffff instead of 0 (like in edp) -class CRC16: - def __init__(self): - self.poly = 0x1021 #CCITT polynom of CRC16 - self.preset = 0xffff - self._table = [ self._initial(i) for i in range(256)] - - def _initial(self, c): - crc = 0 - c = c << 8 - for _ in range(8): - if (crc ^ c) & 0x8000: - crc = (crc << 1) ^ self.poly - else: - crc = crc << 1 - c = c << 1 - return crc - - def _update_crc(self, crc, c): - cc = 0xff & c - tmp = (crc >> 8) ^ cc - crc = (crc << 8) ^ self._table[tmp & 0xff] - crc = crc & 0xffff - return crc - - def compute(self, msg): - crc = self.preset - for c in msg: - crc = self._update_crc(crc, c) - return crc - - - -def toHexPad(decINT, digits): - # Number of bits given the number of digits the hex string has (e.g. 4 Hex digits = 2 Byte = 16 Bit) - numBits = digits*4 - # Convert to hex (considers also negative numbers) + remove "\x" prefix - decINTHex = hex((decINT + (1 << numBits)) % (1 << numBits))[2:] - # Ensure correct length of hex string - return decINTHex.zfill(digits) - -#------------------------------------------------------------------------------------------ - -def sendOdometryTelegram(vx, vy, omega, ts): - - # Import socket - global sock - #Telegram counter - global telegramCount - - # ------------------------------------------------------------------------------------------------------------------------------------------------------ - #| HEADER | PAYLOAD | - # ------------------------------------------------------------------------------------------------------------------------------------------------------ - # MagicWord PayloadLength payloadType(endianess) MsgType MsgTypeVersion SourceID | telegramCounter timestamp Vx Vy Omega | - # 534d4f50 000C 0642 0000 0000 0000 | 00000001 00000000 0001 FFFF 00000001 | - # ------------------------------------------------------------------------------------------------------------------------------------------------------ - - - #---------------- HEADER --------------------------- - # Magic Word - magicWordInByte = 'SMOP'.encode('utf-8') - message = magicWordInByte.hex() - # Payload length (2Byte) in hex (length = 12 byte here) - message = message + toHexPad(16, 4) - # Using big endian - message = message + toHexPad(1602, 4) - # MsgType - message = message + toHexPad(1, 4) - # MsgType Version - message = message + toHexPad(1, 4) - # SourceID - message = message + toHexPad(SourceID, 4) - - #---------------- PAYLOAD --------------------------- - - # Add Telegram count - message = message + toHexPad(telegramCount, 8) - # Timestamp [in ms] - message = message + toHexPad(ts, 8) - # Vx [in mm/s] - message = message + toHexPad(vx, 4) - # Vy [in mm/s] - message = message + toHexPad(vy, 4) - # Omega [in mdeg/s] - message = message + toHexPad(omega, 8) - - - #print('########### DECIMAL ###################') - #print(telegramCount) - #print ("Timestamp :", ts) - #print ("Vx :", vx) - #print ("Vy :", vy) - #print ("Vomega :", omega) - - #print('########### HEX ###################') - #print(toHexPad(telegramCount, 8)) - #print(toHexPad(toHexPad(ts, 8)) - #print(toHexPad(vx, 4)) - #print(toHexPad(vy, 4)) - #print(toHexPad(omega, 8)) - - - # Compute CRC - CRC = CRC16() - crcIN = CRC.compute(bytes.fromhex(message)) - msgCRC16 = toHexPad(crcIN,4) - #print(msgCRC16) - - #Append crc16 to message - #message = message + msgCRC16 - #print ("message:", message) - - # Convert to bytes object - MESSAGEHEX = bytes.fromhex(message) - #print ("message:", MESSAGEHEX) - - # Send datagram - sock.sendto(MESSAGEHEX, (UDP_IP, UDP_PORT)) - - # Increment telegram counter - telegramCount = telegramCount + 1 - - -def startSendingTelegrams(): - - # Send a few telegram - #for i in range(0,5000,25): - # sendOdometryTelegram(1,0,-1, i) - ts = 0 - prevts = 0 - angVel = 10000 - while True: - ts = int(time.time()*1000) - sendOdometryTelegram(200,0,angVel, ts) - #if angVel == 0: - # angVel=25000 - #else: - # angVel=0 - # Delta between telegram timestamps - print("Delta ts: ", ts - prevts, " ms") - # Update previous telegram timestamps - prevts = ts - # Sleep in order to reach 25ms odom telegram cycle time - time.sleep(0.025 - (time.time() % 0.025)) - - - -def initilize(): - global sock - - print ("UDP target IP:", UDP_IP) - print ("UDP target port:", UDP_PORT) - - # UDP - sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) - - # Start sending odometry messages - startSendingTelegrams() - - -if __name__ == '__main__': - initilize() \ No newline at end of file diff --git a/test/rest_server/python/scripts_LLS2-OdometryUDPSender.py b/test/rest_server/python/scripts_LLS2-OdometryUDPSender.py deleted file mode 100644 index 3cc5589..0000000 --- a/test/rest_server/python/scripts_LLS2-OdometryUDPSender.py +++ /dev/null @@ -1,122 +0,0 @@ -import socket -from struct import * -import time - -# IP of localization controller -LLS_DEVICE_IP = "192.168.0.1" # "192.168.0.70" - -# Input port specified in lidarloc_config.yml (communication/smopUdp/input/port) -CONFIG_UDP_PORT = 5009 -# Source ID for odom messages specified in lidarloc_config.yml (vehicle/odometer/external/interface/sourceId) -CONFIG_ODOM_SOURCE_ID = 21 # 100 - -# Network Socket -global sock -# Telegram Count -global telegramCount -telegramCount = 0 - -#------------------------------------------------------------------------------------------ - -def sendOdometryTelegram(vx, vy, omega, ts): - - # Import socket - global sock - #Telegram counter - global telegramCount - - # Odom Telegram Header Data - magicWord = "MOPS" - headerVersion = 2 - payloadLength = 24 - endianess = 1602 - msgType = 1 - msgTypeVersion = 4 - - # Odom Telegram (Header + Payload) - odom_telegram = pack(">4sHHHHHHQQhhi", - magicWord.encode("ASCII"), - headerVersion, - payloadLength, - endianess, - msgType, - msgTypeVersion, - CONFIG_ODOM_SOURCE_ID, - telegramCount, - ts, - vx, - vy, - omega) - - - print('########### DATA ###################') - print("MsgTypeVersion :", msgTypeVersion) - print("SourceID :", CONFIG_ODOM_SOURCE_ID) - print("Vx :", vx) - print("Vy :", vy) - print("Vomega: ", omega) - - # Send datagram - sock.sendto(odom_telegram, (LLS_DEVICE_IP, CONFIG_UDP_PORT)) - - # Increment telegram counter - telegramCount = telegramCount + 1 - - -def startSendingTelegrams(): - # Current and previous timestamp - ts = 0 - prevts = 0 - # Velocity - velX = 0 - velY = 0 - velAng = 0 - # Odom telegram frequency [in seconds] - odom_freq = 0.025 - # Odom message loop - while True: - # Generate timestamp in [us] - ts = int(time.time()*1000000) - # Send odom telegram - sendOdometryTelegram(velX,velY,velAng, ts) - # Delta between telegram timestamps - print("Delta ts: ", (ts - prevts)/1000, " ms") - # Update previous telegram timestamps - prevts = ts - # Sleep in order to reach 25ms odom telegram cycle time - time.sleep(odom_freq - (time.time() % odom_freq)) - - - -def initilize(): - global sock - - print ("UDP target IP:", LLS_DEVICE_IP) - print ("UDP target port:", CONFIG_UDP_PORT) - - # UDP - sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) - - # Start sending odometry messages - startSendingTelegrams() - - -if __name__ == '__main__': - initilize() - - - - - - - - - - - - - - - - - diff --git a/test/rest_server/python/send_odometry_message_0101.py b/test/rest_server/python/send_odometry_message_0101.py deleted file mode 100644 index f825c2c..0000000 --- a/test/rest_server/python/send_odometry_message_0101.py +++ /dev/null @@ -1,66 +0,0 @@ -import math -import os -import rospy -import time -starttime=time.time() - -from sick_lidar_localization.msg import OdometryMessage0101 - -global telegramCount -telegramCount = 0 - -#------------------------------------------------------------------------------------------ - -def sendOdometryTelegram(pub, vx, vy, omega, ts): - - #Telegram counter - global telegramCount - - #odometry_msg_str = "{{telegram_count: {}, timestamp: {}, x_velocity: {}, y_velocity: {}, angular_velocity: {}}}".format(telegramCount, ts, vx, vy, omega) - #command = "rostopic pub --once /localizationcontroller/in/odometry_message_0101 sick_lidar_localization/OdometryMessage0101 \"{}\"".format(odometry_msg_str) - #print(command) - #os.system(command) - - odom_msg = OdometryMessage0101() - odom_msg.telegram_count = telegramCount - odom_msg.timestamp = ts - odom_msg.x_velocity = vx - odom_msg.y_velocity = vy - odom_msg.angular_velocity = omega - pub.publish(odom_msg) - - # Increment telegram counter - telegramCount = telegramCount + 1 - -def startSendingTelegrams(pub): - - # Send a few telegram - ts = 0 - prevts = 0 - angVel = -10000 - while telegramCount < 300: - if (telegramCount % 200) == 0: - angVel = -angVel - ts = int(time.time()*1000) - sendOdometryTelegram(pub, 200, 0, angVel, ts) - #if angVel == 0: - # angVel=25000 - #else: - # angVel=0 - # Delta between telegram timestamps - print("Delta ts: ", ts - prevts, " ms") - # Update previous telegram timestamps - prevts = ts - # Sleep in order to reach 25ms odom telegram cycle time - time.sleep(0.025 - (time.time() % 0.025)) - -def initialize(): - - rospy.init_node("send_odometry_message_0101", anonymous=True) - pub = rospy.Publisher("/localizationcontroller/in/odometry_message_0101", OdometryMessage0101, queue_size=10) - - # Start sending odometry messages - startSendingTelegrams(pub) - -if __name__ == '__main__': - initialize() \ No newline at end of file diff --git a/test/rest_server/python/send_odometry_message_0105.py b/test/rest_server/python/send_odometry_message_0105.py index 6700b65..b5165d3 100644 --- a/test/rest_server/python/send_odometry_message_0105.py +++ b/test/rest_server/python/send_odometry_message_0105.py @@ -38,7 +38,7 @@ def startSendingTelegrams(pub): if (telegramCount % 200) == 0: delta_heading = -delta_heading ts = int(time.time()*1000000) - sendOdometryTelegram(pub, 2000, 1000, heading, ts) + sendOdometryTelegram(pub, 2000, 1000, int(heading), ts) heading = heading + delta_heading # Delta between telegram timestamps print("Delta ts: ", ts - prevts, " microsec") diff --git a/test/rest_server/python/sick_rest_server.py b/test/rest_server/python/sick_rest_server.py index 7b149ca..b1b0eff 100644 --- a/test/rest_server/python/sick_rest_server.py +++ b/test/rest_server/python/sick_rest_server.py @@ -44,7 +44,7 @@ "LocSetOdometryActive" : { "header": std_header_ok, "data": { "success": True } }, "LocSetRecordingActive" : { "header": std_header_ok, "data": { "success": True } }, "LocSetRingBufferRecordingActive" : { "header": std_header_ok, "data": { "success": True } }, - "LocStartLocalizing" : { "header": std_header_ok, "data": { "success": True } }, + "LocStart" : { "header": std_header_ok, "data": { "success": True } }, "LocStop" : { "header": std_header_ok, "data": { "success": True } }, "LocSwitchMap" : { "header": std_header_ok, "data": { "success": True } }, "LocGetLocalizationStatus" : { "header": std_header_ok, "data": { "locStatus": 1, "details": "LOCALIZING" } }, diff --git a/test/scripts/make_ros2.cmd b/test/scripts/make_ros2.cmd index a171d23..b61bf26 100644 --- a/test/scripts/make_ros2.cmd +++ b/test/scripts/make_ros2.cmd @@ -34,7 +34,6 @@ start "sick_lidar_localization.sln" .\build\sick_lidar_localization\sick_lidar_l @echo. if not exist .\build\sick_lidar_localization\Release\gen_service_call.exe ( @echo colcon build gen_service_call.exe failed & @pause ) else ( @echo Successfully build gen_service_call.exe for ROS-2 Windows ) if not exist .\build\sick_lidar_localization\Release\sick_lidar_localization.exe ( @echo colcon build sick_lidar_localization.exe failed & @pause ) else ( @echo Successfully build sick_lidar_localization.exe for ROS-2 Windows ) -if not exist .\build\sick_lidar_localization\Release\pointcloud_converter.exe ( @echo colcon build pointcloud_converter.exe failed & @pause ) else ( @echo Successfully build pointcloud_converter.exe for ROS-2 Windows ) popd popd diff --git a/test/scripts/run_linux_ros1_simu.bash b/test/scripts/run_linux_ros1_simu.bash index 014b7c8..e96b031 100644 --- a/test/scripts/run_linux_ros1_simu.bash +++ b/test/scripts/run_linux_ros1_simu.bash @@ -41,7 +41,7 @@ function unittest_services() call_service LocSetOdometryActive "{active: 1}" "success: True" call_service LocSetRecordingActive "{active: 1}" "success: True" call_service LocSetRingBufferRecordingActive "{active: 1}" "success: True" - call_service LocStartLocalizing "{}" "success: True" + call_service LocStart "{}" "success: True" call_service LocStop "{}" "success: True" call_service LocSwitchMap "{submapname: \"test.vmap\"}" "success: True" call_service LocGetLocalizationStatus "{}" "locstatus: 1" @@ -50,7 +50,7 @@ function unittest_services() } # -# Run sick_lidar_localization simu on native linux +# Run sick_lidar_localization simu on Linux ROS-1 # printf "\033c" @@ -72,7 +72,7 @@ source /opt/ros/noetic/setup.bash source ./install/setup.bash SICK_LIDAR_LOCALIZATION_ROOT=./src/sick_lidar_localization if [ -d ./src/sick_lidar_localization2_pretest ] ; then SICK_LIDAR_LOCALIZATION_ROOT=./src/sick_lidar_localization2_pretest ; fi -roslaunch sick_lidar_localization sick_lidar_localization.launch hostname:=localhost udp_ip_sim_input:=127.0.0.1 udp_ip_sim_output:=localhost verbose:=1 & +roslaunch sick_lidar_localization sick_lidar_localization.launch hostname:=localhost udp_ip_lls_input:=127.0.0.1 udp_ip_lls_output:=localhost verbose:=1 & sleep 3 # @@ -94,16 +94,15 @@ rostopic echo /localizationcontroller/out/code_measurement_message_0304 & rostopic echo /localizationcontroller/out/line_measurement_message_0403 & rostopic echo /localizationcontroller/out/line_measurement_message_0404 & rostopic echo /localizationcontroller/out/localizationcontroller_result_message_0502 & -python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/sim_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --max_message_count=300 +python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/lls_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --max_message_count=300 sleep 3 # -# Run pointcloud_converter and visualize PointCloud2 messages by rviz: -# rviz -> Add by topic /cloud/PointCloud2 +# Run lls_transform and visualize TF messages by rviz: # rviz -> Add by display type TF # -roslaunch sick_lidar_localization pointcloud_converter.launch & +roslaunch sick_lidar_localization lls_transform.launch & sleep 3 rosrun rviz rviz -d $SICK_LIDAR_LOCALIZATION_ROOT/test/config/rviz_sick_lidar_localization_pointcloud.rviz & sleep 3 @@ -112,35 +111,43 @@ sleep 3 # Start pcapng player sending recorded UDP messages # -python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/sim_pcapng_player.py --pcap_filename $SICK_LIDAR_LOCALIZATION_ROOT/test/data/wireshark/20210816_lidarloc2_2.0.0.14R_moving.pcapng # 20210816_lidarloc2_2.0.0.14R_nonmoving.pcapng +python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/lls_pcapng_player.py --pcap_filename $SICK_LIDAR_LOCALIZATION_ROOT/test/data/wireshark/20210816_lidarloc2_2.0.0.14R_moving.pcapng # 20210816_lidarloc2_2.0.0.14R_nonmoving.pcapng sleep 3 # # Start udp receiver and send UDP input message examples # -python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/sim_udp_receiver.py --udp_port=5009 & -rostopic pub --once /localizationcontroller/in/odometry_message_0101 sick_lidar_localization/OdometryMessage0101 '{telegram_count: 1000001, timestamp: 123456789, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' -rostopic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 '{telegram_count: 1000001, timestamp: 123456789, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' -rostopic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 '{telegram_count: 1000002, timestamp: 123456780, x_position: -1234, y_position: -1234, heading: 1234}' -rostopic pub --once /localizationcontroller/in/encoder_measurement_message_0202 sick_lidar_localization/EncoderMeasurementMessage0202 '{telegram_count: 1000003, timestamp: 123456781, encoder_value: 123456789}' -rostopic pub --once /localizationcontroller/in/code_measurement_message_0303 sick_lidar_localization/CodeMeasurementMessage0303 '{telegram_count: 1000004, timestamp: 123456782, code: 1234}' -rostopic pub --once /localizationcontroller/in/line_measurement_message_0403 sick_lidar_localization/LineMeasurementMessage0403 '{telegram_count: 1000005, timestamp: 123456783, num_lanes: 1, lanes: [1234]}' -rostopic pub --once /localizationcontroller/in/line_measurement_message_0404 sick_lidar_localization/LineMeasurementMessage0404 '{telegram_count: 1000006, timestamp: 123456784, lcp1: 12, lcp2: 34, lcp3: 56, cnt_lpc: 78}' -python $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/send_ros_odom_messages.py -python $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/send_odometry_message_0101.py -python $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/send_odometry_message_0104.py -python $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/send_odometry_message_0105.py +python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/lls_udp_receiver.py --udp_port=5009 & +rostopic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 '{telegram_count: 1000001, timestamp: 123456789, source_id: 0, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' +rostopic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 '{telegram_count: 1000001, timestamp: 123456789, source_id: 2, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' +rostopic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 '{telegram_count: 1000002, timestamp: 123456780, source_id: 0, x_position: -1234, y_position: -1234, heading: 1234}' +rostopic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 '{telegram_count: 1000002, timestamp: 123456780, source_id: 3, x_position: -1234, y_position: -1234, heading: 1234}' +rostopic pub --once /localizationcontroller/in/encoder_measurement_message_0202 sick_lidar_localization/EncoderMeasurementMessage0202 '{telegram_count: 1000003, timestamp: 123456781, source_id: 0, encoder_value: 123456789}' +rostopic pub --once /localizationcontroller/in/encoder_measurement_message_0202 sick_lidar_localization/EncoderMeasurementMessage0202 '{telegram_count: 1000003, timestamp: 123456781, source_id: 4, encoder_value: 123456789}' +rostopic pub --once /localizationcontroller/in/code_measurement_message_0303 sick_lidar_localization/CodeMeasurementMessage0303 '{telegram_count: 1000004, timestamp: 123456782, source_id: 0, code: 1234}' +rostopic pub --once /localizationcontroller/in/code_measurement_message_0303 sick_lidar_localization/CodeMeasurementMessage0303 '{telegram_count: 1000004, timestamp: 123456782, source_id: 5, code: 1234}' +rostopic pub --once /localizationcontroller/in/code_measurement_message_0701 sick_lidar_localization/CodeMeasurementMessage0701 '{telegram_count: 1000004, timestamp: 123456782, source_id: 0, code: "1234", x_position: -1234, y_position: -2345, heading: -3456}' +rostopic pub --once /localizationcontroller/in/code_measurement_message_0701 sick_lidar_localization/CodeMeasurementMessage0701 '{telegram_count: 1000004, timestamp: 123456782, source_id: 6, code: "1234", x_position: -1234, y_position: -2345, heading: -3456}' +rostopic pub --once /localizationcontroller/in/line_measurement_message_0403 sick_lidar_localization/LineMeasurementMessage0403 '{telegram_count: 1000005, timestamp: 123456783, source_id: 0, num_lanes: 1, lanes: [1234]}' +rostopic pub --once /localizationcontroller/in/line_measurement_message_0403 sick_lidar_localization/LineMeasurementMessage0403 '{telegram_count: 1000005, timestamp: 123456783, source_id: 7, num_lanes: 1, lanes: [1234]}' +rostopic pub --once /localizationcontroller/in/line_measurement_message_0404 sick_lidar_localization/LineMeasurementMessage0404 '{telegram_count: 1000006, timestamp: 123456784, source_id: 0, lcp1: 12, lcp2: 34, lcp3: 56, cnt_lpc: 78}' +rostopic pub --once /localizationcontroller/in/line_measurement_message_0404 sick_lidar_localization/LineMeasurementMessage0404 '{telegram_count: 1000006, timestamp: 123456784, source_id: 8, lcp1: 12, lcp2: 34, lcp3: 56, cnt_lpc: 78}' +python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/send_ros_odom_messages.py +python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/send_odometry_message_0104.py +python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/send_odometry_message_0105.py # # Finish simulation # +echo -e "\nsick_lidar_localization simu finished, cleaning up\n" sleep 3 popd rosnode kill -a -pkill -f sim_udp_receiver.py +pkill -f lls_udp_receiver.py sudo pkill -f sick_rest_server.py killall sick_lidar_localization +killall lls_transform echo -e "\nsick_lidar_localization simu finished.\n" diff --git a/test/scripts/run_linux_ros2_simu.bash b/test/scripts/run_linux_ros2_simu.bash index 621ef58..ab4ae12 100644 --- a/test/scripts/run_linux_ros2_simu.bash +++ b/test/scripts/run_linux_ros2_simu.bash @@ -41,7 +41,7 @@ function unittest_services() call_service LocSetOdometryActive sick_lidar_localization/srv/LocSetOdometryActiveSrv "{active: 1}" "success=True" call_service LocSetRecordingActive sick_lidar_localization/srv/LocSetRecordingActiveSrv "{active: 1}" "success=True" call_service LocSetRingBufferRecordingActive sick_lidar_localization/srv/LocSetRingBufferRecordingActiveSrv "{active: 1}" "success=True" - call_service LocStartLocalizing sick_lidar_localization/srv/LocStartLocalizingSrv "{}" "success=True" + call_service LocStart sick_lidar_localization/srv/LocStartSrv "{}" "success=True" call_service LocStop sick_lidar_localization/srv/LocStopSrv "{}" "success=True" call_service LocSwitchMap sick_lidar_localization/srv/LocSwitchMapSrv "{submapname: \"test.vmap\"}" "success=True" call_service LocGetLocalizationStatus sick_lidar_localization/srv/LocGetLocalizationStatusSrv "{}" "locstatus=1" @@ -50,7 +50,7 @@ function unittest_services() } # -# Run sick_lidar_localization simu on native linux +# Run sick_lidar_localization simu on Linux ROS-2 # killall sick_lidar_localization printf "\033c" @@ -80,7 +80,7 @@ fi source ./install/setup.bash SICK_LIDAR_LOCALIZATION_ROOT=./src/sick_lidar_localization if [ -d ./src/sick_lidar_localization2_pretest ] ; then SICK_LIDAR_LOCALIZATION_ROOT=./src/sick_lidar_localization2_pretest ; fi -ros2 run sick_lidar_localization sick_lidar_localization $SICK_LIDAR_LOCALIZATION_ROOT/launch/sick_lidar_localization.launch --ros-args -p hostname:=localhost -p udp_ip_sim_input:=127.0.0.1 -p udp_ip_sim_output:=localhost -p verbose:=1 & +ros2 run sick_lidar_localization sick_lidar_localization $SICK_LIDAR_LOCALIZATION_ROOT/launch/sick_lidar_localization.launch --ros-args -p hostname:=localhost -p udp_ip_lls_input:=127.0.0.1 -p udp_ip_lls_output:=localhost -p verbose:=1 & sleep 3 # @@ -102,16 +102,15 @@ ros2 topic echo /localizationcontroller/out/code_measurement_message_0304 & ros2 topic echo /localizationcontroller/out/line_measurement_message_0403 & ros2 topic echo /localizationcontroller/out/line_measurement_message_0404 & ros2 topic echo /localizationcontroller/out/localizationcontroller_result_message_0502 & -python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/sim_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --max_message_count=300 +python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/lls_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --max_message_count=300 sleep 3 # -# Run pointcloud_converter and visualize PointCloud2 messages by rviz: -# rviz -> Add by topic /cloud/PointCloud2 +# Run lls_transform and visualize TF messages by rviz: # rviz -> Add by display type TF # -ros2 run sick_lidar_localization pointcloud_converter $SICK_LIDAR_LOCALIZATION_ROOT/launch/pointcloud_converter.launch & +ros2 run sick_lidar_localization lls_transform $SICK_LIDAR_LOCALIZATION_ROOT/launch/lls_transform.launch & sleep 3 rviz2 -d $SICK_LIDAR_LOCALIZATION_ROOT/test/config/rviz2_sick_lidar_localization_pointcloud.rviz2 & sleep 3 @@ -120,21 +119,28 @@ sleep 3 # Start pcapng player sending recorded UDP messages # -python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/sim_pcapng_player.py --pcap_filename $SICK_LIDAR_LOCALIZATION_ROOT/test/data/wireshark/20210816_lidarloc2_2.0.0.14R_moving.pcapng # 20210816_lidarloc2_2.0.0.14R_nonmoving.pcapng +python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/lls_pcapng_player.py --pcap_filename $SICK_LIDAR_LOCALIZATION_ROOT/test/data/wireshark/20210816_lidarloc2_2.0.0.14R_moving.pcapng # 20210816_lidarloc2_2.0.0.14R_nonmoving.pcapng sleep 3 # # Start udp receiver and send UDP input message examples # -python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/sim_udp_receiver.py --udp_port=5009 & -ros2 topic pub --once /localizationcontroller/in/odometry_message_0101 sick_lidar_localization/OdometryMessage0101 '{telegram_count: 1000001, timestamp: 123456789, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' -ros2 topic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 '{telegram_count: 1000001, timestamp: 123456789, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' -ros2 topic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 '{telegram_count: 1000002, timestamp: 123456780, x_position: -1234, y_position: -1234, heading: 1234}' -ros2 topic pub --once /localizationcontroller/in/encoder_measurement_message_0202 sick_lidar_localization/EncoderMeasurementMessage0202 '{telegram_count: 1000003, timestamp: 123456781, encoder_value: 123456789}' -ros2 topic pub --once /localizationcontroller/in/code_measurement_message_0303 sick_lidar_localization/CodeMeasurementMessage0303 '{telegram_count: 1000004, timestamp: 123456782, code: 1234}' -ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0403 sick_lidar_localization/LineMeasurementMessage0403 '{telegram_count: 1000005, timestamp: 123456783, num_lanes: 1, lanes: [1234]}' -ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0404 sick_lidar_localization/LineMeasurementMessage0404 '{telegram_count: 1000006, timestamp: 123456784, lcp1: 12, lcp2: 34, lcp3: 56, cnt_lpc: 78}' +python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/lls_udp_receiver.py --udp_port=5009 & +ros2 topic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 '{telegram_count: 1000001, timestamp: 123456789, source_id: 0, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' +ros2 topic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 '{telegram_count: 1000001, timestamp: 123456789, source_id: 2, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}' +ros2 topic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 '{telegram_count: 1000002, timestamp: 123456780, source_id: 0, x_position: -1234, y_position: -1234, heading: 1234}' +ros2 topic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 '{telegram_count: 1000002, timestamp: 123456780, source_id: 3, x_position: -1234, y_position: -1234, heading: 1234}' +ros2 topic pub --once /localizationcontroller/in/encoder_measurement_message_0202 sick_lidar_localization/EncoderMeasurementMessage0202 '{telegram_count: 1000003, timestamp: 123456781, source_id: 0, encoder_value: 123456789}' +ros2 topic pub --once /localizationcontroller/in/encoder_measurement_message_0202 sick_lidar_localization/EncoderMeasurementMessage0202 '{telegram_count: 1000003, timestamp: 123456781, source_id: 4, encoder_value: 123456789}' +ros2 topic pub --once /localizationcontroller/in/code_measurement_message_0303 sick_lidar_localization/CodeMeasurementMessage0303 '{telegram_count: 1000004, timestamp: 123456782, source_id: 0, code: 1234}' +ros2 topic pub --once /localizationcontroller/in/code_measurement_message_0303 sick_lidar_localization/CodeMeasurementMessage0303 '{telegram_count: 1000004, timestamp: 123456782, source_id: 5, code: 1234}' +ros2 topic pub --once /localizationcontroller/in/code_measurement_message_0701 sick_lidar_localization/CodeMeasurementMessage0701 '{telegram_count: 1000004, timestamp: 123456782, source_id: 0, code: "1234", x_position: -1234, y_position: -2345, heading: -3456}' +ros2 topic pub --once /localizationcontroller/in/code_measurement_message_0701 sick_lidar_localization/CodeMeasurementMessage0701 '{telegram_count: 1000004, timestamp: 123456782, source_id: 6, code: "1234", x_position: -1234, y_position: -2345, heading: -3456}' +ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0403 sick_lidar_localization/LineMeasurementMessage0403 '{telegram_count: 1000005, timestamp: 123456783, source_id: 0, num_lanes: 1, lanes: [1234]}' +ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0403 sick_lidar_localization/LineMeasurementMessage0403 '{telegram_count: 1000005, timestamp: 123456783, source_id: 7, num_lanes: 1, lanes: [1234]}' +ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0404 sick_lidar_localization/LineMeasurementMessage0404 '{telegram_count: 1000006, timestamp: 123456784, source_id: 0, lcp1: 12, lcp2: 34, lcp3: 56, cnt_lpc: 78}' +ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0404 sick_lidar_localization/LineMeasurementMessage0404 '{telegram_count: 1000006, timestamp: 123456784, source_id: 8, lcp1: 12, lcp2: 34, lcp3: 56, cnt_lpc: 78}' python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/send_ros2_odom_messages.py # @@ -144,8 +150,8 @@ python3 $SICK_LIDAR_LOCALIZATION_ROOT/test/rest_server/python/send_ros2_odom_mes sleep 3 popd killall sick_lidar_localization -killall pointcloud_converter -pkill -f sim_udp_receiver.py +killall lls_transform +pkill -f lls_udp_receiver.py sudo pkill -f sick_rest_server.py sudo pkill -9 -f sick_rest_server.py pkill -f "ros2 topic echo" diff --git a/test/scripts/run_linux_simu.bash b/test/scripts/run_linux_simu.bash index 3e6ae78..66191ba 100644 --- a/test/scripts/run_linux_simu.bash +++ b/test/scripts/run_linux_simu.bash @@ -34,7 +34,7 @@ sleep 3 # pushd ../../build -./sick_lidar_localization ../launch/sick_lidar_localization.launch hostname:=localhost udp_ip_sim_input:=127.0.0.1 udp_ip_sim_output:=localhost verbose:=1 & +./sick_lidar_localization ../launch/sick_lidar_localization.launch hostname:=localhost udp_ip_lls_input:=127.0.0.1 udp_ip_lls_output:=localhost verbose:=1 & sleep 5 popd @@ -42,7 +42,7 @@ popd # Start pcapng player sending recorded UDP messages # -python3 ../rest_server/python/sim_pcapng_player.py --pcap_filename ../data/wireshark/20210816_lidarloc2_2.0.0.14R_nonmoving.pcapng +python3 ../rest_server/python/lls_pcapng_player.py --pcap_filename ../data/wireshark/20210816_lidarloc2_2.0.0.14R_nonmoving.pcapng sleep 5 # @@ -53,7 +53,7 @@ sleep 5 # sleep 30 echo -e "\nShutdown sick_lidar_localization simu...\n" killall sick_lidar_localization -pkill -f sim_pcapng_player.py +pkill -f lls_pcapng_player.py sudo pkill -f sick_rest_server.py pkill -f roslaunch echo -e "\nsick_lidar_localization simu finished.\n" diff --git a/test/scripts/run_linux_unittest_gen_sick_caller.bash b/test/scripts/run_linux_unittest_gen_sick_caller.bash index b96411e..f5d4e0c 100644 --- a/test/scripts/run_linux_unittest_gen_sick_caller.bash +++ b/test/scripts/run_linux_unittest_gen_sick_caller.bash @@ -38,7 +38,7 @@ pushd ../../build ./gen_service_call LocSetOdometryActive POST "{\"data\":{\"active\":1}}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocSetRecordingActive POST "{\"data\":{\"active\":1}}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocSetRingBufferRecordingActive POST "{\"data\":{\"active\":1}}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log -./gen_service_call LocStartLocalizing POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log +./gen_service_call LocStart POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocStop POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocSwitchMap POST "{\"data\":{\"subMapName\":\"test.vmap\"}}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocGetLocalizationStatus POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log diff --git a/test/scripts/run_linux_unittest_gen_sick_caller_2.bash b/test/scripts/run_linux_unittest_gen_sick_caller_2.bash index 06bafac..713274d 100644 --- a/test/scripts/run_linux_unittest_gen_sick_caller_2.bash +++ b/test/scripts/run_linux_unittest_gen_sick_caller_2.bash @@ -38,7 +38,7 @@ pushd ../../build ./gen_service_call LocSetOdometryActive POST "{active: 1}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocSetRecordingActive POST "{active: 1}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocSetRingBufferRecordingActive POST "{active: 1}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log -./gen_service_call LocStartLocalizing POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log +./gen_service_call LocStart POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocStop POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocSwitchMap POST "{subMapName: \"test.vmap\"}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocGetLocalizationStatus POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log diff --git a/test/scripts/run_linux_unittest_gen_sick_caller_3.bash b/test/scripts/run_linux_unittest_gen_sick_caller_3.bash index a920f7f..1506fc1 100644 --- a/test/scripts/run_linux_unittest_gen_sick_caller_3.bash +++ b/test/scripts/run_linux_unittest_gen_sick_caller_3.bash @@ -38,7 +38,7 @@ pushd ../../build ./gen_service_call LocSetOdometryActive "{active: 1}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocSetRecordingActive "{active: 1}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocSetRingBufferRecordingActive "{active: 1}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log -./gen_service_call LocStartLocalizing "{}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log +./gen_service_call LocStart "{}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocStop --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocSwitchMap "{subMapName: \"test.vmap\"}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log ./gen_service_call LocGetLocalizationStatus POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=linux_unittest_gen_sick_caller.log diff --git a/test/scripts/run_linux_unittest_time_sync.bash b/test/scripts/run_linux_unittest_time_sync.bash index b68b00c..9949274 100644 --- a/test/scripts/run_linux_unittest_time_sync.bash +++ b/test/scripts/run_linux_unittest_time_sync.bash @@ -18,7 +18,7 @@ sleep 3 # pushd ../../build -./sick_lidar_localization ../launch/sick_lidar_localization.launch hostname:=localhost udp_ip_sim_input:=127.0.0.1 udp_ip_sim_output:=localhost verbose:=1 | tee sick_lidar_localization.log & +./sick_lidar_localization ../launch/sick_lidar_localization.launch hostname:=localhost udp_ip_lls_input:=127.0.0.1 udp_ip_lls_output:=localhost verbose:=1 | tee sick_lidar_localization.log & sleep 3 popd @@ -27,7 +27,7 @@ popd # sleep 7 -python3 ../rest_server/python/sim_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --udp_output_logfile=../../build/udp_sender.log --max_message_count=1000 +python3 ../rest_server/python/lls_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --udp_output_logfile=../../build/udp_sender.log --max_message_count=1000 sleep 15 grep "WARN" ../../build/sick_lidar_localization.log > ../../build/sick_lidar_localization_error.log grep "ERR" ../../build/sick_lidar_localization.log >> ../../build/sick_lidar_localization_error.log diff --git a/test/scripts/run_linux_unittest_udp_receiver.bash b/test/scripts/run_linux_unittest_udp_receiver.bash index ce425a8..3648da5 100644 --- a/test/scripts/run_linux_unittest_udp_receiver.bash +++ b/test/scripts/run_linux_unittest_udp_receiver.bash @@ -19,7 +19,7 @@ sleep 3 # pushd ../../build -./sick_lidar_localization ../launch/sick_lidar_localization.launch hostname:=localhost udp_ip_sim_input:=127.0.0.1 udp_ip_sim_output:=localhost verbose:=1 udp_sim_output_logfile:=udp_sim_output.log & +./sick_lidar_localization ../launch/sick_lidar_localization.launch hostname:=localhost udp_ip_lls_input:=127.0.0.1 udp_ip_lls_output:=localhost verbose:=1 udp_lls_output_logfile:=udp_lls_output.log & sleep 3 popd @@ -27,7 +27,7 @@ popd # Start udp sender # -python3 ../rest_server/python/sim_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --udp_output_logfile=../../build/udp_sender.log --max_message_count=300 +python3 ../rest_server/python/lls_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --udp_output_logfile=../../build/udp_sender.log --max_message_count=300 # # Shutdown rest server and sick_lidar_localization @@ -38,14 +38,14 @@ killall sick_lidar_localization sudo pkill -f sick_rest_server.py # -# Compare received udp_sim_output.log with udp_sender.log, should be identical +# Compare received udp_lls_output.log with udp_sender.log, should be identical # echo -e "\nrun_linux_unittest_udp_receiver finished.\n" -cat ../../build/udp_sim_output.log -diff ../../build/udp_sim_output.log ../../build/udp_sender.log +cat ../../build/udp_lls_output.log +diff ../../build/udp_lls_output.log ../../build/udp_sender.log if [ $? != 0 ] ; then - echo -e "\n## ERROR unittest for udp messages: files ../../build/udp_sim_output.log and ../../build/udp_sender.log different, should be identical\n" + echo -e "\n## ERROR unittest for udp messages: files ../../build/udp_lls_output.log and ../../build/udp_sender.log different, should be identical\n" echo -e "## ERROR: unittest for udp messagesr failed. Press any key to continue..." read -n1 -s key else diff --git a/test/scripts/run_win64_ros2_simu.cmd b/test/scripts/run_win64_ros2_simu.cmd index bb41e3f..d8cc34b 100644 --- a/test/scripts/run_win64_ros2_simu.cmd +++ b/test/scripts/run_win64_ros2_simu.cmd @@ -62,7 +62,7 @@ ros2 service call LocSetMappingActive sick_lidar_localization/srv/LocSetMappingA ros2 service call LocSetOdometryActive sick_lidar_localization/srv/LocSetOdometryActiveSrv "{\"active\":1}" ros2 service call LocSetRecordingActive sick_lidar_localization/srv/LocSetRecordingActiveSrv "{\"active\":1}" ros2 service call LocSetRingBufferRecordingActive sick_lidar_localization/srv/LocSetRingBufferRecordingActiveSrv "{\"active\":1}" -ros2 service call LocStartLocalizing sick_lidar_localization/srv/LocStartLocalizingSrv "{}" +ros2 service call LocStart sick_lidar_localization/srv/LocStartSrv "{}" ros2 service call LocStop sick_lidar_localization/srv/LocStopSrv "{}" ros2 service call LocSwitchMap sick_lidar_localization/srv/LocSwitchMapSrv "{\"submapname\":\"test.vmap\"}" ros2 service call LocGetLocalizationStatus sick_lidar_localization/srv/LocGetLocalizationStatusSrv "{}" @@ -71,12 +71,11 @@ ros2 service call LocLoadPersistentConfig sick_lidar_localization/srv/LocLoadPer @timeout /t 3 REM -REM Start pointcloud_converter and visualize PointCloud2 messages by rviz -REM rviz -> Add by topic /cloud/PointCloud2 +REM Start lls_transform and visualize TF messages by rviz REM rviz -> Add by display type TF REM -start "pointcloud_converter" /min ros2 run sick_lidar_localization pointcloud_converter %SICK_LIDAR_LOCALIZATION_ROOT%/launch/pointcloud_converter.launch +start "lls_transform" /min ros2 run sick_lidar_localization lls_transform %SICK_LIDAR_LOCALIZATION_ROOT%/launch/lls_transform.launch start "rviz2" ros2 run rviz2 rviz2 -d %SICK_LIDAR_LOCALIZATION_ROOT%/test/config/rviz2_win64_sick_lidar_localization_pointcloud.rviz start "ros2 topic echo /localizationcontroller/out" cmd /k .\src\sick_lidar_localization2_pretest\test\scripts\simu_echo_localizationcontroller_out_topics.cmd @@ -84,14 +83,28 @@ REM REM Start udp sender resp. pcapng player to send UDP output messages REM -rem python %SICK_LIDAR_LOCALIZATION_ROOT%/test/rest_server/python/sim_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --max_message_count=300 -python %SICK_LIDAR_LOCALIZATION_ROOT%/test/rest_server/python/sim_pcapng_player.py --pcap_filename %SICK_LIDAR_LOCALIZATION_ROOT%/test/data/wireshark/20210803_moving_lidarloc2.pcapng +rem python %SICK_LIDAR_LOCALIZATION_ROOT%/test/rest_server/python/lls_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --max_message_count=300 +python %SICK_LIDAR_LOCALIZATION_ROOT%/test/rest_server/python/lls_pcapng_player.py --pcap_filename %SICK_LIDAR_LOCALIZATION_ROOT%/test/data/wireshark/20210803_moving_lidarloc2.pcapng REM REM Start odometry sender REM python %SICK_LIDAR_LOCALIZATION_ROOT%/test/rest_server/python/send_ros2_odom_messages.py +ros2 topic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 "{telegram_count: 1000001, timestamp: 123456789, source_id: 0, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}" +ros2 topic pub --once /localizationcontroller/in/odometry_message_0104 sick_lidar_localization/OdometryMessage0104 "{telegram_count: 1000001, timestamp: 123456789, source_id: 2, x_velocity: -1234, y_velocity: -1234, angular_velocity: 1234}" +ros2 topic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 "{telegram_count: 1000002, timestamp: 123456780, source_id: 0, x_position: -1234, y_position: -1234, heading: 1234}" +ros2 topic pub --once /localizationcontroller/in/odometry_message_0105 sick_lidar_localization/OdometryMessage0105 "{telegram_count: 1000002, timestamp: 123456780, source_id: 3, x_position: -1234, y_position: -1234, heading: 1234}" +ros2 topic pub --once /localizationcontroller/in/encoder_measurement_message_0202 sick_lidar_localization/EncoderMeasurementMessage0202 "{telegram_count: 1000003, timestamp: 123456781, source_id: 0, encoder_value: 123456789}" +ros2 topic pub --once /localizationcontroller/in/encoder_measurement_message_0202 sick_lidar_localization/EncoderMeasurementMessage0202 "{telegram_count: 1000003, timestamp: 123456781, source_id: 4, encoder_value: 123456789}" +ros2 topic pub --once /localizationcontroller/in/code_measurement_message_0303 sick_lidar_localization/CodeMeasurementMessage0303 "{telegram_count: 1000004, timestamp: 123456782, source_id: 0, code: 1234}" +ros2 topic pub --once /localizationcontroller/in/code_measurement_message_0303 sick_lidar_localization/CodeMeasurementMessage0303 "{telegram_count: 1000004, timestamp: 123456782, source_id: 5, code: 1234}" +ros2 topic pub --once /localizationcontroller/in/code_measurement_message_0701 sick_lidar_localization/CodeMeasurementMessage0701 "{telegram_count: 1000004, timestamp: 123456782, source_id: 0, code: "1234", x_position: -1234, y_position: -2345, heading: -3456}" +ros2 topic pub --once /localizationcontroller/in/code_measurement_message_0701 sick_lidar_localization/CodeMeasurementMessage0701 "{telegram_count: 1000004, timestamp: 123456782, source_id: 6, code: "1234", x_position: -1234, y_position: -2345, heading: -3456}" +ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0403 sick_lidar_localization/LineMeasurementMessage0403 "{telegram_count: 1000005, timestamp: 123456783, source_id: 0, num_lanes: 1, lanes: [1234]}" +ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0403 sick_lidar_localization/LineMeasurementMessage0403 "{telegram_count: 1000005, timestamp: 123456783, source_id: 7, num_lanes: 1, lanes: [1234]}" +ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0404 sick_lidar_localization/LineMeasurementMessage0404 "{telegram_count: 1000006, timestamp: 123456784, source_id: 0, lcp1: 12, lcp2: 34, lcp3: 56, cnt_lpc: 78}" +ros2 topic pub --once /localizationcontroller/in/line_measurement_message_0404 sick_lidar_localization/LineMeasurementMessage0404 "{telegram_count: 1000006, timestamp: 123456784, source_id: 8, lcp1: 12, lcp2: 34, lcp3: 56, cnt_lpc: 78}" popd @pause diff --git a/test/scripts/run_win64_simu.cmd b/test/scripts/run_win64_simu.cmd index 84abad2..b41074b 100644 --- a/test/scripts/run_win64_simu.cmd +++ b/test/scripts/run_win64_simu.cmd @@ -14,7 +14,7 @@ REM Run sick_lidar_localization REM pushd ..\..\build -start "sick_lidar_localization" .\Debug\sick_lidar_localization ../launch/sick_lidar_localization.launch hostname:=localhost verbose:=1 udp_sim_output_logfile:=udp_sim_output.log +start "sick_lidar_localization" .\Debug\sick_lidar_localization ../launch/sick_lidar_localization.launch hostname:=localhost verbose:=1 udp_lls_output_logfile:=udp_lls_output.log @timeout /t 3 popd @@ -23,15 +23,15 @@ REM Start udp sender and run unittest for udp messages REM python --version -python ../rest_server/python/sim_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --udp_output_logfile=..\..\build\udp_sender.log --max_message_count=300 +python ../rest_server/python/lls_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --udp_output_logfile=..\..\build\udp_sender.log --max_message_count=300 REM -REM Compare received udp_sim_output.log with udp_sender.log, should be identical +REM Compare received udp_lls_output.log with udp_sender.log, should be identical REM -comp /a/l/m ..\..\build\udp_sim_output.log ..\..\build\udp_sender.log +comp /a/l/m ..\..\build\udp_lls_output.log ..\..\build\udp_sender.log @if not "%errorlevel%"=="0" ( - @echo ## ERROR: files ..\..\build\udp_sim_output.log and ..\..\build\udp_sender.log different, should be identical & @pause + @echo ## ERROR: files ..\..\build\udp_lls_output.log and ..\..\build\udp_sender.log different, should be identical & @pause ) else ( @echo unittest for sick_lidar_localization udp messages passed ) @@ -41,6 +41,6 @@ REM Start pcapng player sending recorded UDP messages REM python --version -python ../rest_server/python/sim_pcapng_player.py --pcap_filename ../data/wireshark/20210816_lidarloc2_2.0.0.14R_moving.pcapng +python ../rest_server/python/lls_pcapng_player.py --pcap_filename ../data/wireshark/20210816_lidarloc2_2.0.0.14R_moving.pcapng @pause diff --git a/test/scripts/run_win64_unittest_gen_sick_caller.cmd b/test/scripts/run_win64_unittest_gen_sick_caller.cmd index 2a2562f..8afa3c9 100644 --- a/test/scripts/run_win64_unittest_gen_sick_caller.cmd +++ b/test/scripts/run_win64_unittest_gen_sick_caller.cmd @@ -6,7 +6,7 @@ REM REM Start rest server REM -start "rest server" /min .\simu_run_sim_rest_server.cmd +start "rest server" /min .\simu_run_lls_rest_server.cmd @timeout /t 3 REM @@ -33,7 +33,7 @@ pushd ..\..\build .\Debug\gen_service_call LocSetOdometryActive POST "{\"data\":{\"active\":1}}" --hostname=localhost --verbose=1 --dump=1 --append=win64_unittest_gen_sick_caller.log .\Debug\gen_service_call LocSetRecordingActive POST "{\"data\":{\"active\":1}}" --hostname=localhost --verbose=1 --dump=1 --append=win64_unittest_gen_sick_caller.log .\Debug\gen_service_call LocSetRingBufferRecordingActive POST "{\"data\":{\"active\":1}}" --hostname=localhost --verbose=1 --dump=1 --append=win64_unittest_gen_sick_caller.log -.\Debug\gen_service_call LocStartLocalizing POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=win64_unittest_gen_sick_caller.log +.\Debug\gen_service_call LocStart POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=win64_unittest_gen_sick_caller.log .\Debug\gen_service_call LocStop POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=win64_unittest_gen_sick_caller.log .\Debug\gen_service_call LocSwitchMap POST "{\"data\":{\"subMapName\":\"test.vmap\"}}" --hostname=localhost --verbose=1 --dump=1 --append=win64_unittest_gen_sick_caller.log .\Debug\gen_service_call LocGetLocalizationStatus POST "{}" --hostname=localhost --verbose=1 --dump=1 --append=win64_unittest_gen_sick_caller.log diff --git a/test/scripts/run_win64_unittest_time_sync.cmd b/test/scripts/run_win64_unittest_time_sync.cmd index 48cf80f..8a46b29 100644 --- a/test/scripts/run_win64_unittest_time_sync.cmd +++ b/test/scripts/run_win64_unittest_time_sync.cmd @@ -6,7 +6,7 @@ REM REM Start rest server for LocTimestampRequests REM -start "rest server" /min .\simu_run_sim_rest_server_time_sync.cmd +start "rest server" /min .\simu_run_lls_rest_server_time_sync.cmd @timeout /t 3 REM @@ -23,7 +23,7 @@ REM Wait 7 seconds until Software-PLL is initialized and start udp sender REM @timeout /t 7 -python ../rest_server/python/sim_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --udp_output_logfile=..\..\build\udp_sender.log --max_message_count=1000 +python ../rest_server/python/lls_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --udp_output_logfile=..\..\build\udp_sender.log --max_message_count=1000 REM REM Check the timestamps calculated from sensor tics by Software-PLL: diff --git a/test/scripts/run_win64_unittest_udp_receiver.cmd b/test/scripts/run_win64_unittest_udp_receiver.cmd index 8b681e3..95c6f90 100644 --- a/test/scripts/run_win64_unittest_udp_receiver.cmd +++ b/test/scripts/run_win64_unittest_udp_receiver.cmd @@ -16,7 +16,7 @@ REM Start sick_lidar_localization REM pushd ..\..\build -start "sick_lidar_localization" .\Debug\sick_lidar_localization ../launch/sick_lidar_localization.launch hostname:=localhost verbose:=1 udp_sim_output_logfile:=udp_sim_output.log +start "sick_lidar_localization" .\Debug\sick_lidar_localization ../launch/sick_lidar_localization.launch hostname:=localhost verbose:=1 udp_lls_output_logfile:=udp_lls_output.log @timeout /t 10 popd @@ -24,15 +24,15 @@ REM REM Start udp sender REM -python ../rest_server/python/sim_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --udp_output_logfile=..\..\build\udp_sender.log --max_message_count=300 +python ../rest_server/python/lls_udp_sender.py --udp_port=5010 --udp_send_rate=30.0 --udp_output_logfile=..\..\build\udp_sender.log --max_message_count=300 REM -REM Compare received udp_sim_output.log with udp_sender.log, should be identical +REM Compare received udp_lls_output.log with udp_sender.log, should be identical REM -comp /a/l/m ..\..\build\udp_sim_output.log ..\..\build\udp_sender.log +comp /a/l/m ..\..\build\udp_lls_output.log ..\..\build\udp_sender.log @if not "%errorlevel%"=="0" ( - @echo ## ERROR: files ..\..\build\udp_sim_output.log and ..\..\build\udp_sender.log different, should be identical & @pause + @echo ## ERROR: files ..\..\build\udp_lls_output.log and ..\..\build\udp_sender.log different, should be identical & @pause ) else ( @echo unittest for sick_lidar_localization udp messages passed ) diff --git a/test/scripts/simu_run_sim_pcap_player.cmd b/test/scripts/simu_run_lls_pcap_player.cmd similarity index 89% rename from test/scripts/simu_run_sim_pcap_player.cmd rename to test/scripts/simu_run_lls_pcap_player.cmd index f7412d6..e50df10 100644 --- a/test/scripts/simu_run_sim_pcap_player.cmd +++ b/test/scripts/simu_run_lls_pcap_player.cmd @@ -16,5 +16,5 @@ REM REM Run sim udp sender REM -python ../rest_server/python/sim_pcapng_player.py --pcap_filename ../data/wireshark/20210816_lidarloc2_2.0.0.14R_moving.pcapng +python ../rest_server/python/lls_pcapng_player.py --pcap_filename ../data/wireshark/20210816_lidarloc2_2.0.0.14R_moving.pcapng @pause diff --git a/test/scripts/simu_run_sim_rest_server.cmd b/test/scripts/simu_run_lls_rest_server.cmd similarity index 100% rename from test/scripts/simu_run_sim_rest_server.cmd rename to test/scripts/simu_run_lls_rest_server.cmd diff --git a/test/scripts/simu_run_sim_rest_server_time_sync.cmd b/test/scripts/simu_run_lls_rest_server_time_sync.cmd similarity index 100% rename from test/scripts/simu_run_sim_rest_server_time_sync.cmd rename to test/scripts/simu_run_lls_rest_server_time_sync.cmd diff --git a/test/scripts/simu_run_sim_udp_sender.cmd b/test/scripts/simu_run_lls_udp_sender.cmd similarity index 90% rename from test/scripts/simu_run_sim_udp_sender.cmd rename to test/scripts/simu_run_lls_udp_sender.cmd index b6364a3..834a98f 100644 --- a/test/scripts/simu_run_sim_udp_sender.cmd +++ b/test/scripts/simu_run_lls_udp_sender.cmd @@ -16,5 +16,5 @@ REM REM Run sim udp sender REM -python ../rest_server/python/sim_udp_sender.py +python ../rest_server/python/lls_udp_sender.py @pause diff --git a/test/scripts/verify_sim_input_messages.cmd b/test/scripts/verify_lls_input_messages.cmd similarity index 68% rename from test/scripts/verify_sim_input_messages.cmd rename to test/scripts/verify_lls_input_messages.cmd index 9979c26..9873b3e 100644 --- a/test/scripts/verify_sim_input_messages.cmd +++ b/test/scripts/verify_lls_input_messages.cmd @@ -6,11 +6,11 @@ REM REM Run sim udp receiver REM -start "sim_udp_receiver" python ../rest_server/python/sim_udp_receiver.py --udp_port=5009 +start "lls_udp_receiver" python ../rest_server/python/lls_udp_receiver.py --udp_port=5009 REM REM Run sim udp sender REM -python ../rest_server/python/sim_pcapng_player.py --pcap_filename ../data/wireshark/20210804_UDP_Port_5009_RecvData.pcapng --udp_port=5009 +python ../rest_server/python/lls_pcapng_player.py --pcap_filename ../data/wireshark/20210804_UDP_Port_5009_RecvData.pcapng --udp_port=5009 @pause diff --git a/test/tools/python/ros_service_prep.py b/test/tools/python/ros_service_prep.py index c5a0143..e3e5d98 100644 --- a/test/tools/python/ros_service_prep.py +++ b/test/tools/python/ros_service_prep.py @@ -4,13 +4,13 @@ ros_service_names = [ "LocAutoStartSavePoseSrv", "LocClearMapCacheSrv", "LocGetErrorLevelSrv", "LocGetMapSrv", "LocGetSystemStateSrv", "LocInitializeAtPoseSrv", "LocInitializePoseSrv", "LocIsSystemReadySrv", "LocLoadMapToCacheSrv", "LocRequestTimestampSrv", "LocResumeAtPoseSrv", "LocSaveRingBufferRecordingSrv", "LocSetKinematicVehicleModelActiveSrv", "LocSetLinesForSupportActiveSrv", "LocSetMappingActiveSrv", - "LocSetMapSrv", "LocSetOdometryActiveSrv", "LocSetRecordingActiveSrv", "LocSetRingBufferRecordingActiveSrv", "LocStartLocalizingSrv", + "LocSetMapSrv", "LocSetOdometryActiveSrv", "LocSetRecordingActiveSrv", "LocSetRingBufferRecordingActiveSrv", "LocStartSrv", "LocStateSrv", "LocStopSrv", "LocSwitchMapSrv" ] rest_service_names = [ "LocAutoStartSavePose", "LocClearMapCache", "GetErrorLevel", "LocGetMap", "LocGetSystemState", "LocInitializeAtPose", "IsSystemReady", "LocLoadMapToCache", "LocRequestTimestamp", "LocResumeAtPose", "LocSaveRingBufferRecording", "LocSetKinematicVehicleModelActive", "LocSetLinesForSupportActive", "LocSetMappingActive", - "LocSetMap", "LocSetOdometryActive", "LocSetRecordingActive", "LocSetRingBufferRecordingActive", "LocStartLocalizing", + "LocSetMap", "LocSetOdometryActive", "LocSetRecordingActive", "LocSetRingBufferRecordingActive", "LocStart", "LocStop", "LocSwitchMap" ] if False: # print ros service callback declarations