From 283bdcd19f3f40f5d19282c76e6a7b9756e529b8 Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Tue, 5 Apr 2022 14:39:21 +0200 Subject: [PATCH 01/27] Added rws client --- abb_rws_client/CMakeLists.txt | 79 ++ .../include/abb_rws_client/mapping.hpp | 260 ++++ .../include/abb_rws_client/rws_client.hpp | 29 + .../rws_service_provider_ros.hpp | 196 +++ .../rws_state_publisher_ros.hpp | 38 + .../include/abb_rws_client/utilities.hpp | 72 ++ abb_rws_client/package.xml | 26 + abb_rws_client/src/mapping.cpp | 478 +++++++ abb_rws_client/src/rws_client.cpp | 25 + abb_rws_client/src/rws_client_node.cpp | 26 + .../src/rws_service_provider_ros.cpp | 1146 +++++++++++++++++ .../src/rws_state_publisher_ros.cpp | 98 ++ abb_rws_client/src/utilities.cpp | 113 ++ 13 files changed, 2586 insertions(+) create mode 100644 abb_rws_client/CMakeLists.txt create mode 100644 abb_rws_client/include/abb_rws_client/mapping.hpp create mode 100644 abb_rws_client/include/abb_rws_client/rws_client.hpp create mode 100644 abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp create mode 100644 abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp create mode 100644 abb_rws_client/include/abb_rws_client/utilities.hpp create mode 100644 abb_rws_client/package.xml create mode 100644 abb_rws_client/src/mapping.cpp create mode 100644 abb_rws_client/src/rws_client.cpp create mode 100644 abb_rws_client/src/rws_client_node.cpp create mode 100644 abb_rws_client/src/rws_service_provider_ros.cpp create mode 100644 abb_rws_client/src/rws_state_publisher_ros.cpp create mode 100644 abb_rws_client/src/utilities.cpp diff --git a/abb_rws_client/CMakeLists.txt b/abb_rws_client/CMakeLists.txt new file mode 100644 index 0000000..a7999d2 --- /dev/null +++ b/abb_rws_client/CMakeLists.txt @@ -0,0 +1,79 @@ +cmake_minimum_required(VERSION 3.8) +project(abb_rws_client) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-W -Wall -Wextra + -Wwrite-strings -Wunreachable-code -Wpointer-arith + -Winit-self -Wredundant-decls + -Wno-unused-parameter -Wno-unused-function) +endif() + +set(THIS_PACKAGE_INCLUDE_DEPENDS + abb_egm_rws_managers + abb_egm_msgs + abb_robot_msgs + abb_rapid_msgs + abb_rapid_sm_addin_msgs + rclcpp + sensor_msgs +) + +# find dependencies +find_package(ament_cmake REQUIRED) + +foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) + find_package(${Dependency} REQUIRED) +endforeach() + +########### +## Build ## +########### + +add_executable(rws_client + src/rws_client_node.cpp + src/rws_client.cpp + src/rws_service_provider_ros.cpp + src/rws_state_publisher_ros.cpp + src/utilities.cpp + src/mapping.cpp +) +ament_target_dependencies(rws_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${THIS_PACKAGE_INCLUDE_DEPENDS}) +target_link_libraries(rws_client abb_egm_rws_managers::abb_egm_rws_managers) +target_include_directories( + rws_client + PRIVATE + include +) + +############# +## Install ## +############# + +install( + TARGETS rws_client + DESTINATION lib/${PROJECT_NAME} +) + +############# +## Testing ## +############# + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_export_include_directories(include) +ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) + +ament_package() diff --git a/abb_rws_client/include/abb_rws_client/mapping.hpp b/abb_rws_client/include/abb_rws_client/mapping.hpp new file mode 100644 index 0000000..14f6575 --- /dev/null +++ b/abb_rws_client/include/abb_rws_client/mapping.hpp @@ -0,0 +1,260 @@ +/*********************************************************************************************************************** + * + * Copyright (c) 2020, ABB Schweiz AG + * 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 ABB 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 HOLDER 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. + * + *********************************************************************************************************************** + */ + +#ifndef ABB_RWS_CLIENT__MAPPING_HPP_ +#define ABB_RWS_CLIENT__MAPPING_HPP_ + +#include +#include + +#include +#include +#include + +namespace abb { +namespace robot { +namespace utilities { + +/** + * \brief Maps RAPID task execution state to ROS representation. + * + * \param state to map. + * + * \return uint8_t containing the mapped state. + */ +uint8_t map(const rws::RWSInterface::RAPIDTaskExecutionState state); + +/** + * \brief Maps RobotWare StateMachine Add-In state to ROS representation. + * + * \param state to map. + * + * \return uint8_t containing the mapped state. + */ +uint8_t map_state_machine_state(const rws::RAPIDNum& state); + +/** + * \brief Maps RobotWare StateMachine Add-In EGM action to ROS representation. + * + * \param action to map. + * + * \return uint8_t containing the mapped state. + */ +uint8_t map_state_machine_egm_action(const rws::RAPIDNum& action); + +/** + * \brief Maps RobotWare StateMachine Add-In SmartGripper command to RWS representation. + * + * \param command to map. + * + * \return unsigned int containing the mapped command. + * + * \throw std::runtime_error if the command is unknown. + */ +unsigned int map_state_machine_sg_command(const unsigned int command); + +/** + * \brief Maps a RAPID 'pos' data type from RWS to ROS representation. + * + * \param rws_pos to map. + * + * \return abb_rapid_msgs::Pos containing the mapped data. + */ +abb_rapid_msgs::msg::Pos map(const rws::Pos& rws_pos); + +/** + * \brief Maps a RAPID 'orient' data type from RWS to ROS representation. + * + * \param rws_orient to map. + * + * \return abb_rapid_msgs::Orient containing the mapped data. + */ +abb_rapid_msgs::msg::Orient map(const rws::Orient& rws_orient); + +/** + * \brief Maps a RAPID 'pose' data type from RWS to ROS representation. + * + * \param rws_pose to map. + * + * \return abb_rapid_msgs::Pose containing the mapped data. + */ +abb_rapid_msgs::msg::Pose map(const rws::Pose& rws_pose); + +/** + * \brief Maps a RAPID 'loaddata' data type from RWS to ROS representation. + * + * \param rws_loaddata to map. + * + * \return abb_rapid_msgs::LoadData containing the mapped data. + */ +abb_rapid_msgs::msg::LoadData map(const rws::LoadData& rws_loaddata); + +/** + * \brief Maps a RAPID 'tooldata' data type from RWS to ROS representation. + * + * \param rws_tooldata to map. + * + * \return abb_rapid_msgs::ToolData containing the mapped data. + */ +abb_rapid_msgs::msg::ToolData map(const rws::ToolData& rws_tooldata); + +/** + * \brief Maps a RAPID 'wobjdata' data type from RWS to ROS representation. + * + * \param rws_wobjdata to map. + * + * \return abb_rapid_msgs::WObjData containing the mapped data. + */ +abb_rapid_msgs::msg::WObjData map(const rws::WObjData& rws_wobjdata); + +/** + * \brief Maps a RobotWare StateMachine Add-In RAPID 'EGMSettings' data type from RWS to ROS + * representation. + * + * \param rws_egm_settings to map. + * + * \return abb_rapid_sm_addin_msgs::EGMSettings containing the mapped data. + */ +abb_rapid_sm_addin_msgs::msg::EGMSettings map(const rws::RWSStateMachineInterface::EGMSettings& rws_egm_settings); + +/** + * \brief Maps a RAPID 'pos' data type from ROS to RWS representation. + * + * \param ros_pos to map. + * + * \return rws::Pos containing the mapped data. + */ +rws::Pos map(const abb_rapid_msgs::msg::Pos& ros_pos); + +/** + * \brief Maps a RAPID 'orient' data type from ROS to RWS representation. + * + * \param ros_orient to map. + * + * \return rws::Orient containing the mapped data. + */ +rws::Orient map(const abb_rapid_msgs::msg::Orient& ros_orient); + +/** + * \brief Maps a RAPID 'pose' data type from ROS to RWS representation. + * + * \param ros_pose to map. + * + * \return rws::Pose containing the mapped data. + */ +rws::Pose map(const abb_rapid_msgs::msg::Pose& ros_pose); + +/** + * \brief Maps a RAPID 'loaddata' data type from ROS to RWS representation. + * + * \param ros_loaddata to map. + * + * \return rws::LoadData containing the mapped data. + */ +rws::LoadData map(const abb_rapid_msgs::msg::LoadData& ros_loaddata); + +/** + * \brief Maps a RAPID 'tooldata' data type from ROS to RWS representation. + * + * \param ros_tooldata to map. + * + * \return rws::ToolData containing the mapped data. + */ +rws::ToolData map(const abb_rapid_msgs::msg::ToolData& ros_tooldata); + +/** + * \brief Maps a RAPID 'wobjdata' data type from ROS to RWS representation. + * + * \param ros_wobjdata to map. + * + * \return rws::WObjData containing the mapped data. + */ +rws::WObjData map(const abb_rapid_msgs::msg::WObjData& ros_wobjdata); + +/** + * \brief Maps a RobotWare StateMachine Add-In RAPID 'EGMSettings' data type from ROS to RWS + * representation. + * + * \param ros_egm_settings to map. + * + * \return rws::RWSStateMachineInterface::EGMSettings containing the mapped data. + */ +rws::RWSStateMachineInterface::EGMSettings map(const abb_rapid_sm_addin_msgs::msg::EGMSettings& ros_egm_settings); + +/** + * \brief Maps EGM state to ROS representation. + * + * \param state to map. + * + * \return uint8_t containing the mapped state. + */ +uint8_t map(const egm::wrapper::Status::EGMState state); + +/** + * \brief Maps motor state to ROS representation. + * + * \param state to map. + * + * \return uint8_t containing the mapped state. + */ +uint8_t map(const egm::wrapper::Status::MotorState state); + +/** + * \brief Maps RAPID execution state to ROS representation. + * + * \param state to map. + * + * \return uint8_t containing the mapped state. + */ +uint8_t map(const egm::wrapper::Status::RAPIDExecutionState rapid_execution_state); + +/** + * \brief Maps a vector to a string (e.g. for logging). + * + * \param vector to map. + * + * \return std::string of the mapped vector. + * + * \throw std::runtime if the mapping failed. + */ +template +std::string map_vector_to_string(const std::vector& vector); + +} // namespace utilities +} // namespace robot +} // namespace abb + +#endif // ABB_RWS_CLIENT__MAPPING_HPP_ diff --git a/abb_rws_client/include/abb_rws_client/rws_client.hpp b/abb_rws_client/include/abb_rws_client/rws_client.hpp new file mode 100644 index 0000000..03c41fa --- /dev/null +++ b/abb_rws_client/include/abb_rws_client/rws_client.hpp @@ -0,0 +1,29 @@ +#ifndef ABB_RWS_CLIENT__RWS_CLIENT_HPP__ +#define ABB_RWS_CLIENT__RWS_CLIENT_HPP__ + +// ROS +#include + +// ABB +#include +#include + +namespace abb_rws_client { + +class RWSClient { + public: + RWSClient(const rclcpp::Node::SharedPtr &node, const std::string &robot_ip, unsigned short robot_port); + + protected: + rclcpp::Node::SharedPtr node_; + abb::robot::RWSManager rws_manager_; + + abb::robot::RobotControllerDescription robot_controller_description_; + + private: + void connect(); +}; + +} // namespace abb_rws_client + +#endif // ABB_RWS_CLIENT__RWS_CLIENT_HPP__ diff --git a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp new file mode 100644 index 0000000..0820444 --- /dev/null +++ b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp @@ -0,0 +1,196 @@ +#ifndef ABB_RWS_CLIENT__RWS_SERCIVE_PROVIDER_ROS_HPP__ +#define ABB_RWS_CLIENT__RWS_SERCIVE_PROVIDER_ROS_HPP__ + +#include + +#include "abb_rws_client/rws_client.hpp" + +// SYSMTEM + +#include +#include + +// ROS + +#include + +// ABB MSG + +#include +#include + +// ABB SRV + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace abb_rws_client { + +class RWSServiceProviderROS : RWSClient { + public: + RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port); + + private: + void system_state_callback(const abb_robot_msgs::msg::SystemState& msg); + + void runtime_state_callback(const abb_rapid_sm_addin_msgs::msg::RuntimeState& msg); + + bool get_file_contents(const abb_robot_msgs::srv::GetFileContents::Request::SharedPtr req, + abb_robot_msgs::srv::GetFileContents::Response::SharedPtr res); + + bool get_io_signal(const abb_robot_msgs::srv::GetIOSignal::Request::SharedPtr req, + abb_robot_msgs::srv::GetIOSignal::Response::SharedPtr res); + + bool get_rapid_bool(const abb_robot_msgs::srv::GetRAPIDBool::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDBool::Response::SharedPtr res); + + bool get_rapid_dnum(const abb_robot_msgs::srv::GetRAPIDDnum::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDDnum::Response::SharedPtr res); + + bool get_rapid_num(const abb_robot_msgs::srv::GetRAPIDNum::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDNum::Response::SharedPtr res); + + bool get_rapid_string(const abb_robot_msgs::srv::GetRAPIDString::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDString::Response::SharedPtr res); + + bool get_rapid_symbol(const abb_robot_msgs::srv::GetRAPIDSymbol::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDSymbol::Response::SharedPtr res); + + bool get_rc_description(const abb_robot_msgs::srv::GetRobotControllerDescription::Request::SharedPtr req, + abb_robot_msgs::srv::GetRobotControllerDescription::Response::SharedPtr res); + + bool get_speed_ratio(const abb_robot_msgs::srv::GetSpeedRatio::Request::SharedPtr req, + abb_robot_msgs::srv::GetSpeedRatio::Response::SharedPtr res); + + bool pp_to_main(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool run_rapid_routine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool run_sg_routine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool set_file_contents(const abb_robot_msgs::srv::SetFileContents::Request::SharedPtr req, + abb_robot_msgs::srv::SetFileContents::Response::SharedPtr res); + + bool set_io_signal(const abb_robot_msgs::srv::SetIOSignal::Request::SharedPtr req, + abb_robot_msgs::srv::SetIOSignal::Response::SharedPtr res); + + bool set_motors_off(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool set_motors_on(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool set_rapid_bool(const abb_robot_msgs::srv::SetRAPIDBool::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDBool::Response::SharedPtr res); + + bool set_rapid_dnum(const abb_robot_msgs::srv::SetRAPIDDnum::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDDnum::Response::SharedPtr res); + + bool set_rapid_num(const abb_robot_msgs::srv::SetRAPIDNum::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDNum::Response::SharedPtr res); + + bool set_rapid_string(const abb_robot_msgs::srv::SetRAPIDString::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDString::Response::SharedPtr res); + + bool set_rapid_symbol(const abb_robot_msgs::srv::SetRAPIDSymbol::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDSymbol::Response::SharedPtr res); + + bool set_speed_ratio(const abb_robot_msgs::srv::SetSpeedRatio::Request::SharedPtr req, + abb_robot_msgs::srv::SetSpeedRatio::Response::SharedPtr res); + + bool start_rapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool stop_rapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool get_egm_settings(const abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Response::SharedPtr res); + + bool set_egm_settings(const abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Response::SharedPtr res); + + bool set_rapid_routine(const abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Response::SharedPtr res); + + bool set_sg_command(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::SetSGCommand::Response::SharedPtr res); + + bool start_egm_joint(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool start_egm_pose(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool start_egm_stream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool stop_egm(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool stop_egm_stream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool verify_auto_mode(uint16_t& result_code, std::string& message); + + bool verify_argument_filename(const std::string& filename, uint16_t& result_code, std::string& message); + + bool verify_argument_rapid_symbol_path(const abb_robot_msgs::msg::RAPIDSymbolPath& path, uint16_t& result_code, + std::string& message); + + bool verify_argument_rapid_task(const std::string& task, uint16_t& result_code, std::string& message); + + bool verify_argument_signal(const std::string& signal, uint16_t& result_code, std::string& message); + + bool verify_motors_off(uint16_t& result_code, std::string& message); + + bool verify_motors_on(uint16_t& result_code, std::string& message); + + bool verify_sm_addin_runtime_states(uint16_t& result_code, std::string& message); + + bool verify_sm_addin_task_exist(const std::string& task, uint16_t& result_code, std::string& message); + + bool verify_sm_addin_task_initialized(const std::string& task, uint16_t& result_code, std::string& message); + + bool verify_rapid_running(uint16_t& result_code, std::string& message); + + bool verify_rapid_stopped(uint16_t& result_code, std::string& message); + + bool verify_rws_manager_ready(uint16_t& result_code, std::string& message); + + rclcpp::Subscription::SharedPtr system_state_sub_; + rclcpp::Subscription::SharedPtr runtime_state_sub_; + + std::vector core_services_; + std::vector sm_services_; + + abb_robot_msgs::msg::SystemState system_state_; + abb_rapid_sm_addin_msgs::msg::RuntimeState runtime_state_; +}; + +} // namespace abb_rws_client + +#endif // ABB_RWS_CLIENT__RWS_SERCIVE_PROVIDER_ROS_HPP__ diff --git a/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp new file mode 100644 index 0000000..d2bbe88 --- /dev/null +++ b/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp @@ -0,0 +1,38 @@ +#ifndef ABB_RWS_CLIENT__RWS_STATE_PUBLISHER_ROS_HPP_ +#define ABB_RWS_CLIENT__RWS_STATE_PUBLISHER_ROS_HPP_ + +#include "abb_rws_client/rws_client.hpp" + +// ROS +#include + +// ROS INTERFACES +#include + +// ABB INTERFACES +#include +#include +#include + +namespace abb_rws_client { + +class RWSStatePublisherROS : RWSClient { + public: + RWSStatePublisherROS(const rclcpp::Node::SharedPtr &node, const std::string &robot_ip, unsigned short robot_port); + + private: + void timer_callback(); + + rclcpp::TimerBase::SharedPtr timer_; + + rclcpp::Publisher::SharedPtr joint_state_pub_; + rclcpp::Publisher::SharedPtr system_state_pub_; + rclcpp::Publisher::SharedPtr runtime_state_pub_; + + abb::robot::MotionData motion_data_; + abb::robot::SystemStateData system_state_data_; +}; + +} // namespace abb_rws_client + +#endif // ABB_RWS_CLIENT__RWS_STATE_PUBLISHER_ROS_HPP_ diff --git a/abb_rws_client/include/abb_rws_client/utilities.hpp b/abb_rws_client/include/abb_rws_client/utilities.hpp new file mode 100644 index 0000000..0e0941c --- /dev/null +++ b/abb_rws_client/include/abb_rws_client/utilities.hpp @@ -0,0 +1,72 @@ +/*********************************************************************************************************************** + * + * Copyright (c) 2020, ABB Schweiz AG + * 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 ABB 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 HOLDER 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. + * + *********************************************************************************************************************** + */ + +// This file is a modified copy from +// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/initialization.h + +#pragma once + +#include + +namespace abb { +namespace robot { +namespace utilities { +/** + * \brief Attempts to establish a connection to a robot controller's RWS server. + * + * If a connection is established, then a structured description of the robot + * controller is returned. + * + * \param rws_manager for handling the RWS communication with the robot + * controller. \param robot_controller_id for an identifier/nickname for the + * targeted robot controller. \param no_connection_timeout indicator whether to + * wait indefinitely on the robot controller. + * + * \return RobotControllerDescription of the robot controller. + * + * \throw std::runtime_error if unable to establish a connection. + */ +RobotControllerDescription establish_rws_connection(RWSManager &rws_manager, const std::string &robot_controller_id, + const bool no_connection_timeout); + +void verify_robotware_version(const RobotWareVersion &rw_version); + +bool verify_state_machine_add_in_presence(const SystemIndicators &system_indicators); + +} // namespace utilities +} // namespace robot +} // namespace abb diff --git a/abb_rws_client/package.xml b/abb_rws_client/package.xml new file mode 100644 index 0000000..de23dc2 --- /dev/null +++ b/abb_rws_client/package.xml @@ -0,0 +1,26 @@ + + + + abb_rws_client + 0.0.0 + TODO: Package description + Grzegorz Bartyzel + Apache2 + + rclcpp + abb_egm_rws_managers + sensor_msgs + abb_egm_msgs + abb_rapid_msgs + abb_robot_msgs + abb_rapid_sm_addin_msgs + + ament_cmake_gtest + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/abb_rws_client/src/mapping.cpp b/abb_rws_client/src/mapping.cpp new file mode 100644 index 0000000..25c1824 --- /dev/null +++ b/abb_rws_client/src/mapping.cpp @@ -0,0 +1,478 @@ +/*********************************************************************************************************************** + * + * Copyright (c) 2020, ABB Schweiz AG + * 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 ABB 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 HOLDER 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. + * + *********************************************************************************************************************** + */ + +// System +#include +#include +#include + +// ROS + +// ABB INTERFACES +#include +#include +#include +#include + +#include "abb_rws_client/mapping.hpp" + +namespace { +/** + * \brief Name for ROS logging in the 'mapping' context. + */ +constexpr char ROS_LOG_MAPPING[]{"mapping"}; +} // namespace + +namespace abb { +namespace robot { +namespace utilities { + +/*********************************************************************************************************************** + * Utility function definitions (mapping from RWS to ROS representations) + */ + +uint8_t map(const rws::RWSInterface::RAPIDTaskExecutionState state) { + switch (state) { + case rws::RWSInterface::UNKNOWN: + return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_UNKNOWN; + break; + + case rws::RWSInterface::READY: + return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_READY; + break; + + case rws::RWSInterface::STOPPED: + return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_STOPPED; + break; + + case rws::RWSInterface::STARTED: + return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_STARTED; + break; + + case rws::RWSInterface::UNINITIALIZED: + return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_UNINITIALIZED; + break; + + default: + return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_UNKNOWN; + break; + } +} + +uint8_t map_state_machine_state(const rws::RAPIDNum& state) { + // Note: Inspect the StateMachine Add-In's RAPID implementation to see defined states. + switch (static_cast(state.value)) { + case 0: + return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_IDLE; + break; + + case 1: + return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_INITIALIZE; + break; + + case 2: + return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_RUN_RAPID_ROUTINE; + break; + + case 3: + return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_RUN_EGM_ROUTINE; + break; + + default: + return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_UNKNOWN; + break; + } +} + +uint8_t map_state_machine_egm_action(const rws::RAPIDNum& action) { + // Note: Inspect the StateMachine Add-In's RAPID implementation to see defined EGM actions. + switch (static_cast(action.value)) { + case 0: + return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_NONE; + break; + + case 1: + return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_RUN_JOINT; + break; + + case 2: + return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_RUN_POSE; + break; + + case 3: + return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_STOP; + break; + + case 4: + return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_START_STREAM; + break; + + case 5: + return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_STOP_STREAM; + break; + + default: + return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_UNKNOWN; + break; + } +} + +abb_rapid_msgs::msg::Pos map(const rws::Pos& rws_pos) { + abb_rapid_msgs::msg::Pos ros_pos{}; + ros_pos.x = rws_pos.x.value; + ros_pos.y = rws_pos.y.value; + ros_pos.z = rws_pos.z.value; + return ros_pos; +} + +abb_rapid_msgs::msg::Orient map(const rws::Orient& rws_orient) { + abb_rapid_msgs::msg::Orient ros_orient{}; + ros_orient.q1 = rws_orient.q1.value; + ros_orient.q2 = rws_orient.q2.value; + ros_orient.q3 = rws_orient.q3.value; + ros_orient.q4 = rws_orient.q4.value; + return ros_orient; +} + +abb_rapid_msgs::msg::Pose map(const rws::Pose& rws_pose) { + abb_rapid_msgs::msg::Pose ros_pose{}; + ros_pose.trans = map(rws_pose.pos); + ros_pose.rot = map(rws_pose.rot); + return ros_pose; +} + +abb_rapid_msgs::msg::LoadData map(const rws::LoadData& rws_loaddata) { + abb_rapid_msgs::msg::LoadData ros_loaddata{}; + ros_loaddata.mass = rws_loaddata.mass.value; + ros_loaddata.cog = map(rws_loaddata.cog); + ros_loaddata.aom = map(rws_loaddata.aom); + ros_loaddata.ix = rws_loaddata.ix.value; + ros_loaddata.iy = rws_loaddata.iy.value; + ros_loaddata.iz = rws_loaddata.iz.value; + return ros_loaddata; +} + +abb_rapid_msgs::msg::ToolData map(const rws::ToolData& rws_tooldata) { + abb_rapid_msgs::msg::ToolData ros_tooldata{}; + ros_tooldata.robhold = rws_tooldata.robhold.value; + ros_tooldata.tframe = map(rws_tooldata.tframe); + ros_tooldata.tload = map(rws_tooldata.tload); + return ros_tooldata; +} + +abb_rapid_msgs::msg::WObjData map(const rws::WObjData& rws_wobjdata) { + abb_rapid_msgs::msg::WObjData ros_wobjdata{}; + ros_wobjdata.robhold = rws_wobjdata.robhold.value; + ros_wobjdata.ufprog = rws_wobjdata.ufprog.value; + ros_wobjdata.ufmec = rws_wobjdata.ufmec.value; + ros_wobjdata.uframe = map(rws_wobjdata.uframe); + ros_wobjdata.oframe = map(rws_wobjdata.oframe); + return ros_wobjdata; +} + +abb_rapid_sm_addin_msgs::msg::EGMSettings map(const rws::RWSStateMachineInterface::EGMSettings& rws_egm_settings) { + abb_rapid_sm_addin_msgs::msg::EGMSettings ros_egm_settings{}; + + ros_egm_settings.allow_egm_motions = rws_egm_settings.allow_egm_motions.value; + ros_egm_settings.use_presync = rws_egm_settings.use_presync.value; + + ros_egm_settings.setup_uc.use_filtering = rws_egm_settings.setup_uc.use_filtering.value; + ros_egm_settings.setup_uc.comm_timeout = rws_egm_settings.setup_uc.comm_timeout.value; + + ros_egm_settings.activate.tool = utilities::map(rws_egm_settings.activate.tool); + ros_egm_settings.activate.wobj = utilities::map(rws_egm_settings.activate.wobj); + ros_egm_settings.activate.correction_frame = utilities::map(rws_egm_settings.activate.correction_frame); + ros_egm_settings.activate.sensor_frame = utilities::map(rws_egm_settings.activate.sensor_frame); + ros_egm_settings.activate.cond_min_max = rws_egm_settings.activate.cond_min_max.value; + ros_egm_settings.activate.lp_filter = rws_egm_settings.activate.lp_filter.value; + ros_egm_settings.activate.sample_rate = rws_egm_settings.activate.sample_rate.value; + ros_egm_settings.activate.max_speed_deviation = rws_egm_settings.activate.max_speed_deviation.value; + + ros_egm_settings.run.cond_time = rws_egm_settings.run.cond_time.value; + ros_egm_settings.run.ramp_in_time = rws_egm_settings.run.ramp_in_time.value; + ros_egm_settings.run.offset = utilities::map(rws_egm_settings.run.offset); + ros_egm_settings.run.pos_corr_gain = rws_egm_settings.run.pos_corr_gain.value; + + ros_egm_settings.stop.ramp_out_time = rws_egm_settings.stop.ramp_out_time.value; + + return ros_egm_settings; +} + +/*********************************************************************************************************************** + * Utility function definitions (mapping from ROS to RWS representations) + */ + +unsigned int map_state_machine_sg_command(const unsigned int command) { + switch (command) { + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_NONE: + return rws::RWSStateMachineInterface::SG_COMMAND_NONE; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_INITIALIZE: + return rws::RWSStateMachineInterface::SG_COMMAND_INITIALIZE; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_CALIBRATE: + return rws::RWSStateMachineInterface::SG_COMMAND_CALIBRATE; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_MOVE_TO: + return rws::RWSStateMachineInterface::SG_COMMAND_MOVE_TO; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_GRIP_IN: + return rws::RWSStateMachineInterface::SG_COMMAND_GRIP_IN; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_GRIP_OUT: + return rws::RWSStateMachineInterface::SG_COMMAND_GRIP_OUT; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_BLOW_ON_1: + return rws::RWSStateMachineInterface::SG_COMMAND_BLOW_ON_1; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_BLOW_ON_2: + return rws::RWSStateMachineInterface::SG_COMMAND_BLOW_ON_2; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_BLOW_OFF_1: + return rws::RWSStateMachineInterface::SG_COMMAND_BLOW_OFF_1; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_BLOW_OFF_2: + return rws::RWSStateMachineInterface::SG_COMMAND_BLOW_OFF_2; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_VACUUM_ON_1: + return rws::RWSStateMachineInterface::SG_COMMAND_VACUUM_ON_1; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_VACUUM_ON_2: + return rws::RWSStateMachineInterface::SG_COMMAND_VACUUM_ON_2; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_VACUUM_OFF_1: + return rws::RWSStateMachineInterface::SG_COMMAND_VACUUM_OFF_1; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_VACUUM_OFF_2: + return rws::RWSStateMachineInterface::SG_COMMAND_VACUUM_OFF_2; + break; + + case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_UNKNOWN: + default: + throw std::runtime_error{"Unknown SmartGripper command"}; + break; + } +} + +rws::Pos map(const abb_rapid_msgs::msg::Pos& ros_pos) { + rws::Pos rws_pos{}; + rws_pos.x.value = ros_pos.x; + rws_pos.y.value = ros_pos.y; + rws_pos.z.value = ros_pos.z; + return rws_pos; +} + +rws::Orient map(const abb_rapid_msgs::msg::Orient& ros_orient) { + rws::Orient rws_orient{}; + rws_orient.q1 = ros_orient.q1; + rws_orient.q2 = ros_orient.q2; + rws_orient.q3 = ros_orient.q3; + rws_orient.q4 = ros_orient.q4; + return rws_orient; +} + +rws::Pose map(const abb_rapid_msgs::msg::Pose& ros_pose) { + rws::Pose rws_pose{}; + rws_pose.pos = map(ros_pose.trans); + rws_pose.rot = map(ros_pose.rot); + return rws_pose; +} + +rws::LoadData map(const abb_rapid_msgs::msg::LoadData& ros_loaddata) { + rws::LoadData rws_loaddata{}; + rws_loaddata.mass.value = ros_loaddata.mass; + rws_loaddata.cog = map(ros_loaddata.cog); + rws_loaddata.aom = map(ros_loaddata.aom); + rws_loaddata.ix.value = ros_loaddata.ix; + rws_loaddata.iy.value = ros_loaddata.iy; + rws_loaddata.iz.value = ros_loaddata.iz; + return rws_loaddata; +} + +rws::ToolData map(const abb_rapid_msgs::msg::ToolData& ros_tooldata) { + rws::ToolData rws_tooldata{}; + rws_tooldata.robhold = ros_tooldata.robhold; + rws_tooldata.tframe = map(ros_tooldata.tframe); + rws_tooldata.tload = map(ros_tooldata.tload); + return rws_tooldata; +} + +rws::WObjData map(const abb_rapid_msgs::msg::WObjData& ros_wobjdata) { + rws::WObjData rws_wobjdata{}; + rws_wobjdata.robhold.value = ros_wobjdata.robhold; + rws_wobjdata.ufprog.value = ros_wobjdata.ufprog; + rws_wobjdata.ufmec.value = ros_wobjdata.ufmec; + rws_wobjdata.uframe = map(ros_wobjdata.uframe); + rws_wobjdata.oframe = map(ros_wobjdata.oframe); + return rws_wobjdata; +} + +rws::RWSStateMachineInterface::EGMSettings map(const abb_rapid_sm_addin_msgs::msg::EGMSettings& ros_egm_settings) { + rws::RWSStateMachineInterface::EGMSettings rws_egm_settings{}; + + rws_egm_settings.allow_egm_motions.value = ros_egm_settings.allow_egm_motions; + rws_egm_settings.use_presync.value = ros_egm_settings.use_presync; + + rws_egm_settings.setup_uc.use_filtering.value = ros_egm_settings.setup_uc.use_filtering; + rws_egm_settings.setup_uc.comm_timeout.value = ros_egm_settings.setup_uc.comm_timeout; + + rws_egm_settings.activate.tool = utilities::map(ros_egm_settings.activate.tool); + rws_egm_settings.activate.wobj = utilities::map(ros_egm_settings.activate.wobj); + rws_egm_settings.activate.correction_frame = utilities::map(ros_egm_settings.activate.correction_frame); + rws_egm_settings.activate.sensor_frame = utilities::map(ros_egm_settings.activate.sensor_frame); + rws_egm_settings.activate.cond_min_max = ros_egm_settings.activate.cond_min_max; + rws_egm_settings.activate.lp_filter = ros_egm_settings.activate.lp_filter; + rws_egm_settings.activate.sample_rate = ros_egm_settings.activate.sample_rate; + rws_egm_settings.activate.max_speed_deviation = ros_egm_settings.activate.max_speed_deviation; + + rws_egm_settings.run.cond_time = ros_egm_settings.run.cond_time; + rws_egm_settings.run.ramp_in_time = ros_egm_settings.run.ramp_in_time; + rws_egm_settings.run.offset = utilities::map(ros_egm_settings.run.offset); + rws_egm_settings.run.pos_corr_gain = ros_egm_settings.run.pos_corr_gain; + + rws_egm_settings.stop.ramp_out_time = ros_egm_settings.stop.ramp_out_time; + + return rws_egm_settings; +} + +/*********************************************************************************************************************** + * Utility function definitions (mapping from EGM to ROS representations) + */ + +uint8_t map(egm::wrapper::Status::EGMState state) { + switch (state) { + case egm::wrapper::Status::EGM_ERROR: + return abb_egm_msgs::msg::EGMChannelState::EGM_ERROR; + break; + + case egm::wrapper::Status::EGM_STOPPED: + return abb_egm_msgs::msg::EGMChannelState::EGM_STOPPED; + break; + + case egm::wrapper::Status::EGM_RUNNING: + return abb_egm_msgs::msg::EGMChannelState::EGM_RUNNING; + break; + + case egm::wrapper::Status::EGM_UNDEFINED: + default: + return abb_egm_msgs::msg::EGMChannelState::EGM_UNDEFINED; + break; + } +} + +uint8_t map(egm::wrapper::Status::MotorState state) { + switch (state) { + case egm::wrapper::Status::MOTORS_ON: + return abb_egm_msgs::msg::EGMChannelState::MOTORS_ON; + break; + + case egm::wrapper::Status::MOTORS_OFF: + return abb_egm_msgs::msg::EGMChannelState::MOTORS_OFF; + break; + + case egm::wrapper::Status::MOTORS_UNDEFINED: + default: + return abb_egm_msgs::msg::EGMChannelState::MOTORS_UNDEFINED; + break; + } +} + +uint8_t map(egm::wrapper::Status::RAPIDExecutionState state) { + switch (state) { + case egm::wrapper::Status::RAPID_STOPPED: + return abb_egm_msgs::msg::EGMChannelState::RAPID_STOPPED; + break; + + case egm::wrapper::Status::RAPID_RUNNING: + return abb_egm_msgs::msg::EGMChannelState::RAPID_RUNNING; + break; + + case egm::wrapper::Status::RAPID_UNDEFINED: + default: + return abb_egm_msgs::msg::EGMChannelState::RAPID_UNDEFINED; + break; + } +} + +/*********************************************************************************************************************** + * Utility template function definitions + */ + +template +std::string map_vector_to_string(const std::vector& vector) { + std::stringstream ss{}; + + ss << "["; + for (size_t i{0}; i < vector.size(); ++i) { + ss << vector[i]; + + if (ss.fail()) { + std::string error_message{"Failed to map vector to string"}; + throw std::runtime_error{error_message}; + } + + ss << (i < vector.size() - 1 ? ", " : ""); + } + ss << "]"; + + return ss.str(); +} + +/*********************************************************************************************************************** + * Utility template function instantiations + */ + +template std::string map_vector_to_string(const std::vector& vector); +template std::string map_vector_to_string(const std::vector& vector); +template std::string map_vector_to_string(const std::vector& vector); +template std::string map_vector_to_string(const std::vector& vector); + +} // namespace utilities +} // namespace robot +} // namespace abb diff --git a/abb_rws_client/src/rws_client.cpp b/abb_rws_client/src/rws_client.cpp new file mode 100644 index 0000000..0f5c149 --- /dev/null +++ b/abb_rws_client/src/rws_client.cpp @@ -0,0 +1,25 @@ +#include "abb_rws_client/rws_client.hpp" + +#include "abb_rws_client/utilities.hpp" + +namespace abb_rws_client { +RWSClient::RWSClient(const rclcpp::Node::SharedPtr &node, const std::string &robot_ip, unsigned short robot_port) + : node_(node), + rws_manager_{robot_ip, robot_port, abb::rws::SystemConstants::General::DEFAULT_USERNAME, + abb::rws::SystemConstants::General::DEFAULT_PASSWORD} { + node_->declare_parameter("robot_nickname", std::string{}); + node_->declare_parameter("no_connection_timeout", false); + + connect(); +} +void RWSClient::connect() { + std::string robot_id; + bool no_connection_timeout; + + node_->get_parameter("robot_nickname", robot_id); + node_->get_parameter("no_connection_timeout", no_connection_timeout); + robot_controller_description_ = + abb::robot::utilities::establish_rws_connection(rws_manager_, robot_id, no_connection_timeout); + abb::robot::utilities::verify_robotware_version(robot_controller_description_.header().robot_ware_version()); +} +} // namespace abb_rws_client diff --git a/abb_rws_client/src/rws_client_node.cpp b/abb_rws_client/src/rws_client_node.cpp new file mode 100644 index 0000000..af3c152 --- /dev/null +++ b/abb_rws_client/src/rws_client_node.cpp @@ -0,0 +1,26 @@ +#include + +#include "abb_rws_client/rws_service_provider_ros.hpp" +#include "abb_rws_client/rws_state_publisher_ros.hpp" + +int main(int argc, char** argv) { + rclcpp::init(argc, argv); + + rclcpp::Node::SharedPtr client_node = rclcpp::Node::make_shared("rws"); + + std::string robot_ip = client_node->declare_parameter("robot_ip", "127.0.0.1"); + int robot_port = client_node->declare_parameter("robot_port", 65535); + + client_node->get_parameter("robot_ip", robot_ip); + client_node->get_parameter("robot_port", robot_port); + + abb_rws_client::RWSServiceProviderROS srv_provider(client_node, robot_ip, robot_port); + abb_rws_client::RWSStatePublisherROS state_publisher(client_node, robot_ip, robot_port); + + rclcpp::executors::MultiThreadedExecutor exec; + exec.add_node(client_node); + + exec.spin(); + + return 0; +} diff --git a/abb_rws_client/src/rws_service_provider_ros.cpp b/abb_rws_client/src/rws_service_provider_ros.cpp new file mode 100644 index 0000000..1f7ff1f --- /dev/null +++ b/abb_rws_client/src/rws_service_provider_ros.cpp @@ -0,0 +1,1146 @@ +#include "abb_rws_client/rws_service_provider_ros.hpp" + +#include + +#include "abb_rws_client/mapping.hpp" +#include "abb_rws_client/utilities.hpp" + +using RAPIDSymbols = abb::rws::RWSStateMachineInterface::ResourceIdentifiers::RAPID::Symbols; + +namespace abb_rws_client { +RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, + unsigned short robot_port) + : RWSClient(node, robot_ip, robot_port) { + system_state_sub_ = node_->create_subscription( + "system_states", 10, std::bind(&RWSServiceProviderROS::system_state_callback, this, std::placeholders::_1)); + runtime_state_sub_ = node_->create_subscription( + "sm_addin/runtime_states", 10, + std::bind(&RWSServiceProviderROS::runtime_state_callback, this, std::placeholders::_1)); + + core_services_.push_back(node_->create_service( + "~/get_robot_controller_description", + std::bind(&RWSServiceProviderROS::get_rc_description, this, std::placeholders::_1, std::placeholders::_2))); + + core_services_.push_back(node_->create_service( + "~/get_file_contents", + std::bind(&RWSServiceProviderROS::get_file_contents, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/get_io_signal", + std::bind(&RWSServiceProviderROS::get_io_signal, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/get_rapid_bool", + std::bind(&RWSServiceProviderROS::get_rapid_bool, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/get_rapid_dnum", + std::bind(&RWSServiceProviderROS::get_rapid_dnum, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/get_rapid_num", + std::bind(&RWSServiceProviderROS::get_rapid_num, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/get_rapid_string", + std::bind(&RWSServiceProviderROS::get_rapid_string, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/get_rapid_symbol", + std::bind(&RWSServiceProviderROS::get_rapid_symbol, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/get_speed_ratio", + std::bind(&RWSServiceProviderROS::get_speed_ratio, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/pp_to_main", + std::bind(&RWSServiceProviderROS::pp_to_main, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/set_file_contents", + std::bind(&RWSServiceProviderROS::set_file_contents, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/set_io_signal", + std::bind(&RWSServiceProviderROS::set_io_signal, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/set_motors_off", + std::bind(&RWSServiceProviderROS::set_motors_off, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/set_motors_on", + std::bind(&RWSServiceProviderROS::set_motors_on, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/set_rapid_bool", + std::bind(&RWSServiceProviderROS::set_rapid_bool, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/set_rapid_dnum", + std::bind(&RWSServiceProviderROS::set_rapid_dnum, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/set_rapid_num", + std::bind(&RWSServiceProviderROS::set_rapid_num, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/set_rapid_string", + std::bind(&RWSServiceProviderROS::set_rapid_string, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/set_rapid_symbol", + std::bind(&RWSServiceProviderROS::set_rapid_symbol, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/set_speed_ratio", + std::bind(&RWSServiceProviderROS::set_speed_ratio, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/start_rapid", + std::bind(&RWSServiceProviderROS::start_rapid, this, std::placeholders::_1, std::placeholders::_2))); + core_services_.push_back(node_->create_service( + "~/stop_rapid", + std::bind(&RWSServiceProviderROS::stop_rapid, this, std::placeholders::_1, std::placeholders::_2))); + + const auto& system_indicators = robot_controller_description_.system_indicators(); + + auto has_sm_1_0 = system_indicators.addins().has_state_machine_1_0(); + auto has_sm_1_1 = system_indicators.addins().has_state_machine_1_1(); + if (has_sm_1_0) { + RCLCPP_DEBUG_STREAM(node_->get_logger(), "StateMachine Add-In 1.0 detected"); + } else if (has_sm_1_1) { + RCLCPP_DEBUG_STREAM(node_->get_logger(), "StateMachine Add-In 1.1 detected"); + } else { + RCLCPP_DEBUG_STREAM(node_->get_logger(), "No StateMachine Add-In detected"); + } + + if (has_sm_1_0 || has_sm_1_1) { + sm_services_.push_back(node_->create_service( + "~/run_rapid_routine", + std::bind(&RWSServiceProviderROS::run_rapid_routine, this, std::placeholders::_1, std::placeholders::_2))); + sm_services_.push_back(node_->create_service( + "~/set_rapid_routine", + std::bind(&RWSServiceProviderROS::set_rapid_routine, this, std::placeholders::_1, std::placeholders::_2))); + if (system_indicators.options().egm()) { + sm_services_.push_back(node_->create_service( + "get_egm_settings", + std::bind(&RWSServiceProviderROS::get_egm_settings, this, std::placeholders::_1, std::placeholders::_2))); + sm_services_.push_back(node_->create_service( + "set_egm_settings", + std::bind(&RWSServiceProviderROS::set_egm_settings, this, std::placeholders::_1, std::placeholders::_2))); + sm_services_.push_back(node_->create_service( + "start_egm_joint", + std::bind(&RWSServiceProviderROS::start_egm_joint, this, std::placeholders::_1, std::placeholders::_2))); + sm_services_.push_back(node_->create_service( + "start_egm_pose", + std::bind(&RWSServiceProviderROS::start_egm_pose, this, std::placeholders::_1, std::placeholders::_2))); + sm_services_.push_back(node_->create_service( + "stop_egm", std::bind(&RWSServiceProviderROS::stop_egm, this, std::placeholders::_1, std::placeholders::_2))); + if (has_sm_1_1) { + sm_services_.push_back(node_->create_service( + "start_egm_stream", + std::bind(&RWSServiceProviderROS::start_egm_stream, this, std::placeholders::_1, std::placeholders::_2))); + sm_services_.push_back(node_->create_service( + "stop_egm_stream", + std::bind(&RWSServiceProviderROS::stop_egm_stream, this, std::placeholders::_1, std::placeholders::_2))); + } + } + + if (system_indicators.addins().smart_gripper()) { + sm_services_.push_back(node_->create_service( + "run_sg_routine", + std::bind(&RWSServiceProviderROS::run_sg_routine, this, std::placeholders::_1, std::placeholders::_2))); + sm_services_.push_back(node_->create_service( + "set_sg_command", + std::bind(&RWSServiceProviderROS::set_sg_command, this, std::placeholders::_1, std::placeholders::_2))); + } + } +} + +void RWSServiceProviderROS::system_state_callback(const abb_robot_msgs::msg::SystemState& msg) { system_state_ = msg; } + +void RWSServiceProviderROS::runtime_state_callback(const abb_rapid_sm_addin_msgs::msg::RuntimeState& msg) { + runtime_state_ = msg; +} + +bool RWSServiceProviderROS::get_rc_description( + const abb_robot_msgs::srv::GetRobotControllerDescription::Request::SharedPtr req, + abb_robot_msgs::srv::GetRobotControllerDescription::Response::SharedPtr res) { + res->description = robot_controller_description_.DebugString(); + + res->message = abb_robot_msgs::msg::ServiceResponses::SUCCESS; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + + return true; +} + +bool RWSServiceProviderROS::get_file_contents(const abb_robot_msgs::srv::GetFileContents::Request::SharedPtr req, + abb_robot_msgs::srv::GetFileContents::Response::SharedPtr res) { + if (!verify_argument_filename(req->filename, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.getFile(abb::rws::RWSClient::FileResource(req->filename), &res->contents)) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::get_io_signal(const abb_robot_msgs::srv::GetIOSignal::Request::SharedPtr req, + abb_robot_msgs::srv::GetIOSignal::Response::SharedPtr res) { + if (!verify_argument_signal(req->signal, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + res->value = interface.getIOSignal(req->signal); + + if (!res->value.empty()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::get_rapid_bool(const abb_robot_msgs::srv::GetRAPIDBool::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDBool::Response::SharedPtr res) { + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + abb::rws::RAPIDBool rapid_bool; + if (interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, &rapid_bool)) { + res->value = rapid_bool.value; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::get_rapid_dnum(const abb_robot_msgs::srv::GetRAPIDDnum::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDDnum::Response::SharedPtr res) { + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + abb::rws::RAPIDDnum rapid_dnum; + if (interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, &rapid_dnum)) { + res->value = rapid_dnum.value; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::get_rapid_num(const abb_robot_msgs::srv::GetRAPIDNum::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDNum::Response::SharedPtr res) { + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + abb::rws::RAPIDNum rapid_num{}; + if (interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, &rapid_num)) { + res->value = rapid_num.value; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::get_rapid_string(const abb_robot_msgs::srv::GetRAPIDString::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDString::Response::SharedPtr res) { + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + abb::rws::RAPIDString rapid_string{}; + if (interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, &rapid_string)) { + res->value = rapid_string.value; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::get_rapid_symbol(const abb_robot_msgs::srv::GetRAPIDSymbol::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDSymbol::Response::SharedPtr res) { + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + res->value = interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol); + + if (!res->value.empty()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::get_speed_ratio(const abb_robot_msgs::srv::GetSpeedRatio::Request::SharedPtr, + abb_robot_msgs::srv::GetSpeedRatio::Response::SharedPtr res) { + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + try { + res->speed_ratio = interface.getSpeedRatio(); + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } catch (const std::runtime_error& exception) { + res->message = exception.what(); + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + } + }); + + return true; +} + +bool RWSServiceProviderROS::pp_to_main(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rapid_stopped(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.resetRAPIDProgramPointer()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} +bool RWSServiceProviderROS::run_rapid_routine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rapid_running(res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.services().rapid().signalRunRAPIDRoutine()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::run_sg_routine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rapid_running(res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.services().sg().signalRunSGRoutine()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_file_contents(const abb_robot_msgs::srv::SetFileContents::Request::SharedPtr req, + abb_robot_msgs::srv::SetFileContents::Response::SharedPtr res) { + if (!verify_argument_filename(req->filename, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.uploadFile(abb::rws::RWSClient::FileResource(req->filename), req->contents)) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_io_signal(const abb_robot_msgs::srv::SetIOSignal::Request::SharedPtr req, + abb_robot_msgs::srv::SetIOSignal::Response::SharedPtr res) { + if (!verify_argument_signal(req->signal, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.setIOSignal(req->signal, req->value)) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_motors_off(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { + if (!verify_motors_on(res->result_code, res->message)) { + return true; + } + + rws_manager_.runPriorityService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.setMotorsOff()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_motors_on(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_motors_off(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.setMotorsOn()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_rapid_bool(const abb_robot_msgs::srv::SetRAPIDBool::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDBool::Response::SharedPtr res) { + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + return true; + } + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + abb::rws::RAPIDBool rapid_bool = static_cast(req->value); + if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, rapid_bool)) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_rapid_dnum(const abb_robot_msgs::srv::SetRAPIDDnum::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDDnum::Response::SharedPtr res) { + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + return true; + } + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + abb::rws::RAPIDDnum rapid_dnum = req->value; + if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, rapid_dnum)) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_rapid_num(const abb_robot_msgs::srv::SetRAPIDNum::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDNum::Response::SharedPtr res) { + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + return true; + } + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + abb::rws::RAPIDNum rapid_num = req->value; + if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, rapid_num)) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_rapid_string(const abb_robot_msgs::srv::SetRAPIDString::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDString::Response::SharedPtr res) { + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + return true; + } + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + abb::rws::RAPIDString rapid_string = req->value; + if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, rapid_string)) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_rapid_symbol(const abb_robot_msgs::srv::SetRAPIDSymbol::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDSymbol::Response::SharedPtr res) { + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + return true; + } + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, req->value)) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_speed_ratio(const abb_robot_msgs::srv::SetSpeedRatio::Request::SharedPtr req, + abb_robot_msgs::srv::SetSpeedRatio::Response::SharedPtr res) { + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + try { + if (interface.setSpeedRatio(req->speed_ratio)) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + } catch (const std::exception& exception) { + res->message = exception.what(); + } + }); + + return true; +} + +bool RWSServiceProviderROS::start_rapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_motors_on(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.startRAPIDExecution()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::stop_rapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { + if (!verify_rapid_running(res->result_code, res->message)) { + return true; + } + + rws_manager_.runPriorityService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.stopRAPIDExecution()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::get_egm_settings(const abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Response::SharedPtr res) { + if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + abb::rws::RWSStateMachineInterface::EGMSettings settings; + + if (interface.services().egm().getSettings(req->task, &settings)) { + res->settings = abb::robot::utilities::map(settings); + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_egm_settings(const abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Response::SharedPtr res) { + if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) { + return true; + } + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_task_initialized(req->task, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + abb::rws::RWSStateMachineInterface::EGMSettings settings = abb::robot::utilities::map(req->settings); + + if (interface.services().egm().setSettings(req->task, settings)) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_rapid_routine( + const abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Response::SharedPtr res) { + if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) { + return true; + } + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_task_initialized(req->task, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.services().rapid().setRoutineName(req->task, req->routine)) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::set_sg_command(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::SetSGCommand::Response::SharedPtr res) { + if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) { + return true; + } + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_task_initialized(req->task, res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + unsigned int req_command = 0; + try { + req_command = abb::robot::utilities::map_state_machine_sg_command(req->command); + } catch (const std::runtime_error& exception) { + res->message = exception.what(); + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + abb::rws::RAPIDNum sg_command_input = static_cast(req_command); + abb::rws::RAPIDNum sg_target_position_input = req->target_position; + + if (interface.setRAPIDSymbolData(req->task, RAPIDSymbols::SG_COMMAND_INPUT, sg_command_input) && + interface.setRAPIDSymbolData(req->task, RAPIDSymbols::SG_TARGET_POSTION_INPUT, sg_target_position_input)) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::start_egm_joint(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rapid_running(res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.services().egm().signalEGMStartJoint()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::start_egm_pose(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rapid_running(res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.services().egm().signalEGMStartPose()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::start_egm_stream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rapid_running(res->result_code, res->message)) { + return true; + } + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.services().egm().signalEGMStartStream()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + } + }); + + return true; +} + +bool RWSServiceProviderROS::stop_egm(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rapid_running(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runPriorityService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.services().egm().signalEGMStop()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::stop_egm_stream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { + if (!verify_auto_mode(res->result_code, res->message)) { + return true; + } + if (!verify_rapid_running(res->result_code, res->message)) { + return true; + } + if (!verify_rws_manager_ready(res->result_code, res->message)) { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.services().egm().signalEGMStopStream()) { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } else { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::verify_auto_mode(uint16_t& result_code, std::string& message) { + if (!system_state_.auto_mode) { + message = abb_robot_msgs::msg::ServiceResponses::NOT_IN_AUTO_MODE; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_NOT_IN_AUTO_MODE; + return false; + } + + return true; +} + +bool RWSServiceProviderROS::verify_argument_filename(const std::string& filename, uint16_t& result_code, + std::string& message) { + if (filename.empty()) { + message = abb_robot_msgs::msg::ServiceResponses::EMPTY_FILENAME; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_EMPTY_FILENAME; + return false; + } + + return true; +} + +bool RWSServiceProviderROS::verify_argument_rapid_symbol_path(const abb_robot_msgs::msg::RAPIDSymbolPath& path, + uint16_t& result_code, std::string& message) { + if (path.task.empty()) { + message = abb_robot_msgs::msg::ServiceResponses::EMPTY_RAPID_TASK_NAME; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_EMPTY_RAPID_TASK_NAME; + return false; + } + + if (path.module.empty()) { + message = abb_robot_msgs::msg::ServiceResponses::EMPTY_RAPID_MODULE_NAME; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_EMPTY_RAPID_MODULE_NAME; + return false; + } + + if (path.symbol.empty()) { + message = abb_robot_msgs::msg::ServiceResponses::EMPTY_RAPID_SYMBOL_NAME; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_EMPTY_RAPID_SYMBOL_NAME; + return false; + } + + return true; +} + +bool RWSServiceProviderROS::verify_argument_rapid_task(const std::string& task, uint16_t& result_code, + std::string& message) { + if (task.empty()) { + message = abb_robot_msgs::msg::ServiceResponses::EMPTY_RAPID_TASK_NAME; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_EMPTY_RAPID_TASK_NAME; + return false; + } + + return true; +} + +bool RWSServiceProviderROS::verify_argument_signal(const std::string& signal, uint16_t& result_code, + std::string& message) { + if (signal.empty()) { + message = abb_robot_msgs::msg::ServiceResponses::EMPTY_SIGNAL_NAME; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_EMPTY_SIGNAL_NAME; + return false; + } + + return true; +} + +bool RWSServiceProviderROS::verify_motors_off(uint16_t& result_code, std::string& message) { + if (system_state_.motors_on) { + message = abb_robot_msgs::msg::ServiceResponses::MOTORS_ARE_ON; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_MOTORS_ARE_ON; + return false; + } + + return true; +} + +bool RWSServiceProviderROS::verify_motors_on(uint16_t& result_code, std::string& message) { + if (!system_state_.motors_on) { + message = abb_robot_msgs::msg::ServiceResponses::MOTORS_ARE_OFF; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_MOTORS_ARE_OFF; + return false; + } + + return true; +} + +bool RWSServiceProviderROS::verify_sm_addin_runtime_states(uint16_t& result_code, std::string& message) { + if (runtime_state_.state_machines.empty()) { + message = abb_robot_msgs::msg::ServiceResponses::SM_RUNTIME_STATES_MISSING; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_SM_RUNTIME_STATES_MISSING; + return false; + } + + return true; +} + +bool RWSServiceProviderROS::verify_sm_addin_task_exist(const std::string& task, uint16_t& result_code, + std::string& message) { + auto it = std::find_if(runtime_state_.state_machines.begin(), runtime_state_.state_machines.end(), + [&](const auto& sm) { return sm.rapid_task == task; }); + + if (it == runtime_state_.state_machines.end()) { + message = abb_robot_msgs::msg::ServiceResponses::SM_UNKNOWN_RAPID_TASK; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_SM_UNKNOWN_RAPID_TASK; + return false; + } + + return true; +} + +bool RWSServiceProviderROS::verify_sm_addin_task_initialized(const std::string& task, uint16_t& result_code, + std::string& message) { + if (!verify_sm_addin_task_exist(task, result_code, message)) return false; + + auto it = std::find_if(runtime_state_.state_machines.begin(), runtime_state_.state_machines.end(), + [&](const auto& sm) { return sm.rapid_task == task; }); + + if (it->sm_state == abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_UNKNOWN || + it->sm_state == abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_INITIALIZE) { + message = abb_robot_msgs::msg::ServiceResponses::SM_UNINITIALIZED; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_SM_UNINITIALIZED; + return false; + } + + return true; +} + +bool RWSServiceProviderROS::verify_rapid_running(uint16_t& result_code, std::string& message) { + if (!system_state_.rapid_running) { + message = abb_robot_msgs::msg::ServiceResponses::RAPID_NOT_RUNNING; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_RAPID_NOT_RUNNING; + return false; + } + + return true; +} + +bool RWSServiceProviderROS::verify_rapid_stopped(uint16_t& result_code, std::string& message) { + if (system_state_.rapid_running) { + message = abb_robot_msgs::msg::ServiceResponses::RAPID_NOT_STOPPED; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_RAPID_NOT_STOPPED; + return false; + } + + return true; +} + +bool RWSServiceProviderROS::verify_rws_manager_ready(uint16_t& result_code, std::string& message) { + if (!rws_manager_.isInterfaceReady()) { + message = abb_robot_msgs::msg::ServiceResponses::SERVER_IS_BUSY; + result_code = abb_robot_msgs::msg::ServiceResponses::RC_SERVER_IS_BUSY; + return false; + } + + return true; +} + +} // namespace abb_rws_client diff --git a/abb_rws_client/src/rws_state_publisher_ros.cpp b/abb_rws_client/src/rws_state_publisher_ros.cpp new file mode 100644 index 0000000..33d632d --- /dev/null +++ b/abb_rws_client/src/rws_state_publisher_ros.cpp @@ -0,0 +1,98 @@ +#include "abb_rws_client/rws_state_publisher_ros.hpp" + +#include "abb_rws_client/mapping.hpp" +#include "abb_rws_client/utilities.hpp" + +namespace { +/** + * \brief Time [s] for throttled ROS logging. + */ +constexpr double THROTTLE_TIME{10.0}; +} // namespace + +namespace abb_rws_client { +RWSStatePublisherROS::RWSStatePublisherROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, + unsigned short robot_port) + : RWSClient(node, robot_ip, robot_port) { + node_->declare_parameter("polling_rate", 5.0); + abb::robot::initializeMotionData(motion_data_, robot_controller_description_); + + auto sensor_qos = + rclcpp::QoS(rclcpp::QoSInitialization(rmw_qos_profile_sensor_data.history, rmw_qos_profile_sensor_data.depth), + rmw_qos_profile_sensor_data); + joint_state_pub_ = node_->create_publisher("~/joint_states", sensor_qos); + + system_state_pub_ = node_->create_publisher("~/system_state", 1); + + if (abb::robot::utilities::verify_state_machine_add_in_presence(robot_controller_description_.system_indicators())) { + runtime_state_pub_ = + node_->create_publisher("~/sm_addin/runtime_state", 1); + } +} + +void RWSStatePublisherROS::timer_callback() { + try { + rws_manager_.collectAndUpdateRuntimeData(system_state_data_, motion_data_); + } catch (const std::runtime_error& exception) { + auto& clk = *node_->get_clock(); + RCLCPP_WARN_STREAM_THROTTLE( + node_->get_logger(), clk, THROTTLE_TIME, + "Periodic polling of runtime data via RWS failed with '" << exception.what() << "' (will try again later)"); + } + + sensor_msgs::msg::JointState joint_state_msg; + for (auto& group : motion_data_.groups) { + for (auto& unit : group.units) { + for (auto& joint : unit.joints) { + joint_state_msg.name.push_back(joint.name); + joint_state_msg.position.push_back(joint.state.position); + } + } + } + + abb_robot_msgs::msg::SystemState system_state_msg; + system_state_msg.motors_on = system_state_data_.motors_on.isTrue(); + system_state_msg.auto_mode = system_state_data_.auto_mode.isTrue(); + system_state_msg.rapid_running = system_state_data_.rapid_running.isTrue(); + + for (const auto& task : system_state_data_.rapid_tasks) { + abb_robot_msgs::msg::RAPIDTaskState state{}; + + state.name = task.name; + state.activated = task.is_active; + state.execution_state = abb::robot::utilities::map(task.execution_state); + state.motion_task = task.is_motion_task; + + system_state_msg.rapid_tasks.push_back(state); + } + + for (const auto& unit : system_state_data_.mechanical_units) { + abb_robot_msgs::msg::MechanicalUnitState state{}; + state.name = unit.first; + state.activated = unit.second.active; + system_state_msg.mechanical_units.push_back(state); + } + + abb_rapid_sm_addin_msgs::msg::RuntimeState sm_runtime_state_msg; + const auto& system_indicators{robot_controller_description_.system_indicators()}; + if (abb::robot::utilities::verify_state_machine_add_in_presence(system_indicators)) { + for (const auto& sm : system_state_data_.state_machines) { + abb_rapid_sm_addin_msgs::msg::StateMachineState state; + state.rapid_task = sm.rapid_task; + state.sm_state = abb::robot::utilities::map_state_machine_state(sm.sm_state); + state.egm_action = abb::robot::utilities::map_state_machine_egm_action(sm.egm_action); + sm_runtime_state_msg.state_machines.push_back(state); + } + } + + auto time = node_->get_clock()->now(); + joint_state_msg.header.stamp = time; + joint_state_pub_->publish(joint_state_msg); + + system_state_msg.header.stamp = time; + system_state_pub_->publish(system_state_msg); + + sm_runtime_state_msg.header.stamp = time; + runtime_state_pub_->publish(sm_runtime_state_msg); +} +} // namespace abb_rws_client diff --git a/abb_rws_client/src/utilities.cpp b/abb_rws_client/src/utilities.cpp new file mode 100644 index 0000000..482f0de --- /dev/null +++ b/abb_rws_client/src/utilities.cpp @@ -0,0 +1,113 @@ +/*********************************************************************************************************************** + * + * Copyright (c) 2020, ABB Schweiz AG + * 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 ABB 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 HOLDER 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. + * + *********************************************************************************************************************** + */ + +// This file is a modified copy from +// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/initialization.cpp + +#include "abb_rws_client/utilities.hpp" + +#include + +#include "rclcpp/rclcpp.hpp" + +namespace abb { +namespace robot { +namespace utilities { +namespace { +/** + * \brief Max number of attempts when trying to connect to a robot controller via RWS. + */ +constexpr unsigned int RWS_MAX_CONNECTION_ATTEMPTS{5}; + +/** + * \brief Error message for failed connection attempts when trying to connect to a robot controller + * via RWS. + */ +constexpr char RWS_CONNECTION_ERROR_MESSAGE[]{ + "Failed to establish RWS connection to the robot controller"}; + +/** + * \brief Time [s] to wait before trying to reconnect to a robot controller via RWS. + */ +constexpr uint8_t RWS_RECONNECTION_WAIT_TIME{1}; +auto LOGGER = rclcpp::get_logger("ABBHardwareInterfaceUtilities"); +} // namespace + +RobotControllerDescription establish_rws_connection(RWSManager& rws_manager, + const std::string& robot_controller_id, + const bool no_connection_timeout) { + unsigned int attempt{0}; + + while (rclcpp::ok() && (no_connection_timeout || attempt++ < RWS_MAX_CONNECTION_ATTEMPTS)) { + try { + return rws_manager.collectAndParseSystemData(robot_controller_id); + } catch (const std::runtime_error& exception) { + if (!no_connection_timeout) { + RCLCPP_WARN_STREAM(LOGGER, RWS_CONNECTION_ERROR_MESSAGE << " (attempt " << attempt << "/" + << RWS_MAX_CONNECTION_ATTEMPTS + << "), reason: '" + << exception.what() << "'"); + } else { + RCLCPP_WARN_STREAM(LOGGER, RWS_CONNECTION_ERROR_MESSAGE + << " (waiting indefinitely), reason: '" << exception.what() + << "'"); + } + rclcpp::sleep_for(std::chrono::seconds(RWS_RECONNECTION_WAIT_TIME)); + } + } + + throw std::runtime_error{RWS_CONNECTION_ERROR_MESSAGE}; +} + +void verify_robotware_version(const RobotWareVersion& rw_version) { + if (rw_version.major_number() == 6 && rw_version.minor_number() < 7 && + rw_version.patch_number() < 1) { + auto error_message{"Unsupported RobotWare version (" + rw_version.name() + + ", need at least 6.07.01)"}; + + RCLCPP_FATAL_STREAM(LOGGER, error_message); + throw std::runtime_error{error_message}; + } +} + +bool verify_state_machine_add_in_presence(const SystemIndicators& system_indicators) { + return system_indicators.addins().state_machine_1_0() || + system_indicators.addins().state_machine_1_1(); +} + +} // namespace utilities +} // namespace robot +} // namespace abb From 4a83dc452e055fe0c4ba263f99186f1c49189905 Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Tue, 5 Apr 2022 15:47:05 +0200 Subject: [PATCH 02/27] Merge abb_rws_client to abb_hardware_interface --- ...tem_position_only.cpp.A4A69E936E6E2EFB.idx | Bin 0 -> 12386 bytes ...tem_position_only.hpp.B82A1AE2C2DC8731.idx | Bin 0 -> 3436 bytes .../index/mapping.cpp.53C83202D804659B.idx | Bin 0 -> 21880 bytes .../index/mapping.cpp.981962BE1449DDD9.idx | Bin 0 -> 21854 bytes .../index/mapping.hpp.83C0C81544CCABFA.idx | Bin 0 -> 9988 bytes .../index/mapping.hpp.F4EF52C8E9EA4882.idx | Bin 0 -> 10136 bytes .../index/rws_client.cpp.B2625E19C4ED09CA.idx | Bin 0 -> 2694 bytes .../index/rws_client.cpp.D2D6995B64F84F58.idx | Bin 0 -> 2692 bytes .../index/rws_client.hpp.3738C46199137910.idx | Bin 0 -> 1198 bytes .../index/rws_client.hpp.F6B6AF448BD65A95.idx | Bin 0 -> 1230 bytes .../rws_client_node.cpp.3230C9A14C046783.idx | Bin 0 -> 2474 bytes .../rws_client_node.cpp.32950DC259F660B7.idx | Bin 0 -> 2466 bytes ...vice_provider_ros.cpp.2F7E35170D7F40E3.idx | Bin 0 -> 44972 bytes ...vice_provider_ros.cpp.F36FFB6C47C5231C.idx | Bin 0 -> 1664 bytes ...vice_provider_ros.hpp.11A527BD4315BF59.idx | Bin 0 -> 13240 bytes ...vice_provider_ros.hpp.FF9EC95DBE8BABD9.idx | Bin 0 -> 12952 bytes ...ate_publisher_ros.cpp.1AEA19B09DBBB081.idx | Bin 0 -> 6158 bytes ...ate_publisher_ros.cpp.8C64C24778513E26.idx | Bin 0 -> 6158 bytes ...ate_publisher_ros.hpp.10B80F8842563FCC.idx | Bin 0 -> 2002 bytes ...ate_publisher_ros.hpp.87F144D7A6D84D06.idx | Bin 0 -> 2070 bytes .../index/utilities.cpp.37995F883B5F548E.idx | Bin 0 -> 5832 bytes .../index/utilities.cpp.8466B813AD21AFA5.idx | Bin 0 -> 5560 bytes .../index/utilities.hpp.62390E5A28AD6DA6.idx | Bin 0 -> 1768 bytes .../index/utilities.hpp.F418EFD6A6E9D646.idx | Bin 0 -> 2284 bytes .../visibility_control.h.F5187384E0A565C2.idx | Bin 0 -> 326 bytes abb_hardware_interface/CMakeLists.txt | 26 ++++ .../abb_hardware_interface}/mapping.hpp | 0 .../abb_hardware_interface}/rws_client.hpp | 0 .../rws_service_provider_ros.hpp | 3 +- .../rws_state_publisher_ros.hpp | 2 +- .../abb_hardware_interface/utilities.hpp | 21 +++- abb_hardware_interface/package.xml | 5 + .../src/abb_system_position_only.cpp | 2 +- .../src/mapping.cpp | 4 +- .../src/rws_client.cpp | 4 +- .../src/rws_client_node.cpp | 4 +- .../src/rws_service_provider_ros.cpp | 6 +- .../src/rws_state_publisher_ros.cpp | 6 +- abb_hardware_interface/src/utilities.cpp | 17 ++- abb_rws_client/CMakeLists.txt | 79 ------------ .../include/abb_rws_client/utilities.hpp | 72 ----------- abb_rws_client/package.xml | 26 ---- abb_rws_client/src/utilities.cpp | 113 ------------------ 43 files changed, 81 insertions(+), 309 deletions(-) create mode 100644 .cache/clangd/index/abb_system_position_only.cpp.A4A69E936E6E2EFB.idx create mode 100644 .cache/clangd/index/abb_system_position_only.hpp.B82A1AE2C2DC8731.idx create mode 100644 .cache/clangd/index/mapping.cpp.53C83202D804659B.idx create mode 100644 .cache/clangd/index/mapping.cpp.981962BE1449DDD9.idx create mode 100644 .cache/clangd/index/mapping.hpp.83C0C81544CCABFA.idx create mode 100644 .cache/clangd/index/mapping.hpp.F4EF52C8E9EA4882.idx create mode 100644 .cache/clangd/index/rws_client.cpp.B2625E19C4ED09CA.idx create mode 100644 .cache/clangd/index/rws_client.cpp.D2D6995B64F84F58.idx create mode 100644 .cache/clangd/index/rws_client.hpp.3738C46199137910.idx create mode 100644 .cache/clangd/index/rws_client.hpp.F6B6AF448BD65A95.idx create mode 100644 .cache/clangd/index/rws_client_node.cpp.3230C9A14C046783.idx create mode 100644 .cache/clangd/index/rws_client_node.cpp.32950DC259F660B7.idx create mode 100644 .cache/clangd/index/rws_service_provider_ros.cpp.2F7E35170D7F40E3.idx create mode 100644 .cache/clangd/index/rws_service_provider_ros.cpp.F36FFB6C47C5231C.idx create mode 100644 .cache/clangd/index/rws_service_provider_ros.hpp.11A527BD4315BF59.idx create mode 100644 .cache/clangd/index/rws_service_provider_ros.hpp.FF9EC95DBE8BABD9.idx create mode 100644 .cache/clangd/index/rws_state_publisher_ros.cpp.1AEA19B09DBBB081.idx create mode 100644 .cache/clangd/index/rws_state_publisher_ros.cpp.8C64C24778513E26.idx create mode 100644 .cache/clangd/index/rws_state_publisher_ros.hpp.10B80F8842563FCC.idx create mode 100644 .cache/clangd/index/rws_state_publisher_ros.hpp.87F144D7A6D84D06.idx create mode 100644 .cache/clangd/index/utilities.cpp.37995F883B5F548E.idx create mode 100644 .cache/clangd/index/utilities.cpp.8466B813AD21AFA5.idx create mode 100644 .cache/clangd/index/utilities.hpp.62390E5A28AD6DA6.idx create mode 100644 .cache/clangd/index/utilities.hpp.F418EFD6A6E9D646.idx create mode 100644 .cache/clangd/index/visibility_control.h.F5187384E0A565C2.idx rename {abb_rws_client/include/abb_rws_client => abb_hardware_interface/include/abb_hardware_interface}/mapping.hpp (100%) rename {abb_rws_client/include/abb_rws_client => abb_hardware_interface/include/abb_hardware_interface}/rws_client.hpp (100%) rename {abb_rws_client/include/abb_rws_client => abb_hardware_interface/include/abb_hardware_interface}/rws_service_provider_ros.hpp (99%) rename {abb_rws_client/include/abb_rws_client => abb_hardware_interface/include/abb_hardware_interface}/rws_state_publisher_ros.hpp (95%) rename {abb_rws_client => abb_hardware_interface}/src/mapping.cpp (99%) rename {abb_rws_client => abb_hardware_interface}/src/rws_client.cpp (90%) rename {abb_rws_client => abb_hardware_interface}/src/rws_client_node.cpp (85%) rename {abb_rws_client => abb_hardware_interface}/src/rws_service_provider_ros.cpp (99%) rename {abb_rws_client => abb_hardware_interface}/src/rws_state_publisher_ros.cpp (96%) delete mode 100644 abb_rws_client/CMakeLists.txt delete mode 100644 abb_rws_client/include/abb_rws_client/utilities.hpp delete mode 100644 abb_rws_client/package.xml delete mode 100644 abb_rws_client/src/utilities.cpp diff --git a/.cache/clangd/index/abb_system_position_only.cpp.A4A69E936E6E2EFB.idx b/.cache/clangd/index/abb_system_position_only.cpp.A4A69E936E6E2EFB.idx new file mode 100644 index 0000000000000000000000000000000000000000..137851f59ef1e4463c6ff627a2f22bf95f62bd45 GIT binary patch literal 12386 zcmd^Fd0bP+_P-OZ$Z~Q?fUe!Qfpf&wJxpJ?WeYC7puRygvkxH_OH=1MZt(n>=KB1MteSWD|=BtZ~d^rzEnmDeoM4f7)sDYVLZS}Us6DClWbAt8il zdU9S~VUaW`J6oEYC(X`GW}Axgaxzn-(`Va2&G3uhM=rRF@`UX&q8 zO`2}rK0P%psW`hxD#&h+O)C^Ssl2WZy;hP^ zT$GtzC{4{xO3qG|8XwNg%}PySozl+)@><2H2DwV6t`e)16=LIESU3!Yp#z!GTMfWorpDcdNG2pxJssyA=t@T1`Il_ zxI(EG%aOsS8TPTw>U?dl9!unG)8HWBr~;; z$k%Ebn^GHTd8pZKY%KBnhWZB`Ny*8D!#K_#S#KU%ZpMhIqvzu?W3hThC4=!iJcBJ(@9lIogUe*90`7y-72Y;u0n0JR?2uNrCJ(FAmB3?uSd#d z?iu$>AV;YnhMgmddQG(zT0juC6Q7R`JRNtF%b7BnfW0837l?(^?58;qR!o3IKklD- z^ewo)Czr65MPFpS~9L>Uq{77M#V;J8wN7k(P)CX@x zAL4StQ2!c$ey0j!9b-LABc51W-g)5%i;pci0mP%;QghtUkvya3q#fZGL_nSg&u92T z5F=bXo7r@6+56F9Tuumji^@wCC5#A<$TYp9`(pCpwI5uxvLjF$@Q9W4UbvHcYzJot zmlJ{J*bhSXgHU0jeWJ5zme=kL$kr9DTxdu5BQ9L|uEODqiHlPm4asoD8V@cf7|qaJ z&^%Wd9TA;ldR|Lc>M8;WVw~>8g7ffrfdvV@qP(IHL?3>Rnpq!8LT|Bm=$VpZS2pUV z3rScUTO9Xn&G{3-;WGorEfwYMx%-0Ll7d z29vN3DEKOHe-#8^%~S9I;2i)yc;&bq*o?qoi2w4}Ep_WG?W)|PmAgF-A%;bkA}joM z5|;Xu`mt1bR(Uq2?EgN0=b3+XJq9Sa1z2tYPDV%(ghTmDWgTz+YmFTR1@VF`Jf4Cc zwjORQMuppj3)sGByJ#~i-Y(vZO0r8bqjGI?&1RWnH^;1xwx!Mbs;#Rhuy5E3 z?6v{{E4LnC-2*0InrmxUa95Rg7p?68;2r?3Sb*Gj=B6!PrTGGN1Pg+vIOYTnTn-<9 z&S|T|*JTC1KcQxRKEDjVhIf`av>|5h3_!vP#|kIhjIEBt838Ib5ORdZVD_?KG)5oD;sC}q6Zl++QeWZ!<`ZA(x)~$gDjwJLYeYtoL2}3v` zE-V#h8D`>(gi)4JW>lPIoEep9nP^6(ankJAS+dD&lWa*i+j2Ia?JKt|H)(-{3Q}P< zay{Uz2Xuwtxx(WJa}0p6ty9Cw#uQdMaxYArz|JN3?TtT0DwoF~*T%pGkEWne z{VZ)%KT8|c&(cP9v$Rp&m=?8(-`->+uo=Tz4I^UvBMPjqk6{r+xLY@^elUrLfXXNM z_85{BN=t|}z#ii{V%kxg&znkJ&@fj=*9kcAQ*a&NtOHh;dRiy!l+`;$O`B8l%?kBG zWDmyd2!kyqhnKbP`HEkW{cHzr+u2YOJMrd+HI}lQm2J zOYBO0=e+ceCubj8$+#L@%q<1geTh<+0Cp9ho_XVPE#_sYN!MI-hkyKGBsYz&>&8Cc)){-G0}) zcR%yU%?7quX^Y}+eaJN_hlG)nBSWz9kT4-IVKSzqJ9qBeEty({Owo()<$*W06fE{A z_QqS;Cmuh1|4Lz76f*H<@8(c*@cS$V;TZfBTmdGo01)@%U66@W>}0TS!2@Jf#FLlr z5aKZm^NP|1sTaAWCRzEZ2Y5K7Xr>&0L;1Hoc_>JT6U3>QrMhaBaKi>dk7U)khhec}Sr-7L>pCexx| zy<5FM8%34_!Ez9Yjbr|ej-~Qz&cC3UHNKk3?64N#+X5!zVGA1ajw<{cZrh-0i@?K7 zW_|)cGb-FO+y}Em!D!EDGb-LQ-i%7}OfsW#1-WLk%<-IK)<+9yv%amsb1U${Qf{_A z_J;S4?@y0dtn6e!7y03vYGc&%l>WGB=Y{1*$>AKt|0&Um*BzFZ7>g05Cv&b2w!&2; zWO5KndG59}>%&$OGC9b~t4|kv+3I_k9Ntx)x)4s#&H3v|$RyggzWHfFZ<~+SSd7T# zU7cSZ5)@%fttYnK%PPL}I*PeW>}=gza`R5dq8sGMZglEk+3ZiPLf^;5h~26;W*7p_ zb&=4x8-4Jk|E+HICo9O2s+aQJ$8T-DTB9MMad$e0E^*dad=N}R;?8J<7$$&Y-?s2d$w!}g51vK2MsY@QCN|`DrN`ZEE@48e-zEm5>n@`!Eq}F| z^2gPa_C-@S?w)sN?ilv6?c1Io(meIuAgYQ=;w2KC?~za)u1>}o9*J_gh{YfchqaD; zMPZctArXl}q^Fk;8zQ}V-U3|vMQ&rN_%YT5izgKaVBN1wm@n2|J3SBWAjQ$*80=d} zsBzJ_4mDqc&s^TOnuK+(b-bAZ@`tvf_z)7#ufa|@=U#BJ$ zhto;81h_5%yc^wZrI(kgz9(TT;I{&|9sYEw*K0ZNV`qYLb*8Y6GxfD+gAXPCW83AC zX%f0-vI zH>TW+7~JRRh}@naTTsZZz1pqX%yIMpw;te)9mfkh4{oBJ^_^oFgq^V+KgM5*aY1U` z4tQpjhE1m%J>Q?X;35*Jm#6HKTsu%!kMcy#RPG06#3} zmtK}h&gy&LMICE^WDO|69b3{;?1dY@b{@kD*qZ16G<9~?6cl;|?gF!TeFWqj0cGd? zz18i~)0NxopKoi)ywrw7C~_5<5WQV_!{T=0dqqe~5_gFo_919j?ou)l@5(7y5n2(8 zO#+wy0X`qV!Qzz;k0Ghc32Ov}Lia*J-;i#3`A~W5o(XYuwR~U?Vz3|Z`T-v&FBCio zcn1L=pI-FF{^LyPy)y%7V5DDU5Ply@0eunzFog#rZ(uwk!~S5e%r*7B`*&YQ3oPT7 znHIRW9fVC8I9rRF8#5aVurt9GH4B^JBQ!RX+yMMHfTNk3Qh{n!ly(eY~(ivV*!z<>cDRY z!8mopyBxe9d-Fkj_|>qDH%C^67i@IDEHyd>cyw*xEm-(c_%|yOk^Ia9(c9CnE2!It zTbW&-cjP2?-h_z>rUd-$?tHafn$;4dlnQ=@DUm(;KeImi=cn8HP^9YxL@%&qan}#5 z`+*Bf?+3(wV2h!};L`daaKZG^-LEWg+B;`D!sR@#d1g6qEAVOs{#ZiqeZI`0Eb=Uu zL0U><1{UOd-)&sD=~C1Qw6fBq(iFUe_g9|ri3zGA#<1u5XLilwH&4ywAjyob&K*np zG{ZSP{w-9<@-E7gEske=P6*#kcJpecdfIZgZas9c}Z@=n4 zi1a84ki?q#I`5JQ?CU;~Si}u{_r+$U#Vl@?>2Ueu0cmDskA@z@>N=5i^~%cWPDjSD z2tJvwZ+kOleKyLtN1vCNmpSp)3x@{mA5g?%KFPrG>a+Xr#;N+8HjH6$4o*Dp;oiTK zIpxy(>4OGCOH@Y=bp4%zOM%}~5acR%aQ-P~UOJZ8cywmwz!zcgn}4rqHGa(ZVD zl~tb4?+ly<`NvaGe)E*|Q*IbbBwPioR{;UW(p^=`8R?VGPd@~jpO@Y0 zxDHR}ktB+ZE@;z)0Z*c{D0_4q#nLD+qT?uR03`Zy$R2$>gbm>5Z})GT*mPwsLLcMV za7vG=nWzYbsb4O>m?a!K!URx5h#`#C^D+>!41{65-dl5g@5@E71TZKNcb1xcY>f)EV=Z^mGisBSwc7dn= z=l}lld!B2%+S}S9xd=TOY2PaG8k>#~a*}^lQ-q&wgwUU5&CP2Qs>Vy5vMOkT9P5aQ zi4dzq23UnhYLdN-y?{8kYSjpEb&aQ@?1B|GXt`+S&fry8NG-I-ya@O86ie&MbTjC zF_i%o;_5<9?2C-+-y=-P&=*DjL%@{OrV>z9IHNj6R;vx--tkQ+bP}=NFV(%HMx!`NP?z5z>&mDvXXd!lK!5F^*%tUpXW4LL6WS$ zd%_V`W5b9L`XTElx4cdZF+oEL&ql~%Ku(7SQsiz~e@Phkf=J#Q5nkmKA#V6V1ByV5 z)r8djDuqzS&L=vK{rwi_z$NL34$TNv7z@hMUy0<&DSad0`C-X*C!U>->_e1yh+^ml zM}y1Mn1A3LyJ-Kx949U%8g8F^FJ&$G5L?OIOxA@Ej7MWkE}uv6%7|8|qu{ zoCgZs8u*B3@fBNRw_5I6l72`4^CxqyE#q%mq_IQpIP4S0smSnBm z>Bbm?#sYdl8EBxr?TKGsIUT5S;!F}loGsSU{%U`_8DZ#`TdU6=!AG39oXAg5-V;eWJ<#miHCW=rHsWF1nr+Y00e@hXDIazp z9eFXn-xC-nqsC8Il?lzDMQKtcg&xF$pk)K~UL7`+=SJ%%P3DPkud^W~V(} zo=yJZ?8NJL<`mlLDqQ7+(b(xA4mzRHuETjF8`sReO%bJ86_XFGi3YAeX4!{F~wtTlIdUBsD(Llk75czVYj_Mt7LmLp9X^{?#%(2K~i=1JR z`4*XFk=Yh$o=t=bEUwEU$?qU|3V|5^Ih5Sd=}Q|+FK^j5=E};>DJ*i&D4v!ZZaIJz+C23=fy}T?GZw%X~OYh)7g?6kqI+YH?GylI9Aw`os@_#Hx;?TsD0UEtl z(U-16s3v-NoKCCg5)-2g)*04E6K&AZ`xb~N`~R{+?-Z+Vf<~XxO&>?rSWi|yAwi>y zF<8)mcUX{s?oA1G$#JndVlKp%-eO3vI~y!7Ww<_Z46&IQUtfKyE+sBO8>Q9j6ZML? zVFue{1H~mPQgtJBiDQTz|HA^`IlupbOK22Er*Ml;)WpPSQZ#M~`dg8bmZVh-(;u?yL7BiOpam<=z_eVX#JREU*8ZiKpf0i_nggISGwbf|s{x&6s8JJg3g>Mt=0~PpI!QNEge~~dMF}d2BBYoed zw%(+vT4qvR1@%Gx8W@T+`LR9i=E>+COpl*`d zg+*YnE=8*!ris@2`U*t&w-Mn#&(LJ`@0uY=?C+T&zhcP=QKZC))4k5})t}pFZFCAL z`$*NHA?2W+?me1oy<)u-!w4Fm7#m9vcflTpr+*{d8fwYc91@L1B%z=i7-N^Wl%1^L zq_lMKVVbyjZOlK5r-Vc*=Ko1i*}Umz-o7NmCZ{NPg&V6W@>@{+H4~PK6Wk^5>-f5u zFmy9kARo|)=2Sxul7c^sTx+7&en1CP_%sZ{;_e4@G=&R8M;2$^*6|I4H7HVOwFV|a z^A|HBExx{ENMTEMOTNC;!&6CdOBon;-Uhq)kRGAbjQ(XGLkJ6E8*O7}V~K6reMeOx zfOw{(- zZ<`W{u!5*+ppPI&0Bk2{N(ieqR73PK z2C7bUyQo$)GroxjP8IL64V!jK@vo!ByZe}ofh0YnF}#~z7$e?GDF_emrWGid$iWo+ z?mhxtlRiw>RrLAS@xa96LqfrOh~JC??;-!-0AS){ushQsfynp8G^Uj%mifj?8+Zsk zUfh$k2%KHq#yhdm&)?Q+aMCv#Kis?j(Xl#?EoLGxIe|}$X#^%FaAy>qwO5);UQ55`iF(}jfm-Q&#w6-TCMS_=i4@9le@$}$F6{m}iPmR$^ zlmo~gO?*80tsR@9*N}h7IdzIMSsOo$JnIsbsk+o;ZH#hQs?KoKDgq6s-&#_L6ErE2 z98eN1YxHp`!^yi|8tW_F|OF|MY zQ4UK^BWLAfm5I9eG>I}UIW0Lwn;=mpN|fa2Juy`utyRXv={t*N??s~Yu((*2ZggCN zDk(lSHdY&>8km?GkeHAZPs9t=s#1o>>0_dZyeVm_wCIEw5fB}((Z#CbMH$Ldl&JiOaUL<3f-?xCr1@iA}c`2)Jek#dwQfT1HTlW09^TAufh`et_$ zT%yQ{vnE!nuPz&+2qH)|Wgwl22-WP&pKtyr2BH*HT~2gs_-_~ET^>iy)gbOKWsrFX93Q_ZBepN|cZb zqNtFtZc(9KdiM_Q)lEWT0l5XB6Y=#WcS-SaDREj-TvJ?hlq}l(RNZP!XH~b6g!R@2 zZPhI-9aP=Q5`myqw4}biZ|*WA(Y{Undijxwk>5m5etrE|lCGlZ^<@6pht8x*R9gl7 zwgU+=wxHszqN8c@{~XFRb5oOGp~%$8yaiK>QoGPulQ2a<5-OsgN>U1V-1y$hE0eXQu3^zw^}iXJ=G+ncP;P)%}NG}%nj za~QQtfMDH7Lexi*%o~@IEN&1iXaHHzV978N1$X~ z$40SR*6ON;PbhEK2v0*5VN?*khOdqm-j$4Amw#_mE2jMPucr8}ao$XN%%o_BV=_d$ zw(=)`R2@{w#6Pr}1e4*tg(@XRJ2qOIl=5CW>TD8{BI#eF22EB)E#0_(5Oj!hI0=!X+(X=pIfY;mkS?kBC|%vyx1QI7uc{fOQ49XFz}J{_c|6HT*qmX2TZ% z832wI#fzP8bhu(AnQEXsjW(yTP6iwRn*&gX(0VtNehZ^1X~Ty<-udFeHAhCe4r{MN zs|;8SwHJdGAyw74oDIp8)VXEQsr|L*`!do)Xmf~i-3c~34P2EDW;0?}xP(aBPTJ1d_*){O-|di}&S~TPw$@f%V$5HIz~dZv5z5w1vN@1SNr!a%y?eT2jR}l2oik78 zEHmH|m|p@*LfXa|=Dk+>m(FU1+0oB!8Lhv$KcVbk-ht9}cH z7H6>eU@~t)P3PUISuIAl?x5}Q8uRA-&iECfO%YZ1aj-dVPCl)^e&lYe8&4_EdfxHzg>xn?tq14zlyaQ&I7-*9vH6Ixl27GYTSQub(gLiOn@^c!p*jouFea9hOS|XpcsYu; z%;3CdaGgvsqT|iO(_^x((w4=jUX1-%AM1M-KTYnEI*_)cb4}8@7Oao0YMGoe<@PamR$7A#sSql=^GG<5ST7>jAdfi5EX2A77Svk=5 z`pO=ZNuWH?g~fT6IXS|@m^B3~e!)7wU|r_Oq~{T|KZ1@dg*uf5XYTlM%Y3SlE8uVi zoCIF_1OuO74>mmOLM1h3T){AB(cvsMV3TQNGpWN@=Etv4uB))lDs*PbBfw#<&SB1( zWeUY$kCiUF_VuQuCE#BIJp}^XNBMnpWdbNpoC^tUzpe$1HA}#G2{f;<>`R9qA6(06 zJnHP^3EQ25sAg86dIg$Xt?^F%@Y`Q>%A|c(q17ssGD%!IwojSuyY?9!I0r0pz|xeq zGhqYDH=q+!Y*YVn4+2{FkD;Usq25Ap5Rh&}i;ZZ>NL{VZh5z~U#x_)vX{esY`>X5D zZjtVJPi9jlSHa;bG!;zrDRz2_!EB<D6sO(u4uu&S^-c*#qu-KqUxyg(xjVd$yR(r~CD|K4S1e zN}3N%^TA!SZ#^s(OMY))&s4rkEz49eXb z?AuMzPpt#hRhvJ*%v`X5eyONm}FJ-@G++IC4?%O6f2`21x0W7_f~$bW>US3dRYx$Vz$Ni9o1 z{@K&JuyGB-z5rwe&``j>5M+fS;3fv#HgQunSuWdFxZPUN))tT#0?y;Rhd8MN|9mAP%bZ8VXu+gl-OH|Zz5ONNB z3siI)<+oA6R>0T!{?U=OH20CP-_OeDA(N}-3|2w zCSHKe3Q);Rykp1+b@;(85=wd)q=&&?VB#0i{UWNEiL(s_ErsZA!mx)BY$Iq8Hf|vV z(QysbSp#(i7PuMgH-jTvyUs5ZZf8`t$I{`iLZ_<`ESUdOba;wQ+5DN&nvr3QI}pJz zh3Hs_4cVj!vy13>5gRhm32+G=FNuIV=z9k{Gwy`qF1Edk9R$D=^mu|^4Cr$FWqk6g zhNGycr=itp=qwQR2Fh-rGb0Vi`fKCC9?iy4(gk3#KonrtqkKIdU;`E{JaBA7$GMbr z4LGlX#sXdKN6Y=Zw+37o`&ZN>=TvG%cR_s@LYWn@m`qo|xZ@J2W;MuGLp=f4O<=!? zUxDt0s~aRdE%=yP?P1R9FehbZ6+Ea4Hu6FJ0h(J=}?cModg_*c?=W2j_?>EeARjAgs*xJz3}xjkIyEMwLLLdt~vP8f%@R%k7W`f5|5ikcl=I}rt$yC4d4az>|$Y8s`eit|ieDr5< z_!%0p@Ifd}qw+NRF#GQF(UvVgdJL~ewRHsCkAOIZI{<1jy$s^SL^(pj}a;wrSTQdYG@Q zH+G$hnqq`J!ky*ih+cMXf6VSwlj3_h&%InL#-hJw?!YxmN_=U{Z=BU{yqOJ{+i97u zVQvFD>}F`T8QcXD9!2RgyQBxPG!z7Vlx}7fy?@pe8{r*(#IQ z;3mPs*U%=R!q@O7;lkH`P5KF62R0dKdi~V-^0)5&9OTq2bZT9H=FEfR;%BY(JGFx1 zhd9eaytxe4kNmjOMYo!o%PDAoN|Z6KqwG4LF$QPdem?2d=E0OnC8#T*FS8CdLz>Er zM^7wZvaKF%F`hJ;TJlGi^$M9Vn{xY1{aGjr7DH{yrgVK-bdcg9@(@$Wstrnr@;#d~ zi3)lc+z*SK^dd?x@=iLee#`}Z^P~HWE+E|ub|M#Oc9eJ0ShwXvr*{v1LPra46&}pi zBv#YXa^k@@;S~P@J-fl`n#_hQYxSew-!gkm3>?L*7&$9`|ND6YS2Qf~0lc7v}(dXSbOjfXU2 zHcVdAnxwh0$&%Lv;J5&sShglW4mjqBfQ8_=Py{Rm#Zqt;D0>+wmWhBoP~?e#<)BzD z0yaYPji3~m)D~#EMHFVYLes4xU>h{uCIWVY*KTMnNKwCn*RRl;shZ5?5O^K}Zvl`G zE%HT1e+qh>5|s+4L46tm1S?wr5d|<%02D%>LKq+bilI-j2q=M&5|K%lLhn-OC+JcJ zL&`ua04{<5CFmvqE<^Xr5Gnw!LXWE=Ny{OmTr|phv|5jK*xr{+e*;==5CI#}YNH4^ zjCBuVeU{5emt$ym3>^f(akM)w0#2aa2@z0&4kf%j6CR~luT)glmZ5zaHeeP{D6XUH zb!@@Bg#b6O(G5OG65uAbxQQwO#VvHd#TULwKla=8u=3jl)ECc#{5&WGnySE%3hd4L zCY>5I+iFST z-jc5-P|;3e?UQKFOk-?k$za=upBK~dW}0Z&o(ln2Jy&zmtduxkpP zL_XT)lT(aln!#5z%}0&0>_3q^IBlFcRrnmvdk&{&b-~2cSBHwMM#RyU;8wxiSpJ<@FuwlS zkl$=5{t!GLf+=-=QC4wm``Evp8Rbx}2OohPhp^@$v}VJSzWHdDk5Z;H#+_Cp^e&6l zA{ie~==agLZ8Pa;{;vL=7+u!n?jwIav)0jyC~iC2ZAUrF$^_Vfb~{ACPPE%80(PO@ zE)j4KJ?`<>2!zLdY%7 za0kQg-~hI!gyJstyo-GWz&-4A4+90jee7_b59*}L1MK)fbWK@_0hRnH-#-c)lJn{0 ziBx4H)FUF9))$Wn{lq6MKG1^TnVce%Q!#TSz*J5#RRql76f;D?98NJu1mtjv98Sd+ zitt#>DHe->JWi1(0@iSfHJpkC1kzi1{DC8y%WD@1= z{nEv$RNax1ZUmQ&;3mjqhf#VMWh|2|-+%d=RowXYRQMCn_XG?UaJ`0&u8Atra%^0V zo~#i2;U{_HK-tcCs=F!ZIR#Cg^TWlkdNw{k6w?@U0Baw>I&4$6x>Z<(qh!TJ+Gh>t zy@tPkTw^`!)sV?ShI6)Tu+IiZ!TxJLILwCz?B1UAU5Cxrp$9AL*Q~r!e7hu4ODB9D zLe7g$=POWN!Jp2rO}o(bxi5W&*PzL_hcT6uO`Ph0x6>KDes#=gI5KO6he z8N)S6K1lPSt{@haVT&?;*k9D)w_Jh}vW?RWDT64{H0722PVaz6aA#R-E3NTGh=8|Hc8doN{t(goaqWvLYAw4!xeI&*mB?wVc^a)*5l<-2 zpxGIevWw9CmbyU;BS$WzGGBuBm!OMa+(+o}i1)L@Uwt)i`w^Q(QbKwceC|RgmR1Q+ z2|kq~;0gFV5dqJ^=eY=Y1wOAtKsx%QqmXG9`eccKY3MUe1k6OAnId2g`pgjl^U!CW z2*^R791*Y>eHM#=W$3d^1gt=x6+CccP;_$V;`<}0%JzVC57-OTU5M_5sAB3q@^P+h z@WuWwDd|R#ZUmVqY`Y&uB@5ffPJgmvQ_oyWN_qk07r;}n5O*;04i0AqaD0;MvM2TL z`ccwyP?w9oUU-I%&-kwwj!*Ji5i{=O2I`Z=Xj_bOw&i8qsiPUcY-5ggrdH&z($*`U zQ%{)6c~9lP@hPZP^J>rj`{Z=sUqSjSf8Ixc67(#=)+}@~mCz7s{2Y$4C#2*%!*k%x zBq-PuYrZ1d?+42D9LUd!cBi*7kRh-4|e{KTG zbsIF^COT6%fzlKFnF0#|R2B3?JI1ppJh)z_SC`)?i$fqiB#Jnt=uwK^Y`VqTij!Tx zOTR}+mx1*%kP0f^9q6H5w=^&I|4{Dfvdp#{6#xE!@8_T<6ZK6F~8ATI?sw!Q>-fPoMA z%Zk9+WH7ru{{kuLjH2U@J(Szo7Fk=)y83TM>G9yVdYHq(Hs=dqK1!G8zQXh0SxBy`nLeTfJ&5A z^1vU3SI-sCbpDR&Fb}NrL^|AwPCI!W-ufo<)OEehMMHsvR{O9nyREpbnr&qk9Bl}n z#UL*h6@d3J=pKf%HM_m{>)j!LqpCf8*A9?hqekeRkQc!Cym#1Ow>@>FN4Ena1ofwW9;}CyRl&(_Nc7CxxCh2lz9&4 zox}OEVIQ@tbLRM{fjcOZD-d`EdI*?2L5C;&jVSX(8ctUkJ_%;7@uc2-r@XZ%lBjC7 zq0KgQWEWLWUAs51YE)#nLwf<9FTiw%_H@LC4Kw;qHMD$-p5O8pW6$z7xMlTk@Db&9 z8EaqWFZG_ctZkKUzC6xYskq&R)}l(qtx^O$0k-Ip~%n0v4m&ViB+m-Ij@f73j8t2cD~=&Q0p( zZul~8I(km$w{tI-2DDJLoFz4G5}i+oww@! zx~E}>TL?jgqRW|ED8I$uYU;J|8v3mg`F}LYkmUaXKG4B~ literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/mapping.cpp.981962BE1449DDD9.idx b/.cache/clangd/index/mapping.cpp.981962BE1449DDD9.idx new file mode 100644 index 0000000000000000000000000000000000000000..4fc9269a078a2e187c738db064b1cbc90e43a685 GIT binary patch literal 21854 zcmc(G3tY_E`~N)82c_Gjk;0TAq|20$OPGy>6j2e@8ly%S3KWIYk$*NQsG0?y62!L?n(sGa6li0HdPyuLWkj*|6hxctVx>iKb9k5Y(jFl zMyFMT(sdZ9iHMGg*D88NMk)j1_3NXF(Cg@33&fNCe_5foiWM5C(IxlO#gH}Dk(G~& z)5J&WEhzjg79^m1Rl@kBn5cMSF2t7JU`REc^_G_$txK3pY$npjN0$=-~YfRGzx=LIL9VvA|o})8fOLlR3xV*Y8B&j z32}P&q(<;I9qSU3)QkaLkXIC~o1En16GR5+Ls{4EvUJqf_4OX&5xL%Fqh$QIiKiJm zR;|+{#zd;)lA`{#qzNR<#V6NUjfU=TQev>4dEHd_Cc)lQfo~M-RrUQF850wd>a01^ z_f2XWOq%LscD2g$o(ij7o>#T?Z$#7n8(ryhZ*7iBB+}MdTeXPv{_3htq+0YVgkuceWMyGwfVxLG#{Km*eNP242DOOysuKU5q>~fIj{jGRWDIJNRG%usgU61q zyCNC)IxCVfs71V26l$ZB(2(sfJ4}^UJHAOxJ#a~-tsW{a|@~)0G z#e}|_p#pi2PBf?Ldyo|Te&kvsz4kpi7{jN25EggeqoXlg=sU7F^QMlk7_45ALaWs? z5t_f45oz)9nM?{>vRm@;p&p(>id)J+zw_4H#ryOaNX_UU_R)thf40#!bT*XO#@)BN z76HT?g|@=FT`Z}d&}bVZ3e;vBdLn}@5Q^7qfi=^$H?+U9_Id*SOa`UIDcTx#y0yr` zle}q4B*F@!s-8ZK909zdpttnaYp`aMF5o1#hF5}NEs_chmk`%(xcXTO43!YpZm9a` zWe8L~=yp-1Xlr;951b<2W$QQXl;R&pi?{bN8Usms24i?Ty)Z_+lTr{K-cBn}Fp+~P z`0afJx+Z;?u50P@kK=)n$NPkWcM!iC1>Qma-T}bKM{jq=LjsZSi)oB2O)T@3mDckR zdc3$NX%RTPxQ%yWgP*^tRqv#)G`_!gzt*uXjxA;)Fgbxwi)jQVCU9pX%^N-0NKu;; zyGWGENL|b%txg%25UK4M<>n?)_URoQ92%zX6%?c%6s!&k=*>f6!2<*Q)O|(_BJiL< zBOc=4&wu#qaOjB8F#mzC<6-?n{Co8g;(h%4_8J-#rVbext_~PDILLpX|Ddp5VFAH| zdg|gPt0U4PViU+IUu2RxA~BH+8{#)KEFdUU?LVkj?;wA*p>x2X0selpk3<>Z8J!TP z^^DR@8LQEHPEOEGNJ=EtuqQ2SBDIs$laoA?bP@VTQp|MFe~H%UA}5p6R5dwDG!)OC zG4TSSe-Hg+8O9-p90iBCz=Mk>dp#Ose-MWFr^ zTuXQoG%-QXU8&KO@7+s{ANSd7HnHCWjDFPy5HStlNu`y#k4d1*v zc(nIuFCh{|_Kb>8adY$PA`uN(o5J5sLDWq=Gd5Pg8nh;&#iwx%-Z{W)-AN=-ljCJg zlvY<)He}93kUGjhIujA<*qJ}f{8tP_`KGR%=sxhDF2?(~7p1A$0C`Zq_Do1j_9Xu3 z8KsG(5j=tyI3-D^H^A7~NpVWA_MT&7;tj^AqzPI=E`QWP!Tr<&dkr2OFsPq|_&GV@ zr*ixFkb9!onB*8ODV!-TIwlrvY-(>cq^jE6NHTh3gSPe-7V2wnWkFuhDq2AwpI3Jf zk_eyHzJq+p#KmM)30M^qN2L@)Yh>p(^wt5Gp)XV zcagan^)6V}cd?>tGRRl0jz~@Q@*=AL_izR!5D5RuEzeVp^Uw-RR3gk7yEz z>M))mUW>FxLs{)Z*G5dG&`Usami{95e=JXuZjvWCbyO!sso4!`T~)*9k2h~F zk^ZSB1?j)jti!%&4d33BTSN!h22vIq4Nol8N%T9Rn(=F1F_8%OKIE;Iw79W5IEjQa z=^h=XULmuP%z<%|Ot=GSmPk0io zPGX}BH~>}$pb;VUYA(%!Bud)+@%nq8KK#v|k^X=Ue?W^2_!=614Hksdv#I$4NTj5W z?fp;fZ+sf_h869Sxrn34K+E z{Pawl;=8?}=OxB$1;|%GiwuaCN4FrOc5P)AJ&AJa^?ksi{73V`7+nFH6`*AXYzDK< zU`Z(3H?v#_6DeuG-gcu+GH!ptNVB17HpnwT-Bc|ngx#DhVkT2M_0i$mu}_~QMt23> zuAoN-oCmk_;6W%mI>#E)%44T`VM@={Xi~76qIl173i| z3s4ZQz1(cSfR8EZ&Rx$}**5QgmT}GIOta~9Zh`47{dBxrG^r8bc-hw93Qz2u&Pb1e z>oHJfKsLB$gOYGnwQC&rAIkKM&x^13_G_@8QRahVKD5k$OdxCCl2Cr&Vm%>^Ql4|a z=j{XMjVj6m$2>|o#c>Ly>(bIRDuvP&SIWGXWlkh(K3hMd6w{Q}84ze1*qTsvZ&R;E z#PUBK=1VnCC$WL|f#W{PZXP(!(+}+HY7;w!GQ9r5fjjf!nyq4#ThU@GN;6`iHKCP|Br&7A=DG?V=PP1`0(s8D_ zRFzd=TBTQIX9d>CDbZ=iCEZg>B%n|ISQ$slguUpv7h5uOXRZ!r z%*{2ElBd0p;uDqa}!w<%#?0kR5c zVqC;bxCpX~BH$9pE{TB4AiFFA9$}|P*v05AneZ69JVqY@P>sIT=qCW4VAm(uodMim zGuBSXX|o!LK&#PxHTtn>)h|xJ<31_%8r4Jrv?~Cm(TXzR3`);nV-~|2n17f*|C6Q< zDd|tp_9qePX_TJECXCdiySeI=|KVUd-V0E@fWd4$6K!XOZN<@Zl*u>X@C~#u#-B{c zN6UPaG8-{(GOYN1#Ai8_$qZD@z!1j7eENm{EAwAYq%HF}uX$V#V|eKP`!Dk%XI-T& z%Tcu)hq6AF56m`B@0Buwwxn~d(m7Yw$J%~J{>j5Rzgy~Cnx%6J)!Z~w@mOfG}nWoRv!=o9Sm z1OwPa+g|zY$$;yTT^bNlUprspLX*edR=u0CbtjK~t@;Wd2UradJ`S=PBzz393Nb!9 zhbK-A|L+&gsWiL6WjA;VLS7L{i_n%WX1jU518$5TT}Vj}LhFOzB5;~=l$K*-<}@x# zgRHB6`?G+~J_Fq|@B^l8*B&40oX#!lNY~*MTAxC>OS8Q@8+6mYbPX*~{xxRtB+9-R z!ir&xKrfXjuf%ptFK(YbZQ5vY<^f8&3LI96;^q#t+`-39cbHeY-BlSvN!Nj59XJV+ z+s|nJGg>j9@RZn1`BT&A7A3t3_E({eK!B&HdWwNe0MBNnZHMo;pG9Y}5fmH2Jw9-G z{glqDV%mRq;=m^-GM~_vwIE*$t*?CK8@S`n`NZ}YKHTl@b+%RG%HCP*_bZdKF(wxXF23r!1=Uw9-nubwa>=YtkQwDj8TmV zWc8xABIL6^^=?0=(>)IE$DzmhqaRI<4D1o=?KZtsD(#g{TXunB7r2{S9_+N`X{TYG zuP)qlVvqG~$}1gJ={STLN4FM!BU*fZ_7WBKECii}!2%WCM)_@2uoduetU5ZOfu;%x z`@LNKy_^XPBm_9d)j!4qJ{_#GN;=;7mU8_Gq(4Cufr+2Swx?0aOuT#0c-4@?Z4yd) z2&9L=R$$^6(B%SpG81Qe30ex#jf8&tAlO0BAZ*w@2%_V9XtW+03oP(Qu>BG2+1mB| zOW|DPc{h~~e;ImQh5*6*pP=0nY|ZA+jMjt<*L)%s^(1sS2|Wd(UPsw=bY!G{ zv!4A}IH2tmO1cEhmWTpu9?J9h0PDBns{_Y2cVA3N*MsAFXerRuUNqm!d#hhb>N9n< zV+ysRN>Ek8KxRcOCesx#Y_GuUqCSD^pd@0-OvJ@X;8+C!YhAx_H7 zDqv(tlMAQ1+0&M@*zhbL7YCf_H8QWw$w(@68T2WGV1X(gp!@+kGgSm%xH;y}H4hUg z=_t2R9hn=E$CUOdUD*y}$n+(%UfO=SoRXD-yi^p4?ql!!d}J81;HHyXv;5%}gmjGC zm>vR-k#3Q~$7r``;bW{@tne|>Em8QG=9bojNkceKb(<=DOb54g5CSv6ZH5S#18#Ff zzn^kZp zExHNS)?sit44wj~tw3o7U(AIJe&%?{&Rm~+w}EsUG-9qt`W{2)W9Y)dW@tnIf;g@9 z0?M_3t6#vGGfN=ALC*Xj*9ew&DQ(d??YFQ2rfZv|=6O<643USpu)G{L$j13rR*(7= zFW}q@xDJfPFwNo-KddVEp)J317Qgal7QVR0H}TC^HlxG-2yK4^7lDMop!65CVG<5M z|C{y9ztTb)5z=GO?HCLZ*xfy_xd*PyB?!esuz4r~o`B605%3&ro{NB&VDnN0WS~t3 z3YpGCo0%eDF51i$0SnM(fe2WHHj6|+Hriy1fTd`&R0OO*n-wBpHQKBe0avj86?9-; zMrL~zO|D{#6;9=0J(p$pj_4FPyv3H4XQ}UQK=Tb~Q`zYQH@{VfZjbbyw!bXULSJ;8 z0NDvqF?J1A*D#oI9kojq>t^jcgcf6dt^C@vRVI)9TJ;k?2DScj#j+v?F4!y%KgppLED~sOIR3pV8FNSskPp`zVN*u%1FfMz%y-&I04O$l+1lxnqgatza zlwNx1ZaKOwvtjZ$xz%K6Hd*qx1nif91IyL~ z$N~Et5wH~Omx_RupjZiQ1j=3oid7-3qO@ zihymcLnql02iVEMHnam zF2jJ!B1x}8&{feWd1#S`jo99oOn)Of*rZHU)|R7fIW}V!PbjWon``LGyoCVQvBh;hND|;Cy52-j z0mUtJxy2X0iR*{{^!U+#mr`Fm2l8{E5NPTS2HnBItZ(9}R7BK!RqTGJfO{KnA4XSD|9`EV=?Mu$I%9PQTT&`6v=grQNlGYdPUNn2mRLXuI z*J2;%#L5c-9O0TA;hHfZ=~#u^{C4@(l*u6ZAY)WcX}o=W@Ur2dG%;R9Iw;;viZdB*$27HKVU++D)ADAH|gN zwykbZ{Z@cog~*H^Vb@34i;eqn<_BKiKDzcdWpWyup2jw;^8I+mp_SPQw+>MzInX3W zw6))eW*hmf{l~X&9e6QII)N@l9@yrAgCGKK1iOvUf*oNHib7NtqBm3c)cwD%9Gy1B zlqx)n^UC5>tS*?A^7o-qi}5kErC*1B{aF5;cIM-zsX-^LDE<)KAA&J;ep*p^Y-j4T z=LR{HdEhOOqY&#Cq9q%a^gW0s2T{s&#<u56tM z@Bm#O@K+H8sKO3a*jqsH2%R2bM*;8{+djt50^kWcKjH5;2#=@O?kPVC%coQc^p=h( zVb;^a-@}IdF4tvSlbYjFFk33x=x;*#CVrzoyUJ7< z7}cqRA-qVpiZ)_L(fKG}<9+rpD!g(;S3T(gXnO#Zf*?|g(o$@~g2?>GFY*F*U3a2f z3qV=`jRh(C47NMNpY$x4yD8PL-E;jB;#KH&Rdjyw6lG7*j;+ap(|F}z++BU)Je~8J z&iOE9E&T4>vfnp6DyN>g9~Aq+Jq-6t>IV#o{QSV`t^XN5@(68tjt!qV{|f z%IRaM`lhO;hA`zVx|V%-?96XTo}{Obva4Vx2t-e@+f)8@X7Q=8CmnAo^)+@jx@Ti= zR=6#`;=0#&&$qWJ^F5r&9!@r)ao0y)J*K%VS@hMxkI%NMNBwRE*sg%)f-353u=^Su z*daQh*otmj(TjP@(qpYYeAHZ~KNw9^B@PnUQWmJPU=W+bvMxjY;y>`$Z+Nr0R@t08 zv!Z25gP&*Fd{mDL_5|FYfG-pItDm-4=w3$nAKQ_yoDJ0}9pgY3KrC~RnK2!Q+8?LHsWNtXxM{ekG3vI_mG_)(Tu2aj3y(e!ClWznkW;Y{maPaZhRJ2is_suGe-i<<`lCmbjjlsc_Ls7r`W;+t6E3*eX6L}old2%yl+bun^rpo*`;_EWKf$w4Si2TsKDlL zqWmVhFa@su`}f(XsB|%u61MxmK@bJ@gWY~;!F-P}D@J88db6lJKqMO2Yq#guUtgQcG?Uk~-<-@gf!sj69oal7^4$ANFr}G<< zN*YAmZJ?l}CqZ@+90e1;j$N+sl=a$F4#t3|g%JJE6{e>=3resP+5Q{GidS_JYU(Z>1~ z2HxU*e9N-ZU-Pos^`vW<3%0q?RIn#r3wCRvIlJj06b0x~fJ(L=TZiB7Xx5w*tE6Q! zNH>d4G!A3i!+f^eTH3OE(Zc2n=+dp`yjF9)m}jzDo+f_7%QQ>_+dKcb-b&c2IN^L%fX(3XRo%|WgOJG0!m?b7TO87Ib2k;*|{4xWM)s=}ZuR5L?o z0?>gCuja6U3j!wHj0+~>6DEg2dRTN_Qh_cN{B=peq`;Tk>=X1iv(G^FjDHDY&lf{~ z^l=`#kj{8MsOFQaznT|q_Abm-cX02wiME7x2n}XoWAC$u&r?4r(qEGt1nEI&EQkf= z=vvMXyH7Rbwv&I{62mlu%0Vrfro4*Z=^bzj=qc-Hp*7sk^*jy!0@5PrQ3QPiz)h6h z#O6#zM8I1}5~L9*{4Q+plZF>PskP*TG9SDJmB>k~e-bTO5l<*ip~)$fvWw8e?c+y& zHGINXROSlkS^>QT<32*WN4%f?GH1@0JC9hckP^~L@UDa&EUglt3cRaCKs9(*i-2d~ z{Y(VB0PhzfARWEaQOI-#de0C6bI^N^2$+xF^F=@wdS{7%#pu0Q1mvK1jtE$e-pfV6 zD)e3@0@k4S8Xh<@G9syGS=D%|vfUuv4YmSx7okfLdNOq%`EaFmz{O!NDd{GVZXy*1 zd;g1^OrpynRI;#r?DVMoErBb|Dd~BTpC|X5?DexuxQoN@Vl*>=HH}UO65307wt;=Y0eyMfXzd$U-Mm2@Ro!x8WFjLV6ZF&Vm<{;LM&V z)7%K(?mjt<*-QWk0GbPaFzG0{lhbKr4~ zSKtU+xa|n!R(Q`@sZJibbYf>mBk-vTy*kX_}PBtcp6Bu zp`XSpNq!W%-#!Wy&PVtRb@>_0P?$6G3U`*A~u~ z6^PfS70Q)qpFN|@*Ma#uuok4wpV9GWbYhv3tq8rlHM|ZfQ14!Bv{&>B(=TZI3;zle zV@j{Y4ev(^`tAn%-O!v_A`#>e*dK!CY&i*V80-&=fb-yUUbHPNhR(&%O`yX|;C2Z- z7;vNf%PpM)Uii~#o`>P*A)2)i;4aGVqB{#0H^Jp>{-+N=qom(}(iY({A@0X!m2FukV9qvSjoxBcjFPeGkhR*7uzCc2YJ=mDtR^0W>vM>pV(1*_wke7%G zz1hRS{s>@I?nz*HV%_s7_e4f}Y&qo!N0HF!pu=Wt#*oDUne zx=W*?;}b{ZQzn<7&m|ZjU{Z~C)%=Yp^F$g>bM>zTGuQZ|Nshy}8-7iss@aBC+t8j} zR6T9eznMjgQvDs;b8vso-=RGnzj^b5(7F1SMd-eWzZiS|?Plj$!oKNtO*adXjq zF29|7x!TWF(f)I(VUy^1OtkepPBJk0JAj&ZtH^?1!O$x>ni_^3ME;5nR{hiszr0PA5nF zGvSkIpOVYV43MPrR1)%N{F!F_CizqVPv^grzmAS|B~&BZMf#DyTkqFDU_fBFCVWh| gI{d@%i11P2ABB$&8aQZZSV(Z_kijFy4jcae0P#DlumAu6 literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/mapping.hpp.83C0C81544CCABFA.idx b/.cache/clangd/index/mapping.hpp.83C0C81544CCABFA.idx new file mode 100644 index 0000000000000000000000000000000000000000..fdd7769a781fcd5c5d593366b3967d9936d4d562 GIT binary patch literal 9988 zcmc&(3vg7`8NLUId9ZT&3^DRd6fMZ*X7?t0VR!H5-Wvj` zRL7upY;1jWqK+L=XKd+XY#CdN^f4Wv(;1uA&PZcx(Uf7(UPlEw3?&3>surru0eD!}xoa z9oiexdLWO-WnfbKzJ!vHMXM+l2Q=B|lTCTCNIymMKv)qwbS=orlO{njAM2VSp#U0? zI7jO}hR1U=Y_Oh+b}m`E>v(^qpdRQoQI5j?$<&kE+a+BNt3D}cbWU1R4cc7DOxukX zdm<-pX2R2RVIsv+bYMco;@vkH9mATDw&#F1k=wQaDXp|~)F(xUIqMVet;wjSOvYF2 z>~$(s&`3$!TMjCv?k*>l9Q>80cBZBUCe`6kK%y*bgALN}a43CzOjC3q3UE*_-iedb zv`1^-Gbu-+00&LkQL%k<`=0b2iPF<{Bnog)FW!;qYMOKmh@8kUB)2N238QVYo|uz( zcBZGY(ixPDh!h8Vn7iR<=ZC=Nkg4b$vRCnVI2A6pBTU*tJL{8K2nYKF7Dgjx1SJ@8 z)KKJND55!Ol2H!1g8d9Y`l^JgWW#aCfIjVV6@u>W5hm_h%qil&rtY9vV%>Bd^oT+dnFJk{>#7Xj z2Co3(9F&Bcc`$NG=Oo2uLtHa-(3DGD06Qlxvzkj(06Hfs>t0r)T1BsmYs3=kTkOW& zvA1k?X{U(G?iR^;>|}sL&q{{mc)mwWh~(NsaxCXy&;uQuoQLx@@Sv|9crLpi*fLUS z1rvbdyTAnSlpBC8hvl99k|3t`V=;E5Av5D5&1CQuAIk|8uGnK~(IU3$JQ0-@X&f>2 z>K@0KPGQFi;ZlyP=~xVxVq7`fn1q#VBbv-i6Ug&*O>t0Gf z-!7oG!)`H~M3$%$ECDV@w4r;gtk8^Q)&ofK2Ivd)m_4ZQ$a3V;%RC0p0{mGw32*`X z4U4@Hu+DG?qR}Zuey4FF(u)yWw+2}l;38EdfCkZ9to1F@*cpZPa(qy%r$ik)=BUx_F>`z zjC=NUbrWEUs~Z1$BKrvshdEAW9A|PWW@UEX44Bmidh1@yb`NtH|2+SEkh0>soEzH! zQU8g! zl=bTk4lzW^he#!0t}n{py9F@2o6c|OE1Y(a!wi$GVKN;sUn?dW^^LsGylX7~rDId3 zbghecuPUc19}w2Jdy3bHnJ<4ckCRcGRZAtTUObgaxc{j=LrS&hF_)mAcN?-AsKu*F zu40JiPvs3xd+gEkoQy#-W03i6*}SWR+dz+B8i$teo%ukSOXxr;W5hK^M37ToUJ&{^ zV2&OCz^Qvd; z@b8BN3NO2#z7BFke@|w2;=5I^it?`f{-tOMwUW!M`?!7jNpU~hr*6qLH{AwO&aXZB@BZMNXE@9e;yOZR zf}G02Z2v~UytVnW56umi>N!l;oUS53coxpsa4R7G)9XF+%3aqi^FBUU5qZ&e{`fF%e7tMrh7bq55i z-jGmo_S{D|o%byV;d>c=x_A^ zv;ac_1gr3o;Lrd0ewN@veBV>W8vRly{<1GEEpxFqhuw9y64Q+^3zYBJqY~$q@thH*cBlUl8ix;i=E-l zcScT*-9K|L0DB91i|pcqcvl=JHJAW*zj5(T$M*m46AG*7t>IxA$4M^2Fb}|N+N;p$ zdv_eXW$pKFxQ}MbqS{r6!ngvO_ANx;|M95{ZCn3)=qf-9wV8;9To4*Ek;f&s2rZeI z3$zl1VUme%r)7MP{bNmJVxqKALkC1AN!jsEySr=N{ zNE2j)l#Y;PDDTc0E!6BT=?>q@0^-gOy=Nfx>e zg9`jspGSW56%c51$7ReFShhMk5E3BopaAU=R4=#`*uUi%9VTO3Bq!B%MQP+;YorZ6u_UVDc--8zytZ0BW~(Y zymF_w8i!P|sd=@iYFLv+EhuhS+a@Y zZ$MitX`(9#I^KXc&?RafSp-x_b~CN295HU%4GrsBR*3Qr*%cA+iSP6>4zLX3lb*s&f6|GtELXH*4yx)%l zZpxsINf>0n#d{b~yPM5WY*E~O2IwwYb=h!{K?$I9UYQ_LteM!SGy+cX%O06KubG} zOg&K$*HYu@g)ot0DF!g1WAWjeh>xM5ns($sH&NKufhaB7nfjArz|8%LkJdz7lP3}@ zy7!tDDtIKP9W4`=QV*AzOD6G3(>pB~^i8P4aRZ51)(#V--{H9R(K$^qfZTwId+|Y> zn5R9#j;#|4BsXBGejvH^v;)Zvn79`o$aFnTdJKr{$Z$w*lQj*Fw#j;8 zPU5pO*_GukzobU2n5>6}8@6`iA+RN&$x0`7$xf%ih4FTT39nFReX3k*|9aO~sAmv({}cehBcqmuzPJw}G)cw>(k6KQA<$+3n2gC9J=$#o2|1|1%26P0r4o^k`w?NHw7F9~95KNh2B8kiZEX==k*@v)j9F%)~OELy~@&J#&# zk;VyAukKNb=@fRX5d-B6H64pFP|Q%yIwoNy>j<+Vt`K0Whj(G*q~~hC5&I9IBmSJ-ljBq)UT=? zb;0?HTuqkFUT(;n%Yzk3Q?OT4V+DqUE{BA+2%T`Ja5@|gPtY$rx|H4yEIWFF$~H9w zH$w+0YPY;y>QNmXVXx0k2cqv#9dOF`x_wfY9FP@46Uh|{#bbb84h>$JNaS5Yl_wPX zistN*;QhsyFlkKM##(VKm@M6Ra3A05y>QKfe9?FkE6{=@_$dT;$%^Xm23)?dn`LN} zQ18oCp45YFoX+R%fZ1Xui3|}ZC;`S}T2)+(6+v|&eE@p8d*D|o34W4cFCk*)G7(2E z!Q+cyD)SNyHxBF-;F7NB7?ig+_KkNdft~?a%Mcl#3nRyY0i zRQ3~2hB{-(I|H^(pu7{*mi_81&&`0kac6J+bJ>pb47Cr<+=pgi&rHuOu(bHvoR#f> zY4}CUBga4JZ)cd3mYkE8TznMe97VZ+s-B*^Z7rah8?WA+b>G{MGSmQ?Hh^YgX__<> zFmaF#Y zah^&yb27trGDE~8$TosRu+>mm6#O=zj-B}A zsiGOHUS_riGOPozs$paurmL!*^-VhC;49BwJoA@hyBX?5H2+0p#{+2o0J4LvrRCpf zy&Y`5MiXh zm_^rEo7w<#?s8%6-o9?gts8s~Tf=j3tF?6wAa0mDiF)*}PfH%k#~*KJb3Knrp9d@b zsI;HXRX=~~O}BxaOUq8b)9;`D6hl30u{~?a$A^&Z5XuKzRmIuf)qr|q?dKnAt3GRB zsDo(wK~#dfr+1eC#yKZ%)vbW}Pp|9Mvv*Hj5W!?v4?>)-AnO$xr|U%v^-7UD)%P-^ zRfV!?EpbxV9%?u`Yp`Yr<>0y2xpNpJ1R?jmoL}y42;Yuuz^C%_sG3u)p!he(&;IF& zw=#%8Jdet_zy>K2hf$fHJ#a<5g37p;ykcQ~R;SzpUZfykrO5@nER*! zOYTMBT;0`mvpIixg#w<`B}en3gke^ST)^uP1f=@-@Y+}3-16yx_k++X8Y>&G)47jZ zt6LXy7Hkk6tUovXwL1XRhl=`8iB2?Fo&7Yb<;!i$ZaV3g3w{W`j-bpDG?~{x`0f-&-@9YiEz5p< z{r!Y3bL*CH6wfQ5NiXB*2R=UYR{Q$@?!F4pLR}U|0~dtGEUsh2twL)S=K`q&;XKOX zVJDR!45KV#B?wng77x$kkNo71cfEY=Bv_88$TP#3g~~&yhG${#qFa^+mNgNA45RX4 zw2<3-`ir-|ZxJt7(C`-ZqY`6y?SrV6hxfp#e?RiGjJp;CZ~(Oppv^`m%^E`UIfD-8 z?)hTN?k2)!sYoj3g+cbp^8KiiS17j&A!Dtb2kn`?|NQfjhs$pS{qCafX-2|S97T3c z7|w9eXHB2$^Ob>s^?5Eh^V9ZqA7#Jp0K$B^B^n+9Ott52iQl&9;nfsBIhmI!|^jWXx z`aD)3AnlzGbFRQJ>*!qY`P0kii`9GbVZH%WI)Ezp%5BgD+J?|(o>N8kVbaavz^OKq ohfU;z{kxMt2!a%S+!B4n$HapNetWy;M5eT5)18}z%~8?+0U(FNIRF3v literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/rws_client.cpp.B2625E19C4ED09CA.idx b/.cache/clangd/index/rws_client.cpp.B2625E19C4ED09CA.idx new file mode 100644 index 0000000000000000000000000000000000000000..f5466171225f93195c6ee738ce76cce5a8b137a8 GIT binary patch literal 2694 zcmcImeQXnD7{8Ua*Xv3*+U_cY@!`-p&g*ScKC)!M+Fh}u?dDcQ63OLy_qIE@kLEtM z6%q^tF(ihMKZqp8V2u1_Vn{H88skT@5F;pmYK)07QPAKLB1Zj7pWA%f4hSgdrR}}X z^FF`d^YuP=9m}NC`-23Lk~7m9vPCaJ5UudFY*QKa!@|8-RyLJMWU`teqk%HR5bRKL zWMsS`3}&-JeniM-l66&KB$r7ELp$@J&Tp&f$M~)Mv$w0qca9hM-0k|pQ)B$#P@{f` zPY-U-7KE|f4k42p&GI=uUl=T8M)CuuHYG?^Ni}pN%a$NjD&Tf3wY`wZjthK#Fq!3r zd2l8_%%@xo!DhG#LqlBI+*=e8H)WW6tcoZhPAnD$8BGdP7H65#oM;+W-~3_<*i{AT zHmB&4>d1&-cfdzfRrp2Iwkg70(G{DukXnMZZm^E-SV(3|jxO1Xp)XKYL{o&iBNMb0 zL(yTyil$;ufNUb!(PdG$Ss6*H1sX>;ktj`wMHR6U^a4~5}SYb1ai9Dmo{@ z<0_RC_n@?*BCC-AreJQu7jh;HVr<8FYHr90_gPTi?(eVd^!F1mGCGoMq6EDC9Cz=7 zcDLOAewy5J_#300fOP*)SB|Zyimf0k@t=9RL&L19R@?%wl!-HE+ds?g3ecWMy9mbD z?2C1WJ>g~|;J$$1I(K+Qzj@{LQ>~uIU_aa%j(5k&c(}H2qLTI8B6wHL>`os%VSLpT zV%j>|*41D)A|LWS8*NaBm9dtN)j zdO{58CnI%&w)JgE3|a0^=Z;_g^P5E>#z*+5x{;e5-V8BeUpR~*Yg4lukH6!kT;3%!KfZ@yt}KXGU`SU2V~PVpaTsP(9u0q<+@MDEXO~JX|;_RJsk<$51!-pXiilW-FRfq{v!J6cJ_x-QKo7VGS z6!XMZVoGq(M~`6XK;Y}yZfEue_$71XF3j}O=8hBJUYfB08=)dJwuWv}(VBEJ{vtiN zKepfFWhj>F!B{WT5^kY!Vi*ccAy25*&EVWw#Q9uEpPYVc%hfNvz_g5F>P*39!M?f_ ziATCHpO=ZoqX{g%`ScmtutAED5eh>f3Nl)gW?%h1*?#2o58y7aA+Qw( zZX#85XA#EO>V$g}b9H9&)X`&~_j%$g?8BCpR+1}J(p jy^3B*FQYr@<#Y$VBG?>?Mp_pyX$dclKN5Sm?IGeX92$y4 literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/rws_client.cpp.D2D6995B64F84F58.idx b/.cache/clangd/index/rws_client.cpp.D2D6995B64F84F58.idx new file mode 100644 index 0000000000000000000000000000000000000000..6564422294da98579c79c95f2763b88251f9dadb GIT binary patch literal 2692 zcmcgueQXnD7{48Duh$*j=%-7POXGa?KO&Xx}f zLjyar1#u*|OU&f9XN8=QFANki!})%wPl$3&)=UE^iY3a`DsnrL-dV_GM@1n&kje_; zjBzHvRYhh4xwrF)fW{BDiaa} zqH5RxmRxn!kTpjE1h)%)BuzuVVA6&Xx~qn2a~9A_XllL2xRPVYwrU!4gjESj zsQv&VY1OQ=a}reT3c?U5j-g0~%_%_EEF^IZ2qd{86*a)gs3%A?fs_H~w#_Ibm6BC6 zY-y4+4Xs9Ss#UXWpc5PfmgztlaEc21=j5M|O{1iid1GAF`KsoW%Ru4BOebyXRSgA} z1H4^Pp(3J4?HXT`b!Cn~)+D3MYig07S@rfMdJ;VZib&}%8%}q3?|Nd6!+RC{{u-#< zmW`@h?*=IAqHdL~Mi1`m;4X7GVTrnANM!&YmImdF0(r<7kTDA3A&sF_Rh37nzzl(< zi;|+K#v?JAMbrMb1P?M^u8!LzSyO>wC*0BI&8p3#k>tygCZSQ1o8@yXSU-cBHm-BM zJ$z9$X3isLo2EvL>>5qic?fsNo3zPfV<(v;&?Fc@wuzFefh5o0|4=w zj3rS)DgK|X9b45@TLspC@A)3hBdnTU+>Bl-l{05MKF{s;$H!6Dh7KMxziMIF=#uE#hS{yq zrJsc98(xO>`FyR|8^h8hO*K(~49r3yGDKklh7FV91_~v<*wORW5sqY7%14Eo1krWT z6gFAx8_G>x`}3Q54C^JlbW_RA4sSAS&>IY5lQrq-4O8!XXqWdXD%CXcFY!N#QSbD{ zmpk?@SnMhdQrobYVf_jJT8y4v_}+z6t3F)S;+d1MaOHLCliP#8qVjlGdb_ap_IKWf zJC7aOgS2PoGfE2|>7f0nn}Oh+<%#a2H(*`9Am_X9f7`looq&`gWMmnpL=O65 z!x$a#e?7h0nZAYmQaNfjW_oqgl4IXqy=)=d5FLtPZPZOV+(0MdufzuSNA{B*mgeXl zZ0lj$f^9LJ7&b*r49PUQ8K|E{oX>@!6O-?5{_#r>Vp>FZH<<#90)0&siif%|pN9>{ z!wHN&_+9<^w{5Gv4W_Gq+};FkW)GsaMV3caVC|b5 zU%US4we!EYQBZUvR1X`V0<%zv3engEML~rdX!?yisg5J3en9U0>-}4B;1Fn%JBw(J zt(EBB!XAyB9lL!od5P@oB0AlznX3yg2m<{v(AFUM82fk&InU$uQGPnQEV>j8=fdcU YXh(EWba9}S35VL}FK7$Kmq%iM0lh$tod5s; literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/rws_client.hpp.3738C46199137910.idx b/.cache/clangd/index/rws_client.hpp.3738C46199137910.idx new file mode 100644 index 0000000000000000000000000000000000000000..01ec672d8c3ac06657b37c657a58593c11933380 GIT binary patch literal 1198 zcmcgqJ!lhA9DjF>$>kEy4i+g0b`ks>)&E`kE>vAyJjlC${vYr6asP?YO667z zp;B%1ludjLABisw7K^{ti^XUXYKH4L#PHFS zX_2C)X${vVTAj{RG0|EsJ;6L|5G_Eck&}9hX{N(`Y*}H7)a?-1#tyC%8WatyS?l!w zQ4A=qb>$lDe$W2_lQv>FheMb;Eqa^CF3^=WB3_ zR>u}LeA9@=sbLwOr*&T8h~w6Xj;LF8eH}iHPhHC*6uf5!H9g;S9jJDF)L|#4?dl4w zL*|pZxLW@BK@sH`lClHYt>J;BV0qwC^Uue3T|2*15z|mt`_=8?5!JWED`S_Q{d}7c zg&riOCi?RlXfihPA7S(f`a0=hdpSfnp*T*-(V`2D?!UL~5RWQvUlU8RB?D&)kuKu8Db zc$&XOIn={Rq(kn!SYEoCc=+|e7ZK6}${<&oma=kI;m%Gb%lB=PxgbE(K4m{|I@T^6 z-tn~k3UI-sp^n=K@v@Lyhr~^S?!X~VfNO{DKr>H2xO{r)(Y?8|0k3V!FuxOcWwQO8 z*XuV6pTA#!w-zi_c%}vP b<6Hwm$!?hFhSEZ5_eNv&+|iz7Jb``zMjULu literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/rws_client.hpp.F6B6AF448BD65A95.idx b/.cache/clangd/index/rws_client.hpp.F6B6AF448BD65A95.idx new file mode 100644 index 0000000000000000000000000000000000000000..594ad3868a141f221864e45396f05ca3824aff84 GIT binary patch literal 1230 zcmcgrOK1~87@pn4WV4NH5`t}`R1t(0G^-IkMCrkpK!t*B!N)T;9K@W-)6nhbT^{CEnIvXFocyVE8X8-S>|NFjwW=DrA zl?PD(O2*I$8&SxXAjMunvAIrU3;!8CG*+@q8|4- zoq}=GLPb?o>#mK|8lJ2|q&8iAjCfE-s?T7c<64ubrb8&StRRGHc0g=H2i6ewLEUN? z?fkz$U*d9RzWzT5$poRu)(l9Y=0Qvl{uf??^}r-{Ng-I&AvT&2Bh7Ru!sC8le)YQo z+&Pqd-Sa}ru18f?Rjok_>eST3GFZ2C&r{n|u*Go=qyg+!U8=F8qS&=8gxOgT9h)9C zU5BBazH01_OxV>0c0E#`GINXNj~^6Kjshv2OK%7UAo-VxJ(>K|k!@GbZdJr2!!x~^ z&A|}j>tmJS3r~K$j*CJBNXb}oO)!8&d%qwF_3P8QN5e;@wW6?GQ&L2wE3D91c=v7p z;I6VFb}@$RK(-PLA%5fL`C4m6D2O7z(vmF8J)8mDn(8a!XV)&J#8te0cf4B(_hU3p z28E7OK@J>p;oKk#`|fy{&!Qao;UbcOb`F;3FURkF-Se#}ef` zHcFinSkfM4FHbtsDjeMMxb=eZvL^MnyA1$`g~V@6yh$wE?+_Qjy|ZlJGY{Xrcyj*! z?dj9Lu8qn7ugP?!(!E^Q%U83Xm#)6u&2(jzY(Hms6K%}R92kkSa7M}W@b+M2!A(pg zrvRtEPfk5gwH}6n+4nmnBeJxU{SZX;?IgG-0OFmcG+WxfT3%u@%6)kB3NxjYHgsFf}%eZ#9ytTf>;%NAPB{?*-jpPYOBNU z%st=S^PTUWbI;u2cr5lxEkaQ>K4lOadk{iF_**v99N9Cch6u_zN^Z2lIpEP6=nXSXpz|dlR zNQw>YOl0KYN?)D~2t=oTOjWdtkZII9yufm#4G36qIXDi_Ve6a@)6t4M7;C74t% zB0;l?mQ4&Km`Gs6G99K6LDg9QlGR5PljgL%NGCKyEa*-?PgHTtbfTtF&_Q03i1xU~ zR2lTzMX{(D>JmWFG0ls*mKDpRb?YN*BWn@pQv37N35VBhMoR)-G2K~5)74Az{14nT zYS~bLIY*K=WW&l^^X0jI)JxqN)Y!lj=Lx$}8b|~Pxj_x!3=(e8nc;$_-b@C{1ePIV zRn_QCF_~G@{bTOoQgO-+C{t*FNU7CDvtWzRqGBHF7+OqO$em*`F{@Egfp1nc ziFcEjrW0!sO9WbBuFbDN95GQ2rr#xs*WX0f(tYtuammJ>6JZfHp(#WzFmpmv36o(N zk#Shl{~p-JHiUJux@L|4*Kw~_D0fj;tCz?W9SVB!F_#AeYZOkSqLFQfgJ}O}J@0Pi zr%%?QUWE86PnCD>hEVC)f{T%y_24puD&L%K+p_wHii$cuR1@;KZp(Z32PR(s>+1>+ zALN65;kLHXWZ+0oM{;cT+4tMG1KbpD5})fhbYg37q^Ga-$g!6?Kj;LwIoQ0yC6P`) zU-Qv#L%%Mo>W&v<$H7|b?Q^Y>TIsk!f=^Y}@mvk($I?TwLkG{F1goEm zE?E9Ge%|HXy)i!1{@6EPg65`{re0Tt^G;*#=$38!ARO1lZC>#8wfokM{&eon(G9J8 zAGxq+-xtAG&wy{RG1%=c%%!g2E~crRr6=xL`OMi*PFXz+uweN% z`=YL95AW~w_qn_tKCmVbajg%(+u&6z|JVpo8X6nA`VPM!@7@38juX=lpFVZ$?MF+& zgWgs*__;TZ94^Lc8vt&uX|8uke%vzi`Ru1h&wD^cC)c$|#VTL>A{BoBybGxC2j;B{ zzpqTsoay}qHb6sn!zNb+>@ppfG6~z<5=(>b(ye^;xC2zdAN;t!TUhb)fy$n)ZqzmZ z0>R;_3t-+F?yOi=>8Yx&@z#b`huTB8g;s<*LT#ayp;er(uBkETZ>SHn-g0~MnwI70 EZ^Y+F4FCWD literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/rws_client_node.cpp.32950DC259F660B7.idx b/.cache/clangd/index/rws_client_node.cpp.32950DC259F660B7.idx new file mode 100644 index 0000000000000000000000000000000000000000..8e251a0c3f07935a7afd7c5e93a67fae4d87d92b GIT binary patch literal 2466 zcmcgtYiJx*6rMDjWHX!HY#tjMo7ObRCNW_$Nt?DHrkZRf?Y8^SWNVBl!`+#?yF+L0 zEO%yhvlUT6LVpxRODO6O5g)~X53n^6v1*`{f})gaMJ&`eXoG^a6ol%TO($unrL{$e z-8<)edmi6C=iI%c;gON&Dj6muhbJ{`A{WCje)t+DRUR(~!G1VSrb-S|PSa&PknZkg zxZ$CAd@LajMj~P?E=Iyb%TOX74Tr?xi5S4KolE$ruuZuCN_cEyEFna%#1q>`g~8#= z@nK4Jia}qJoxehD&Jgr?(&8-Z}kI71O~m!7^8w zySOlnePzKzamsjT6~mOiKHs!;{m&&ORl$ae29M*mx@)g5_sXANmAHcbPJjQ|3p3g; zf1L=mMknTU7)VZVPU;po0{FaV+zu-?d+CiUr)2A@739ZWGesl=|?W^nL6oz z={WfMYyBP0#+=Y4?4>d-R%zc|Yo9*z@lgXpdaJ!nj#X9ASM6KUUM5rPFSNIAfRN>E zxz90rXXA^3nWyeN1F(Cud(heM+{pCg8+ZToWtl6;3T)hA3EI8vgUgy{izno8b_Km% z-hL;pE9h(S^*Gv*A2+(?(({`jOHFM}ds)}QzUuE!&3-Wb@Uf$FZ#`-!_q!XN~ z4j&G$O=;7$OF~j=T3pB0F-dW0?;cL*m>Ac_@{E<15I8t5Co?c>#76_tGXqEGjTo9g zJbhqhVETXoX&ITL(njY8=8qWo7LLfv4}SNT(NO!a?9AMP!0gPfy46Qmyx+6GSdeRP9HEVQyU0#0Y8m~!kL<7 zx^lCi$UrM?Q2yB5g7h(3Uhc55R$6xc*!+Ub94jr)N*j@xpEq*Ez)US8dqmXVdT$z- zmpdpsD=>Fdc23~%VI#A$GBW~u=8bHVmot1AG_ONuV8P(*5gBRF-h#1#V+ZDB{OyN< z!_srJ0*7S}2z>XqropBlQ;-$3D`L)yYKfm=qK0X5GI43|7kTa5YUkS!#2Rf(1icPhexCj z&(8S28G&~dsPW~L1vkvA$kBXdL= zh^NUS^MQH83jzTIW~C2H2U#1)2XSQnh`<5axq$;gd9~?~J~T5vdst@v+v?uQvk7G4 zt-SwtZ!qOqrL;~?h)o@vGawHnGNpTJ>bu4yzi&%Qr&KG80gw-Hu zLPTKT|IDF+T<|f4er9J3OUug4%^ZZ}dXJrP$<9m5&(6wCANCf#6XpSVc_Pfn9hoCg|Bl`n5`mom zmet?=Fc9ow{=gC0!{3@Q%j@!oXJ%%k0sm#^Sq&eaR*(mpGdtI6#K>Iu(V~e)77G7`0afsuM&2ng@Xyfy6qaR|Xp%N{f~Eqz4R z$Q!MILieQ~yvJ>QP(5W%aZU=?5-dv&UVa#6s0$p&IPJ4$*bUv$jkilBU zhdSH{ymhKj$G88pvU=ZA|BKgu$zSlKzdbfV9Tl=ig&g4jDWabu{+<>uuU-4K-UfGj z+!o5LS3K4$e*QBNor&t!zNg*IwZr!7LUa?VU;C!ciERu6e5>x+ z<1i?51bZC8{{Ee5XBS>#eB`{(JmUQAaU7I5K|D^70RItm1n*I|>aF?c*{MJ5aXTpS zns~e>{{Ca=7+y#3Ps+Yd@tuL~aZ4yMA9>72!Tw=1jL%Nrgse=TZ;vgo$GxFMnd(ud zM)-e)=vTOX}5l!^k=9&PJ}X#6_3X- zy7Lj8FN|(~ABR?Nehpe`j{~7hG4d!zntwPAuUGq~jP>CiJqC~c&>qJ?i9+I0Nc{YV z(P4aSv&Kn3{&eEXWP98LN?cbxuB$=*TM^xg+-qwYv#rAiJMbY-d)x}jT#!62zzhwf z19>fD4$K+tF+HV$J?;x7j;kKW)ky!%h;BxWYipTseD3f8i6dg|aWg2h7<(+n0sif1 zJ3jss)2er-e;v8l9(RHgTV#(dawGqb>BkPWbu4cFxx+B;{*m@L2ukcg9y?GI|416? zTw7vkl-xb|tBWP}xFeJ}L_H2sfB&V3E=7D6iwfrlhrT@NXpf_z%s$CupVY*^Kkd(J zS-I}>ANo4C2W|?160eZQD|k;FjpHT0NbP^y$~qOsJ^@NxRy-~%{{C|iog=(w!-)e% z->?;@>~R#7`BL)uQquhU(!P9tHa*z9Wc9My+4k5BB`PJ4N@&R-I*7k#bH@QvolSXD z>~XNA1oEgve*Q5uhL3&OPYe6CEqw8-J#GypUP&IWV0N-;HZQT`UTc@k)*tS&$0<#7J#GPIu3(QV zxRHMs+J(>YiMVmkfA~pGvd8VA#60RT52Rxuq6-D-xUjv)P`tO@IeXj&%4{VbTS*iD zJetSH?ZP(|rUTyHtnG0(D6vxYSgC6MUn2UY(3b0`m)$>o{W-PA@ld9ccvON$7)eKR zj=a_M=R@np@7`pOyF-cfs>gaYz`qpHQlTwBpTFSlo3QGlJr0F3o3O_w;Oq9ZJ+I}L zR|zRM*S`q1$B|ItC)wjC(59au`k7G6ubDe0-O^WVx5ueaX1eMz9dz6pMAry9?s0y> z^TE9ineA~;C{w9=RD!H-Lv))UtIz!p_j=l~H?+7plv#v479o>=N7~V?b{=1k-hFVk z?hx=?Qz&r?d7J`{YDHUdei@NDC_ici7%a)@u2q+L-yprVUh1-5>cbe?s(r5!wl%sr zM6b;vjX1yHvZwU%Y zF$bgsCYpM!LJF&pqB%Y;>5fZ|3}ekV+rfG60j$?{;yOFAEt>_swj0~-#!d|5JwG1( z?T?(hE_%%gJJ~bisn=YwtAGsHARtfdDIjm`Eg&E4BcMjOk${@uCISk;0RjrdfdT@H zEuc^wDxem)g@9V(mI8{#(E@6XTMH-_#|o$|ZY!WfoG73UxPyR_ak79?acV7+Xv@J} z(pEYF0~}DA98ltz&6jFACI&p&I1C7@)bLem0uwjV^7+}Ht=y*q;S|=L!Y<4%D>GI* z$7FAM0fZ%L=n^%axjL$~i`AMA%QJy+T!}uebY$;Pr!MI-_T0LKia;XTo@eDGZLBWi}_1YEWcLkY59B~Cji#X{DN@ke(aPY=4EykD` zuUNl#=O(=VXzE4#HUG9wJkfITu3M9UX&c2i>cWcY!KSrajJq*A2OY&ROK>v7*1PU~ zwCrW8^jb0XET-N} zQGy6i&z;npH6O-{dY+};%oJK*cxqGDBCizMTaDURqZDRS^x9n%b{9o+`~>NqAV-FE z-ZS@{n^vzkOwBPV=$I7Bq)+#I!gA%mUw%x-I;O7}~ z;~8==a{+CR{W5I(pc(@Z%284|>cTt^n;W*@p9`3<90<4N-nZp}Y}V}DTOPS^+V3Ka zvQNBEXVwrscn@)}P%`r<^xA9G>NQGa*gm6lOdIDYJ=9mChL)%?Op@$p4SP|#+{)78 z^~#|2N*-f(`$vuke~r6;r;%Q>aj|jdFS2vB^WezI-N~CHS9ezd8Qcv5@^tqUkhiPdw_rf-2(*_>>ezjQ1?&)wQz4CpqB0}1r+TbEuhx!tpyb8 z9xI@>?rjB>=$H1*=fjg8pjS%d;hwz zWkm#V&R1&qS85{jVjMncIs0^xxg`)5$X*L%AI9wt%cj2YIeaz;gy;zkeL@qN#|ZXa z4V|SXGVjD;WzCRpbC2x<`QAp_ZzCz(u$Pm-a?+gR-6U)`iRQS1=qiXK!;Ypior6kd zX!U`+5nhjM*;+=g?MHY&vSsq7*DfJ^3E46ot=H}&d>`2|9i`W%VmuYwGI`Q#D=}V) zZJE{u`NgP zZhW4}_?c|W)R3YE%W7}e+oXT*fQ;-*Qyj;rPy-gG>PI#)Rr5kl@za}w%j(I_a)3|6<$eka{EJaPlg>&?ArDDsoxx-zE@J0S5j{_@Q%;l47t;OqKl`6 z1MSu$H<1JF_9Hiu1MMy$H<1JF?jtvm1MQ|_H<1JFR$@1i1MSMO8}mr@+6ioT0=tPE zX!i?t6FJcCHFgs@(5^^w6FJasi{vJ9pxsf)jdS25$?lQlCUTtJ4C2N*uGiKOyEVj3 zXSWjD@o=VZHcvKyNLz4lDDdnUVy9A>vn zaT7Vr?x^A>a+qC};wEyK-6ZNJa+uvp>c%Q3S`EkZF@huRx{>6wNv8F!DQ$A~-&ROh-ieHDtOb`mHyR-whPOIr1hl z-4y9H$W-%pzs~Ooir^gk6q%li^qJT+6Gw9no{jxx;|PxDVAC9tz8afW<7m#|Yq8&2 z9KrEAY+5JM_h8c=9L*(QFZSDuBRJlNP5VUpX>2-;qq&5f!=`g0uEM4&9L*)>4)(i) zBRHNYnI=lnT!JP^ev_mKjwef|$s&EZWLhpoa|v51`K^>9I4+h<#Ui~-GL=cuTmrXC ze%qx8j(13=9U}cZ$@Jad7qfoHr3fyuCnVDek$zn=U6-P{4Y?`#-IO9Yek_?DOVM1y zpGtmDr3j8^6Vq%G%_V*=@taE`IG#sL^F;a=#PkJ;<{Du=@mo(KI4&ioQjz{GF@5`Y zAxCqKwO;mHFGp~^OE&G2qq)u8Bm3=6J)dp_o=E(Og3oD}KdF z1ji+csYIk#C;=5pB-fxP71K#2n&Z=o-)SX+<1>osj7YzunC>XiT;twV{O&3d9RH@6 zeiP}RQPXEMnrq~#)Nd+{;CLD}O%v%Q)Ko&FxyD{i{Z`Wmj@MAr8j-$>ns(7>?lbJ6 zetT#H$KO!XHzNHUHJzi;%mV1O3)Jrdjo|nqHC+_xKTw|^Xb9Vf*K4#!MG;Ly`5{lQ>pUy^X`n^JvH!@Il^4rZ-YBSG}`{ z-z;Jhal|Z970)6`vq&~(srMSKeZwTy2mpyc>u0j0*L z3MeB!LqH$4`>-#sv!GppfJV0)EufDQKN5WI35gQ~^ciaR84}7~!7*2GcW#ZZ;>fGG zGsh2b!UNooTjPhg%|qOS<5^PtEU7oQzOyCsY^f{97o_+LQg3bzFG}W%Qdf>ErMOC| z7q^C0QmZPd3&)?!Z9bQKaBaU-j#?_GaJ)s1*&=u6+J37XxmE7W@nxm$Wu*_-j#re{ zSCnoXKUU%&E4{fke4?12C|x<8N88P#eYy6VPh;lO?i_ER<_)wf*LGjgh_7fTjt|kc zhiD(J-44^%hiNy44dK6Bv(ugO1MZKGkFMPjv#fvOUr8y9vtXesnO{pu47+!Yo6)(8 zdt+en+j8b@IhR={_lsXn-~8`A_kfqLAjd1HA$L0;BFBfQA$KdMW5?;ZA$J=~uww~s z$lO8?CBDP_Q*Um<8}y3aj`5wxH-|?yozV9asDCpyZN|Y&wk)z1vJ;1ixXn)7R>WO* z;+_n9K0Vd&O=SK=sAwk&+KF0nvEPGy_n;t-E0C@Nxo~_0>5g#x0d4rOU2083Xy{E^ z_a^;-8HNw?-8(cK-@$;1X5(yAm-T>Xc6IGs81l0HG<=47@+a6#IfLt+!M@y${Z?`L zR`FqG*y}{cW(~7iX86F?rMIoHz2l&Bs2v@>R##V7KyErW0eR>=1mvaj5>NwO0|EK! zdO{yCjq7CQUugh*Hu7+Yz8^7`Os_GHrWEovCDDdwBdHc1(a`>FQ8F&qXaa@ zeT)}>ZoI?z+WFUOpE!IXpsC1iDiWTYf$U~*>~*7ANspTIZzQ7iA$?p~l|<`D`U$8% z>0gVyJ1kq4uYG6&hO8nfRiqd5gzH~zyT~Q!ek2f1kn|H|2y?0H|Jvu`w*Ik6@RGCG z=`40;Oh{ns&uM||%zR@4hbayR6-UOD4Ynr+?Ar3XJ=C~UcHAj9WNME&KcH4tA-W2A z@zrgqL`x+vW-G1V$DA-**s#Ur0`G$vS3zjbsp>h^nz;c)JFlweIc}I5ueVhmt%6s7 zFYCUSotQt}@P4~L&*VDS2f{YB;Wo7ib3}ZD_7!()P}&`OS%{npkuzJ76YT)9JAmw& zgcDFDb~~{>Qx(47IMvDJdkx{J!Qci0^3C!UN*ae4hw+mBL;M9~$~Fz`p?(~&mAtH{G5ED-^MZ%La(6AXCn_gcp)dior032)MX%oaBv-`lVDMLXGzHj-hd(Rgjy4#3p z8wqCoY6*z&J3ve#jyNE0l^h^R2S_rb2MtwsHu^d_2efWLd_XFz-*WES_6Y96v^wn4 zy-2Vqm-gHFEsck+Ea)!E=;66)m zCQ~y_KM%ibHVhA%ZHNs*JJ z7{0VvDMhZ7V)#;GyA-)yieaV;^qUlUT#8}qL-7Bk$eU6OUs^nsBA-ezd?_)PM9w8K zOl`tZ0*PEtVwe&FeM=%MNDP}z=r4)9L1LJd)@x5m=XREHlnfpB%Yf zj^Rs_J#yq8IfmI}FfwxF6*-3KHof+j9Ql_V!(4YTN=jt062m4&uboyRPb)FZ*u%z# z5_wmN;Y*jPG;%79;Y*d(G;%eK;Y*V}G;$A(;Y*PVH1YzCVM~u@50j5vs(&jMxOKnU zZ@-!zlvOoj-_}2FL&%2ecTm;%4#8=)-)S}dk!kVeE&({JSXgz+Xjw|flw{trt{u7x?Htr?P!CSa?v^c}obEY2Ic<3N z;R4FBZ}uin>lk!jm&l*BKm#t{N28DA08x zaKmeo_L>Z4^3XiJeeYEbDtAH%&2%Mpy3(FA_ADiEmeQQ#xk}VrC6?m_O6&r${30cB zkj2@OTl6=1<`DbWR8R=F=(wIcINS^)G+P0pD!5WmJhNVd3 zs&1>)c&ik|R7;C_tNuNIx1?A&yy1|>Y$%u{!t*mwzzh_@2-fc-s+k8A-bj($CQ0>V zOJq%WHHqaq<1X>MON<=fBfj@Y5XX;+?lE!U_!-eX<2YRNess;Pg=Kla8HaDiv0Ry! zVc#+w#PJ@i+k;&=-iLMjI1b%oG-Pj#_~6m;p-TFre_(SW%huYg z=xVbX>e@+tcG4iGaiYU#q{oh{7Yu|8YUl+ujx8oy9qR48yt3v`AS{zSmq}hs$G1B3 z;#=G%cQO!4P?r+ahs}_=)1Z1ud!AZ?n2HcBLXONQHK&Z!_20U=1PEVBy}p#v*&Mdk z<=p#n$RGmjw*cV<$ex9RTh=AYHr1I~S&RB}+pjj}>Tkbl-miA#_@Jsks2W6d=yqCd z%+w+1Y1MpM?Z|NJc8jc(v}0laU<6~dC->I9OrH5q9(mDx{4Wcyx3&Q@Md9C2w(S9{ zPMT6hd$A=TOfZeEq49jbd%BuDUG2g5rx&Un7pmRZJ}ks!sHT-_bH4w)UWH)VP_{Y% zp;B9xscrc1?NyWasy+Dd99O#?SNpNK)Ac?fOqUrV{!{o+s+ zEFy9~C`K9V#?HIND1kfF?hbY4WB!=hKc;p0nEy!~|D>)QzoCwAL_AZ~%~b9AoGeyt z7OReIPTFn1m3!fQ+qF8qmO(P?S;O^O7ReIOP-Unir{yZS0{T$-P(TGrfq+IUqXqPl z`jIoQWr8|EK%XJyGbEIqhLmX>vnd2uaxJ23#a)Lzi0(mN+?70!=y~MDUCFzM-bG&A zm7Ij>B<#gq$s$aPuorhF%P=j&UR=8!!}J*TVji_#`w`P0u@`qOUtszIdvVutiA0xh zwF9oNL^twX5lcWbt&qI9Yk5zi_arawN=_kk3h`o$0(hB$$Ny}BVJ7DLeQv8C(B;Ubb|JiX^HH`UCC22Jtcc_*Re*XHL@3X9Sap&sCY38 z2yxX4-K}_W3AwG%+lm)=9bYT-wc^EH$0ACLs26t~%P1|QUQCgLgi(5edNJ40`u*)7 zX73WmDm7((h0VdIfqqYa}`eH95zuhPm~flhb@=P%cVqS*g$Ja<}xXf zStq^ron-z_O5_}NT{2&n68Ylgv1EQMC323NP0X`NBImd-i1`bW$T{v?V*ZvS@`1cY z%-2XF=eWnj{Fo$ij+-gR%#@Qj$9*B2zmO9-$L*5MyW~W^c)28-FUg6V17FDI7jh!! zz!i#lg_6iQ@T6issU&g^yrY=!D2bc{KcnW)Xd>sp5^64?iJSv>QS&aE$T{#FHJ_u2 zj04+uvmM%`eB2dK&C`|O=}HuT@hru2mSW_1uHrvebT$_#!3)IliQb{cl6x!NkI&*dCDaL$PBe&Q0YJ25=V`(Gm=xLvV5rnq<-w|JfK zje$+h?-bkb6qgs(QD-7cNfPT4Ooz#63S%v{et*f34Gj|uD3)MMXu*rUyJ=WkY;LuW zzhQR|D0WV5c8)u+de{wbcAn$Tr;{h$E$p}g+FwoDSCbSrg0N^OfpjhvyzaJ*2B zUZ}=0mq@QIQd=xiqd8uwCazSIMYlC!z1m51Tf3L3eMPr5X0O_gNuOTZr$+8mV>mvp zwmYtNWWobdtHzvA+i`qd?QmU972Vnnm1?T!)^>iNc4t0O>Zn_DZ_he51X#Zq^(sc` z%yM<8aQ_6`PsIDoiyI#iGt&m34Q1mrF&1vEY+Ngwxs@)LgUaQ0 z+)AI5jpt-Dw;<tZpBwp<4S7gR=k`BmD6_Iil3pzGt|tiI9rkfcR3gx zqPZG=cUhZpSMLj(qAzc#==Klzw)f*V&l=ektpQ>A8u$4cXEGM)Gyl@3)+?6J{|9yT zSsGb%;;&=9pspEM2lvStJN7x!efEmMH5;M%`&EbiYCXPXa9VXZt=3~(0!-;x!+>M@ z9Q$$xTqx0nk}qe#V=_G^`|=6=Ri?knzI?*wDs-;m%O_}yLboWse1dK%^p@hwC+MX@ zUn;(Qf(j`uq`qu|tlwXHXCuwDx3gZmhUqoz$|dI!rjM{IZ}=RE&XHVs!>c7)ExB?@ zm_+C#;>smqIibsmE0=_FLd%IOmxQx~o+Yka67CXum$-6Cm?+bUvMbX^upW?Uk?hJP zp-QGzvMV2`Sqhz{xblJ8q|i-@D<7z<3caeh@_~A)(5H$kAE*VCE}*V#pkRea=|<|x zIr#{sN2n{~Wb5~t0cr>GgSrlVTMZopJX0e%)<~XgVAAv(e<&$A)f+s8GbsEFisicR zJn}t{f;hg0bk~pz$2XDgCdaI$zYZES*bfL>N$;&BgH2_+ za$-=6?_Mnc!b=+dlBO~fpPpqk?(Q?Iz<(fm=^y{n=jY(XmMechsNp}T9hhkw5INMZ z%>wfcARNJINAO^#@(0Wb4H|uadMXe~P`?tC#rnxO5Bl52*rqw}@4G|`tiKtXtv6S@ zq&mR!g``U%>CK+Ybo%y(e;v2+g^4>w+MgmRoK??~z_X+|#}`Q01u;PS2GQLhj*QN_ zPzUaBVfqBSbD5ei(fN`)m#H$DmdWm1yWddg4aJ@F>>mpKLvd%E04@=wi>N#2+0B%0 zrtX|)zoYa!>dtxgT?Pr(^{j&r>OKklDhn1OhvneIaunA>$7KIwa&wN4%fZJ*`YGA> zlpMtAmt@@~*@fe)vhFI!gV${_oaoS3g)tUm%Z7aL>1y+(?+f7PO4PR!4PtJA?ia2)p+cH(wBaYtqhEH~m? z%_4DJORXcV){!_i=avKDRtHENV{OZg_*Pd*9GgnZ=6S0c634aFpH%lJbzmGnEamc) zH$zVifF6}9-Ak1;rhamk45=4!{e!9?0=HG{mLhw$lp=5l>$DL$Gp;4tVdQieIWv!m zz#**D4dl#5fM`#U(-Y*(Mu2FuvD0kq%tnA{tFXf=?8rudXlt?4TI|g6UhK3NJF^iX za473^2Rk#pPqayr(!XU3yM+b%h6mzA2*~JSGB%vQ9T8 zXXY^x?WyGSRB~qOkZ5y>(_G@rW`Mw6HuS*v|e^*c7kYoWT!o{Gm|L-hq6vrWM{^z1P*1L{*s-U9U*Wi z>r|{bGdn`yP}b?R;>;$Jz@eWGL$t2NMQ>WF`naL!)pE~WK&P*l= zM87*-pw3JtiS`54|3Gb+Atu_dRR1frVaq0%Z>oPnZ5W3U?FH4p5b;D+KT#FvvsC>o z)rKvj2wdpbFHvpSvWdV&W_^ij!UwmYQvNqfmj=TwQ9qbAOx(4{*h|KtVqs|PULLU#hI|fa0azMgHjk{ z!wMUPofof3-9Wk<$dS>9mn5tX>-SR+P{&u%2Un2~BY>SkA3Q=nOd>2!o97JNfJp>I z#9{AM*q2GbhyLLOUoA*}0Wx|T^*D{vSw$n_FVo9uAGd_2dB%IDFoOZ=AH|;%8+sa< zPs29H`%E4A4KB`}JABq8Jv0obUd6qcD8c1P-0LA8z(fh+2c+(^r8Fi=a9SaCzbK_K zQ2}RL>Q*K7W1<2V+vF}wi#q83Y0E2alW-mZL_7~MP$tabMW-CLDycs{W6jCQalE<|+;Q7|huDrav^X76L4 z0v9YL?U#}irZ@E3auT?lH0QXOgcXaoqSh1Ldg93FqozHsIMZvT<;3?5>Gg&TWC~=o zW5(^IGp#HEHLp7b)bJWLk+JmX^G~AA-2d|yY=*y)!rw@- zOt*YG_)Z}~9M2}Y*~Eq8c|p&1V=-mi_({XL8hq1q{&vK8+FN0Y-MZ!;!STO62W?$dlhoNzfuV*&>CT69j8&dl>V&MNI5;%!8=R7fm zgiR5zpv)z@xx|st$8|6M!J($c{jICi`3maJ)DmbP)cGOm&eh^{+<7|g&c~+&cP_!* znOcOieB5g%?#~uUm7U|AjWJw;>c^&D_1jynlbv{74Ged3R$<9|vcRnmNq;n1F z&I~nll2pyoOCn;4_op|h zGc%R2v8F1;suMG1;B%?8RCQ*i%(6R1Z>Y}9G=Y9ql`7SVnWpire4CFMRcZ@!P%1Sm zm0B^M#&SC7yOBqSSk7{EWs(c0?~rsmI37Q_RnxVPe|ZBlei_xfj2f^VJpwy=zB5S> z+tC}pxYF!ovjsz+w~~~tq$eA^@i&XNudojr3WOb~_YRc7+`kEl56<@;+vs~ByoL=x zl*XoyjTVTQ(P$JlwBMy}W0E+bYD=$;qo+-UrWIpDF>b^npurC!O|Fmt76Hv3=nA{M zR@QYHp8|puhKvY-UX5&9a+-sKLnDsrI@A@An}eHxJRCd(N1mx@BDlAhUy6Ky4h_2q@kmUO)*B2?9!T zND@#dhfV@YaYzwRSBI_w8ss#{$VV{SDO*4}b#weUZFt?`0?MzOFQ8F%M+s<5{V}yF zUayUJ9Us7J`NZ`T0Zm19ry}9W8K~|I5zj^PTx8(#Hy_FKk%4XEfmJ~AB4l8;*|O0s z7b62(%2;?=-hm8^mo1KzdWv4OF=9@4kTo3Mdv zs3TZDf(^`=fIo!gE7-vOuLoFufDPRLnkC7zBm?taECEFFmy&^t^*%}7CmGmM1`hEh z`GRC%))Q8#l3XbnxPSIal3z&%t|1GFTu2ODLvAJVR$^d64krpkK0ypzLsk;Gk{Gy# zd`;xn#K1feJtX>*KbH;M|Jx$VTVw-=GGr zpR1@`MGb5z1CBbCA5jCd@nEr4dAe#~OBFrb_mmf^2DVhO1SZKVRRh=W>s5KZYT)|4 zOqI)219MX$-dL6Qig8=VRr$DTU~Y{iFiF0y8n`{EROL$5!0dq~FiC!(8kk@AiSFcH z?=K!-d%t}(eMn^eu|2Hzzq<;w@X6}k+e4d=BbwzZP}S+rbUT}+_L-P^`D@?Nzf(}x z7iFJ|vWd+Nn=???U5#CXnLt{<&!fo{?8Ne^cgLRS^)Gn7TJfn?nzOn2)b~usO?^*Y z1Y0#-X*^x==aafXX}mzhixlwInsWMbC44zQ{+^V4Ed9+>&m4HeAvyDqoXc7`>BkT) zp_}0(5DHO9A&O>VJ*DlqK8qhJ4Z$97Q|oS1efW6qSB?AC=6n-;zuIZP+Lz;ls{28; z33J^nadXDgYIC+pZo!>St9==s`ea-?6nLgNw19@wBzC4Wtz($~)vszS2Wh2BdZ{vm z@$a- zjoq5qH6#e$uutl}Ps(5#U}hVHj&`YY2nZEwXoZ@{x-zrfgo(4ejr$1JHwV=^2UT4y zVUsc>`@)+a;EAb9_*8zfGRvj7%fG&!nrG<+axCQuZDxB^r%n&JYz;GeKngk_wPY{1 z#3cDvNI@KbC+WVETsS@<=}vGw`_u5EuReS>i&jKu5dlV-h#XXqLpO@x*U0qRW z1%zXg<1v1De17+PaXb1fI0A%9>{yBYm{pj+=FeN@rIo$^!7%-6%})_N{>v^vUEe8T z-zo8oasKtdDrmrSr3G~J81_AegIKeGwXyCr&#wsK1Xy>D5x~1v|OlvNDnzFgh@6}(zoNrJXZ&3W1IDvR8jkk%oT!D37Q%*mw_#IbF9G_79 zPH@b+04?w^dW3Qn_bw4IQ*n#G&{E@0@9$HeXkrpPqKQfHh$be%Bbt~5k7!~NJfew7 z@Q5ZR!6TZO1dnK95PJfew7 z@Q9WuB*7z^m;{e#ViG)}iAnH?CZ@I{nwZ*-XkuzRqKT>Ph$g1CBbu1nj%Z?PJEDoH z?T99(wj>w{ab3g#pl$H-9LS`44BtD-dor}t3>gYVq(iGWUfL<%Om&gwTS1jIi{ofPb+1cma4lOBYw)NaQJA0|=J@2o>J~~#YygVBA$JU1MrmRj` z{TQ!Vl&*2A62^_+G^N2bZVW&7-#g*sCm&f-W}ZTQPoY7~6dfuPfVXgu@_mt&t1)!n(1UH7G?|+c>i7c>e^zvWV9jXQ=XNz6&UeN%LzLGQ=zPL_+C=hU|6)b7lqDf;u<2t(`L^MP=ehTo-$%+*?! zI=%P6Hy>ofiw?_;56k{cFMEu_#Wak0m@9S_p84jh zicvt=gwr?SAxyimB>{}DuhCZ+-*?Hs+4vTJu(oSa=~aup-honfpq@-874N&|x5@X; z85oaJDZW(dzkegzH ztRHdMkAF{~rMrV2dHF{;@DXm#*ELUY$P+9i(0Y!ep5s_fe}ThZ;J+o@(oK>aIem^4 zI7e#E*G2QCkojVQt%Xw5LMfKhmq=kt#DrTbCEZHNk<-7I0>77<^L5irNq19n7GiCoL(dc7Rk-|x@d(QxI)Awa#+dV6G-XS!*%)h zNz`FGM-C|y6GrWkb$et-=A*+-mJ)cC``)mwQ9^Er372juQMZ&>=9@!G4khfin1Jc7 zqPwd&a{5yx@TtDx+a#VnU}qRJVsZ z^72P$;1SxK=}PdDXvlYBf~ON8;$niQ3siT3IeTCTewj z8{2@QAD#YzYFS&SXL@F#*Wj3^;Xqh|Q&ldzGj}~2x6if zI8koS8$MYMn=D6jJX^Mz&9iw}68q{F$c~I&x_WY(_-D-qf>jER5AMpG3(LM#!k1DH zKK|>aHtVGnhS{IMZ_SL&gg~Bm->_i(w&6FAe-)=jOo3vhD6kZ@ia?U#+2iuJNuy`-)LQG3vqVD?x2aPzuAFer|M3?zMRo zJhlqOuR##}0L2;@8`N%fTEGAP zMs2Z)2OPRDaIiGvs$_Rns?Y6DxolT1*XR1aoZ6Ms`fR?pIFFyuLbqu>#OrKOf;T8p zoRKyuo|_aS$6FNtElP8aw<*Ef#Pa1zi*lt6r|(vLcPl|0S15HVcx(a0?<=~KiVLTo zQFLcG-l~1tX28QgEMDqKl5&#tViL9W&Zmn;W%fD^geuafiexg;D%nar|3VGPYivoMD5zEHx(uF-NY+G7D-ykD< z1Nfns7GfjUdYdubjE!9Dy^-h}NjQ96O6XEz8yn{S-d|X^JKshXyG@ zwHFPE7NUd*Z*Q(N7wQaG!iD!mDv<)MmC{O}#V9cXic{i*lI@gsLR;D^?FH0P=_s_U zv(i}@vo1;(p`Dp(rYG;;V0Ey7hFK4*P4Q2(JnK9Gjj$de^lzl~Na5{ctj7p%7^ffi z0e{2C`j3S-OhMLDknrSmWIdhZUBesdD7|J0-Mor)SCKuFrClq(_+9#UMmSua+MvX4 zP}*}1vq=fuBxvD?J*aPV@X# zyN(nz@44Lg6!>?)8n$1J5+; zj(^0yKjI*ctFW#LyKwvndp^QO?(96l^`GDXj-O-y=i*}O1@?V`gE)Pnq?;(Ya6DPk zO&0MS$#afmA$;ge@ zbxC(!a^bjI@~oDO%yz;~fb_v#sR_sTB;R{d5XX-t-DAmx<09F!NH#LfqSsc)o-0IL zBKwxeL7e`DtouTC;kZn$UnU1|W4cS$?UG$MzN&a$RgB#Ex}ns+p#*SzOYy%YF1Btf zzPFViPQRn*?kFxC|EB1E6Y*2U^QmIw&fFhL{Xdidj$bPNFU7^zYsL4q62$4BQQc?M zh2v>dH%-I~sOJJ|Pn~!$7`r=jfgi=&yCc` zoDbOdrS&({0FKM3Zy8Uqpx1U$-7f0F>EBS@HzGblJ&#Z$b5<>jvHIW90FF<=P-Cfpx7I-D}6u1(7y!td@73sBpUi}2r->ZKu`X;*h)YoS62h=rD z4V|dgMhAV98r&p2=BPIiN>NHF>c#BkH+fz9Oy7Dx6<*RLzKO8Gwh6b}gu8Ly;APEGeUwE3wOYLKdd{ zKy4558zii7-+gC}xg7`O&raSZ5woC}U9w#tKE?A<_xWfbiyJsl;633&_kizUk_vJA zLY%@~xFQ@@Bxa^xi*;*xEc1bh)&ZlvT(>~`J|`VNC*7DYcVO|jV@Gyv`2+~ot*sN; zi@!D7#eZ{ZbqxGmL;BT_fy^!b_TTI7m5lo40<7Sc64O!=%qp@3Ir*(4CJ{%h6Qc;% zk)(AbnbE(!e!qL8uYa*5Jb6vv!%BVG(yjsxZ+||jZ%^o>A>PoLwaBtB8Mgx^^QC?{ zYE{l}u~)eMv9i(5!Uk`nxdN}C5N5$G(OiKKQ3&^jr{losID~t{B{;AIhw!1?iCgT% zk&MGF(OiMENC@-$EgcP9M?zRffO|;b0TRO3>{m(PRT9Eh7?u$XtRW$61ohfus(VcB znEQUXXvVr-pIR@6fp|lb-;f?`AdWZ}4xGB`VvD!Yv3;-NLEJDu#2F894&yCLbZq); zX$Uuj7p3%z(hzRws-*r^QZ_eSOXYq`a;r z{d_ubJ{`st^H;R@S2Tkw*28qbVLFs4Mka8;+}VEFf(*R-k|L9VqiLtgtG`)nk)icc zzx7fUbKP0L;rXVp*lx0KrTP6kjzTrE>$79!?Ty-y_EpTUIe4?NxD@nUb(v44Y6^W_hpZz*MY+t{p zQAOEstL+VTd?QBIER!6UiIFuIWygzRWXhkiRP0I-cc`D969vF?{N8!z>3T*CfYl(g%!**kr>bj5m!J?jOGU zkR_XhlRmrd-){130Wj?q-17?V&n6E-L~#EHIEypwEUE7-DT6cZ1*z`^DTBSw5;D}M zQX0sa_H(({=W;q{+AVU=EpmU(w3n5Bmz7M;w2zg(kChBQ5c6o-JUWQ=1N?c~eFN>s znf4IvcZg;(ragIW`_G3@@A?b|;(HnXt-Y~xYUHVBxlVzWTNA;!vNoNac=LNSKWPChULT-(4^RX4F*vw- zLVVW}BRj-Ddp<2;(8j#Xf55@#5`X_~UaVuqKX~N4y6xa^WBhMJJ0Bt4BV^BdcA>?d zont4gIR;GMI=;1VI$22K3&lY4&x!eSlEgG4(}=(_@y2*zQ|jG!O&QCu<8~-^SE6^N zdTh$A-+$he6}-4BWJu8ugJfu5IqFu9(wHsye$mVL+0)S~XkTc2s9-YoNpbt6WWIs2 zUuw0VCla}I@a2N`OQv6h`mPYu6%xWCIxj!IUGVuL1|N`ASISj&|Smu^iOxmy-5NU0Ca`hCdE-&FWxbINFh>vKXGL{W|7OIoINA z__-2wsYJcmq+A^`qpV~@k>%Q?9k#1o1z+5<1U{K& zxP;u9WhZb2-f$nevk`#{Mc6PEyEDrU7qGBlC3a_)oxms44CUCJS#|;+tTLRy?re9T zz!iAIFW8-_ECQcQGrZ=P4heiR%}~TI9TK<#Z`dNaGdo4#lWB&dk~^DG0=uUTu1Y>k zrNM|Koe~rG3+DmOpYK%niwt1OB+_wS#O0!Lf9;EPuyQ#A@^f?#oZ{T?Edh$9|~-^F@}k{+UDM!)@RLuAFkyjr9SwdNC+--zyS33_oVN2G@+o|^Jo)EU??J6LHw?ROj-kt*T_VyN# zkGGG28hJMoP!sPa0t)aB5Ky3Zpn!tCg9Q}o9V(y}-Yo>w(z~UAqP?R9)Y`kXfMUI4 z1=QBNt$-4}69v@4yMus|y^{r$>YXZ}KAwGqgNJ^e{RGtCv%i2cyfcL7vb?hdG_=9c z+7EF+fLnuH0e#ruLje^uC=k%-2BQV^QNxdFZ(u-xTf+$gf)BTThJ>>4;nry)E<`fy zcQHw{T;`U+LE*Rv$&jv;<5kE9oG-?_a5)DbbvB83C#nz9!bAf;#DGljbrunuck+zjaG4qT zz}H$heGdxVgTgpIfan2KN5p<0eHOj^Gj&GnkaBZ36o2U+C@!+@`1%Q=fCJQc0qcHfyg@_a2E8ra8MLzJ! z3lWFHSHU@ch>Tz*Mcm>c|CA&F6PgHClG7idI`r(+{r+Z1t&>HO1{1nzVu!nI9K zpMmQ@N*<19;yPf;IG&B`z(F*}b8sCnZ5$WkfI@8IzH}iDgRggpI05z~IWEFJ@HGz+ zhr%8u$0gWUg8lwiW%nK&Re6R1JbTV}&dJxL)nl5_vaAc|u$YA`n?w(ZtV1EDLQ)wh zOlNe|84)DfAaa|bLrZl834%zOq9PM(yr2Yi6tF}POhp*H#T(wBrmeLCRW2GtDk}6j z?R-4%zs~H8`OTLBgk-b(z0do;()Ar&wTWhXtGUCvoaYZ(8Ua)KAxmRB2>pnqapy^| zvoyAa&`()aSi@vqvnYhb>o6Bux(T^)dXp7mPPBA{968-(d0m#4uEAO-=`mf_rP7nT ztY6VvtWR`d2xHR!utL-qr6Yth=>wKVy^%g- z=|j?ASV`0$&2sWZ?=`XD`>XFhl2y@aWtt{%3(glP&=~GsSdZl!PuqS=1tx>V z5GJMDZH;;;{U=)^TuMJ+Yt%>SPCM+hGkovbY1g8cSGo~_U-}6!P-=RUt=2?7xR_~i;wK#=<<;s-OY^__<3lD==$OL zPCMFZ*U@|ILCDWY58oqyy_al_E+L-3V(V9=U$r&5hIsz2okV@vygO8Qw}?lc{;RD~ zZ>D=~jW92L&`zTM%)5Ytb`IfQ`cr!V>e14}5%#5z*dglE(h@x$E~U}WPp?!OGa%^uR23>zyi2)H)#2Vtx(RbI=ysLF zJ(zSn7lVF4g}4`!jxZ;K#&s<^ugs0DLY1fz6)~Q#Q}ye(dN@9BMn#P0k1CCOHhR6% zn7cuDDvf(Ldb6s+3Lf4KZB}&{C@tNzS^a|EqLLUeEuGt<^7K{}V&JrNv=zg-p1Gpc z+CC0VB5HDl!u&;Oz{23XTOmEI}+qS6>>&GQ~r z)x$X*3Zo|KFl~Z&Up=Y`!^P+~RT9%Dq%n;mPw!PBrcp>o7(Pa$qaU}x<_Z|ES5+lO zh46fzs^7=e&hdFOMuqTvztWg)L4T+;hMCd5N@LmueNa^$RKt09cTm+~0fuxF=Ht?z zsw5U-NXPSX=_4w{f(+>h^K6bpPG!|~qCzQrK zUivGgv4DfV71P+9l({QX2>iyGUwV-fVr{*2gbXl!hm*O(xqx2glwhqreWz1`j4-{z zDZ!e1dX=M*8K&1dN#u2S7rNHLT*N$mzmr6MM;aG?;=IENk>}xghZCV$f_~J|$oJ6e z9lc(9laof?hj*`=oEkJ!(9b#=`5$_lqtRSJ?{YF|Na9`XE~gr!=cF6ZiAwKrvKU1t zT|j3l{fd)8Lz8qhM%76-pmUY(aYBr)laA2IO26aOq9KZY*U{K^NWbT3jJl&ga5Oq! z>3xpI=sWsjC-X7q=qSWXs*x};cZRVWF!q@~;3Sbak_sm#)V6cig?^kz4ME@J6wWa6b8kSL|MxWmw8EIk65dFgRToYGs}5E**u2nkfW+igM& zihjZMkVvI>x*jt3G^PNcrQ7s#W0;{^i7scJzv@<^%b9-7)yU}6ue%xvSNaWCBePHM zbCbwFnsPpV-nwyf8U3M~MjleS2F+&l-`ykzY z(VRwq=4#|A=@V`ec}i2-$FM~gk39V!H;sIybPbx>=x^LC@|MyCG`G>G-4OXp=?Kkk z^kPpVk4Z1_^b+YdPa~hn^Hp9F`Aids!1`Pdk37BFOCzr-U4v#h`d%-K{HAmP&2#ix zFGQYGIzlrY-Qj8EJL!i!jpjP~VNWCPNk8Ewk@sZn@CgrdhV%4OUK;sN=^8ZS(VM&w zc~I#H&3W{*o<=^D-sWjE>(S478hKHAx0gg-)Wk(pZnuX=o_@(oBR?u#gXTW^RWC%I zR60VlAN`i6kuRn9dK%4t^gEtL-qiTW+~>AD{+kOv8ie%|e%aZaJKB%@enS2I{z54~ zB{a|(>fJek4@y*9#T=g3u^`l+YM|j8LQBC^Xg| zE7a^a3yt^33r+MV3QhJW3r+K<3AOkwLak-3XS)$Fl%s5>(Co6=Li5Vz3C%B?FSMY1 z!P!DsX>MWpLZQWpvc(DUxowHEHu}hp5tqKK*TsROHR_5rYKnOec;utcTK?5^B!z=^ zH`DH3XnuGdRb?;F-Mwcgs+qX5z1ONWx1jNm-=Q76#f?3(L&ipN<=SCQG@pO;_O7GL z_q~@uVK`pt{r_djMc5<~uk@zkIX*^5*KL_};<~Sr-y;%ptZ356^6I$<@c*&IZCJwa z?6LPhORb%L&Ko$m+nRE>^=tFz`ux_fF8=+t33G68AaTWk#1wPQ{`ro!=Vx8=#?Nu^ zm_79|dxp7B>bqtCg8Ta4lKWpS?Ya-FR&((f=hALGX3a4dd5C-3)0f*fn~Sn|l-2aT z_RZ$vCeEc@|A{@*T&%>SrlziOW|$ZL*o)v?_q5Y$Ubx4jqFUZ}XPF-qh=01%kGnUU zC*soFO7Di1-fZ(k7w6Kh-QeA5o@g*^$ZL7gn`OSy``+BXcl+p@;HR8a^pLH;yKKmzeZj;!0C2IPvn^qZdDT{yjLrl>x>+nOg%>-NP?k zURgepiJ;Yq0jm?k%`bdv;)JWl7nXg9Pdj6!&R7BeaoXKfyBnA<^i%iy6b&Ct{LIwx;zr8MBZ+DnMZXP+3K~VeC+Tmhb?Ktw zb@4cew!|;n64#hNa~v|Au-?7OykJ3|-fimSs-kaK_dLDw@sCp9hq;CVvx2hSH;Fl50+{P$ltWT6mh--{FCb5Z+lqfe(wE<3tx=2Cn`qsZIM zI&Qo!@kcKt%1oX1^zaoAe>rvLXnZ1W=R573c>;@9JT`8$FE>72v*3p9E1r29UzjK} zcgY@jl$Ez3fI4E0KV#svmtc-bqGVU%JY!Q)#qW@=OpE^2p2UEj#8C4+c;@_y&J`Cf zosMs<*VNUosq4+nRneU5XH1Eo?dQ&!I=6uTCUU8h!56Cz{q_YlEIYKSXsG#7P*haK z53~Gm7(bkP)3g~mu>Y{Z3CmWF>lN#YK@|fl(iO>yuwp<(s^a_~l$4g8ckU1UbAI&G MewiN!1{)22z&s!5xq%@ZhUP_%t1P{0RSUN@WS5y%P>p9n5FS`p=v3z92Y z?T;w>8+z+8w;b~$@*jHbsn^a*i4)faoH`|T#o@Q}9?ocx?(FQJC8Vv={Q{ymO$fP+ zZ-`#MJcC5NC{nFpLf!&H_))(P1}5XuZM8&hXZ_& ze4ji$3h(ai4wLRteE49Hw6@>Ix09XLYnjN$s57W*rPkODbPQn+$Y42guu4M>K+1M4pa{p5%fK8qMF_c0A6IsR;O!zdg z;N|@2UD%itW8u|Qc;MPb@S~btTWKln zsGU6omck3nKX^n-H`h*u*Kv$z52~_C*hm#f6A-Da2O-BIGe9NQ1feN11Fg$ub7UEX znT=wfI%{Tx>M#ot3PL>uS9u9kX}@_W{-$(xq;qB`x?rWL@*EV~b5+|Fr9sEKz~WeY z#nIC^V>4N(Lx42G=FI4fEvWU4=2~-&phs#mx7F(E`nTke!GBBm@f?`$5HZX1YCvA_ zBIMzq2FDsWBJQVw7s84h{7Kbd%;?AoeL!J!;e^6olv=${1{MlJ!G%)VzLzGKx%gid zyi0r4Jav%*_=%RlOYbIHf#=wh&AQQ*VkC4?c#RQ z=$s*Sqt~jX(O@GPX#?LecKjX6Ds9xOxo{9QdZ3lzIau%_I$sZ=fAZj6Wv}DFPAr`b z5Sn8Q;+<{(FDWBoR%Ewuu>bz-m;ATqOB>6}ck4Ni>;B4xm1~65e*?HYjKX3!qTbPZ zxQhF!`#1l(^XIRB{QP3+9=TV4Su7k1<{KoheSK$X`PAt%XV0BqX?)fAvT?KVdE<8D ai^lcFjSC-q_{o*a7eBuA(bZd@e)cy@#5&dh literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/rws_service_provider_ros.hpp.11A527BD4315BF59.idx b/.cache/clangd/index/rws_service_provider_ros.hpp.11A527BD4315BF59.idx new file mode 100644 index 0000000000000000000000000000000000000000..149975ab03367ea443a145c77b3cb84cc20dc2bb GIT binary patch literal 13240 zcmd5j33yXg);X`s3nf4RE!)G#zI3Mxr5jz+q-h({onmWA(=;t9NmG-wP>LW3Qb4wk zrEIbYh`?Ye!nA;hg1{&O!!|1G03zxPpn}NYApdzyPhN0lzW<;3{}29rK<+vB+;i?d z_pG-iJ5{CH5hjr+N>e9Vj1Il0L?V&nU%SI*^6!EJ;gg-8lVh~im<+~Do3+MNYP4l% zr^}GeV6_=_b|*u-PEuwv8>54RgU4Ad#^7?>q!PU` zc!Je7-d?3Q7=r~VrN$cF1bc8vwaHxCim>UcOr<)zMW-( z<8(Hoz1r-+ilOx1tkq1FSl*b;ttGqJRDzvFu&L5ut}b=<0BtCt;b<*`bQZl~92SH+ z6P6~nGHexs#{JI=c)QKu>~Dg_;lCFs|3gu2{gJM!t>e;R;q-qe zSlCpnDxF=}lTxs8a%s|9?{VH^al5& z+=_B@E=g6D&S6CpG*wEljci-q)}pjxuuX6S#XeIf%({UFH2D&}Vf=5<_UaOyMDS?$ zwy+iPq#6VgQ4IoQv7!d;I%`>3D>;Fct&p3J1X?H9sv{8;bR0y=UcanV{4V57S{mdK^qZH zw9&ZrOQ=V8$ffWnu&w&8G1^RJwK~16yxM}@PHTlyskayEsD(wEx4jZ~~oiqRH;~=ToLilf$Gpn&SR| zNcg=Fuot4+z9drNfeAnD2CnU~=*o{4IivEB^x4XCTiF5pGGLcMCl^hJ#a$N-4jhvx zXVQ>nK5+A47$3n#a4rhpw`PsfANbRGIg^1Di>2IRX(+!5*iF#eMbq7{zGKa%U(Wk7 zfHXecd;<7TCbXMtzW?kU;QO#*q@2;<{MRh^H5<;a0d@`WE*k%{7rwGDx>qb`1|ZEr zFYcgM06z`bX&~|$@yq%1-*(^HOU}e2%{$)QJKlc$9AM|b^DaJ#?Jc)9SCn~nWQL(; zK7havAg1lhMWfzzrSi<_l#LykM5NgV0sCM?+m}dlX=By?)wkBmnLLzrN6OuihV#3D z-R-t#&1}h~pD#0GiV;9Wel>Txi4k?a#a>qOacpGaIH8c8V zlO66Ke;{WPkm6TQ?pIHLej+6C$2u2274 zgq%?z&0TNqF5c2YU>CaGQgQ#z@sGa^Ss`ZzBF$Rh)}C%2mNSt^ zbH;-^gEwSg4I-C`2j)%S>a+XFnK4N5sg(Ov8p}5V+X#bQTft&EM>T*OaQND)#4q!^6RA6&&oG^!ZN@}_z>@qUakK~ z+By9dcz9KJvswRc>{23?>mp}{Bh7vfZokJ+zL+f* zxvbf={BqHA>1dNfk>U|>k5G=1Rf-gE=M-O)_~hUXCLzV=-rVQj{`@>(=efz*dhEcE zfst<>mopJav)O~&>=DQpu|?u7Z@<&H?5$OAnB>d|q`2Y1-N2ocv1Ov1Ms0~lyY1GQ za%PA?0o)Dn5(m$Gr`E^4#VAH0{MJ4Up(=V!7Xd~OOH$BOe|8&^yX%I2lBIk zods?*_ewk5p49%LoC!jjFBt9%W)Ppt=8AT3Oj-By<*QyAIg^YO3s`Oe`r%?=7rXi4 znO$SXGw-WU$(b0WY4YTnJcsgD)+*}u%)Wy`2l|ZmkuzCHu|~?Rkp}Xcf!*x3moF=3 z?_9Ta<;0Fm7@oQXv@KBF_T@VDg%hi8pSbWdD`!R`pBtXs4UA9KY_(|nSB70bv}y95 z?Q$j?Dc+HC???mqEx>MZ+wb+$XL=1xU4K^2_#@4BhTD!Fl+LD$T)ujgntkb=hoN#N z94W4PaaS=%%m8+V8<%g5yQg1~9o!{nv`AAgCQ-q+*4ei?UHBI=W9gA7o za%DOr^egkOvLAaQ zbzEdzJO!8z7dxIi74XVxM9&1(Owf|WVYLdL87R1pNp=b9gG zSuNpk^&H5W0|k`1yKL;UdHjPFjktOm#7=`WO8YW?It-r<$pm*f*3z>4_+Ppp2UEOB zMLtf|2p+;&gU~Uk1i=ZR^dNN4$bG(+x36FBF5`0pbCZs=IhKsi8=My_LiyqOspPsc zeoW99g$NZ4D^O9Qm+^)Eg$W{L7-mpWijnc9{-p^bR2EXEr0^!=%l*pZMW`;QPC)@j z#!ntHIZlM81Wrk!L?Gj*4xSn-Lh~SW9;8s{mGSc-U_K;@@In~25LA?aW&9%WUjzvv zycoh3gPMYej9&tQOCU*vmx2E>NFei*@eMGr0is2C1%$4E6iP8NekBB~ghYaSMtya@ zQ~Tq7c)6xwrZ~DY8DHUF5lK+5Jmu`H++KrQ4J&gdyhw({d82beCjz9CroNn7HxCrHzy~YKJs-YqBFD^qbVBDD&+61O^JU1yQ9`{ z`_t`6UlmyuPq8;(!kga@`cqUnqRnb^78NxChciBYyK#3sqNjsuI%tV+pr5p9<3-P9 zIH8HtC@Ca{jF&bKdN5(Xi8)k4MwV84p4*Xm9nn>ZRcUk*@?bordEkJ%0iD&1vR4JI~1Diw+{tTDMJ7(nHx3^ND!9t@zQ zBEv2LE3+Z$wgy6ZbQSyIz2v*7h|ocyeiW!wR|-ZpyfjHLu!^XPM6x?-O;A71zJ&Bc z>`?#CE`%m18sUV{dJvknk7#GV;hOlUFi<-CkEc*@wlZ5w)}!6$X#R8EXa0z;R#c~v zpJf!xS({QfvIkn8HbR?Cet=#PoS`8oqqM`vyXsT7;#yUtDxR_cvBoV3?F?;zd==3` z4@2mjcFO%0qkMi>)RQ_?OL`K_A$&DNyPJdm8W<*;!y0&T4d_I8Jp`?XaCh?v+yG&s zd2E3E4NxS)n_%cB2o}v{6Xb1zLJ{5!5t|{#-F(8gK(xF0By9t=yZHoehcME=U{3kl zp-6-qA*>OiM009{qDC-?a1)GZf|2g#HR3%O>26-JyCI3}A*bfb{A+WMR-o>qlu;UT zzg%sX!QU*3^}>7G3+!I#K*fd(?TXz89mvpf4`!?w{9V9tT%Qn?kVr)hMFYGfp^cC6yshwRZ(O0}M z?X84AopT_4k~%4iIvjKM=QAIVKVE|9xsWs$(kSG<>>uUWwkY!Z$umYdW|Uau6ebm>Q6RxWCaE+{ zEM&?P%TvYDWpe!F6tP&DI&!K?EKlZxVm_pc<;WsPS_ElyRYJLuyaY62xzPZz4UjCB z7b`)r64I%haQy!6cXOH>?0D>HpqU0alq73r-931+V2w9U)GBMWWU3RolwQ-Ej2H5s zQl-qGC`1RrYY-ZLx&-n!L_52EnyC9|UXX%27>8`s3UwN#QF;Tw!0dbgAo|HmZzOc> zu!BK*Yn(NiENk+mwY%PwM~+8ytSUBx>gre0?wl^F9dr)Sszg;9ZIYzmZiF`j;!WR- zPwP{`)}0H=H|&8>jF4_MF6kfF3U39pW_spP{o|i{TTs$;$ea!@lKN(8BmKYJ_M;Fn z=7MG}Y8Y*U$iG zKHG{-s+ikmr$N9%$7*W zPR824PQH84x()eTN;U6x1!7V<5eFC-juFLPb1#zEwYErZ10LU^ZuTQYoo%W6cmLqCI>~w5k!#* z*9z}Ow3eAyDN4S7kc$Vf$Jv#noThK4EvYdUoIrF-6MIKUub=BszX#9V z4AIS?AW9iNyd<~4D0-9GXU%=7zUg)j5~hcxC(@l_ZVlAL5VSw0->@xT92Xj>ddRMa zLNa)Y{C`%$G!2?U{jvj8=F%{9F0ih98)qQy3cK)DuzY0b4#Kehe3gHK#D*bd^(TjMX z*pS#5GHHC8@QaHe=;M{MH?>UjS&eIJV`>$&_V9BJhS%4h9U){obzYWRrpp*JhR%u& zyrwYEEz@aA^C&@Jlb&9lOZJ3qdFteBx;kvc)l;)5(h80DsQECOtX^oeHH#q6J=1BI zK)!pXQ#C+_d!`$;5=K*Op&P-QaJ~f6T^!LJ|NYHboqZ zOe^ZUPFbfB^*tqdO1h};d5}5}GDUqa1ocA55cRzn(iTG&?Nx@)W=YE+Rn+$iNL>M$ zr0?U^$M08m4K6~BD54aJ6e~{j==;Oi4SR$FOq;7Mq*!=n#NOuGS2i3)HJOK*YH3?6wq$KJZ5bbS_tQrZ^hH?gZuK8t64Hb|QXfy~FUM*tXPz4IE~1m-lT>sna#*wq=j$zPfo>T0 zCcM=W`qE+J?|vF{G!nO94Y9`1!SFS}uPTC|%T2%A^TvY-T~Stie7uU1B{fCJ()qYc zOt0KHmw)2sDZ!9ufMy2dP~y1S$@H$Z-QNZXXGzqj(OIsQJh;T~_H4o+6fq(~L2s8r zKn!SxNHHMphi?0!9~EcU?r)7fh`;oQd!HCOF`hyL28w{%D1s<3;wFXHW!fU`2+__b zWtzCT!fWfSJ~uky7Bj|V=*cX;k$>`5_($Htd(}EfUI#f8|EaS?M$UIB}J3-FvfFKp}ZAb;77$=bJt0_uj@oB;An81qV>ZDU+#eq6xlA?HE1i%;L{AgqEWSgPYd{x<2-z`^Ycv~A6|rPi{pxu$wYq%X(xM4y2*s==Rouv zP*GSF%IfgBkU%gw2g(!NURZq@vbCq!GpQ7@8O{367`5p+R6_I;{DmTW zIpCBxMRtkgIdRxQ9QG53oy6hu;;^GQ#9t<$&kHn=NPNX%UvVh>D5LGul?D1}MMu)zqNF?I$f4jqGnl%sy{3jzfGt+3RHW`d*Hfy!1*l5d0 z%@pa2igdObyUt)X87+>+g#vWKyWil6cA#D0eQ?broq0<)^n=HBtd#OFpX0@A&&AL*f z#c0zztTvsYvhqJNgLhj6R#S3sm@@nsL)%A|La?_7Fiwtlg$b|ys6q}+Z{%a*ot!B3woaMUJ9?~@^)7y$`^w=txu=uc*@Xdh9VlY<~JDY-EAPe2d zuZv~>N20r18eL^~lcd91=Yfq_D;<2B5?HD?>kST*!F3*+!OV9n&aVfiRM~AVF2lHx zc>FIgD$r@yu72g0nW~KjY=cBUZ!WqJ4+P&Xj4LE|K|-K%1Nrdb20jRNZ;6-Yob1f3 zPJV-XhU-GPS*obAQs=PhD)c6c2z#>b>D~2y7Y1u?H&AHWbUf7!H0aIdBE6yfXJ~s> zkxsDHPX zqAP54%@H~cCn#iU5q7>p|BPLM&3U#NR&*6?-3hL=+Kp}?3Nz|)KV9^$?c&&4$*aXR zz#gNU2?^aiZp{bk(H(Lr`~hs2zN?KkQ^{njG~_toO*Lwi>^}d zDEki_4!ynn-$>5(z=f{j?Fb_eA?U*J{<_5y#zF|Ec(fx6mY@$JdF50Zi(N>3>%hKG z&xbnHQSoddxZWWiutxj8k@*wojI&I3$1jsi7L&uIH=AlvCa(__D-tmW{(Sr|cPqZ? z&-Cmel5~P!Crs}C67}I9Yw*)|T`7)1{!M$!aq6AW;1c&-|}VuJtEGLBIb zM;IIC?V@{aUYMdk@~4X&lS1@1VB27%i({zIqW;xee!S?#0C5B}!9!g1F%7%G>)wo5 zj?oZ(1F#$52^WX&`AeVLSKOY?F;5c5Twv#dutwyM7cYJ}bo&U7i6M>#U>o3Z*BY{Z z6*qr7qoiklCJ?o882k@|wEN4&quzVfa_($GTYn}Fc@BWz0f_AW5_m4RRUTe{a}&p8 zlBB)B?seO3a)apd4_BCJ91}nsd2F7rlN9e>3zl8ovz%kHiM|8a9WdG@BV8jOUNr9W zn;hdy9BFKtmq33edfD^dN?(qV5`88+Q_x1vjoo&*bMh|7#1g%Rtr6xIJiDhoV_XBn zF+oJ1#7+`!tT3_EIOdHLD>x>L=-Ywa4&z)qnC77n|JC2plVh~R(E@CX+l}ay{#UO* z_xEs)krBr-V3)bw$n-G-i!z?%m>i|0HxQ+UM)-E{Dz5EW# z03(tF_6{7;^^d5p(+5EUb9Fa5^zG429HXKY>e>2%E(uMOng^OkO^@c7u|$`$(#Kr% zwK2VNLtZ_n8WYx5UHTS;cmQy-$}jhty{{CW<&LtVPh|xr0Xoj*QCj;FwgRZv}R%+a5le(XeOZ z_I0!RGr@S$4$yYM^zJX$NiUshxpnH&4=l$-(<%Hek28 z?eqHCb0fwjZaU8~PZ5WP)d(wm`cq=YpLpjJl$It-Q&U2qWQ>dQNtl-OJn^Y{Z^^gA zkvlpfI*!7H=g0joobjt)kLc$?^*m@v;{!%WkDWW^a~`*#2vSJN`Na~Yk20JfZi)Hc zE9*txIJ*JT8z7%@?4Y($zb(JJb|=oB3(<2yL+M#8nFo{Rfr8*c@9p2;eDW`YaD}qC zG8K6+RSb9tXQe>Lph5u&e1Smd;SmSDDz;v~GE^+d^v{ex-t9nQN!Em{XaULz%Sj~n z6iadga^(V)7o4Y}v@Dk7`{qv(prYU+6(tI>#Nca~B0$Ce|<=tDAvi#)z%SZ^61WuqE z9F@}2V)vgJfat22DkX)M(H|weauj&=2Ksst~q=B^E53-=^1O?lq3*>Wx9>cln1a%sPgW%?< zbC%yNdIr%8LA?;tD9?m%Dv22%IAksoYBV*ORQN>{SM|KGEA2X>tum{IPC_1xCwErI zbn>{<_ugRSmifpZ6&IC2mD!Yxs(#aV@7##!smiIz6!WN*#+c`Ab_k%tRV>*7(j6eDQd=x(2U$BLQo$#d>;msyFqTS4v1AW; z?}4$DPQ;SEFlsMMRCgEq$`dW@8@CnTp(29E2m4T&w;;3u z@>N9hod=;a`zjAt7`Yb*qn^~kTGA754q+`Y+1(s`H$bpp4jUkE1Ly>JBLr-OFn9Ct z-wdIGd2EK<%}^-7ZSYhZ1PbQT2H9;;Ai!H8d@D%Z%_nRdOm;V)`0b!}Hy{5U5K8*z z%_(;W6bf)VgtkMJU{38&*bW8(-UX4nAlBWyBKJV7yLmTf$aoODmKJuSL^}sBty$On!0wvSAHjPeq2SESuTLYzDECu;eND|7C5YV0%2`@6)tW)Y*OE`i z@%c}oQlwH8qJ!Wy@C`g&0{I)FoqanI>fT%$Aoo5RgUcky6Eu`Yshh{Z>}=(U|Cy%G zrVRGn#UQ^W#-bq0dggNL-VIztIijU1X)4v#^_s8G7S0}j0ntjCQbU_0DYzTH|EIO- zoAKys`?v2|R{C-$gkXept8q#HIG6AIY0h(LC-nEfA6bEt=0Vy#$RqVF)JFJz^y;^K z#8?c;iy@ortl`A$-J0ysASCEix>V}>7r)kfhUwh>D~MhI+69nJ1;mS<%=%{ECD+gZ z=R@>-&`>GI_Y9Ms2L-{)v_q=T-tptNk}ge`lb0>O6dmyS?~^8WMU63?;Nu=O#vA}2 ziW;OmJR$#fK__fF(?^>-@23`=FAJ8%kROR9@xJj91g+`)Ba0*F}v$+UaE z9Ew;7DuSDR57p1PU0Z;gj8(^`lLL`8qHO282uUaPAc21laiRA&-d_Jg-DQ+FGjyhm zlATy$^S4O}YMFg{&ytpavnb1v?8v5MyJ7#D(+6KYT8(H;vL>6NBN+)w;vZH>Qmdpb zd)+G^y@lM;7^#Akv{CI@9M(E^F`{S6XKF~~#!E7WS(1YXMT9|)Y!)nJs+~?!!){K@_F2%^KFMV`O4<` za@CzM1FB{t5JZs) z=kjktG?%U)(fm^op?CYwlNWt+HwzD7i?Jz5IlI4@_foYn{}iID5~|YZKK2|Mcq37} zHwn=uxha`yH2TK1`DY|rn<@@OJ7158K;aSz{G$<}>CFfuiu1vU2nQnjT)*JCs1wh< z4<_#eIdO{dp+(UFDf9+&(3&-M(e7KB$fya`$mmWnxB4eZ2|6r&GWeAbPx1}aLdaMM z1!V9P{c&6TI}}Mj((C#6ul1a~q=#5CDSnccGCnUmyaQw;Ta5MlsKek#1^tn^9)2}X z4B3TZ%u!|;CBY+2btjJP-}Nk_gZ+ZTsj7S9(yiR_?VpAqx<*!`rVxGj^!B=jE&JzrtjD>tq_gBS_t;}=3=1}$kK{9*IxF2R)1~G0%vME7elb%$PMfQYkd174#T^%;!>N)8YY5B%GWhvy4)$@&Z@^Z*_&ve>V zkn5i5RI4G?J=3MEg&c}4bR&2Z&KEzri{rYJ`)(X;;(NEk#KH{n6FM96^Y4GeeIl>$ z*6i$8zeaCZ z|0*d#bOw~=d`l#0?~mDk>)KOyR-nE!6`4u2C$S_aDJMhFcb+;gRnT{lx+qo9w=uz} z74%)JtW6g5U9YH567<~&iH(pZ=zAHcmqDta@0Flg3F)*~F+Q8cH$kGH?`BABhBVUm z$*PlgEQ13JQ6uqD@iK}Pr-qIG+q9QE`2s8@E2V&9;kn2I9kc6SK7nc~4=#@(%SJo* zHAfIcX&=?ZKd6$DsB1v9^Bt84=l6%sSa+qQ7s`s3MQg~mFTC`ls&Nr)LRq>Xos@En zSTfybdN@HJhDN`x{=-y0O-zrN9!KbprfDrNoQZ5lv@A}hqEnH>qE$FwYiSE~!?-v8 zb(YYVj~RD-|MZCn+=3;@BBg`jYk-e6oS-YacXT%1tr?86V&h^}lq{(!!X=##y0qxk z&o1Pix^ad#$#NTcjN!+WC}B zgd1ynZC^O*vjMn8?bBL4nZ*~}JDbDa?9IPdwSuA*GAaI3XNe0rUz};7ubzDK*2kBA zvf_+LZDcNGu$zY`$=~U_g||kt+?-4n^|dHt^5a4F&k?-jKiV|Oc@RyP6N(P)p zLPByvHs$7T=H7{#b0F1*=y-X2GF|^ShZp|7GWxU<(Nnckb18&;`|QQqwZotF=e;*2 zGsn$)vvLaEyf-~B-_3i|i}KyPH_e#m=Dph5TsQAcsn2ou-i$^laQEKyWsvXgy_qXv zs=N0lH9?lU_hvLh0eLTV!l+;8dp+s*cH1A~KkLKs4xorpD5z|r3qyYX^`5xzO?vO< zapfPY(N^|>$3E~9jH&}XI>3t@=iY{akMDl_*a}=$7o$^~M4~5zA^&5J?#~b!h(sfWVIN^QSQw5Lh9iVwFJVZ3 k41yT`4@9~@-ZT)21_{G{!f?1S^bm%_gkfJ{C>DnQ0!v2UNdN!< literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/rws_state_publisher_ros.cpp.1AEA19B09DBBB081.idx b/.cache/clangd/index/rws_state_publisher_ros.cpp.1AEA19B09DBBB081.idx new file mode 100644 index 0000000000000000000000000000000000000000..e220525d5e8b78a117848e2bb62a93ce5bcedaea GIT binary patch literal 6158 zcmcgw30PBC7Jgt@n?T4$NWvBZ_<+X~WRb{XBw-OkAc+D4H4VuFqFFEt2smxEwPLku zTWuZJ>eSYbwzaEW-0GBCT9+1EwXL02>r$;+vDPkHofGB0VA}aQ)0uDhG`#b_bN_SB zJ@=k-g0`}(ELezPrRK_+Hp*>eU>L@R|1P)FA`XEE?+-zkot93@N!T1_s;DhJ9V3(z zH5#4Xps21k)MyOVl@ooCUZbuoH7FZv0IsQ`ajmLc)$nUr*QnF0)W62{6np2u233t> zVztU}YjI`GBvq+*4MtRw?G777wmExRj1<}Ba87r17)=yuY-ur=sZK+ei*z|nH$|tz zm3{M}-RLxT8J(2DVs}%{RMVKHb0Cj;fMR?O@Zv&N9SGV15oJlzB)^3cjxVl|#%7zh6%H{AlO%!3aIE!wJ zKhxx}w_4grd#A-lc33@aZIqd8ba+Y~whk*erlv@DyTxfXfT!+mvfE@c-v*ehMtd7+ zwX~48p0ctt$7GJdz$0@}o86P1o|TW?X7IN*{P#6ryIpSB<(t`{+H3}!tIb8{;CBuD zYPqw^Ww06T#x~0NM`<8taO4mA0E@weKe*Uw?68>sn;p1C;IbKvX0yfqUokma9Pa;= z;NQ7kUL9|eAnR_*(BWyZT3qdv(*Rd8(|gZJM~9mPfowBcjc~6_zPAa-1h*PW4VNiB7dOeg2eWhB3c}s!UxXEgv>~6XIx0cA| zSgXZK$w~6}Pv5^2@Nhl(SLMcL?C5|ip4kqu|3B^is~r5l{qVRgR*Tz0x&HS%@Owwi zZLz_@GePxfF`A}BkLaW_9OZ20~4?_)KO52Rfb1SY|HmVlL($_wNP==Dyj)paov!vbfd zeHqlpSP;a-Gh;JTkXa^9CX#7BNs*`+AyuSQkiK`iG~HMv1#!&nd1h=+00XZgsub5= zaXs+d*E<%3mIU27^Nm#*0Zd#Kqsri24=cF)a1|@`fyeaSA8z0SoLZBrMI>QQXLaeW z-kS<=QFsv-!R#T_B!1ijav5_yUnn5(cmq~y0e4C`|T~@LAkViG*aTkMK}r%QdtmPPEyX; z_33l_m$AOR%E>%XH|B}?1ZYbcQZ~}&^|J4J`pv=T04@tJi$JhImDhXU=Ie*3DJhw1+BGP8!d4+i+qFBg6OF)BCMXlrOxHt|t^raCX_FGt5(Gn- z@wr((DK9>6gp{9@pX+;9AS%f4NlKA&gj6G{p{4kU*#+}M_Z|Zek_1UfXi5ChoF^JC z4c-{uaReuPdWc+ma>=Q{+YF=s#0>%io#5olPmk>zTK9}!JSor2ima}BDhGU$MoH;SL1qKOZBGSTtVQd^YKCc0|<)h_9-zUpfJ!+60Am)*OUmY$E_cKYV zp8jIz&oyHLnYb`e$VDdsoDXcK?`;+)e>tZv?1JCg?9bn4>@dnGfYajBGSfCK7Pd@T zbZMMY_UBpmA8iJ|^7Habkzew-q4%Z-8;9ULdT$Ma8F;E9l~w|2a%w$#H(|}H$;*DM zngL7|{EB1*D=L;^!G=Bge(p>pE}!3Uwe~?jxOCk2tG24#zd@ z9l)#tRuKxkBJro#z5OK@A(>H0Q6z#PAquG)t!3ir{B(N5>lU3(N*BG}08AR0CU?Vk z*v6v!d(P>?RNHM7dy&^b6U&I0^Z}DL4i2on2C#y!NI;a6pRZlb{bnNta6UJmhNl>p zHEv$_ncOd?#w`I6FIkUYf~<)dVgcfYLl$V@AIp;9Aq!6Y9V(d5k<2ou)hWH!=@?nKv5XT1hS4bc}6S@7XID zIZT2oqiG&HtKfn;)Q`J;!xqu|>N`V$WMn$&A2knFXM|#dPwK_PiF)%@N{lEZ~4z>a%YuUw=nPwUIu^r zs=hh$ZtMjHPDB&J0^QVgn!(Fs8F+!PAjWE}$f%q>u#@Y_?y z-PODOCorCyol9TsNBa&Q_{$@EfAPZHT)G4=9h&jO@#$ZT1(+AXi$aZH*|D@;6Lvg# zcG%Uo7Mz{G=WD~WE1!8|HN|zW@{3?i*}~G|!L^?ONiDNhfZ|;{6nf`tAN82wNbxdw z<%k=kI-b=h@i}|~N$bl>BQjQe$@Md^;Y6#(xXb+x7^thPt3w8!dabvE{Ojhoyw2Nr zPDJwj+zb6Hk3`M|5*4A!Mq}BQg#lS(2anl6o6INaj{PEeVALbx`tidi(e-?({)M3W zPGzB2TS(Hi=ar?q1^q9Vd^N0{+WS;==Bo?Wyqfpo^4<^6RSd&uzqanrx_jG-O-}$x z0Z}jx`TbhivYF3KIDLe{z}aFpj!q)XBvpbYpCqgm-sO`d)sj{uy{>=qe)34}KHyD> zOrdYy_8W!S=dxA|4SRviq2362U|}qJ=m81lXY`VZCj=$XOgn?_-+P=PUjTPSQY@K- z>@xAHgsKcQ{_b4XyQlxPE%$&ItP)lQQrh{%gyq3&6So3fC@2&mFLovG>}Xk~JPQ@9 zA+dq(TMWEO+CvyhgU!9tu!@64Sh`xXh)47 zJoCvqfTJR!q$s8Xwkd^U4zs*1N0X-+kJ{M>gNDl1%?@v~A35}XIO*Isic>+tn=##>+H{KZfE6a4ITS^GH-WJXXTs6-Aj z@ibmq9GW)1*wx(nRi(fiT!tirZpz0(7&~RWCvorEKmo_MwlT1ggX|t}`SJ7kR~RpV zlCV@bq7mdo=Sb0agA-Kl(9fR_?Duo-#J9F*j;B7j5KfvvBFOL=5XK4#pCpNt#3SjX zr+sVc+?-%w;&FIFbcauV+_x>e{iiA~9L!_V@KFKl=;WDla84$aC89nJ!!5r)4h^@b z4o!B=SwGDV(Pt8w^!R;-ol_UJ|MU)k>zH-)L~u4KW6r6h4DWQ^z-gen=egp?KiIu* z>-jt2j)t(qkh^e4MFNRW5{iYfK1sro(BD8{k`Ty*$U_DWU&f{AfoGuW>xB)kYQJx}BKAwdxAx0P`zg+R2&g=~oSs*QF3o>@ z_vAZ{09;&HT!mag-?#(AhremxYI#stq$wmSZ&yN=+G!rQQn4`RJuhFW@{}I;~RjZY%vA9ZI zpqyEz)m4|*>Wa%N%hcuS3awIGtf|PcTRL=xPJ`KIrHw|1&d}ZtW~=jOYKzNibm|J_ zj54)uWN~pti8|lC1|y59Hk*Z}TJ2rUdYbC6+2=Xh^#+>KH#h5y^a5RngL2pncSXC+ zF?r;n1K7IXWFq+JccbjI`4Zo6ByXNu$Z0b5Hbg zgU#AvYNf0TOctu$>}qYLja0qOm2b1Oo58(unsT<8>_#2<>+GaD4Hn})fWfS{wo+zO zGd1#*I$53~Pr<-1V@|8pC6lFQV)q#Qr|E8XnaoD7JpUWZOjd^zHsJ0;y49kyI9eUd z_WZO}@8x#bV~gIZZ>8-&mj)66j{Hm?U@^GxGZ)+S?Iz=YlYtQehefA18co*!ipkb& zbN;6UKUQ(>cka!B-FDKtc2~36W3}w-`w?jLSw?R_=pLYILuKwS4T~3qP zx<`VVni`X$r1h$ z;aGrskiyT^^W2wLQ~VANmWW|QU}#{}-46^KeSiDwNX^sz$yacn1X$0(ImyX_-DGe7yHZx8EXUp66+lqVpwY=VlVl0A|#Ryjs0N+_Z{?`o23rXa~T%-EJ; z#P*G25v63QQkU`>K6iaM9+2ldd*PdFiE(T~JyA`#Y`tRfoYQpyzkW*F`B85;z=;)! z)rchU`P7b@Tfa&KI43BFhhXk-*gF^0Ltpr_39b*Ss z|A{SNpedp$l7W})3I4_Aoo0Y@L^)Cfi~S19A3t#CGk`<>=bLsTwZR4yFPB5)qgN7^hxz!!vjBvFJ&fTXBPyPpUcI#Ul!1$cpoVY(fla`aOY z*ft3%$wM%N8J(W$kust)#z>iQndzQ)S;8#BBdLU{F;a!Ff{~(w7iTRG*gps!#Nlyq zXi4;mw2gIF2kwk!9KkW49HBOxef*ryy&C~1K~fu!PJ+aDXaPS`*aMXOBEH7|_zd1_ zo7;Qiiu*4VMsDT`6q^77Q#<}>cN2*pl z(|H({)bs0^tg(s4@J41g*n|$(F&i9z{rM?9!<%04iYMWPMImLS&!vG+l28eg6l8W> z(A_q&^W2mG)_4A+a`mQ3yhfN541Uz&Sz=L1twcu_opl|@fte!6{`Uhd2wuV3!HRr!z?oImyJwS8)5A&_KD&X|Ts z)ce->@4l|O1~4a!lY;^;iv2cn|K7YSu$iH8p%j8)LzI$ow3bcC!evats~$ZcClkI= z2TU5NCcVyYmfx9`2X55_s^7NI+(+F88aR5yq#akXb)bL4_W&!yl`)8N=I<-l@xI(j z1DwgrWZ+r)RrT98eX8(^seZ?};8)D2uEMT~SRx#8!y)t0@eyUip_g)x{%+4KueFWr z|$d)_w5?Mvao7&S+T1P0boI26%C|_3jXUP(C{VNXGUv%Tsd&ich1?!9mFm$!3}{ zizo;w7$a3iR0>e2&YHoZzr1?J1xyXRhKUGvy%N^ams|2{fVqKOX2Q5mo&CBbH$&~- z`c#VhY-I;! zGXtXQ;jffJ&Gk~~OM+&B0a3CDahuqLq^@_eOF~;Ve+g?ZncEr4Yb z88f)L7f4TASVDh*t1GL2fwb?Ru>Y-?=dOJ+n%SY+o0&c@^(6hOhbLL^-Pzr6K7^4% zB{In-$|K8_Xzk*`b8&yV-zOd@-32*vE5Wb_qH<&W-~S~S;M^&>8Ay9+VRz%ID}L@N zQzNQLLh!QnbC1xeil+gtl2@q_ykc?I>KEtVnCrFUkL7hy_RF8l_hk_>o{V4Om@rs+ z|DyX?1i>f5^K7<@DNV<}Wf5cqDOmp$toX~!GS$=1B^<~o|^TOQw9btpiN~`%*1|~Iyio%sCL?@ zNmQP%)c(P@c7ZC}tu3IK-t*d%d+@!l=A9nZR{w1vr#)fG=|5(?{7m;pmx@MVl&`)I zQ-Ar^>K8WxNfwzk75V*o!K#JZr=LH@Vi8;sHwm3YxRaFP4IW8QDVXDt#AV_ZB)y^C zvV=O8egJqALK2wDd;3oIfX2a^&R(v7o0p!5mMTao&i0|;ABOiGTOQJwKIpDdDwSet^e>NnE}1&174u5U`(2wpKDzEV?oLxd zRxo99uzLKofeXhs0UR0}DnT(Fw9Lv*Im&U598HF18X9MR9nclGY_qwC{n$(IMhdt}1eLU&nZE4%3 zFxVM94=+XzvWaAVaum94e7?J}<#aLb4vr8L%upWmXYG>mw#rVaV>O z=5IcWevS19P!i+|#teeAh%^cMZgA!+%L}IxA6fxN3K!#qhe;4AAU%>eL>!Hzv#z$j z#HDF|5D!0$FF?h5_HfTzliR*6b;EvqHUpo)IVWZ=RDc&!fixBkWVpqK*G8dR?71T| z9S>}tYlSf7q@1~DpI_a(q&M?6s!|3XtP00=|@mAXivK zEw45lg#l7bt;8eMht)IQv4}=qBXbdF5jwt(>90e*f2{tx`G&~rgnVVa9`_*~wj2T~ z3@T*qtHW29KfPz>gku2bX6Ke7SI{?ZpPLhbEF;@)kKeE6~ZQoNOnxZ9a)F!~HQ)CnFH3y)cgX-(v#XgXzJKz- zj>ldcjP!~EB^B=XW82i7;r>IL7xkG&wNbaW(`LQfarnE0gK|G4yFW&LlF$P-j>zX; zo3^g=*~0P3Nis~vyujcOv}O`Sp-ei?XFSW-&p#j#kHur~Xk3KH!4Z$dqk<-|d0|{m PXh`tHhY6hR7Ng;xAQ#1}zP@Ie|w{ew2Xlu)TJ`s7bhBS;k=Le=_%M9-bg*=(?)7V*NK zxqHsJ-#O!>DduGdy&8y5W z7D|Mc%Z5M44b!oi8;p$nNpYo9;5KbLY(&@fs#jxr#ecX=nLg+FGrUesrVCVyJ!s5v zy*z6>R;ci4-L?!~GpJ?Ru2JI^uKOOhEyt)Zm-#gCe8a5Q|I!&w=>Du5*fnNwQOV9~ zy?#}hcx5m6y9CyK!nk4b0p&CQduV=$2ds8AVYzQM$n^M7xT#X#nxj55Y&T&3v}l#> zn$E1%XxSCa>$CCi$o`K)hix|MII#xI%Z5C>dLU* zZtkI4d7A{c_H@Voh2dkjsB&i;Q8M{VUnqzot~jioRb>x9r*Bhb73{q|y@R1>+WUX| z=Chw3eX7tYZ(4f~C|hD%HaG41*sGr}{(4|gl{?^kZZua6Mbm!w^}lH6&)%`3%1N;2 zGx@$yH0=jZO6r2Md`XqB1-rIiyFV07`C0GT zaeMmZ0ad;R5VE&rCqvOhSp88eJa_KKm2O$W3es}AyJ`2?G@p`ziZ!OBM92^Z&U|=c z$LnvEl5I&PyDNJuMoTKWn{#(!^+`n=)%Ia6x#;-hlOOzkK}sqqE!B@mNHqiyJfj*J zmf|6^s77e;7ObLr_u+|)&nU_lpoZFq!ybYdTY4e(-Vb}ehmh&M^Z?e3?1Q(U9zhBh zKbh!`U7iB(%;roFR$hvaovyLY;{s$NJ&7P#7J!KUAjrWtpI+Vh%B8K~-K+L$Se;wA zX{G)7uRaBJUd?aC432!%bDSQVIU_0 z3O^qBc6EF8yA-Ii{n zVys035!4E;ctJ!T1VuqmT7#Ds+VrKALVeLEFGYy3=Zs>n5Ii_6mAJtS-p7s1`T32;bW~hewurfV(BZ3f%TTDJsD@#=ibHEu_C0DDwo)@)(^mt}SM+-Qy2)@u_GjF{a!iG?Nw!bb z>uc)7)4brH8ffN(b;ITZl}`WfrRhN$n9f?tQeSV7>CwT)A=xs>Ctsu;_ zQjl>dZl;@uJj)GQcGvPh8(Sfc7g(OF7;2y@WRkk zK27LBN88N7mw&2r@7&PgTSb0-j0m}6t}ir1U_TS^^ezj#>3Mmx$ag}#)LR+|O%(6{ z7oUld_ENr77B(g~ZiwRY$lG7f|9;$CW`Mr#))(G!WEGhAujEe9t=$sKmGjsGw`AWei+mao^0(*5LlYq^|14ErKEHLbhv#5|j-HOKLYB|=L~-9dKqq;iVudL# z6*7c{bDtjF_TER;bSy38cjRxwYH6WxOW`h@J}pSQq;FUES3OOueD+mP$U$*b)nryR5E2m=|*jw1+;1t4rc2(tgf7nZlbb!8J| zm&B5U)47$K7TaF=?n`hN#o{LH;IYqokEn;IPqUJ#TsM|H{>~U~sw`GTL!q3Y;E^nE-oB?;fKRKvO??y?bnON58}rmyHG9+VV4L7du;85 z_@=F{hZUhJ2;vaBT&LLP?|s~FqC9MCP1N-(hdOz!lOKLZ}@6bwiWqS>c6zEX)-VO~z5iX&5+} zGIYjJ8LS&ZBq8f@Mqor$QLt#pszP=IMpGlIL8ykNCK6a%t~0^j5Tj#l5NkGzh4Drw zOUe3#J}lKTMjR`^0bZm}%!MhU|dD-3ASFt96FB1W!A37U{(w2aOt z1x1Kqjftun6BiUIAuBOc2XRYOlgYFqi-M^1*J!J&uVvu5k|8O{>10;OHf&?? zkeEnI1iOSKFAZ9Tr>;OD^5Xxx$`R93oFbtp(7ZX*Bo`}|jMO`zRea-Zv@EZuuBl~~ zj5Ig^wmL`=h>+OHRw_-j^XO=gwmeB3ymZ7@&6oy-|B;o+t2 zqBF~;;DZQE6G<(ZSZ5Ff<(uAruyK0Vb4+L8^-9FDk|sl8*`zAr)>usqV%_Tkfl!!t zc6IUo0N>?ZH$e&qd|nst?)L-Pe_4(m^mKUorjkSbp|Hm{l^*U4dYtZjy4%z4?CA>g zL0>QL^>uf7d>((;8TJPJty(g}i^F0^d;RM@ zE+PXALL|b+1x?BT+@XsNtVIP8^Pax$KrkFate1sVr=X~jIx zCK1i^1SYr!)Rby^%L*Et7qEsiDy>L@Vz3ex6FN}RiiTmDk?F{aP&6QAfElyd{s0yc zvC(d?3!eJ0VhBSlnG=YWv!F$+idYzaYFZO9E6G~xq+HklVNp58DT8v7OC{2=7?!wx zHSJQ9sRTIb!<-S9HHinWjbUzBOiGgoVgjZPmyjb|_N~6bR%fe2;GNVOQ_?jx^^Itf z!BZwbl9m(FG+93baT)pz%3&(Nu_T{2SM*%bPVYs&8i)uq{qMryLIJ{O0zSf%HspkC zz{zJLjlroYg9E&BF(DxU&cq3eX^Z{9yuI{3`!(AmbCfXfCZi=Pg|(%YjlZ@2#5@#+%?n024H^ta)hFg z7YE0k9vo*XAGY5|T&Nn~-;WhIv_29DB_nQPYo$7svN`;LAwk}5-Wz~P$j zsx==u8=u|t(Xq-CtCo}@7WUmG?m6Zox3A%-&do-s^!i_fhY#&KcZSv8)6&zH3*O$} z(w|$E#TGTnyU#yZRBVqI$1ACKl)1=arb!qyt~*h&_px&ie17Q8YpXt(QEU%g8gf#u zVtbei*VEO7bGO)kQ2PA4Gp+XSh22Xj*=py@_(c;d`E2=oYVN`}SKrn5(TiWrEVc(r zgE^*Rdv9rP-YVb2>U~=L=;oH|!EwHnpF{O7{rKKhHyq!2UjdqyJ@~VcMPrMbimZ0u zJYNOXM4>R#VnTqX0GKZIT~3*-_HaYkM_24t?x{O0Rh9yb*CWRxt2fL(R)7e_V6nx- z-h^YJ`5_y1#cJ=H-`g9ZAJ>=1+0XUouU!2(xn}X+9narC^A#wL zdx4vw*mrhrM`!VWY%Cyc>)4M!-1T|)4+{|Ke0lex#cjL`J1jiyKc<(_}-yozssom{+69Wb4M#9^)Gzu`*fPZ6e6RPB7O5+FP5k8ysr@) zClet%nGxFh=^y?X-tfuyfb6ok=Fu_w<1O~vc7J>9$^zoqUU_HiTF&r8-QiB^FM0f} zdms4j+Xrrb_mYEc2Yz*AT+{wP1v_h4{hVwBNB{iS!_Ma5_G|>B&TB8;_UmUxZ+Xnx zvgq*jKYW)cV7xwOV%aZXv!Zx;oYLI?b%GgF?XPng5#09pL=7@(^nq>GH%D~X=WZ>^Uy6L zhmLj@keSEYZytJ}?H`9B0(Z5$jW#yz8YnqA8)?ZO|Ei_oX#H)+3kd9q^({ur6Mx@C zifG3U>gu!G-oB`5MGO_7>4g`0Z*-4}3lKT9{^$qW-1DC-K;-3FqxOStWBDG#!5Jz(->{-)RO-9jGIBe!h9)!ym2NP`wARs8lJ{w9;0)TBYVz zZxyGX*xS8f7RYwa=(JKV-a8cSSabQ8E=XqnAxwL0hQ++1&}so@*ntizdu-RE!T&_Y zstSmJq5+OLa=)3-8?uDTsa`nZEPZ*a_`>)F6h2>U|I35hcE7v00Gmj|34ydETyJ%b zyfl+X_T!*0sK`ERe?VOQd&h5QHZ?m?Q*HynuhqnIST0>!W0_+un|pToy!jQ?msBsS eUS7T8!gJ1Du=xB%l~w00TyjzE1uL10(SHFz>pk%R literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/utilities.cpp.8466B813AD21AFA5.idx b/.cache/clangd/index/utilities.cpp.8466B813AD21AFA5.idx new file mode 100644 index 0000000000000000000000000000000000000000..c2a1397de4e20c96c8104c9312e347616403b490 GIT binary patch literal 5560 zcmb_f4R93Y8U6wXgyVupK#=ovkpRZzvLvJ=cZB3Fcb9OGyG!ma1Po=nxBJ~?$=>dD zcP}BvA80!uwpH3f2N8d8styG^j9Nz+v|tOhmd+S-{6VMcbVQ3t2epx^Xy4t-cew~Cs1FcTpU@86Kb8f!ubO@n``rU;*!;YI&3Q)^?2fa8=~({M7S zsgx#DSk>5=D5zZ&OL4L!VNMfdN$0SXBFAJ+r)r8Uidb2wQsIsWrDCNAD-~ul<&Tfl z64YUPm@lWaE-ZlrM3LsSw1Rnx$10}?DZ_^x*99_O%sFl-Fr#3QmoTq;S({=NHc2VH zDwAX-Hh~o?E-O?QEAgTrB@82aT%4RtrX_)64ePyv*7fD~E3y{#{FveV7=bq|vl1on zSki>JfE5}nc1vs$8!QOeOlho=z#3#T8lbFYN!HB{fyrn>63c0g5+q)a4r1@^!eB`O zn9Wo#D;O*s7bHQ$VjrdBPk_n6#lRv13>DTx_hc*M9Rt?U+FF+)_d-2*r&CEof=SF^ zMS*~XIF**55%AbOQDLUgbtV0kPQW@aREGsQMY*}0D(SCsLf)#DaiMn~)MtSK(@2~R z;l)G3F7;VqUv1=?ipxB{e7flq)&ww_Y=HTYJqA{m~07D zU15w&%5~VjK@vo6?D)aQ*N2`J`UX*#BDd$&odYs4s9SJ-R&Xb9-~?USE^Dy(P+o109S% z(Awe)_<~V))E^2iQg6_r^ACpn`2Uqw!x(>4Y z=`J~m>4b7)jKy@XtaPg>mcuj~i!nUzVR}_sRXF3Q$ZA#Q1r`D)3NWa&AaP=v$H?9R zzpN<26K~KI7XIo(WmmBnhj&S~r=_%td3!u98H;WN(bzLE*a}cnvLL~momF6uz!{cT zTH;wrv-6k}RiLCL1+!e2J~Va?Y5}BP5XSaQ+k*&)>~XbE(%21lSrYq@UC4AHvdhS> zU{y{l9Jcdk<^6fq1n(x{pip zBM6+xN(ovNVsz%MvZ`WH#Ucc8@yilYx~#0S290p|rEtg6g2<1;`5UMSFgQ>ELlGyE zOj1p#+46k7*U{=Z`{mo30U#idZy5t9LkQneSz%KG|6LHs7*LZ8%kzTtoh%twU7p4G zs)^HiX-yCXO~7h}KIF8V(r6e?I>Cx83>P|&{Y%5QI?Z!=lh*erIZf1Zh zUA7QdWMlGS{W?vY=qGmjyU@)^T7+*LX3Nry;B;s!N8O(rtb*_Lr3VWr+aG13{s5?rd4(d_I&eYie5W%Tk<*FvMUOaVi7V&=5qKIhu88X^Y;n#QsPv%h zhZbX`o&7pMalpb!(_cRuUsaBw1vqM6b1KvY75ZL0U0QfzcC7l-3MWE?4E?FdjYMw@ z5;`}(su6x^2Mvn~Z{ToBLvYUt@jk|Yxfd>ea@!LI>>3TjS0UFWNLZf|xZs%-tX3>> z81={k58uFj$=GT5{GE1eebY~VCBJGxHC4#rwR#uV)?4crqsgWT;|eOP3u+6>_uM$J z>b~CuiVzJF)w8Orj0Zyc=QR8*dA9nl7e5OW7oiH^J1=vV8ILS~<88&)_I&d85er%d zd|`r6TI-qMDFqLcOla{Bz{A0hg)=+f?O$j?bs({B!a7^6dxF~r5);Rx`XwN7x^CW~ zv!C^+iqImEa7}lW8;`7yPagW<+^ma>ONx*k_@F$+cx3qsj;r)!gbFwRHrhAv;LLFr zM_Zt+Et|X}x;FYFaw-L;7$B25*=X|m<^cN9_`kP#Rs39`Shm)_ugWC zZ=A^yYz>Bql*titg&N7}nyH%{TMJLTHQwTAncXsznLY|rwR zau4r5@yPg>pg8U;+!X13_wwy%BJlMnWQ$Su&6^rJ1HG=yjBl%azRX|W-=En+k%9X*oobl)4%w!#h4fWQI(_5) zC#R+F-CF~J>l-1nnGxD@;V=J=wtf6FAiK=2%gGx3#U{tDeLo&tpGQ91XWg5)h1P;l zcQ(KV2e;jR|M9J+zwdbK`XjEVe|KiclH2oB?Zbwa^_dKIY}xwp%Kz=1k;&jOQ|OO> z;@dCme9}@k=atRBgdMCSLqdh=gvCZqckexP4=&br=Mmv<=N%X7-mRT6YJ?wX@=Pt? z^=5G%mL8+G-{id8+W@Euiv$;e{IQGvO=^AnM!h+vcFZEp@%RJJy*B08O=p12HnA%R zGEXddbZ7s-+2wg4^JLSG4S#UG^9p3(p6hmz!6s7!CD-ppQu3$1sH-|#x$Ar$i5*>0 zr_~+(SGQh72kRuEK6~dI*VbN_KzUet{v_j%@0W2NDg!IdzIUg0`ZIZ`yg2E!M&FBKo1epeorUU~KD4+i(VxfCpUkvDsPzJBrjpEtJ6-4DIE-nxD+ zskFt>ZSBsU{%J}dJ=oedN!P9R){`jS9*8$Dx#4pUfSG#u?s_FjpUs8+5FX{eLma%j{|q^d&`!GPo!Xx z)khLOZ&g}#Z2nza%<^T*P#Ccmm%W% literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/utilities.hpp.62390E5A28AD6DA6.idx b/.cache/clangd/index/utilities.hpp.62390E5A28AD6DA6.idx new file mode 100644 index 0000000000000000000000000000000000000000..a9efc8864328041068e3035df8dcffab8bd71982 GIT binary patch literal 1768 zcma)6L5mzk7_HIWBs-2~%t8VYp^#C~*gjNJvxN{q=O2?y9k> zddAHrBzV$`Ab1cw`5U}sLB$aK4<-l6MF<`}CT|h#UY_xV;~_N6}6phlot^*Y^3_MhVV2_MAk)TAH~fi8;36bfP*gN_s* zIt`gvK&eunk)cSV0PzB1t8#hB6w9d^>mX->4M5REDw;A8XIu;%iS-r9JTC-~m}4Jv zlRlrnHD$E*1yAY=c$aqz-9NZQfu2aL*01Q_1bU;&PAua7B%)sy* zWML>5v2};u$0;C_!kFuH%(&ZvgbQvU+o3l9DwvsEToz?8blY0*O*?a8POML#HmQ__bTs=xws2tX+`#1mQw90Zs@6RkQWZ?5dV?PJ#OP5Q7p)07+QbY=I9k9BKPO4#Yc z{;ax~_UG)tXD8rL%8WiYvKwoqWJ&6ZzQh!K2uj;2Mfm_n(Z26T_IEUn_*Rv-rmNbm z1k)C1dtgo_>o&Fn6j9;k`$vucw>||O!1WrL-+98q5c_H;!}klrGj2F&-zU}|iTst$ z`yGVfzr%F;o&Vs9{1A_f$n<^)Y^$-D$xxGoXW)CDm&zQxfw~ql@WxVI)k7A6hdMzF zqhPE(j#08Kb4xJD9na)DwwqB_#3lZj&6(k9r3V+(Dso~<>NDkwb)IqjqW9^!g39G- zTCH?ABsfw$*$G@qV;r|?#;Ogh#{k|%QOX4bERJ!kf}sKpA_6j!JjR=MCl3?6beq3^ zvibSf@?L|yvgB@I(rmxhK1-Gs7GJ0xd8yW{-TGqrjnTh<{L&!DDnxIww}yzr3#8sa z#NI#r&u<^@o@$U+D@1p(`#K^Hy-1c{MudVy-=0ycEjbl7GB+PB@7?Y%z57!R&97>W zX8WV|mC959$Kl1}>i&IP?yhtRi_YbO;zaM z?*07N-`_ttXC+DdWF`6gLUCvB;s=NA@edo*58?~e4 Is9h+Z$Fh)dZvX%Q literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/utilities.hpp.F418EFD6A6E9D646.idx b/.cache/clangd/index/utilities.hpp.F418EFD6A6E9D646.idx new file mode 100644 index 0000000000000000000000000000000000000000..dff9eaa3b97e7093ca1ec35ea69fe99f3a819d4d GIT binary patch literal 2284 zcma)7L2D#M6t0Ph*~C%fj_!gY6cUpS%uZ)_MWKacmaKsgc3CqadvKwt>3%(3Zg*t58^>VJbF+N1mCNfo=nUnn}Hd6s=oT(_rCXD z_14Dv`mbjgTZ=aCW?;o6V{8t;#%j4UjSuvh<+qz!Ld>sP3t8J5ZWRY(MKhHq;ev-M z&mpu@<+LNXR!wDT)oPWdpcf6_y4BzYbQg4Oc9w6%hfhg!zz0#4+XQk%po>I~pP$ zfeE#2yBI1az>z2%Su`L#hlqmQZVN3ku6riPL@rvOd8{-~L>{FwZ#fQ<6{;-j;-!%p&J9g51hjg7%Q{PA)QVTcp)x&B; zzOOr&Uj_kaje2CvJ2|!iCU;y%U~&fyv;&&V!3Ii%?H7O)-4Ysj!wL)6MVQDO_|+)7 zxPf*W-qv8yQ#64ZV%J~?juf}Q5DXo1t%*%0RXP4Hak6B{ z$uGzn)HvJ?(@sRaOOO#8bT25RU?E2GKdEvQ`iLk>CCA|%h9)mA%5{nAzZhVzErY_dG9A8F(%IPE&x_ zQ~Hi+ix51F6GYGrdd8FJt4LF~1g*^R4DMvwq^|Dck8F-~S}i$!K%+w!Oe=HQJtRU$ zJ)9}LDlF)j^o_c9cD{%ff#=+zj8)elTuYd4~dQfK1l--+_RaRbDxx!{9rzcCZPn9Yq(Y5dWTiL%qG4bpZ z1B5s0RS?nt_x?wfm%9J__I;V1D;Tz?wwG{!=JAOqpGJoLzvUmF{l2$YX3rIf&8f{7 z5pibfvGa3?&=8yZBWg-BPDK&AG4sZ^8O(iLDpyt)S1%Tt8{f2Vp3@H>;_~MF<|{>* zLJ*RWkb>lE@6&hv&#$c_dV6`hUZ9Foh$c}5`lkoq{rT6Izr2p<6}Iwx5%TBB&JX)H n-<&2T6RYK7Swkww4Xn92PY;#G%U{iXQSGjm&a$(#(Et1g4__Ws literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/visibility_control.h.F5187384E0A565C2.idx b/.cache/clangd/index/visibility_control.h.F5187384E0A565C2.idx new file mode 100644 index 0000000000000000000000000000000000000000..b28bc37255e1e25e11c3d7ca85e6269bdfc6f86a GIT binary patch literal 326 zcmWIYbaS&~WMFVk@vO*AElFfyU|>`WgATsruDKjUtq%uA^Kd+=HKSwWvp|~2QTgJcu0RAvrtpET3 literal 0 HcmV?d00001 diff --git a/abb_hardware_interface/CMakeLists.txt b/abb_hardware_interface/CMakeLists.txt index 25158e9..f5f2e80 100644 --- a/abb_hardware_interface/CMakeLists.txt +++ b/abb_hardware_interface/CMakeLists.txt @@ -20,9 +20,14 @@ endif() set(THIS_PACKAGE_INCLUDE_DEPENDS abb_egm_rws_managers + abb_egm_msgs + abb_rapid_msgs + abb_rapid_sm_addin_msgs + abb_robot_msgs hardware_interface pluginlib rclcpp + sensor_msgs ) # find dependencies @@ -51,10 +56,31 @@ target_include_directories( pluginlib_export_plugin_description_file(hardware_interface abb_hardware_interface.xml) +add_executable(rws_client + src/rws_client_node.cpp + src/rws_client.cpp + src/rws_service_provider_ros.cpp + src/rws_state_publisher_ros.cpp + src/utilities.cpp + src/mapping.cpp +) +ament_target_dependencies(rws_client ${THIS_PACKAGE_INCLUDE_DEPENDS}) +# target_link_libraries(rws_client abb_egm_rws_managers::abb_egm_rws_managers) +target_include_directories( + rws_client + PRIVATE + include +) + ############# ## Install ## ############# +install( + TARGETS rws_client + DESTINATION lib/${PROJECT_NAME} +) + install( TARGETS ${PROJECT_NAME} DESTINATION lib diff --git a/abb_rws_client/include/abb_rws_client/mapping.hpp b/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp similarity index 100% rename from abb_rws_client/include/abb_rws_client/mapping.hpp rename to abb_hardware_interface/include/abb_hardware_interface/mapping.hpp diff --git a/abb_rws_client/include/abb_rws_client/rws_client.hpp b/abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp similarity index 100% rename from abb_rws_client/include/abb_rws_client/rws_client.hpp rename to abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp diff --git a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp b/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp similarity index 99% rename from abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp rename to abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp index 0820444..c6f6d91 100644 --- a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp @@ -1,9 +1,8 @@ #ifndef ABB_RWS_CLIENT__RWS_SERCIVE_PROVIDER_ROS_HPP__ #define ABB_RWS_CLIENT__RWS_SERCIVE_PROVIDER_ROS_HPP__ -#include -#include "abb_rws_client/rws_client.hpp" +#include "abb_hardware_interface/rws_client.hpp" // SYSMTEM diff --git a/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp b/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp similarity index 95% rename from abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp rename to abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp index d2bbe88..617222e 100644 --- a/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp @@ -1,7 +1,7 @@ #ifndef ABB_RWS_CLIENT__RWS_STATE_PUBLISHER_ROS_HPP_ #define ABB_RWS_CLIENT__RWS_STATE_PUBLISHER_ROS_HPP_ -#include "abb_rws_client/rws_client.hpp" +#include "abb_hardware_interface/rws_client.hpp" // ROS #include diff --git a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp b/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp index 80f34bf..2fbc3c6 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp @@ -60,10 +60,29 @@ namespace utilities * * \throw std::runtime_error if unable to establish a connection. */ -RobotControllerDescription establishRWSConnection( +RobotControllerDescription establish_rws_connection( RWSManager & rws_manager, const std::string & robot_controller_id, const bool no_connection_timeout); +/** + * \brief Verifies that the RobotWare version is supported. + * + * Note: For now, only RobotWare versions in the range [6.07.01, 7.0) are supported (i.e. excluding 7.0). + * + * \param rw_version to verify. + * + * \throw std::runtime_error if the RobotWare version is not supported. + */ +void verify_robotware_version(const RobotWareVersion &rw_version); + +/** + * \brief Verifies that the RobotWare StateMachine Add-In is present in a system. + * + * \param system_indicators to verify. + * + * \return bool true if the StateMachine Add-In is present. + */ +bool verify_state_machine_add_in_presence(const SystemIndicators &system_indicators); } // namespace utilities } // namespace robot } // namespace abb diff --git a/abb_hardware_interface/package.xml b/abb_hardware_interface/package.xml index 1d688ea..7f97050 100644 --- a/abb_hardware_interface/package.xml +++ b/abb_hardware_interface/package.xml @@ -15,9 +15,14 @@ ament_cmake abb_egm_rws_managers + abb_egm_msgs + abb_rapid_msgs + abb_robot_msgs + abb_rapid_sm_addin_msgs hardware_interface pluginlib rclcpp + sensor_msgs ament_cmake_gtest diff --git a/abb_hardware_interface/src/abb_system_position_only.cpp b/abb_hardware_interface/src/abb_system_position_only.cpp index 2215677..3f21826 100644 --- a/abb_hardware_interface/src/abb_system_position_only.cpp +++ b/abb_hardware_interface/src/abb_system_position_only.cpp @@ -40,7 +40,7 @@ CallbackReturn ABBSystemPositionOnlyHardware::on_init(const hardware_interface:: // Get robot controller description from RWS abb::robot::RWSManager rws_manager(rws_ip, rws_port, "Default User", "robotics"); const auto robot_controller_description_ = - abb::robot::utilities::establishRWSConnection(rws_manager, "IRB1200", true); + abb::robot::utilities::establish_rws_connection(rws_manager, "IRB1200", true); RCLCPP_INFO_STREAM( LOGGER, "Robot controller description:\n" << abb::robot::summaryText(robot_controller_description_)); diff --git a/abb_rws_client/src/mapping.cpp b/abb_hardware_interface/src/mapping.cpp similarity index 99% rename from abb_rws_client/src/mapping.cpp rename to abb_hardware_interface/src/mapping.cpp index 25c1824..85fd502 100644 --- a/abb_rws_client/src/mapping.cpp +++ b/abb_hardware_interface/src/mapping.cpp @@ -39,15 +39,13 @@ #include #include -// ROS - // ABB INTERFACES #include #include #include #include -#include "abb_rws_client/mapping.hpp" +#include "abb_hardware_interface/mapping.hpp" namespace { /** diff --git a/abb_rws_client/src/rws_client.cpp b/abb_hardware_interface/src/rws_client.cpp similarity index 90% rename from abb_rws_client/src/rws_client.cpp rename to abb_hardware_interface/src/rws_client.cpp index 0f5c149..64f2339 100644 --- a/abb_rws_client/src/rws_client.cpp +++ b/abb_hardware_interface/src/rws_client.cpp @@ -1,6 +1,6 @@ -#include "abb_rws_client/rws_client.hpp" +#include "abb_hardware_interface/rws_client.hpp" -#include "abb_rws_client/utilities.hpp" +#include "abb_hardware_interface/utilities.hpp" namespace abb_rws_client { RWSClient::RWSClient(const rclcpp::Node::SharedPtr &node, const std::string &robot_ip, unsigned short robot_port) diff --git a/abb_rws_client/src/rws_client_node.cpp b/abb_hardware_interface/src/rws_client_node.cpp similarity index 85% rename from abb_rws_client/src/rws_client_node.cpp rename to abb_hardware_interface/src/rws_client_node.cpp index af3c152..331a23a 100644 --- a/abb_rws_client/src/rws_client_node.cpp +++ b/abb_hardware_interface/src/rws_client_node.cpp @@ -1,7 +1,7 @@ #include -#include "abb_rws_client/rws_service_provider_ros.hpp" -#include "abb_rws_client/rws_state_publisher_ros.hpp" +#include "abb_hardware_interface/rws_service_provider_ros.hpp" +#include "abb_hardware_interface/rws_state_publisher_ros.hpp" int main(int argc, char** argv) { rclcpp::init(argc, argv); diff --git a/abb_rws_client/src/rws_service_provider_ros.cpp b/abb_hardware_interface/src/rws_service_provider_ros.cpp similarity index 99% rename from abb_rws_client/src/rws_service_provider_ros.cpp rename to abb_hardware_interface/src/rws_service_provider_ros.cpp index 1f7ff1f..40b9786 100644 --- a/abb_rws_client/src/rws_service_provider_ros.cpp +++ b/abb_hardware_interface/src/rws_service_provider_ros.cpp @@ -1,9 +1,9 @@ -#include "abb_rws_client/rws_service_provider_ros.hpp" +#include "abb_hardware_interface/rws_service_provider_ros.hpp" #include -#include "abb_rws_client/mapping.hpp" -#include "abb_rws_client/utilities.hpp" +#include "abb_hardware_interface/mapping.hpp" +#include "abb_hardware_interface/utilities.hpp" using RAPIDSymbols = abb::rws::RWSStateMachineInterface::ResourceIdentifiers::RAPID::Symbols; diff --git a/abb_rws_client/src/rws_state_publisher_ros.cpp b/abb_hardware_interface/src/rws_state_publisher_ros.cpp similarity index 96% rename from abb_rws_client/src/rws_state_publisher_ros.cpp rename to abb_hardware_interface/src/rws_state_publisher_ros.cpp index 33d632d..c73054e 100644 --- a/abb_rws_client/src/rws_state_publisher_ros.cpp +++ b/abb_hardware_interface/src/rws_state_publisher_ros.cpp @@ -1,7 +1,7 @@ -#include "abb_rws_client/rws_state_publisher_ros.hpp" +#include "abb_hardware_interface/rws_state_publisher_ros.hpp" -#include "abb_rws_client/mapping.hpp" -#include "abb_rws_client/utilities.hpp" +#include "abb_hardware_interface/mapping.hpp" +#include "abb_hardware_interface/utilities.hpp" namespace { /** diff --git a/abb_hardware_interface/src/utilities.cpp b/abb_hardware_interface/src/utilities.cpp index 9206bf9..90ab79e 100644 --- a/abb_hardware_interface/src/utilities.cpp +++ b/abb_hardware_interface/src/utilities.cpp @@ -69,7 +69,7 @@ constexpr uint8_t RWS_RECONNECTION_WAIT_TIME{1}; auto LOGGER = rclcpp::get_logger("ABBHardwareInterfaceUtilities"); } // namespace -RobotControllerDescription establishRWSConnection( +RobotControllerDescription establish_rws_connection( RWSManager & rws_manager, const std::string & robot_controller_id, const bool no_connection_timeout) { @@ -96,6 +96,21 @@ RobotControllerDescription establishRWSConnection( throw std::runtime_error{RWS_CONNECTION_ERROR_MESSAGE}; } +void verify_robotware_version(const RobotWareVersion& rw_version) { + if (rw_version.major_number() == 6 && rw_version.minor_number() < 7 && + rw_version.patch_number() < 1) { + auto error_message{"Unsupported RobotWare version (" + rw_version.name() + + ", need at least 6.07.01)"}; + + RCLCPP_FATAL_STREAM(LOGGER, error_message); + throw std::runtime_error{error_message}; + } +} + +bool verify_state_machine_add_in_presence(const SystemIndicators& system_indicators) { + return system_indicators.addins().state_machine_1_0() || + system_indicators.addins().state_machine_1_1(); +} } // namespace utilities } // namespace robot } // namespace abb diff --git a/abb_rws_client/CMakeLists.txt b/abb_rws_client/CMakeLists.txt deleted file mode 100644 index a7999d2..0000000 --- a/abb_rws_client/CMakeLists.txt +++ /dev/null @@ -1,79 +0,0 @@ -cmake_minimum_required(VERSION 3.8) -project(abb_rws_client) - -# Default to C99 -if(NOT CMAKE_C_STANDARD) - set(CMAKE_C_STANDARD 99) -endif() - -# Default to C++14 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-W -Wall -Wextra - -Wwrite-strings -Wunreachable-code -Wpointer-arith - -Winit-self -Wredundant-decls - -Wno-unused-parameter -Wno-unused-function) -endif() - -set(THIS_PACKAGE_INCLUDE_DEPENDS - abb_egm_rws_managers - abb_egm_msgs - abb_robot_msgs - abb_rapid_msgs - abb_rapid_sm_addin_msgs - rclcpp - sensor_msgs -) - -# find dependencies -find_package(ament_cmake REQUIRED) - -foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) - find_package(${Dependency} REQUIRED) -endforeach() - -########### -## Build ## -########### - -add_executable(rws_client - src/rws_client_node.cpp - src/rws_client.cpp - src/rws_service_provider_ros.cpp - src/rws_state_publisher_ros.cpp - src/utilities.cpp - src/mapping.cpp -) -ament_target_dependencies(rws_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${THIS_PACKAGE_INCLUDE_DEPENDS}) -target_link_libraries(rws_client abb_egm_rws_managers::abb_egm_rws_managers) -target_include_directories( - rws_client - PRIVATE - include -) - -############# -## Install ## -############# - -install( - TARGETS rws_client - DESTINATION lib/${PROJECT_NAME} -) - -############# -## Testing ## -############# - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_export_include_directories(include) -ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) - -ament_package() diff --git a/abb_rws_client/include/abb_rws_client/utilities.hpp b/abb_rws_client/include/abb_rws_client/utilities.hpp deleted file mode 100644 index 0e0941c..0000000 --- a/abb_rws_client/include/abb_rws_client/utilities.hpp +++ /dev/null @@ -1,72 +0,0 @@ -/*********************************************************************************************************************** - * - * Copyright (c) 2020, ABB Schweiz AG - * 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 ABB 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 HOLDER 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. - * - *********************************************************************************************************************** - */ - -// This file is a modified copy from -// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/initialization.h - -#pragma once - -#include - -namespace abb { -namespace robot { -namespace utilities { -/** - * \brief Attempts to establish a connection to a robot controller's RWS server. - * - * If a connection is established, then a structured description of the robot - * controller is returned. - * - * \param rws_manager for handling the RWS communication with the robot - * controller. \param robot_controller_id for an identifier/nickname for the - * targeted robot controller. \param no_connection_timeout indicator whether to - * wait indefinitely on the robot controller. - * - * \return RobotControllerDescription of the robot controller. - * - * \throw std::runtime_error if unable to establish a connection. - */ -RobotControllerDescription establish_rws_connection(RWSManager &rws_manager, const std::string &robot_controller_id, - const bool no_connection_timeout); - -void verify_robotware_version(const RobotWareVersion &rw_version); - -bool verify_state_machine_add_in_presence(const SystemIndicators &system_indicators); - -} // namespace utilities -} // namespace robot -} // namespace abb diff --git a/abb_rws_client/package.xml b/abb_rws_client/package.xml deleted file mode 100644 index de23dc2..0000000 --- a/abb_rws_client/package.xml +++ /dev/null @@ -1,26 +0,0 @@ - - - - abb_rws_client - 0.0.0 - TODO: Package description - Grzegorz Bartyzel - Apache2 - - rclcpp - abb_egm_rws_managers - sensor_msgs - abb_egm_msgs - abb_rapid_msgs - abb_robot_msgs - abb_rapid_sm_addin_msgs - - ament_cmake_gtest - - ament_lint_auto - ament_lint_common - - - ament_cmake - - diff --git a/abb_rws_client/src/utilities.cpp b/abb_rws_client/src/utilities.cpp deleted file mode 100644 index 482f0de..0000000 --- a/abb_rws_client/src/utilities.cpp +++ /dev/null @@ -1,113 +0,0 @@ -/*********************************************************************************************************************** - * - * Copyright (c) 2020, ABB Schweiz AG - * 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 ABB 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 HOLDER 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. - * - *********************************************************************************************************************** - */ - -// This file is a modified copy from -// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/initialization.cpp - -#include "abb_rws_client/utilities.hpp" - -#include - -#include "rclcpp/rclcpp.hpp" - -namespace abb { -namespace robot { -namespace utilities { -namespace { -/** - * \brief Max number of attempts when trying to connect to a robot controller via RWS. - */ -constexpr unsigned int RWS_MAX_CONNECTION_ATTEMPTS{5}; - -/** - * \brief Error message for failed connection attempts when trying to connect to a robot controller - * via RWS. - */ -constexpr char RWS_CONNECTION_ERROR_MESSAGE[]{ - "Failed to establish RWS connection to the robot controller"}; - -/** - * \brief Time [s] to wait before trying to reconnect to a robot controller via RWS. - */ -constexpr uint8_t RWS_RECONNECTION_WAIT_TIME{1}; -auto LOGGER = rclcpp::get_logger("ABBHardwareInterfaceUtilities"); -} // namespace - -RobotControllerDescription establish_rws_connection(RWSManager& rws_manager, - const std::string& robot_controller_id, - const bool no_connection_timeout) { - unsigned int attempt{0}; - - while (rclcpp::ok() && (no_connection_timeout || attempt++ < RWS_MAX_CONNECTION_ATTEMPTS)) { - try { - return rws_manager.collectAndParseSystemData(robot_controller_id); - } catch (const std::runtime_error& exception) { - if (!no_connection_timeout) { - RCLCPP_WARN_STREAM(LOGGER, RWS_CONNECTION_ERROR_MESSAGE << " (attempt " << attempt << "/" - << RWS_MAX_CONNECTION_ATTEMPTS - << "), reason: '" - << exception.what() << "'"); - } else { - RCLCPP_WARN_STREAM(LOGGER, RWS_CONNECTION_ERROR_MESSAGE - << " (waiting indefinitely), reason: '" << exception.what() - << "'"); - } - rclcpp::sleep_for(std::chrono::seconds(RWS_RECONNECTION_WAIT_TIME)); - } - } - - throw std::runtime_error{RWS_CONNECTION_ERROR_MESSAGE}; -} - -void verify_robotware_version(const RobotWareVersion& rw_version) { - if (rw_version.major_number() == 6 && rw_version.minor_number() < 7 && - rw_version.patch_number() < 1) { - auto error_message{"Unsupported RobotWare version (" + rw_version.name() + - ", need at least 6.07.01)"}; - - RCLCPP_FATAL_STREAM(LOGGER, error_message); - throw std::runtime_error{error_message}; - } -} - -bool verify_state_machine_add_in_presence(const SystemIndicators& system_indicators) { - return system_indicators.addins().state_machine_1_0() || - system_indicators.addins().state_machine_1_1(); -} - -} // namespace utilities -} // namespace robot -} // namespace abb From 7afc426fe57e9957d999aea2f2fe3f6ac037004f Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Tue, 5 Apr 2022 15:59:24 +0200 Subject: [PATCH 03/27] Add debug logs --- .../src/rws_service_provider_ros.cpp | 63 ++++++++++--------- 1 file changed, 33 insertions(+), 30 deletions(-) diff --git a/abb_hardware_interface/src/rws_service_provider_ros.cpp b/abb_hardware_interface/src/rws_service_provider_ros.cpp index 40b9786..949076a 100644 --- a/abb_hardware_interface/src/rws_service_provider_ros.cpp +++ b/abb_hardware_interface/src/rws_service_provider_ros.cpp @@ -138,6 +138,7 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node std::bind(&RWSServiceProviderROS::set_sg_command, this, std::placeholders::_1, std::placeholders::_2))); } } + RCLCPP_INFO(node_->get_logger(), "RWS client services initialized!"); } void RWSServiceProviderROS::system_state_callback(const abb_robot_msgs::msg::SystemState& msg) { system_state_ = msg; } @@ -172,7 +173,7 @@ bool RWSServiceProviderROS::get_file_contents(const abb_robot_msgs::srv::GetFile } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -196,7 +197,7 @@ bool RWSServiceProviderROS::get_io_signal(const abb_robot_msgs::srv::GetIOSignal } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -220,7 +221,7 @@ bool RWSServiceProviderROS::get_rapid_bool(const abb_robot_msgs::srv::GetRAPIDBo } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -244,7 +245,7 @@ bool RWSServiceProviderROS::get_rapid_dnum(const abb_robot_msgs::srv::GetRAPIDDn } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -268,7 +269,7 @@ bool RWSServiceProviderROS::get_rapid_num(const abb_robot_msgs::srv::GetRAPIDNum } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -292,7 +293,7 @@ bool RWSServiceProviderROS::get_rapid_string(const abb_robot_msgs::srv::GetRAPID } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -316,7 +317,7 @@ bool RWSServiceProviderROS::get_rapid_symbol(const abb_robot_msgs::srv::GetRAPID } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -336,6 +337,7 @@ bool RWSServiceProviderROS::get_speed_ratio(const abb_robot_msgs::srv::GetSpeedR } catch (const std::runtime_error& exception) { res->message = exception.what(); res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -359,7 +361,7 @@ bool RWSServiceProviderROS::pp_to_main(const abb_robot_msgs::srv::TriggerWithRes res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -386,7 +388,7 @@ bool RWSServiceProviderROS::run_rapid_routine(const abb_robot_msgs::srv::Trigger } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -414,7 +416,7 @@ bool RWSServiceProviderROS::run_sg_routine(const abb_robot_msgs::srv::TriggerWit } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -436,7 +438,7 @@ bool RWSServiceProviderROS::set_file_contents(const abb_robot_msgs::srv::SetFile } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -458,7 +460,7 @@ bool RWSServiceProviderROS::set_io_signal(const abb_robot_msgs::srv::SetIOSignal } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -476,7 +478,7 @@ bool RWSServiceProviderROS::set_motors_off(const abb_robot_msgs::srv::TriggerWit res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -500,7 +502,7 @@ bool RWSServiceProviderROS::set_motors_on(const abb_robot_msgs::srv::TriggerWith res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -526,7 +528,7 @@ bool RWSServiceProviderROS::set_rapid_bool(const abb_robot_msgs::srv::SetRAPIDBo } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -552,7 +554,7 @@ bool RWSServiceProviderROS::set_rapid_dnum(const abb_robot_msgs::srv::SetRAPIDDn } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -578,7 +580,7 @@ bool RWSServiceProviderROS::set_rapid_num(const abb_robot_msgs::srv::SetRAPIDNum } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -604,7 +606,7 @@ bool RWSServiceProviderROS::set_rapid_string(const abb_robot_msgs::srv::SetRAPID } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -629,7 +631,7 @@ bool RWSServiceProviderROS::set_rapid_symbol(const abb_robot_msgs::srv::SetRAPID } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -652,10 +654,10 @@ bool RWSServiceProviderROS::set_speed_ratio(const abb_robot_msgs::srv::SetSpeedR } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); } } catch (const std::exception& exception) { res->message = exception.what(); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -679,7 +681,7 @@ bool RWSServiceProviderROS::start_rapid(const abb_robot_msgs::srv::TriggerWithRe res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -697,7 +699,7 @@ bool RWSServiceProviderROS::stop_rapid(const abb_robot_msgs::srv::TriggerWithRes res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -728,7 +730,7 @@ bool RWSServiceProviderROS::get_egm_settings(const abb_rapid_sm_addin_msgs::srv: } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -764,7 +766,7 @@ bool RWSServiceProviderROS::set_egm_settings(const abb_rapid_sm_addin_msgs::srv: } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -799,7 +801,7 @@ bool RWSServiceProviderROS::set_rapid_routine( } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -846,7 +848,7 @@ bool RWSServiceProviderROS::set_sg_command(const abb_rapid_sm_addin_msgs::srv::S } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -874,7 +876,7 @@ bool RWSServiceProviderROS::start_egm_joint(const abb_robot_msgs::srv::TriggerWi } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -902,7 +904,7 @@ bool RWSServiceProviderROS::start_egm_pose(const abb_robot_msgs::srv::TriggerWit } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -930,6 +932,7 @@ bool RWSServiceProviderROS::start_egm_stream(const abb_robot_msgs::srv::TriggerW } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -954,7 +957,7 @@ bool RWSServiceProviderROS::stop_egm(const abb_robot_msgs::srv::TriggerWithResul } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -979,7 +982,7 @@ bool RWSServiceProviderROS::stop_egm_stream(const abb_robot_msgs::srv::TriggerWi } else { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - // ROS_DEBUG_STREAM_NAMED(ROS_LOG_SERVICES, interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); From 8c7985cf2c88520b7eef6b67aac9a39c8b6ad4bc Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Tue, 5 Apr 2022 16:08:49 +0200 Subject: [PATCH 04/27] Clean up header guards --- .../abb_hardware_interface/abb_system_position_only.hpp | 5 ++++- .../include/abb_hardware_interface/mapping.hpp | 6 +++--- .../include/abb_hardware_interface/rws_client.hpp | 6 +++--- .../abb_hardware_interface/rws_service_provider_ros.hpp | 6 +++--- .../abb_hardware_interface/rws_state_publisher_ros.hpp | 6 +++--- .../include/abb_hardware_interface/utilities.hpp | 5 ++++- 6 files changed, 20 insertions(+), 14 deletions(-) diff --git a/abb_hardware_interface/include/abb_hardware_interface/abb_system_position_only.hpp b/abb_hardware_interface/include/abb_hardware_interface/abb_system_position_only.hpp index 95c199c..a5e2e2e 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/abb_system_position_only.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/abb_system_position_only.hpp @@ -12,7 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#pragma once +#ifndef ABB_HARDWARE_INTERFACE__ABB_SYSTEM_POSITION_ONLY_HPP__ +#define ABB_HARDWARE_INTERFACE__ABB_SYSTEM_POSITION_ONLY_HPP__ #include #include @@ -74,3 +75,5 @@ class ABBSystemPositionOnlyHardware : public hardware_interface::SystemInterface }; } // namespace abb_hardware_interface + +#endif // ABB_HARDWARE_INTERFACE__ABB_SYSTEM_POSITION_ONLY_HPP__ diff --git a/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp b/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp index 14f6575..3d01b62 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp @@ -34,8 +34,8 @@ *********************************************************************************************************************** */ -#ifndef ABB_RWS_CLIENT__MAPPING_HPP_ -#define ABB_RWS_CLIENT__MAPPING_HPP_ +#ifndef ABB_HARDWARE_INTERFACE__MAPPING_HPP_ +#define ABB_HARDWARE_INTERFACE__MAPPING_HPP_ #include #include @@ -257,4 +257,4 @@ std::string map_vector_to_string(const std::vector& vector); } // namespace robot } // namespace abb -#endif // ABB_RWS_CLIENT__MAPPING_HPP_ +#endif // ABB_HARDWARE_INTERFACE__MAPPING_HPP_ diff --git a/abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp b/abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp index 03c41fa..1ff3040 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp @@ -1,5 +1,5 @@ -#ifndef ABB_RWS_CLIENT__RWS_CLIENT_HPP__ -#define ABB_RWS_CLIENT__RWS_CLIENT_HPP__ +#ifndef ABB_HARDWARE_INTERFACE__RWS_CLIENT_HPP__ +#define ABB_HARDWARE_INTERFACE__RWS_CLIENT_HPP__ // ROS #include @@ -26,4 +26,4 @@ class RWSClient { } // namespace abb_rws_client -#endif // ABB_RWS_CLIENT__RWS_CLIENT_HPP__ +#endif // ABB_HARDWARE_INTERFACE__RWS_CLIENT_HPP__ diff --git a/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp b/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp index c6f6d91..9d47d24 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp @@ -1,5 +1,5 @@ -#ifndef ABB_RWS_CLIENT__RWS_SERCIVE_PROVIDER_ROS_HPP__ -#define ABB_RWS_CLIENT__RWS_SERCIVE_PROVIDER_ROS_HPP__ +#ifndef ABB_HARDWARE_INTERFACE__RWS_SERCIVE_PROVIDER_ROS_HPP__ +#define ABB_HARDWARE_INTERFACE__RWS_SERCIVE_PROVIDER_ROS_HPP__ #include "abb_hardware_interface/rws_client.hpp" @@ -192,4 +192,4 @@ class RWSServiceProviderROS : RWSClient { } // namespace abb_rws_client -#endif // ABB_RWS_CLIENT__RWS_SERCIVE_PROVIDER_ROS_HPP__ +#endif // ABB_HARDWARE_INTERFACE__RWS_SERCIVE_PROVIDER_ROS_HPP__ diff --git a/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp b/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp index 617222e..e33e2e8 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp @@ -1,5 +1,5 @@ -#ifndef ABB_RWS_CLIENT__RWS_STATE_PUBLISHER_ROS_HPP_ -#define ABB_RWS_CLIENT__RWS_STATE_PUBLISHER_ROS_HPP_ +#ifndef ABB_HARDWARE_INTERFACE__RWS_STATE_PUBLISHER_ROS_HPP_ +#define ABB_HARDWARE_INTERFACE__RWS_STATE_PUBLISHER_ROS_HPP_ #include "abb_hardware_interface/rws_client.hpp" @@ -35,4 +35,4 @@ class RWSStatePublisherROS : RWSClient { } // namespace abb_rws_client -#endif // ABB_RWS_CLIENT__RWS_STATE_PUBLISHER_ROS_HPP_ +#endif // ABB_HARDWARE_INTERFACE__RWS_STATE_PUBLISHER_ROS_HPP_ diff --git a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp b/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp index 2fbc3c6..aac080d 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp @@ -37,7 +37,8 @@ // This file is a modified copy from // https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/initialization.h -#pragma once +#ifndef ABB_HARDWARE_INTERFACE__UTILITIES_HPP__ +#define ABB_HARDWARE_INTERFACE__UTILITIES_HPP__ #include @@ -86,3 +87,5 @@ bool verify_state_machine_add_in_presence(const SystemIndicators &system_indicat } // namespace utilities } // namespace robot } // namespace abb + +#endif // ABB_HARDWARE_INTERFACE__UTILITIES_HPP__ From dc60fee0a1ebfbc709b33f4e95c53811d9742153 Mon Sep 17 00:00:00 2001 From: Souphis Date: Tue, 5 Apr 2022 17:55:16 +0200 Subject: [PATCH 05/27] Remove .cache --- ...ystem_position_only.cpp.A4A69E936E6E2EFB.idx | Bin 12386 -> 0 bytes ...ystem_position_only.hpp.B82A1AE2C2DC8731.idx | Bin 3436 -> 0 bytes .../index/mapping.cpp.53C83202D804659B.idx | Bin 21880 -> 0 bytes .../index/mapping.cpp.981962BE1449DDD9.idx | Bin 21854 -> 0 bytes .../index/mapping.hpp.83C0C81544CCABFA.idx | Bin 9988 -> 0 bytes .../index/mapping.hpp.F4EF52C8E9EA4882.idx | Bin 10136 -> 0 bytes .../index/rws_client.cpp.B2625E19C4ED09CA.idx | Bin 2694 -> 0 bytes .../index/rws_client.cpp.D2D6995B64F84F58.idx | Bin 2692 -> 0 bytes .../index/rws_client.hpp.3738C46199137910.idx | Bin 1198 -> 0 bytes .../index/rws_client.hpp.F6B6AF448BD65A95.idx | Bin 1230 -> 0 bytes .../rws_client_node.cpp.3230C9A14C046783.idx | Bin 2474 -> 0 bytes .../rws_client_node.cpp.32950DC259F660B7.idx | Bin 2466 -> 0 bytes ...ervice_provider_ros.cpp.2F7E35170D7F40E3.idx | Bin 44972 -> 0 bytes ...ervice_provider_ros.cpp.F36FFB6C47C5231C.idx | Bin 1664 -> 0 bytes ...ervice_provider_ros.hpp.11A527BD4315BF59.idx | Bin 13240 -> 0 bytes ...ervice_provider_ros.hpp.FF9EC95DBE8BABD9.idx | Bin 12952 -> 0 bytes ...state_publisher_ros.cpp.1AEA19B09DBBB081.idx | Bin 6158 -> 0 bytes ...state_publisher_ros.cpp.8C64C24778513E26.idx | Bin 6158 -> 0 bytes ...state_publisher_ros.hpp.10B80F8842563FCC.idx | Bin 2002 -> 0 bytes ...state_publisher_ros.hpp.87F144D7A6D84D06.idx | Bin 2070 -> 0 bytes .../index/utilities.cpp.37995F883B5F548E.idx | Bin 5832 -> 0 bytes .../index/utilities.cpp.8466B813AD21AFA5.idx | Bin 5560 -> 0 bytes .../index/utilities.hpp.62390E5A28AD6DA6.idx | Bin 1768 -> 0 bytes .../index/utilities.hpp.F418EFD6A6E9D646.idx | Bin 2284 -> 0 bytes .../visibility_control.h.F5187384E0A565C2.idx | Bin 326 -> 0 bytes 25 files changed, 0 insertions(+), 0 deletions(-) delete mode 100644 .cache/clangd/index/abb_system_position_only.cpp.A4A69E936E6E2EFB.idx delete mode 100644 .cache/clangd/index/abb_system_position_only.hpp.B82A1AE2C2DC8731.idx delete mode 100644 .cache/clangd/index/mapping.cpp.53C83202D804659B.idx delete mode 100644 .cache/clangd/index/mapping.cpp.981962BE1449DDD9.idx delete mode 100644 .cache/clangd/index/mapping.hpp.83C0C81544CCABFA.idx delete mode 100644 .cache/clangd/index/mapping.hpp.F4EF52C8E9EA4882.idx delete mode 100644 .cache/clangd/index/rws_client.cpp.B2625E19C4ED09CA.idx delete mode 100644 .cache/clangd/index/rws_client.cpp.D2D6995B64F84F58.idx delete mode 100644 .cache/clangd/index/rws_client.hpp.3738C46199137910.idx delete mode 100644 .cache/clangd/index/rws_client.hpp.F6B6AF448BD65A95.idx delete mode 100644 .cache/clangd/index/rws_client_node.cpp.3230C9A14C046783.idx delete mode 100644 .cache/clangd/index/rws_client_node.cpp.32950DC259F660B7.idx delete mode 100644 .cache/clangd/index/rws_service_provider_ros.cpp.2F7E35170D7F40E3.idx delete mode 100644 .cache/clangd/index/rws_service_provider_ros.cpp.F36FFB6C47C5231C.idx delete mode 100644 .cache/clangd/index/rws_service_provider_ros.hpp.11A527BD4315BF59.idx delete mode 100644 .cache/clangd/index/rws_service_provider_ros.hpp.FF9EC95DBE8BABD9.idx delete mode 100644 .cache/clangd/index/rws_state_publisher_ros.cpp.1AEA19B09DBBB081.idx delete mode 100644 .cache/clangd/index/rws_state_publisher_ros.cpp.8C64C24778513E26.idx delete mode 100644 .cache/clangd/index/rws_state_publisher_ros.hpp.10B80F8842563FCC.idx delete mode 100644 .cache/clangd/index/rws_state_publisher_ros.hpp.87F144D7A6D84D06.idx delete mode 100644 .cache/clangd/index/utilities.cpp.37995F883B5F548E.idx delete mode 100644 .cache/clangd/index/utilities.cpp.8466B813AD21AFA5.idx delete mode 100644 .cache/clangd/index/utilities.hpp.62390E5A28AD6DA6.idx delete mode 100644 .cache/clangd/index/utilities.hpp.F418EFD6A6E9D646.idx delete mode 100644 .cache/clangd/index/visibility_control.h.F5187384E0A565C2.idx diff --git a/.cache/clangd/index/abb_system_position_only.cpp.A4A69E936E6E2EFB.idx b/.cache/clangd/index/abb_system_position_only.cpp.A4A69E936E6E2EFB.idx deleted file mode 100644 index 137851f59ef1e4463c6ff627a2f22bf95f62bd45..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 12386 zcmd^Fd0bP+_P-OZ$Z~Q?fUe!Qfpf&wJxpJ?WeYC7puRygvkxH_OH=1MZt(n>=KB1MteSWD|=BtZ~d^rzEnmDeoM4f7)sDYVLZS}Us6DClWbAt8il zdU9S~VUaW`J6oEYC(X`GW}Axgaxzn-(`Va2&G3uhM=rRF@`UX&q8 zO`2}rK0P%psW`hxD#&h+O)C^Ssl2WZy;hP^ zT$GtzC{4{xO3qG|8XwNg%}PySozl+)@><2H2DwV6t`e)16=LIESU3!Yp#z!GTMfWorpDcdNG2pxJssyA=t@T1`Il_ zxI(EG%aOsS8TPTw>U?dl9!unG)8HWBr~;; z$k%Ebn^GHTd8pZKY%KBnhWZB`Ny*8D!#K_#S#KU%ZpMhIqvzu?W3hThC4=!iJcBJ(@9lIogUe*90`7y-72Y;u0n0JR?2uNrCJ(FAmB3?uSd#d z?iu$>AV;YnhMgmddQG(zT0juC6Q7R`JRNtF%b7BnfW0837l?(^?58;qR!o3IKklD- z^ewo)Czr65MPFpS~9L>Uq{77M#V;J8wN7k(P)CX@x zAL4StQ2!c$ey0j!9b-LABc51W-g)5%i;pci0mP%;QghtUkvya3q#fZGL_nSg&u92T z5F=bXo7r@6+56F9Tuumji^@wCC5#A<$TYp9`(pCpwI5uxvLjF$@Q9W4UbvHcYzJot zmlJ{J*bhSXgHU0jeWJ5zme=kL$kr9DTxdu5BQ9L|uEODqiHlPm4asoD8V@cf7|qaJ z&^%Wd9TA;ldR|Lc>M8;WVw~>8g7ffrfdvV@qP(IHL?3>Rnpq!8LT|Bm=$VpZS2pUV z3rScUTO9Xn&G{3-;WGorEfwYMx%-0Ll7d z29vN3DEKOHe-#8^%~S9I;2i)yc;&bq*o?qoi2w4}Ep_WG?W)|PmAgF-A%;bkA}joM z5|;Xu`mt1bR(Uq2?EgN0=b3+XJq9Sa1z2tYPDV%(ghTmDWgTz+YmFTR1@VF`Jf4Cc zwjORQMuppj3)sGByJ#~i-Y(vZO0r8bqjGI?&1RWnH^;1xwx!Mbs;#Rhuy5E3 z?6v{{E4LnC-2*0InrmxUa95Rg7p?68;2r?3Sb*Gj=B6!PrTGGN1Pg+vIOYTnTn-<9 z&S|T|*JTC1KcQxRKEDjVhIf`av>|5h3_!vP#|kIhjIEBt838Ib5ORdZVD_?KG)5oD;sC}q6Zl++QeWZ!<`ZA(x)~$gDjwJLYeYtoL2}3v` zE-V#h8D`>(gi)4JW>lPIoEep9nP^6(ankJAS+dD&lWa*i+j2Ia?JKt|H)(-{3Q}P< zay{Uz2Xuwtxx(WJa}0p6ty9Cw#uQdMaxYArz|JN3?TtT0DwoF~*T%pGkEWne z{VZ)%KT8|c&(cP9v$Rp&m=?8(-`->+uo=Tz4I^UvBMPjqk6{r+xLY@^elUrLfXXNM z_85{BN=t|}z#ii{V%kxg&znkJ&@fj=*9kcAQ*a&NtOHh;dRiy!l+`;$O`B8l%?kBG zWDmyd2!kyqhnKbP`HEkW{cHzr+u2YOJMrd+HI}lQm2J zOYBO0=e+ceCubj8$+#L@%q<1geTh<+0Cp9ho_XVPE#_sYN!MI-hkyKGBsYz&>&8Cc)){-G0}) zcR%yU%?7quX^Y}+eaJN_hlG)nBSWz9kT4-IVKSzqJ9qBeEty({Owo()<$*W06fE{A z_QqS;Cmuh1|4Lz76f*H<@8(c*@cS$V;TZfBTmdGo01)@%U66@W>}0TS!2@Jf#FLlr z5aKZm^NP|1sTaAWCRzEZ2Y5K7Xr>&0L;1Hoc_>JT6U3>QrMhaBaKi>dk7U)khhec}Sr-7L>pCexx| zy<5FM8%34_!Ez9Yjbr|ej-~Qz&cC3UHNKk3?64N#+X5!zVGA1ajw<{cZrh-0i@?K7 zW_|)cGb-FO+y}Em!D!EDGb-LQ-i%7}OfsW#1-WLk%<-IK)<+9yv%amsb1U${Qf{_A z_J;S4?@y0dtn6e!7y03vYGc&%l>WGB=Y{1*$>AKt|0&Um*BzFZ7>g05Cv&b2w!&2; zWO5KndG59}>%&$OGC9b~t4|kv+3I_k9Ntx)x)4s#&H3v|$RyggzWHfFZ<~+SSd7T# zU7cSZ5)@%fttYnK%PPL}I*PeW>}=gza`R5dq8sGMZglEk+3ZiPLf^;5h~26;W*7p_ zb&=4x8-4Jk|E+HICo9O2s+aQJ$8T-DTB9MMad$e0E^*dad=N}R;?8J<7$$&Y-?s2d$w!}g51vK2MsY@QCN|`DrN`ZEE@48e-zEm5>n@`!Eq}F| z^2gPa_C-@S?w)sN?ilv6?c1Io(meIuAgYQ=;w2KC?~za)u1>}o9*J_gh{YfchqaD; zMPZctArXl}q^Fk;8zQ}V-U3|vMQ&rN_%YT5izgKaVBN1wm@n2|J3SBWAjQ$*80=d} zsBzJ_4mDqc&s^TOnuK+(b-bAZ@`tvf_z)7#ufa|@=U#BJ$ zhto;81h_5%yc^wZrI(kgz9(TT;I{&|9sYEw*K0ZNV`qYLb*8Y6GxfD+gAXPCW83AC zX%f0-vI zH>TW+7~JRRh}@naTTsZZz1pqX%yIMpw;te)9mfkh4{oBJ^_^oFgq^V+KgM5*aY1U` z4tQpjhE1m%J>Q?X;35*Jm#6HKTsu%!kMcy#RPG06#3} zmtK}h&gy&LMICE^WDO|69b3{;?1dY@b{@kD*qZ16G<9~?6cl;|?gF!TeFWqj0cGd? zz18i~)0NxopKoi)ywrw7C~_5<5WQV_!{T=0dqqe~5_gFo_919j?ou)l@5(7y5n2(8 zO#+wy0X`qV!Qzz;k0Ghc32Ov}Lia*J-;i#3`A~W5o(XYuwR~U?Vz3|Z`T-v&FBCio zcn1L=pI-FF{^LyPy)y%7V5DDU5Ply@0eunzFog#rZ(uwk!~S5e%r*7B`*&YQ3oPT7 znHIRW9fVC8I9rRF8#5aVurt9GH4B^JBQ!RX+yMMHfTNk3Qh{n!ly(eY~(ivV*!z<>cDRY z!8mopyBxe9d-Fkj_|>qDH%C^67i@IDEHyd>cyw*xEm-(c_%|yOk^Ia9(c9CnE2!It zTbW&-cjP2?-h_z>rUd-$?tHafn$;4dlnQ=@DUm(;KeImi=cn8HP^9YxL@%&qan}#5 z`+*Bf?+3(wV2h!};L`daaKZG^-LEWg+B;`D!sR@#d1g6qEAVOs{#ZiqeZI`0Eb=Uu zL0U><1{UOd-)&sD=~C1Qw6fBq(iFUe_g9|ri3zGA#<1u5XLilwH&4ywAjyob&K*np zG{ZSP{w-9<@-E7gEske=P6*#kcJpecdfIZgZas9c}Z@=n4 zi1a84ki?q#I`5JQ?CU;~Si}u{_r+$U#Vl@?>2Ueu0cmDskA@z@>N=5i^~%cWPDjSD z2tJvwZ+kOleKyLtN1vCNmpSp)3x@{mA5g?%KFPrG>a+Xr#;N+8HjH6$4o*Dp;oiTK zIpxy(>4OGCOH@Y=bp4%zOM%}~5acR%aQ-P~UOJZ8cywmwz!zcgn}4rqHGa(ZVD zl~tb4?+ly<`NvaGe)E*|Q*IbbBwPioR{;UW(p^=`8R?VGPd@~jpO@Y0 zxDHR}ktB+ZE@;z)0Z*c{D0_4q#nLD+qT?uR03`Zy$R2$>gbm>5Z})GT*mPwsLLcMV za7vG=nWzYbsb4O>m?a!K!URx5h#`#C^D+>!41{65-dl5g@5@E71TZKNcb1xcY>f)EV=Z^mGisBSwc7dn= z=l}lld!B2%+S}S9xd=TOY2PaG8k>#~a*}^lQ-q&wgwUU5&CP2Qs>Vy5vMOkT9P5aQ zi4dzq23UnhYLdN-y?{8kYSjpEb&aQ@?1B|GXt`+S&fry8NG-I-ya@O86ie&MbTjC zF_i%o;_5<9?2C-+-y=-P&=*DjL%@{OrV>z9IHNj6R;vx--tkQ+bP}=NFV(%HMx!`NP?z5z>&mDvXXd!lK!5F^*%tUpXW4LL6WS$ zd%_V`W5b9L`XTElx4cdZF+oEL&ql~%Ku(7SQsiz~e@Phkf=J#Q5nkmKA#V6V1ByV5 z)r8djDuqzS&L=vK{rwi_z$NL34$TNv7z@hMUy0<&DSad0`C-X*C!U>->_e1yh+^ml zM}y1Mn1A3LyJ-Kx949U%8g8F^FJ&$G5L?OIOxA@Ej7MWkE}uv6%7|8|qu{ zoCgZs8u*B3@fBNRw_5I6l72`4^CxqyE#q%mq_IQpIP4S0smSnBm z>Bbm?#sYdl8EBxr?TKGsIUT5S;!F}loGsSU{%U`_8DZ#`TdU6=!AG39oXAg5-V;eWJ<#miHCW=rHsWF1nr+Y00e@hXDIazp z9eFXn-xC-nqsC8Il?lzDMQKtcg&xF$pk)K~UL7`+=SJ%%P3DPkud^W~V(} zo=yJZ?8NJL<`mlLDqQ7+(b(xA4mzRHuETjF8`sReO%bJ86_XFGi3YAeX4!{F~wtTlIdUBsD(Llk75czVYj_Mt7LmLp9X^{?#%(2K~i=1JR z`4*XFk=Yh$o=t=bEUwEU$?qU|3V|5^Ih5Sd=}Q|+FK^j5=E};>DJ*i&D4v!ZZaIJz+C23=fy}T?GZw%X~OYh)7g?6kqI+YH?GylI9Aw`os@_#Hx;?TsD0UEtl z(U-16s3v-NoKCCg5)-2g)*04E6K&AZ`xb~N`~R{+?-Z+Vf<~XxO&>?rSWi|yAwi>y zF<8)mcUX{s?oA1G$#JndVlKp%-eO3vI~y!7Ww<_Z46&IQUtfKyE+sBO8>Q9j6ZML? zVFue{1H~mPQgtJBiDQTz|HA^`IlupbOK22Er*Ml;)WpPSQZ#M~`dg8bmZVh-(;u?yL7BiOpam<=z_eVX#JREU*8ZiKpf0i_nggISGwbf|s{x&6s8JJg3g>Mt=0~PpI!QNEge~~dMF}d2BBYoed zw%(+vT4qvR1@%Gx8W@T+`LR9i=E>+COpl*`d zg+*YnE=8*!ris@2`U*t&w-Mn#&(LJ`@0uY=?C+T&zhcP=QKZC))4k5})t}pFZFCAL z`$*NHA?2W+?me1oy<)u-!w4Fm7#m9vcflTpr+*{d8fwYc91@L1B%z=i7-N^Wl%1^L zq_lMKVVbyjZOlK5r-Vc*=Ko1i*}Umz-o7NmCZ{NPg&V6W@>@{+H4~PK6Wk^5>-f5u zFmy9kARo|)=2Sxul7c^sTx+7&en1CP_%sZ{;_e4@G=&R8M;2$^*6|I4H7HVOwFV|a z^A|HBExx{ENMTEMOTNC;!&6CdOBon;-Uhq)kRGAbjQ(XGLkJ6E8*O7}V~K6reMeOx zfOw{(- zZ<`W{u!5*+ppPI&0Bk2{N(ieqR73PK z2C7bUyQo$)GroxjP8IL64V!jK@vo!ByZe}ofh0YnF}#~z7$e?GDF_emrWGid$iWo+ z?mhxtlRiw>RrLAS@xa96LqfrOh~JC??;-!-0AS){ushQsfynp8G^Uj%mifj?8+Zsk zUfh$k2%KHq#yhdm&)?Q+aMCv#Kis?j(Xl#?EoLGxIe|}$X#^%FaAy>qwO5);UQ55`iF(}jfm-Q&#w6-TCMS_=i4@9le@$}$F6{m}iPmR$^ zlmo~gO?*80tsR@9*N}h7IdzIMSsOo$JnIsbsk+o;ZH#hQs?KoKDgq6s-&#_L6ErE2 z98eN1YxHp`!^yi|8tW_F|OF|MY zQ4UK^BWLAfm5I9eG>I}UIW0Lwn;=mpN|fa2Juy`utyRXv={t*N??s~Yu((*2ZggCN zDk(lSHdY&>8km?GkeHAZPs9t=s#1o>>0_dZyeVm_wCIEw5fB}((Z#CbMH$Ldl&JiOaUL<3f-?xCr1@iA}c`2)Jek#dwQfT1HTlW09^TAufh`et_$ zT%yQ{vnE!nuPz&+2qH)|Wgwl22-WP&pKtyr2BH*HT~2gs_-_~ET^>iy)gbOKWsrFX93Q_ZBepN|cZb zqNtFtZc(9KdiM_Q)lEWT0l5XB6Y=#WcS-SaDREj-TvJ?hlq}l(RNZP!XH~b6g!R@2 zZPhI-9aP=Q5`myqw4}biZ|*WA(Y{Undijxwk>5m5etrE|lCGlZ^<@6pht8x*R9gl7 zwgU+=wxHszqN8c@{~XFRb5oOGp~%$8yaiK>QoGPulQ2a<5-OsgN>U1V-1y$hE0eXQu3^zw^}iXJ=G+ncP;P)%}NG}%nj za~QQtfMDH7Lexi*%o~@IEN&1iXaHHzV978N1$X~ z$40SR*6ON;PbhEK2v0*5VN?*khOdqm-j$4Amw#_mE2jMPucr8}ao$XN%%o_BV=_d$ zw(=)`R2@{w#6Pr}1e4*tg(@XRJ2qOIl=5CW>TD8{BI#eF22EB)E#0_(5Oj!hI0=!X+(X=pIfY;mkS?kBC|%vyx1QI7uc{fOQ49XFz}J{_c|6HT*qmX2TZ% z832wI#fzP8bhu(AnQEXsjW(yTP6iwRn*&gX(0VtNehZ^1X~Ty<-udFeHAhCe4r{MN zs|;8SwHJdGAyw74oDIp8)VXEQsr|L*`!do)Xmf~i-3c~34P2EDW;0?}xP(aBPTJ1d_*){O-|di}&S~TPw$@f%V$5HIz~dZv5z5w1vN@1SNr!a%y?eT2jR}l2oik78 zEHmH|m|p@*LfXa|=Dk+>m(FU1+0oB!8Lhv$KcVbk-ht9}cH z7H6>eU@~t)P3PUISuIAl?x5}Q8uRA-&iECfO%YZ1aj-dVPCl)^e&lYe8&4_EdfxHzg>xn?tq14zlyaQ&I7-*9vH6Ixl27GYTSQub(gLiOn@^c!p*jouFea9hOS|XpcsYu; z%;3CdaGgvsqT|iO(_^x((w4=jUX1-%AM1M-KTYnEI*_)cb4}8@7Oao0YMGoe<@PamR$7A#sSql=^GG<5ST7>jAdfi5EX2A77Svk=5 z`pO=ZNuWH?g~fT6IXS|@m^B3~e!)7wU|r_Oq~{T|KZ1@dg*uf5XYTlM%Y3SlE8uVi zoCIF_1OuO74>mmOLM1h3T){AB(cvsMV3TQNGpWN@=Etv4uB))lDs*PbBfw#<&SB1( zWeUY$kCiUF_VuQuCE#BIJp}^XNBMnpWdbNpoC^tUzpe$1HA}#G2{f;<>`R9qA6(06 zJnHP^3EQ25sAg86dIg$Xt?^F%@Y`Q>%A|c(q17ssGD%!IwojSuyY?9!I0r0pz|xeq zGhqYDH=q+!Y*YVn4+2{FkD;Usq25Ap5Rh&}i;ZZ>NL{VZh5z~U#x_)vX{esY`>X5D zZjtVJPi9jlSHa;bG!;zrDRz2_!EB<D6sO(u4uu&S^-c*#qu-KqUxyg(xjVd$yR(r~CD|K4S1e zN}3N%^TA!SZ#^s(OMY))&s4rkEz49eXb z?AuMzPpt#hRhvJ*%v`X5eyONm}FJ-@G++IC4?%O6f2`21x0W7_f~$bW>US3dRYx$Vz$Ni9o1 z{@K&JuyGB-z5rwe&``j>5M+fS;3fv#HgQunSuWdFxZPUN))tT#0?y;Rhd8MN|9mAP%bZ8VXu+gl-OH|Zz5ONNB z3siI)<+oA6R>0T!{?U=OH20CP-_OeDA(N}-3|2w zCSHKe3Q);Rykp1+b@;(85=wd)q=&&?VB#0i{UWNEiL(s_ErsZA!mx)BY$Iq8Hf|vV z(QysbSp#(i7PuMgH-jTvyUs5ZZf8`t$I{`iLZ_<`ESUdOba;wQ+5DN&nvr3QI}pJz zh3Hs_4cVj!vy13>5gRhm32+G=FNuIV=z9k{Gwy`qF1Edk9R$D=^mu|^4Cr$FWqk6g zhNGycr=itp=qwQR2Fh-rGb0Vi`fKCC9?iy4(gk3#KonrtqkKIdU;`E{JaBA7$GMbr z4LGlX#sXdKN6Y=Zw+37o`&ZN>=TvG%cR_s@LYWn@m`qo|xZ@J2W;MuGLp=f4O<=!? zUxDt0s~aRdE%=yP?P1R9FehbZ6+Ea4Hu6FJ0h(J=}?cModg_*c?=W2j_?>EeARjAgs*xJz3}xjkIyEMwLLLdt~vP8f%@R%k7W`f5|5ikcl=I}rt$yC4d4az>|$Y8s`eit|ieDr5< z_!%0p@Ifd}qw+NRF#GQF(UvVgdJL~ewRHsCkAOIZI{<1jy$s^SL^(pj}a;wrSTQdYG@Q zH+G$hnqq`J!ky*ih+cMXf6VSwlj3_h&%InL#-hJw?!YxmN_=U{Z=BU{yqOJ{+i97u zVQvFD>}F`T8QcXD9!2RgyQBxPG!z7Vlx}7fy?@pe8{r*(#IQ z;3mPs*U%=R!q@O7;lkH`P5KF62R0dKdi~V-^0)5&9OTq2bZT9H=FEfR;%BY(JGFx1 zhd9eaytxe4kNmjOMYo!o%PDAoN|Z6KqwG4LF$QPdem?2d=E0OnC8#T*FS8CdLz>Er zM^7wZvaKF%F`hJ;TJlGi^$M9Vn{xY1{aGjr7DH{yrgVK-bdcg9@(@$Wstrnr@;#d~ zi3)lc+z*SK^dd?x@=iLee#`}Z^P~HWE+E|ub|M#Oc9eJ0ShwXvr*{v1LPra46&}pi zBv#YXa^k@@;S~P@J-fl`n#_hQYxSew-!gkm3>?L*7&$9`|ND6YS2Qf~0lc7v}(dXSbOjfXU2 zHcVdAnxwh0$&%Lv;J5&sShglW4mjqBfQ8_=Py{Rm#Zqt;D0>+wmWhBoP~?e#<)BzD z0yaYPji3~m)D~#EMHFVYLes4xU>h{uCIWVY*KTMnNKwCn*RRl;shZ5?5O^K}Zvl`G zE%HT1e+qh>5|s+4L46tm1S?wr5d|<%02D%>LKq+bilI-j2q=M&5|K%lLhn-OC+JcJ zL&`ua04{<5CFmvqE<^Xr5Gnw!LXWE=Ny{OmTr|phv|5jK*xr{+e*;==5CI#}YNH4^ zjCBuVeU{5emt$ym3>^f(akM)w0#2aa2@z0&4kf%j6CR~luT)glmZ5zaHeeP{D6XUH zb!@@Bg#b6O(G5OG65uAbxQQwO#VvHd#TULwKla=8u=3jl)ECc#{5&WGnySE%3hd4L zCY>5I+iFST z-jc5-P|;3e?UQKFOk-?k$za=upBK~dW}0Z&o(ln2Jy&zmtduxkpP zL_XT)lT(aln!#5z%}0&0>_3q^IBlFcRrnmvdk&{&b-~2cSBHwMM#RyU;8wxiSpJ<@FuwlS zkl$=5{t!GLf+=-=QC4wm``Evp8Rbx}2OohPhp^@$v}VJSzWHdDk5Z;H#+_Cp^e&6l zA{ie~==agLZ8Pa;{;vL=7+u!n?jwIav)0jyC~iC2ZAUrF$^_Vfb~{ACPPE%80(PO@ zE)j4KJ?`<>2!zLdY%7 za0kQg-~hI!gyJstyo-GWz&-4A4+90jee7_b59*}L1MK)fbWK@_0hRnH-#-c)lJn{0 ziBx4H)FUF9))$Wn{lq6MKG1^TnVce%Q!#TSz*J5#RRql76f;D?98NJu1mtjv98Sd+ zitt#>DHe->JWi1(0@iSfHJpkC1kzi1{DC8y%WD@1= z{nEv$RNax1ZUmQ&;3mjqhf#VMWh|2|-+%d=RowXYRQMCn_XG?UaJ`0&u8Atra%^0V zo~#i2;U{_HK-tcCs=F!ZIR#Cg^TWlkdNw{k6w?@U0Baw>I&4$6x>Z<(qh!TJ+Gh>t zy@tPkTw^`!)sV?ShI6)Tu+IiZ!TxJLILwCz?B1UAU5Cxrp$9AL*Q~r!e7hu4ODB9D zLe7g$=POWN!Jp2rO}o(bxi5W&*PzL_hcT6uO`Ph0x6>KDes#=gI5KO6he z8N)S6K1lPSt{@haVT&?;*k9D)w_Jh}vW?RWDT64{H0722PVaz6aA#R-E3NTGh=8|Hc8doN{t(goaqWvLYAw4!xeI&*mB?wVc^a)*5l<-2 zpxGIevWw9CmbyU;BS$WzGGBuBm!OMa+(+o}i1)L@Uwt)i`w^Q(QbKwceC|RgmR1Q+ z2|kq~;0gFV5dqJ^=eY=Y1wOAtKsx%QqmXG9`eccKY3MUe1k6OAnId2g`pgjl^U!CW z2*^R791*Y>eHM#=W$3d^1gt=x6+CccP;_$V;`<}0%JzVC57-OTU5M_5sAB3q@^P+h z@WuWwDd|R#ZUmVqY`Y&uB@5ffPJgmvQ_oyWN_qk07r;}n5O*;04i0AqaD0;MvM2TL z`ccwyP?w9oUU-I%&-kwwj!*Ji5i{=O2I`Z=Xj_bOw&i8qsiPUcY-5ggrdH&z($*`U zQ%{)6c~9lP@hPZP^J>rj`{Z=sUqSjSf8Ixc67(#=)+}@~mCz7s{2Y$4C#2*%!*k%x zBq-PuYrZ1d?+42D9LUd!cBi*7kRh-4|e{KTG zbsIF^COT6%fzlKFnF0#|R2B3?JI1ppJh)z_SC`)?i$fqiB#Jnt=uwK^Y`VqTij!Tx zOTR}+mx1*%kP0f^9q6H5w=^&I|4{Dfvdp#{6#xE!@8_T<6ZK6F~8ATI?sw!Q>-fPoMA z%Zk9+WH7ru{{kuLjH2U@J(Szo7Fk=)y83TM>G9yVdYHq(Hs=dqK1!G8zQXh0SxBy`nLeTfJ&5A z^1vU3SI-sCbpDR&Fb}NrL^|AwPCI!W-ufo<)OEehMMHsvR{O9nyREpbnr&qk9Bl}n z#UL*h6@d3J=pKf%HM_m{>)j!LqpCf8*A9?hqekeRkQc!Cym#1Ow>@>FN4Ena1ofwW9;}CyRl&(_Nc7CxxCh2lz9&4 zox}OEVIQ@tbLRM{fjcOZD-d`EdI*?2L5C;&jVSX(8ctUkJ_%;7@uc2-r@XZ%lBjC7 zq0KgQWEWLWUAs51YE)#nLwf<9FTiw%_H@LC4Kw;qHMD$-p5O8pW6$z7xMlTk@Db&9 z8EaqWFZG_ctZkKUzC6xYskq&R)}l(qtx^O$0k-Ip~%n0v4m&ViB+m-Ij@f73j8t2cD~=&Q0p( zZul~8I(km$w{tI-2DDJLoFz4G5}i+oww@! zx~E}>TL?jgqRW|ED8I$uYU;J|8v3mg`F}LYkmUaXKG4B~ diff --git a/.cache/clangd/index/mapping.cpp.981962BE1449DDD9.idx b/.cache/clangd/index/mapping.cpp.981962BE1449DDD9.idx deleted file mode 100644 index 4fc9269a078a2e187c738db064b1cbc90e43a685..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 21854 zcmc(G3tY_E`~N)82c_Gjk;0TAq|20$OPGy>6j2e@8ly%S3KWIYk$*NQsG0?y62!L?n(sGa6li0HdPyuLWkj*|6hxctVx>iKb9k5Y(jFl zMyFMT(sdZ9iHMGg*D88NMk)j1_3NXF(Cg@33&fNCe_5foiWM5C(IxlO#gH}Dk(G~& z)5J&WEhzjg79^m1Rl@kBn5cMSF2t7JU`REc^_G_$txK3pY$npjN0$=-~YfRGzx=LIL9VvA|o})8fOLlR3xV*Y8B&j z32}P&q(<;I9qSU3)QkaLkXIC~o1En16GR5+Ls{4EvUJqf_4OX&5xL%Fqh$QIiKiJm zR;|+{#zd;)lA`{#qzNR<#V6NUjfU=TQev>4dEHd_Cc)lQfo~M-RrUQF850wd>a01^ z_f2XWOq%LscD2g$o(ij7o>#T?Z$#7n8(ryhZ*7iBB+}MdTeXPv{_3htq+0YVgkuceWMyGwfVxLG#{Km*eNP242DOOysuKU5q>~fIj{jGRWDIJNRG%usgU61q zyCNC)IxCVfs71V26l$ZB(2(sfJ4}^UJHAOxJ#a~-tsW{a|@~)0G z#e}|_p#pi2PBf?Ldyo|Te&kvsz4kpi7{jN25EggeqoXlg=sU7F^QMlk7_45ALaWs? z5t_f45oz)9nM?{>vRm@;p&p(>id)J+zw_4H#ryOaNX_UU_R)thf40#!bT*XO#@)BN z76HT?g|@=FT`Z}d&}bVZ3e;vBdLn}@5Q^7qfi=^$H?+U9_Id*SOa`UIDcTx#y0yr` zle}q4B*F@!s-8ZK909zdpttnaYp`aMF5o1#hF5}NEs_chmk`%(xcXTO43!YpZm9a` zWe8L~=yp-1Xlr;951b<2W$QQXl;R&pi?{bN8Usms24i?Ty)Z_+lTr{K-cBn}Fp+~P z`0afJx+Z;?u50P@kK=)n$NPkWcM!iC1>Qma-T}bKM{jq=LjsZSi)oB2O)T@3mDckR zdc3$NX%RTPxQ%yWgP*^tRqv#)G`_!gzt*uXjxA;)Fgbxwi)jQVCU9pX%^N-0NKu;; zyGWGENL|b%txg%25UK4M<>n?)_URoQ92%zX6%?c%6s!&k=*>f6!2<*Q)O|(_BJiL< zBOc=4&wu#qaOjB8F#mzC<6-?n{Co8g;(h%4_8J-#rVbext_~PDILLpX|Ddp5VFAH| zdg|gPt0U4PViU+IUu2RxA~BH+8{#)KEFdUU?LVkj?;wA*p>x2X0selpk3<>Z8J!TP z^^DR@8LQEHPEOEGNJ=EtuqQ2SBDIs$laoA?bP@VTQp|MFe~H%UA}5p6R5dwDG!)OC zG4TSSe-Hg+8O9-p90iBCz=Mk>dp#Ose-MWFr^ zTuXQoG%-QXU8&KO@7+s{ANSd7HnHCWjDFPy5HStlNu`y#k4d1*v zc(nIuFCh{|_Kb>8adY$PA`uN(o5J5sLDWq=Gd5Pg8nh;&#iwx%-Z{W)-AN=-ljCJg zlvY<)He}93kUGjhIujA<*qJ}f{8tP_`KGR%=sxhDF2?(~7p1A$0C`Zq_Do1j_9Xu3 z8KsG(5j=tyI3-D^H^A7~NpVWA_MT&7;tj^AqzPI=E`QWP!Tr<&dkr2OFsPq|_&GV@ zr*ixFkb9!onB*8ODV!-TIwlrvY-(>cq^jE6NHTh3gSPe-7V2wnWkFuhDq2AwpI3Jf zk_eyHzJq+p#KmM)30M^qN2L@)Yh>p(^wt5Gp)XV zcagan^)6V}cd?>tGRRl0jz~@Q@*=AL_izR!5D5RuEzeVp^Uw-RR3gk7yEz z>M))mUW>FxLs{)Z*G5dG&`Usami{95e=JXuZjvWCbyO!sso4!`T~)*9k2h~F zk^ZSB1?j)jti!%&4d33BTSN!h22vIq4Nol8N%T9Rn(=F1F_8%OKIE;Iw79W5IEjQa z=^h=XULmuP%z<%|Ot=GSmPk0io zPGX}BH~>}$pb;VUYA(%!Bud)+@%nq8KK#v|k^X=Ue?W^2_!=614Hksdv#I$4NTj5W z?fp;fZ+sf_h869Sxrn34K+E z{Pawl;=8?}=OxB$1;|%GiwuaCN4FrOc5P)AJ&AJa^?ksi{73V`7+nFH6`*AXYzDK< zU`Z(3H?v#_6DeuG-gcu+GH!ptNVB17HpnwT-Bc|ngx#DhVkT2M_0i$mu}_~QMt23> zuAoN-oCmk_;6W%mI>#E)%44T`VM@={Xi~76qIl173i| z3s4ZQz1(cSfR8EZ&Rx$}**5QgmT}GIOta~9Zh`47{dBxrG^r8bc-hw93Qz2u&Pb1e z>oHJfKsLB$gOYGnwQC&rAIkKM&x^13_G_@8QRahVKD5k$OdxCCl2Cr&Vm%>^Ql4|a z=j{XMjVj6m$2>|o#c>Ly>(bIRDuvP&SIWGXWlkh(K3hMd6w{Q}84ze1*qTsvZ&R;E z#PUBK=1VnCC$WL|f#W{PZXP(!(+}+HY7;w!GQ9r5fjjf!nyq4#ThU@GN;6`iHKCP|Br&7A=DG?V=PP1`0(s8D_ zRFzd=TBTQIX9d>CDbZ=iCEZg>B%n|ISQ$slguUpv7h5uOXRZ!r z%*{2ElBd0p;uDqa}!w<%#?0kR5c zVqC;bxCpX~BH$9pE{TB4AiFFA9$}|P*v05AneZ69JVqY@P>sIT=qCW4VAm(uodMim zGuBSXX|o!LK&#PxHTtn>)h|xJ<31_%8r4Jrv?~Cm(TXzR3`);nV-~|2n17f*|C6Q< zDd|tp_9qePX_TJECXCdiySeI=|KVUd-V0E@fWd4$6K!XOZN<@Zl*u>X@C~#u#-B{c zN6UPaG8-{(GOYN1#Ai8_$qZD@z!1j7eENm{EAwAYq%HF}uX$V#V|eKP`!Dk%XI-T& z%Tcu)hq6AF56m`B@0Buwwxn~d(m7Yw$J%~J{>j5Rzgy~Cnx%6J)!Z~w@mOfG}nWoRv!=o9Sm z1OwPa+g|zY$$;yTT^bNlUprspLX*edR=u0CbtjK~t@;Wd2UradJ`S=PBzz393Nb!9 zhbK-A|L+&gsWiL6WjA;VLS7L{i_n%WX1jU518$5TT}Vj}LhFOzB5;~=l$K*-<}@x# zgRHB6`?G+~J_Fq|@B^l8*B&40oX#!lNY~*MTAxC>OS8Q@8+6mYbPX*~{xxRtB+9-R z!ir&xKrfXjuf%ptFK(YbZQ5vY<^f8&3LI96;^q#t+`-39cbHeY-BlSvN!Nj59XJV+ z+s|nJGg>j9@RZn1`BT&A7A3t3_E({eK!B&HdWwNe0MBNnZHMo;pG9Y}5fmH2Jw9-G z{glqDV%mRq;=m^-GM~_vwIE*$t*?CK8@S`n`NZ}YKHTl@b+%RG%HCP*_bZdKF(wxXF23r!1=Uw9-nubwa>=YtkQwDj8TmV zWc8xABIL6^^=?0=(>)IE$DzmhqaRI<4D1o=?KZtsD(#g{TXunB7r2{S9_+N`X{TYG zuP)qlVvqG~$}1gJ={STLN4FM!BU*fZ_7WBKECii}!2%WCM)_@2uoduetU5ZOfu;%x z`@LNKy_^XPBm_9d)j!4qJ{_#GN;=;7mU8_Gq(4Cufr+2Swx?0aOuT#0c-4@?Z4yd) z2&9L=R$$^6(B%SpG81Qe30ex#jf8&tAlO0BAZ*w@2%_V9XtW+03oP(Qu>BG2+1mB| zOW|DPc{h~~e;ImQh5*6*pP=0nY|ZA+jMjt<*L)%s^(1sS2|Wd(UPsw=bY!G{ zv!4A}IH2tmO1cEhmWTpu9?J9h0PDBns{_Y2cVA3N*MsAFXerRuUNqm!d#hhb>N9n< zV+ysRN>Ek8KxRcOCesx#Y_GuUqCSD^pd@0-OvJ@X;8+C!YhAx_H7 zDqv(tlMAQ1+0&M@*zhbL7YCf_H8QWw$w(@68T2WGV1X(gp!@+kGgSm%xH;y}H4hUg z=_t2R9hn=E$CUOdUD*y}$n+(%UfO=SoRXD-yi^p4?ql!!d}J81;HHyXv;5%}gmjGC zm>vR-k#3Q~$7r``;bW{@tne|>Em8QG=9bojNkceKb(<=DOb54g5CSv6ZH5S#18#Ff zzn^kZp zExHNS)?sit44wj~tw3o7U(AIJe&%?{&Rm~+w}EsUG-9qt`W{2)W9Y)dW@tnIf;g@9 z0?M_3t6#vGGfN=ALC*Xj*9ew&DQ(d??YFQ2rfZv|=6O<643USpu)G{L$j13rR*(7= zFW}q@xDJfPFwNo-KddVEp)J317Qgal7QVR0H}TC^HlxG-2yK4^7lDMop!65CVG<5M z|C{y9ztTb)5z=GO?HCLZ*xfy_xd*PyB?!esuz4r~o`B605%3&ro{NB&VDnN0WS~t3 z3YpGCo0%eDF51i$0SnM(fe2WHHj6|+Hriy1fTd`&R0OO*n-wBpHQKBe0avj86?9-; zMrL~zO|D{#6;9=0J(p$pj_4FPyv3H4XQ}UQK=Tb~Q`zYQH@{VfZjbbyw!bXULSJ;8 z0NDvqF?J1A*D#oI9kojq>t^jcgcf6dt^C@vRVI)9TJ;k?2DScj#j+v?F4!y%KgppLED~sOIR3pV8FNSskPp`zVN*u%1FfMz%y-&I04O$l+1lxnqgatza zlwNx1ZaKOwvtjZ$xz%K6Hd*qx1nif91IyL~ z$N~Et5wH~Omx_RupjZiQ1j=3oid7-3qO@ zihymcLnql02iVEMHnam zF2jJ!B1x}8&{feWd1#S`jo99oOn)Of*rZHU)|R7fIW}V!PbjWon``LGyoCVQvBh;hND|;Cy52-j z0mUtJxy2X0iR*{{^!U+#mr`Fm2l8{E5NPTS2HnBItZ(9}R7BK!RqTGJfO{KnA4XSD|9`EV=?Mu$I%9PQTT&`6v=grQNlGYdPUNn2mRLXuI z*J2;%#L5c-9O0TA;hHfZ=~#u^{C4@(l*u6ZAY)WcX}o=W@Ur2dG%;R9Iw;;viZdB*$27HKVU++D)ADAH|gN zwykbZ{Z@cog~*H^Vb@34i;eqn<_BKiKDzcdWpWyup2jw;^8I+mp_SPQw+>MzInX3W zw6))eW*hmf{l~X&9e6QII)N@l9@yrAgCGKK1iOvUf*oNHib7NtqBm3c)cwD%9Gy1B zlqx)n^UC5>tS*?A^7o-qi}5kErC*1B{aF5;cIM-zsX-^LDE<)KAA&J;ep*p^Y-j4T z=LR{HdEhOOqY&#Cq9q%a^gW0s2T{s&#<u56tM z@Bm#O@K+H8sKO3a*jqsH2%R2bM*;8{+djt50^kWcKjH5;2#=@O?kPVC%coQc^p=h( zVb;^a-@}IdF4tvSlbYjFFk33x=x;*#CVrzoyUJ7< z7}cqRA-qVpiZ)_L(fKG}<9+rpD!g(;S3T(gXnO#Zf*?|g(o$@~g2?>GFY*F*U3a2f z3qV=`jRh(C47NMNpY$x4yD8PL-E;jB;#KH&Rdjyw6lG7*j;+ap(|F}z++BU)Je~8J z&iOE9E&T4>vfnp6DyN>g9~Aq+Jq-6t>IV#o{QSV`t^XN5@(68tjt!qV{|f z%IRaM`lhO;hA`zVx|V%-?96XTo}{Obva4Vx2t-e@+f)8@X7Q=8CmnAo^)+@jx@Ti= zR=6#`;=0#&&$qWJ^F5r&9!@r)ao0y)J*K%VS@hMxkI%NMNBwRE*sg%)f-353u=^Su z*daQh*otmj(TjP@(qpYYeAHZ~KNw9^B@PnUQWmJPU=W+bvMxjY;y>`$Z+Nr0R@t08 zv!Z25gP&*Fd{mDL_5|FYfG-pItDm-4=w3$nAKQ_yoDJ0}9pgY3KrC~RnK2!Q+8?LHsWNtXxM{ekG3vI_mG_)(Tu2aj3y(e!ClWznkW;Y{maPaZhRJ2is_suGe-i<<`lCmbjjlsc_Ls7r`W;+t6E3*eX6L}old2%yl+bun^rpo*`;_EWKf$w4Si2TsKDlL zqWmVhFa@su`}f(XsB|%u61MxmK@bJ@gWY~;!F-P}D@J88db6lJKqMO2Yq#guUtgQcG?Uk~-<-@gf!sj69oal7^4$ANFr}G<< zN*YAmZJ?l}CqZ@+90e1;j$N+sl=a$F4#t3|g%JJE6{e>=3resP+5Q{GidS_JYU(Z>1~ z2HxU*e9N-ZU-Pos^`vW<3%0q?RIn#r3wCRvIlJj06b0x~fJ(L=TZiB7Xx5w*tE6Q! zNH>d4G!A3i!+f^eTH3OE(Zc2n=+dp`yjF9)m}jzDo+f_7%QQ>_+dKcb-b&c2IN^L%fX(3XRo%|WgOJG0!m?b7TO87Ib2k;*|{4xWM)s=}ZuR5L?o z0?>gCuja6U3j!wHj0+~>6DEg2dRTN_Qh_cN{B=peq`;Tk>=X1iv(G^FjDHDY&lf{~ z^l=`#kj{8MsOFQaznT|q_Abm-cX02wiME7x2n}XoWAC$u&r?4r(qEGt1nEI&EQkf= z=vvMXyH7Rbwv&I{62mlu%0Vrfro4*Z=^bzj=qc-Hp*7sk^*jy!0@5PrQ3QPiz)h6h z#O6#zM8I1}5~L9*{4Q+plZF>PskP*TG9SDJmB>k~e-bTO5l<*ip~)$fvWw8e?c+y& zHGINXROSlkS^>QT<32*WN4%f?GH1@0JC9hckP^~L@UDa&EUglt3cRaCKs9(*i-2d~ z{Y(VB0PhzfARWEaQOI-#de0C6bI^N^2$+xF^F=@wdS{7%#pu0Q1mvK1jtE$e-pfV6 zD)e3@0@k4S8Xh<@G9syGS=D%|vfUuv4YmSx7okfLdNOq%`EaFmz{O!NDd{GVZXy*1 zd;g1^OrpynRI;#r?DVMoErBb|Dd~BTpC|X5?DexuxQoN@Vl*>=HH}UO65307wt;=Y0eyMfXzd$U-Mm2@Ro!x8WFjLV6ZF&Vm<{;LM&V z)7%K(?mjt<*-QWk0GbPaFzG0{lhbKr4~ zSKtU+xa|n!R(Q`@sZJibbYf>mBk-vTy*kX_}PBtcp6Bu zp`XSpNq!W%-#!Wy&PVtRb@>_0P?$6G3U`*A~u~ z6^PfS70Q)qpFN|@*Ma#uuok4wpV9GWbYhv3tq8rlHM|ZfQ14!Bv{&>B(=TZI3;zle zV@j{Y4ev(^`tAn%-O!v_A`#>e*dK!CY&i*V80-&=fb-yUUbHPNhR(&%O`yX|;C2Z- z7;vNf%PpM)Uii~#o`>P*A)2)i;4aGVqB{#0H^Jp>{-+N=qom(}(iY({A@0X!m2FukV9qvSjoxBcjFPeGkhR*7uzCc2YJ=mDtR^0W>vM>pV(1*_wke7%G zz1hRS{s>@I?nz*HV%_s7_e4f}Y&qo!N0HF!pu=Wt#*oDUne zx=W*?;}b{ZQzn<7&m|ZjU{Z~C)%=Yp^F$g>bM>zTGuQZ|Nshy}8-7iss@aBC+t8j} zR6T9eznMjgQvDs;b8vso-=RGnzj^b5(7F1SMd-eWzZiS|?Plj$!oKNtO*adXjq zF29|7x!TWF(f)I(VUy^1OtkepPBJk0JAj&ZtH^?1!O$x>ni_^3ME;5nR{hiszr0PA5nF zGvSkIpOVYV43MPrR1)%N{F!F_CizqVPv^grzmAS|B~&BZMf#DyTkqFDU_fBFCVWh| gI{d@%i11P2ABB$&8aQZZSV(Z_kijFy4jcae0P#DlumAu6 diff --git a/.cache/clangd/index/mapping.hpp.83C0C81544CCABFA.idx b/.cache/clangd/index/mapping.hpp.83C0C81544CCABFA.idx deleted file mode 100644 index fdd7769a781fcd5c5d593366b3967d9936d4d562..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 9988 zcmc&(3vg7`8NLUId9ZT&3^DRd6fMZ*X7?t0VR!H5-Wvj` zRL7upY;1jWqK+L=XKd+XY#CdN^f4Wv(;1uA&PZcx(Uf7(UPlEw3?&3>surru0eD!}xoa z9oiexdLWO-WnfbKzJ!vHMXM+l2Q=B|lTCTCNIymMKv)qwbS=orlO{njAM2VSp#U0? zI7jO}hR1U=Y_Oh+b}m`E>v(^qpdRQoQI5j?$<&kE+a+BNt3D}cbWU1R4cc7DOxukX zdm<-pX2R2RVIsv+bYMco;@vkH9mATDw&#F1k=wQaDXp|~)F(xUIqMVet;wjSOvYF2 z>~$(s&`3$!TMjCv?k*>l9Q>80cBZBUCe`6kK%y*bgALN}a43CzOjC3q3UE*_-iedb zv`1^-Gbu-+00&LkQL%k<`=0b2iPF<{Bnog)FW!;qYMOKmh@8kUB)2N238QVYo|uz( zcBZGY(ixPDh!h8Vn7iR<=ZC=Nkg4b$vRCnVI2A6pBTU*tJL{8K2nYKF7Dgjx1SJ@8 z)KKJND55!Ol2H!1g8d9Y`l^JgWW#aCfIjVV6@u>W5hm_h%qil&rtY9vV%>Bd^oT+dnFJk{>#7Xj z2Co3(9F&Bcc`$NG=Oo2uLtHa-(3DGD06Qlxvzkj(06Hfs>t0r)T1BsmYs3=kTkOW& zvA1k?X{U(G?iR^;>|}sL&q{{mc)mwWh~(NsaxCXy&;uQuoQLx@@Sv|9crLpi*fLUS z1rvbdyTAnSlpBC8hvl99k|3t`V=;E5Av5D5&1CQuAIk|8uGnK~(IU3$JQ0-@X&f>2 z>K@0KPGQFi;ZlyP=~xVxVq7`fn1q#VBbv-i6Ug&*O>t0Gf z-!7oG!)`H~M3$%$ECDV@w4r;gtk8^Q)&ofK2Ivd)m_4ZQ$a3V;%RC0p0{mGw32*`X z4U4@Hu+DG?qR}Zuey4FF(u)yWw+2}l;38EdfCkZ9to1F@*cpZPa(qy%r$ik)=BUx_F>`z zjC=NUbrWEUs~Z1$BKrvshdEAW9A|PWW@UEX44Bmidh1@yb`NtH|2+SEkh0>soEzH! zQU8g! zl=bTk4lzW^he#!0t}n{py9F@2o6c|OE1Y(a!wi$GVKN;sUn?dW^^LsGylX7~rDId3 zbghecuPUc19}w2Jdy3bHnJ<4ckCRcGRZAtTUObgaxc{j=LrS&hF_)mAcN?-AsKu*F zu40JiPvs3xd+gEkoQy#-W03i6*}SWR+dz+B8i$teo%ukSOXxr;W5hK^M37ToUJ&{^ zV2&OCz^Qvd; z@b8BN3NO2#z7BFke@|w2;=5I^it?`f{-tOMwUW!M`?!7jNpU~hr*6qLH{AwO&aXZB@BZMNXE@9e;yOZR zf}G02Z2v~UytVnW56umi>N!l;oUS53coxpsa4R7G)9XF+%3aqi^FBUU5qZ&e{`fF%e7tMrh7bq55i z-jGmo_S{D|o%byV;d>c=x_A^ zv;ac_1gr3o;Lrd0ewN@veBV>W8vRly{<1GEEpxFqhuw9y64Q+^3zYBJqY~$q@thH*cBlUl8ix;i=E-l zcScT*-9K|L0DB91i|pcqcvl=JHJAW*zj5(T$M*m46AG*7t>IxA$4M^2Fb}|N+N;p$ zdv_eXW$pKFxQ}MbqS{r6!ngvO_ANx;|M95{ZCn3)=qf-9wV8;9To4*Ek;f&s2rZeI z3$zl1VUme%r)7MP{bNmJVxqKALkC1AN!jsEySr=N{ zNE2j)l#Y;PDDTc0E!6BT=?>q@0^-gOy=Nfx>e zg9`jspGSW56%c51$7ReFShhMk5E3BopaAU=R4=#`*uUi%9VTO3Bq!B%MQP+;YorZ6u_UVDc--8zytZ0BW~(Y zymF_w8i!P|sd=@iYFLv+EhuhS+a@Y zZ$MitX`(9#I^KXc&?RafSp-x_b~CN295HU%4GrsBR*3Qr*%cA+iSP6>4zLX3lb*s&f6|GtELXH*4yx)%l zZpxsINf>0n#d{b~yPM5WY*E~O2IwwYb=h!{K?$I9UYQ_LteM!SGy+cX%O06KubG} zOg&K$*HYu@g)ot0DF!g1WAWjeh>xM5ns($sH&NKufhaB7nfjArz|8%LkJdz7lP3}@ zy7!tDDtIKP9W4`=QV*AzOD6G3(>pB~^i8P4aRZ51)(#V--{H9R(K$^qfZTwId+|Y> zn5R9#j;#|4BsXBGejvH^v;)Zvn79`o$aFnTdJKr{$Z$w*lQj*Fw#j;8 zPU5pO*_GukzobU2n5>6}8@6`iA+RN&$x0`7$xf%ih4FTT39nFReX3k*|9aO~sAmv({}cehBcqmuzPJw}G)cw>(k6KQA<$+3n2gC9J=$#o2|1|1%26P0r4o^k`w?NHw7F9~95KNh2B8kiZEX==k*@v)j9F%)~OELy~@&J#&# zk;VyAukKNb=@fRX5d-B6H64pFP|Q%yIwoNy>j<+Vt`K0Whj(G*q~~hC5&I9IBmSJ-ljBq)UT=? zb;0?HTuqkFUT(;n%Yzk3Q?OT4V+DqUE{BA+2%T`Ja5@|gPtY$rx|H4yEIWFF$~H9w zH$w+0YPY;y>QNmXVXx0k2cqv#9dOF`x_wfY9FP@46Uh|{#bbb84h>$JNaS5Yl_wPX zistN*;QhsyFlkKM##(VKm@M6Ra3A05y>QKfe9?FkE6{=@_$dT;$%^Xm23)?dn`LN} zQ18oCp45YFoX+R%fZ1Xui3|}ZC;`S}T2)+(6+v|&eE@p8d*D|o34W4cFCk*)G7(2E z!Q+cyD)SNyHxBF-;F7NB7?ig+_KkNdft~?a%Mcl#3nRyY0i zRQ3~2hB{-(I|H^(pu7{*mi_81&&`0kac6J+bJ>pb47Cr<+=pgi&rHuOu(bHvoR#f> zY4}CUBga4JZ)cd3mYkE8TznMe97VZ+s-B*^Z7rah8?WA+b>G{MGSmQ?Hh^YgX__<> zFmaF#Y zah^&yb27trGDE~8$TosRu+>mm6#O=zj-B}A zsiGOHUS_riGOPozs$paurmL!*^-VhC;49BwJoA@hyBX?5H2+0p#{+2o0J4LvrRCpf zy&Y`5MiXh zm_^rEo7w<#?s8%6-o9?gts8s~Tf=j3tF?6wAa0mDiF)*}PfH%k#~*KJb3Knrp9d@b zsI;HXRX=~~O}BxaOUq8b)9;`D6hl30u{~?a$A^&Z5XuKzRmIuf)qr|q?dKnAt3GRB zsDo(wK~#dfr+1eC#yKZ%)vbW}Pp|9Mvv*Hj5W!?v4?>)-AnO$xr|U%v^-7UD)%P-^ zRfV!?EpbxV9%?u`Yp`Yr<>0y2xpNpJ1R?jmoL}y42;Yuuz^C%_sG3u)p!he(&;IF& zw=#%8Jdet_zy>K2hf$fHJ#a<5g37p;ykcQ~R;SzpUZfykrO5@nER*! zOYTMBT;0`mvpIixg#w<`B}en3gke^ST)^uP1f=@-@Y+}3-16yx_k++X8Y>&G)47jZ zt6LXy7Hkk6tUovXwL1XRhl=`8iB2?Fo&7Yb<;!i$ZaV3g3w{W`j-bpDG?~{x`0f-&-@9YiEz5p< z{r!Y3bL*CH6wfQ5NiXB*2R=UYR{Q$@?!F4pLR}U|0~dtGEUsh2twL)S=K`q&;XKOX zVJDR!45KV#B?wng77x$kkNo71cfEY=Bv_88$TP#3g~~&yhG${#qFa^+mNgNA45RX4 zw2<3-`ir-|ZxJt7(C`-ZqY`6y?SrV6hxfp#e?RiGjJp;CZ~(Oppv^`m%^E`UIfD-8 z?)hTN?k2)!sYoj3g+cbp^8KiiS17j&A!Dtb2kn`?|NQfjhs$pS{qCafX-2|S97T3c z7|w9eXHB2$^Ob>s^?5Eh^V9ZqA7#Jp0K$B^B^n+9Ott52iQl&9;nfsBIhmI!|^jWXx z`aD)3AnlzGbFRQJ>*!qY`P0kii`9GbVZH%WI)Ezp%5BgD+J?|(o>N8kVbaavz^OKq ohfU;z{kxMt2!a%S+!B4n$HapNetWy;M5eT5)18}z%~8?+0U(FNIRF3v diff --git a/.cache/clangd/index/rws_client.cpp.B2625E19C4ED09CA.idx b/.cache/clangd/index/rws_client.cpp.B2625E19C4ED09CA.idx deleted file mode 100644 index f5466171225f93195c6ee738ce76cce5a8b137a8..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2694 zcmcImeQXnD7{8Ua*Xv3*+U_cY@!`-p&g*ScKC)!M+Fh}u?dDcQ63OLy_qIE@kLEtM z6%q^tF(ihMKZqp8V2u1_Vn{H88skT@5F;pmYK)07QPAKLB1Zj7pWA%f4hSgdrR}}X z^FF`d^YuP=9m}NC`-23Lk~7m9vPCaJ5UudFY*QKa!@|8-RyLJMWU`teqk%HR5bRKL zWMsS`3}&-JeniM-l66&KB$r7ELp$@J&Tp&f$M~)Mv$w0qca9hM-0k|pQ)B$#P@{f` zPY-U-7KE|f4k42p&GI=uUl=T8M)CuuHYG?^Ni}pN%a$NjD&Tf3wY`wZjthK#Fq!3r zd2l8_%%@xo!DhG#LqlBI+*=e8H)WW6tcoZhPAnD$8BGdP7H65#oM;+W-~3_<*i{AT zHmB&4>d1&-cfdzfRrp2Iwkg70(G{DukXnMZZm^E-SV(3|jxO1Xp)XKYL{o&iBNMb0 zL(yTyil$;ufNUb!(PdG$Ss6*H1sX>;ktj`wMHR6U^a4~5}SYb1ai9Dmo{@ z<0_RC_n@?*BCC-AreJQu7jh;HVr<8FYHr90_gPTi?(eVd^!F1mGCGoMq6EDC9Cz=7 zcDLOAewy5J_#300fOP*)SB|Zyimf0k@t=9RL&L19R@?%wl!-HE+ds?g3ecWMy9mbD z?2C1WJ>g~|;J$$1I(K+Qzj@{LQ>~uIU_aa%j(5k&c(}H2qLTI8B6wHL>`os%VSLpT zV%j>|*41D)A|LWS8*NaBm9dtN)j zdO{58CnI%&w)JgE3|a0^=Z;_g^P5E>#z*+5x{;e5-V8BeUpR~*Yg4lukH6!kT;3%!KfZ@yt}KXGU`SU2V~PVpaTsP(9u0q<+@MDEXO~JX|;_RJsk<$51!-pXiilW-FRfq{v!J6cJ_x-QKo7VGS z6!XMZVoGq(M~`6XK;Y}yZfEue_$71XF3j}O=8hBJUYfB08=)dJwuWv}(VBEJ{vtiN zKepfFWhj>F!B{WT5^kY!Vi*ccAy25*&EVWw#Q9uEpPYVc%hfNvz_g5F>P*39!M?f_ ziATCHpO=ZoqX{g%`ScmtutAED5eh>f3Nl)gW?%h1*?#2o58y7aA+Qw( zZX#85XA#EO>V$g}b9H9&)X`&~_j%$g?8BCpR+1}J(p jy^3B*FQYr@<#Y$VBG?>?Mp_pyX$dclKN5Sm?IGeX92$y4 diff --git a/.cache/clangd/index/rws_client.cpp.D2D6995B64F84F58.idx b/.cache/clangd/index/rws_client.cpp.D2D6995B64F84F58.idx deleted file mode 100644 index 6564422294da98579c79c95f2763b88251f9dadb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2692 zcmcgueQXnD7{48Duh$*j=%-7POXGa?KO&Xx}f zLjyar1#u*|OU&f9XN8=QFANki!})%wPl$3&)=UE^iY3a`DsnrL-dV_GM@1n&kje_; zjBzHvRYhh4xwrF)fW{BDiaa} zqH5RxmRxn!kTpjE1h)%)BuzuVVA6&Xx~qn2a~9A_XllL2xRPVYwrU!4gjESj zsQv&VY1OQ=a}reT3c?U5j-g0~%_%_EEF^IZ2qd{86*a)gs3%A?fs_H~w#_Ibm6BC6 zY-y4+4Xs9Ss#UXWpc5PfmgztlaEc21=j5M|O{1iid1GAF`KsoW%Ru4BOebyXRSgA} z1H4^Pp(3J4?HXT`b!Cn~)+D3MYig07S@rfMdJ;VZib&}%8%}q3?|Nd6!+RC{{u-#< zmW`@h?*=IAqHdL~Mi1`m;4X7GVTrnANM!&YmImdF0(r<7kTDA3A&sF_Rh37nzzl(< zi;|+K#v?JAMbrMb1P?M^u8!LzSyO>wC*0BI&8p3#k>tygCZSQ1o8@yXSU-cBHm-BM zJ$z9$X3isLo2EvL>>5qic?fsNo3zPfV<(v;&?Fc@wuzFefh5o0|4=w zj3rS)DgK|X9b45@TLspC@A)3hBdnTU+>Bl-l{05MKF{s;$H!6Dh7KMxziMIF=#uE#hS{yq zrJsc98(xO>`FyR|8^h8hO*K(~49r3yGDKklh7FV91_~v<*wORW5sqY7%14Eo1krWT z6gFAx8_G>x`}3Q54C^JlbW_RA4sSAS&>IY5lQrq-4O8!XXqWdXD%CXcFY!N#QSbD{ zmpk?@SnMhdQrobYVf_jJT8y4v_}+z6t3F)S;+d1MaOHLCliP#8qVjlGdb_ap_IKWf zJC7aOgS2PoGfE2|>7f0nn}Oh+<%#a2H(*`9Am_X9f7`looq&`gWMmnpL=O65 z!x$a#e?7h0nZAYmQaNfjW_oqgl4IXqy=)=d5FLtPZPZOV+(0MdufzuSNA{B*mgeXl zZ0lj$f^9LJ7&b*r49PUQ8K|E{oX>@!6O-?5{_#r>Vp>FZH<<#90)0&siif%|pN9>{ z!wHN&_+9<^w{5Gv4W_Gq+};FkW)GsaMV3caVC|b5 zU%US4we!EYQBZUvR1X`V0<%zv3engEML~rdX!?yisg5J3en9U0>-}4B;1Fn%JBw(J zt(EBB!XAyB9lL!od5P@oB0AlznX3yg2m<{v(AFUM82fk&InU$uQGPnQEV>j8=fdcU YXh(EWba9}S35VL}FK7$Kmq%iM0lh$tod5s; diff --git a/.cache/clangd/index/rws_client.hpp.3738C46199137910.idx b/.cache/clangd/index/rws_client.hpp.3738C46199137910.idx deleted file mode 100644 index 01ec672d8c3ac06657b37c657a58593c11933380..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1198 zcmcgqJ!lhA9DjF>$>kEy4i+g0b`ks>)&E`kE>vAyJjlC${vYr6asP?YO667z zp;B%1ludjLABisw7K^{ti^XUXYKH4L#PHFS zX_2C)X${vVTAj{RG0|EsJ;6L|5G_Eck&}9hX{N(`Y*}H7)a?-1#tyC%8WatyS?l!w zQ4A=qb>$lDe$W2_lQv>FheMb;Eqa^CF3^=WB3_ zR>u}LeA9@=sbLwOr*&T8h~w6Xj;LF8eH}iHPhHC*6uf5!H9g;S9jJDF)L|#4?dl4w zL*|pZxLW@BK@sH`lClHYt>J;BV0qwC^Uue3T|2*15z|mt`_=8?5!JWED`S_Q{d}7c zg&riOCi?RlXfihPA7S(f`a0=hdpSfnp*T*-(V`2D?!UL~5RWQvUlU8RB?D&)kuKu8Db zc$&XOIn={Rq(kn!SYEoCc=+|e7ZK6}${<&oma=kI;m%Gb%lB=PxgbE(K4m{|I@T^6 z-tn~k3UI-sp^n=K@v@Lyhr~^S?!X~VfNO{DKr>H2xO{r)(Y?8|0k3V!FuxOcWwQO8 z*XuV6pTA#!w-zi_c%}vP b<6Hwm$!?hFhSEZ5_eNv&+|iz7Jb``zMjULu diff --git a/.cache/clangd/index/rws_client.hpp.F6B6AF448BD65A95.idx b/.cache/clangd/index/rws_client.hpp.F6B6AF448BD65A95.idx deleted file mode 100644 index 594ad3868a141f221864e45396f05ca3824aff84..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1230 zcmcgrOK1~87@pn4WV4NH5`t}`R1t(0G^-IkMCrkpK!t*B!N)T;9K@W-)6nhbT^{CEnIvXFocyVE8X8-S>|NFjwW=DrA zl?PD(O2*I$8&SxXAjMunvAIrU3;!8CG*+@q8|4- zoq}=GLPb?o>#mK|8lJ2|q&8iAjCfE-s?T7c<64ubrb8&StRRGHc0g=H2i6ewLEUN? z?fkz$U*d9RzWzT5$poRu)(l9Y=0Qvl{uf??^}r-{Ng-I&AvT&2Bh7Ru!sC8le)YQo z+&Pqd-Sa}ru18f?Rjok_>eST3GFZ2C&r{n|u*Go=qyg+!U8=F8qS&=8gxOgT9h)9C zU5BBazH01_OxV>0c0E#`GINXNj~^6Kjshv2OK%7UAo-VxJ(>K|k!@GbZdJr2!!x~^ z&A|}j>tmJS3r~K$j*CJBNXb}oO)!8&d%qwF_3P8QN5e;@wW6?GQ&L2wE3D91c=v7p z;I6VFb}@$RK(-PLA%5fL`C4m6D2O7z(vmF8J)8mDn(8a!XV)&J#8te0cf4B(_hU3p z28E7OK@J>p;oKk#`|fy{&!Qao;UbcOb`F;3FURkF-Se#}ef` zHcFinSkfM4FHbtsDjeMMxb=eZvL^MnyA1$`g~V@6yh$wE?+_Qjy|ZlJGY{Xrcyj*! z?dj9Lu8qn7ugP?!(!E^Q%U83Xm#)6u&2(jzY(Hms6K%}R92kkSa7M}W@b+M2!A(pg zrvRtEPfk5gwH}6n+4nmnBeJxU{SZX;?IgG-0OFmcG+WxfT3%u@%6)kB3NxjYHgsFf}%eZ#9ytTf>;%NAPB{?*-jpPYOBNU z%st=S^PTUWbI;u2cr5lxEkaQ>K4lOadk{iF_**v99N9Cch6u_zN^Z2lIpEP6=nXSXpz|dlR zNQw>YOl0KYN?)D~2t=oTOjWdtkZII9yufm#4G36qIXDi_Ve6a@)6t4M7;C74t% zB0;l?mQ4&Km`Gs6G99K6LDg9QlGR5PljgL%NGCKyEa*-?PgHTtbfTtF&_Q03i1xU~ zR2lTzMX{(D>JmWFG0ls*mKDpRb?YN*BWn@pQv37N35VBhMoR)-G2K~5)74Az{14nT zYS~bLIY*K=WW&l^^X0jI)JxqN)Y!lj=Lx$}8b|~Pxj_x!3=(e8nc;$_-b@C{1ePIV zRn_QCF_~G@{bTOoQgO-+C{t*FNU7CDvtWzRqGBHF7+OqO$em*`F{@Egfp1nc ziFcEjrW0!sO9WbBuFbDN95GQ2rr#xs*WX0f(tYtuammJ>6JZfHp(#WzFmpmv36o(N zk#Shl{~p-JHiUJux@L|4*Kw~_D0fj;tCz?W9SVB!F_#AeYZOkSqLFQfgJ}O}J@0Pi zr%%?QUWE86PnCD>hEVC)f{T%y_24puD&L%K+p_wHii$cuR1@;KZp(Z32PR(s>+1>+ zALN65;kLHXWZ+0oM{;cT+4tMG1KbpD5})fhbYg37q^Ga-$g!6?Kj;LwIoQ0yC6P`) zU-Qv#L%%Mo>W&v<$H7|b?Q^Y>TIsk!f=^Y}@mvk($I?TwLkG{F1goEm zE?E9Ge%|HXy)i!1{@6EPg65`{re0Tt^G;*#=$38!ARO1lZC>#8wfokM{&eon(G9J8 zAGxq+-xtAG&wy{RG1%=c%%!g2E~crRr6=xL`OMi*PFXz+uweN% z`=YL95AW~w_qn_tKCmVbajg%(+u&6z|JVpo8X6nA`VPM!@7@38juX=lpFVZ$?MF+& zgWgs*__;TZ94^Lc8vt&uX|8uke%vzi`Ru1h&wD^cC)c$|#VTL>A{BoBybGxC2j;B{ zzpqTsoay}qHb6sn!zNb+>@ppfG6~z<5=(>b(ye^;xC2zdAN;t!TUhb)fy$n)ZqzmZ z0>R;_3t-+F?yOi=>8Yx&@z#b`huTB8g;s<*LT#ayp;er(uBkETZ>SHn-g0~MnwI70 EZ^Y+F4FCWD diff --git a/.cache/clangd/index/rws_client_node.cpp.32950DC259F660B7.idx b/.cache/clangd/index/rws_client_node.cpp.32950DC259F660B7.idx deleted file mode 100644 index 8e251a0c3f07935a7afd7c5e93a67fae4d87d92b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2466 zcmcgtYiJx*6rMDjWHX!HY#tjMo7ObRCNW_$Nt?DHrkZRf?Y8^SWNVBl!`+#?yF+L0 zEO%yhvlUT6LVpxRODO6O5g)~X53n^6v1*`{f})gaMJ&`eXoG^a6ol%TO($unrL{$e z-8<)edmi6C=iI%c;gON&Dj6muhbJ{`A{WCje)t+DRUR(~!G1VSrb-S|PSa&PknZkg zxZ$CAd@LajMj~P?E=Iyb%TOX74Tr?xi5S4KolE$ruuZuCN_cEyEFna%#1q>`g~8#= z@nK4Jia}qJoxehD&Jgr?(&8-Z}kI71O~m!7^8w zySOlnePzKzamsjT6~mOiKHs!;{m&&ORl$ae29M*mx@)g5_sXANmAHcbPJjQ|3p3g; zf1L=mMknTU7)VZVPU;po0{FaV+zu-?d+CiUr)2A@739ZWGesl=|?W^nL6oz z={WfMYyBP0#+=Y4?4>d-R%zc|Yo9*z@lgXpdaJ!nj#X9ASM6KUUM5rPFSNIAfRN>E zxz90rXXA^3nWyeN1F(Cud(heM+{pCg8+ZToWtl6;3T)hA3EI8vgUgy{izno8b_Km% z-hL;pE9h(S^*Gv*A2+(?(({`jOHFM}ds)}QzUuE!&3-Wb@Uf$FZ#`-!_q!XN~ z4j&G$O=;7$OF~j=T3pB0F-dW0?;cL*m>Ac_@{E<15I8t5Co?c>#76_tGXqEGjTo9g zJbhqhVETXoX&ITL(njY8=8qWo7LLfv4}SNT(NO!a?9AMP!0gPfy46Qmyx+6GSdeRP9HEVQyU0#0Y8m~!kL<7 zx^lCi$UrM?Q2yB5g7h(3Uhc55R$6xc*!+Ub94jr)N*j@xpEq*Ez)US8dqmXVdT$z- zmpdpsD=>Fdc23~%VI#A$GBW~u=8bHVmot1AG_ONuV8P(*5gBRF-h#1#V+ZDB{OyN< z!_srJ0*7S}2z>XqropBlQ;-$3D`L)yYKfm=qK0X5GI43|7kTa5YUkS!#2Rf(1icPhexCj z&(8S28G&~dsPW~L1vkvA$kBXdL= zh^NUS^MQH83jzTIW~C2H2U#1)2XSQnh`<5axq$;gd9~?~J~T5vdst@v+v?uQvk7G4 zt-SwtZ!qOqrL;~?h)o@vGawHnGNpTJ>bu4yzi&%Qr&KG80gw-Hu zLPTKT|IDF+T<|f4er9J3OUug4%^ZZ}dXJrP$<9m5&(6wCANCf#6XpSVc_Pfn9hoCg|Bl`n5`mom zmet?=Fc9ow{=gC0!{3@Q%j@!oXJ%%k0sm#^Sq&eaR*(mpGdtI6#K>Iu(V~e)77G7`0afsuM&2ng@Xyfy6qaR|Xp%N{f~Eqz4R z$Q!MILieQ~yvJ>QP(5W%aZU=?5-dv&UVa#6s0$p&IPJ4$*bUv$jkilBU zhdSH{ymhKj$G88pvU=ZA|BKgu$zSlKzdbfV9Tl=ig&g4jDWabu{+<>uuU-4K-UfGj z+!o5LS3K4$e*QBNor&t!zNg*IwZr!7LUa?VU;C!ciERu6e5>x+ z<1i?51bZC8{{Ee5XBS>#eB`{(JmUQAaU7I5K|D^70RItm1n*I|>aF?c*{MJ5aXTpS zns~e>{{Ca=7+y#3Ps+Yd@tuL~aZ4yMA9>72!Tw=1jL%Nrgse=TZ;vgo$GxFMnd(ud zM)-e)=vTOX}5l!^k=9&PJ}X#6_3X- zy7Lj8FN|(~ABR?Nehpe`j{~7hG4d!zntwPAuUGq~jP>CiJqC~c&>qJ?i9+I0Nc{YV z(P4aSv&Kn3{&eEXWP98LN?cbxuB$=*TM^xg+-qwYv#rAiJMbY-d)x}jT#!62zzhwf z19>fD4$K+tF+HV$J?;x7j;kKW)ky!%h;BxWYipTseD3f8i6dg|aWg2h7<(+n0sif1 zJ3jss)2er-e;v8l9(RHgTV#(dawGqb>BkPWbu4cFxx+B;{*m@L2ukcg9y?GI|416? zTw7vkl-xb|tBWP}xFeJ}L_H2sfB&V3E=7D6iwfrlhrT@NXpf_z%s$CupVY*^Kkd(J zS-I}>ANo4C2W|?160eZQD|k;FjpHT0NbP^y$~qOsJ^@NxRy-~%{{C|iog=(w!-)e% z->?;@>~R#7`BL)uQquhU(!P9tHa*z9Wc9My+4k5BB`PJ4N@&R-I*7k#bH@QvolSXD z>~XNA1oEgve*Q5uhL3&OPYe6CEqw8-J#GypUP&IWV0N-;HZQT`UTc@k)*tS&$0<#7J#GPIu3(QV zxRHMs+J(>YiMVmkfA~pGvd8VA#60RT52Rxuq6-D-xUjv)P`tO@IeXj&%4{VbTS*iD zJetSH?ZP(|rUTyHtnG0(D6vxYSgC6MUn2UY(3b0`m)$>o{W-PA@ld9ccvON$7)eKR zj=a_M=R@np@7`pOyF-cfs>gaYz`qpHQlTwBpTFSlo3QGlJr0F3o3O_w;Oq9ZJ+I}L zR|zRM*S`q1$B|ItC)wjC(59au`k7G6ubDe0-O^WVx5ueaX1eMz9dz6pMAry9?s0y> z^TE9ineA~;C{w9=RD!H-Lv))UtIz!p_j=l~H?+7plv#v479o>=N7~V?b{=1k-hFVk z?hx=?Qz&r?d7J`{YDHUdei@NDC_ici7%a)@u2q+L-yprVUh1-5>cbe?s(r5!wl%sr zM6b;vjX1yHvZwU%Y zF$bgsCYpM!LJF&pqB%Y;>5fZ|3}ekV+rfG60j$?{;yOFAEt>_swj0~-#!d|5JwG1( z?T?(hE_%%gJJ~bisn=YwtAGsHARtfdDIjm`Eg&E4BcMjOk${@uCISk;0RjrdfdT@H zEuc^wDxem)g@9V(mI8{#(E@6XTMH-_#|o$|ZY!WfoG73UxPyR_ak79?acV7+Xv@J} z(pEYF0~}DA98ltz&6jFACI&p&I1C7@)bLem0uwjV^7+}Ht=y*q;S|=L!Y<4%D>GI* z$7FAM0fZ%L=n^%axjL$~i`AMA%QJy+T!}uebY$;Pr!MI-_T0LKia;XTo@eDGZLBWi}_1YEWcLkY59B~Cji#X{DN@ke(aPY=4EykD` zuUNl#=O(=VXzE4#HUG9wJkfITu3M9UX&c2i>cWcY!KSrajJq*A2OY&ROK>v7*1PU~ zwCrW8^jb0XET-N} zQGy6i&z;npH6O-{dY+};%oJK*cxqGDBCizMTaDURqZDRS^x9n%b{9o+`~>NqAV-FE z-ZS@{n^vzkOwBPV=$I7Bq)+#I!gA%mUw%x-I;O7}~ z;~8==a{+CR{W5I(pc(@Z%284|>cTt^n;W*@p9`3<90<4N-nZp}Y}V}DTOPS^+V3Ka zvQNBEXVwrscn@)}P%`r<^xA9G>NQGa*gm6lOdIDYJ=9mChL)%?Op@$p4SP|#+{)78 z^~#|2N*-f(`$vuke~r6;r;%Q>aj|jdFS2vB^WezI-N~CHS9ezd8Qcv5@^tqUkhiPdw_rf-2(*_>>ezjQ1?&)wQz4CpqB0}1r+TbEuhx!tpyb8 z9xI@>?rjB>=$H1*=fjg8pjS%d;hwz zWkm#V&R1&qS85{jVjMncIs0^xxg`)5$X*L%AI9wt%cj2YIeaz;gy;zkeL@qN#|ZXa z4V|SXGVjD;WzCRpbC2x<`QAp_ZzCz(u$Pm-a?+gR-6U)`iRQS1=qiXK!;Ypior6kd zX!U`+5nhjM*;+=g?MHY&vSsq7*DfJ^3E46ot=H}&d>`2|9i`W%VmuYwGI`Q#D=}V) zZJE{u`NgP zZhW4}_?c|W)R3YE%W7}e+oXT*fQ;-*Qyj;rPy-gG>PI#)Rr5kl@za}w%j(I_a)3|6<$eka{EJaPlg>&?ArDDsoxx-zE@J0S5j{_@Q%;l47t;OqKl`6 z1MSu$H<1JF_9Hiu1MMy$H<1JF?jtvm1MQ|_H<1JFR$@1i1MSMO8}mr@+6ioT0=tPE zX!i?t6FJcCHFgs@(5^^w6FJasi{vJ9pxsf)jdS25$?lQlCUTtJ4C2N*uGiKOyEVj3 zXSWjD@o=VZHcvKyNLz4lDDdnUVy9A>vn zaT7Vr?x^A>a+qC};wEyK-6ZNJa+uvp>c%Q3S`EkZF@huRx{>6wNv8F!DQ$A~-&ROh-ieHDtOb`mHyR-whPOIr1hl z-4y9H$W-%pzs~Ooir^gk6q%li^qJT+6Gw9no{jxx;|PxDVAC9tz8afW<7m#|Yq8&2 z9KrEAY+5JM_h8c=9L*(QFZSDuBRJlNP5VUpX>2-;qq&5f!=`g0uEM4&9L*)>4)(i) zBRHNYnI=lnT!JP^ev_mKjwef|$s&EZWLhpoa|v51`K^>9I4+h<#Ui~-GL=cuTmrXC ze%qx8j(13=9U}cZ$@Jad7qfoHr3fyuCnVDek$zn=U6-P{4Y?`#-IO9Yek_?DOVM1y zpGtmDr3j8^6Vq%G%_V*=@taE`IG#sL^F;a=#PkJ;<{Du=@mo(KI4&ioQjz{GF@5`Y zAxCqKwO;mHFGp~^OE&G2qq)u8Bm3=6J)dp_o=E(Og3oD}KdF z1ji+csYIk#C;=5pB-fxP71K#2n&Z=o-)SX+<1>osj7YzunC>XiT;twV{O&3d9RH@6 zeiP}RQPXEMnrq~#)Nd+{;CLD}O%v%Q)Ko&FxyD{i{Z`Wmj@MAr8j-$>ns(7>?lbJ6 zetT#H$KO!XHzNHUHJzi;%mV1O3)Jrdjo|nqHC+_xKTw|^Xb9Vf*K4#!MG;Ly`5{lQ>pUy^X`n^JvH!@Il^4rZ-YBSG}`{ z-z;Jhal|Z970)6`vq&~(srMSKeZwTy2mpyc>u0j0*L z3MeB!LqH$4`>-#sv!GppfJV0)EufDQKN5WI35gQ~^ciaR84}7~!7*2GcW#ZZ;>fGG zGsh2b!UNooTjPhg%|qOS<5^PtEU7oQzOyCsY^f{97o_+LQg3bzFG}W%Qdf>ErMOC| z7q^C0QmZPd3&)?!Z9bQKaBaU-j#?_GaJ)s1*&=u6+J37XxmE7W@nxm$Wu*_-j#re{ zSCnoXKUU%&E4{fke4?12C|x<8N88P#eYy6VPh;lO?i_ER<_)wf*LGjgh_7fTjt|kc zhiD(J-44^%hiNy44dK6Bv(ugO1MZKGkFMPjv#fvOUr8y9vtXesnO{pu47+!Yo6)(8 zdt+en+j8b@IhR={_lsXn-~8`A_kfqLAjd1HA$L0;BFBfQA$KdMW5?;ZA$J=~uww~s z$lO8?CBDP_Q*Um<8}y3aj`5wxH-|?yozV9asDCpyZN|Y&wk)z1vJ;1ixXn)7R>WO* z;+_n9K0Vd&O=SK=sAwk&+KF0nvEPGy_n;t-E0C@Nxo~_0>5g#x0d4rOU2083Xy{E^ z_a^;-8HNw?-8(cK-@$;1X5(yAm-T>Xc6IGs81l0HG<=47@+a6#IfLt+!M@y${Z?`L zR`FqG*y}{cW(~7iX86F?rMIoHz2l&Bs2v@>R##V7KyErW0eR>=1mvaj5>NwO0|EK! zdO{yCjq7CQUugh*Hu7+Yz8^7`Os_GHrWEovCDDdwBdHc1(a`>FQ8F&qXaa@ zeT)}>ZoI?z+WFUOpE!IXpsC1iDiWTYf$U~*>~*7ANspTIZzQ7iA$?p~l|<`D`U$8% z>0gVyJ1kq4uYG6&hO8nfRiqd5gzH~zyT~Q!ek2f1kn|H|2y?0H|Jvu`w*Ik6@RGCG z=`40;Oh{ns&uM||%zR@4hbayR6-UOD4Ynr+?Ar3XJ=C~UcHAj9WNME&KcH4tA-W2A z@zrgqL`x+vW-G1V$DA-**s#Ur0`G$vS3zjbsp>h^nz;c)JFlweIc}I5ueVhmt%6s7 zFYCUSotQt}@P4~L&*VDS2f{YB;Wo7ib3}ZD_7!()P}&`OS%{npkuzJ76YT)9JAmw& zgcDFDb~~{>Qx(47IMvDJdkx{J!Qci0^3C!UN*ae4hw+mBL;M9~$~Fz`p?(~&mAtH{G5ED-^MZ%La(6AXCn_gcp)dior032)MX%oaBv-`lVDMLXGzHj-hd(Rgjy4#3p z8wqCoY6*z&J3ve#jyNE0l^h^R2S_rb2MtwsHu^d_2efWLd_XFz-*WES_6Y96v^wn4 zy-2Vqm-gHFEsck+Ea)!E=;66)m zCQ~y_KM%ibHVhA%ZHNs*JJ z7{0VvDMhZ7V)#;GyA-)yieaV;^qUlUT#8}qL-7Bk$eU6OUs^nsBA-ezd?_)PM9w8K zOl`tZ0*PEtVwe&FeM=%MNDP}z=r4)9L1LJd)@x5m=XREHlnfpB%Yf zj^Rs_J#yq8IfmI}FfwxF6*-3KHof+j9Ql_V!(4YTN=jt062m4&uboyRPb)FZ*u%z# z5_wmN;Y*jPG;%79;Y*d(G;%eK;Y*V}G;$A(;Y*PVH1YzCVM~u@50j5vs(&jMxOKnU zZ@-!zlvOoj-_}2FL&%2ecTm;%4#8=)-)S}dk!kVeE&({JSXgz+Xjw|flw{trt{u7x?Htr?P!CSa?v^c}obEY2Ic<3N z;R4FBZ}uin>lk!jm&l*BKm#t{N28DA08x zaKmeo_L>Z4^3XiJeeYEbDtAH%&2%Mpy3(FA_ADiEmeQQ#xk}VrC6?m_O6&r${30cB zkj2@OTl6=1<`DbWR8R=F=(wIcINS^)G+P0pD!5WmJhNVd3 zs&1>)c&ik|R7;C_tNuNIx1?A&yy1|>Y$%u{!t*mwzzh_@2-fc-s+k8A-bj($CQ0>V zOJq%WHHqaq<1X>MON<=fBfj@Y5XX;+?lE!U_!-eX<2YRNess;Pg=Kla8HaDiv0Ry! zVc#+w#PJ@i+k;&=-iLMjI1b%oG-Pj#_~6m;p-TFre_(SW%huYg z=xVbX>e@+tcG4iGaiYU#q{oh{7Yu|8YUl+ujx8oy9qR48yt3v`AS{zSmq}hs$G1B3 z;#=G%cQO!4P?r+ahs}_=)1Z1ud!AZ?n2HcBLXONQHK&Z!_20U=1PEVBy}p#v*&Mdk z<=p#n$RGmjw*cV<$ex9RTh=AYHr1I~S&RB}+pjj}>Tkbl-miA#_@Jsks2W6d=yqCd z%+w+1Y1MpM?Z|NJc8jc(v}0laU<6~dC->I9OrH5q9(mDx{4Wcyx3&Q@Md9C2w(S9{ zPMT6hd$A=TOfZeEq49jbd%BuDUG2g5rx&Un7pmRZJ}ks!sHT-_bH4w)UWH)VP_{Y% zp;B9xscrc1?NyWasy+Dd99O#?SNpNK)Ac?fOqUrV{!{o+s+ zEFy9~C`K9V#?HIND1kfF?hbY4WB!=hKc;p0nEy!~|D>)QzoCwAL_AZ~%~b9AoGeyt z7OReIPTFn1m3!fQ+qF8qmO(P?S;O^O7ReIOP-Unir{yZS0{T$-P(TGrfq+IUqXqPl z`jIoQWr8|EK%XJyGbEIqhLmX>vnd2uaxJ23#a)Lzi0(mN+?70!=y~MDUCFzM-bG&A zm7Ij>B<#gq$s$aPuorhF%P=j&UR=8!!}J*TVji_#`w`P0u@`qOUtszIdvVutiA0xh zwF9oNL^twX5lcWbt&qI9Yk5zi_arawN=_kk3h`o$0(hB$$Ny}BVJ7DLeQv8C(B;Ubb|JiX^HH`UCC22Jtcc_*Re*XHL@3X9Sap&sCY38 z2yxX4-K}_W3AwG%+lm)=9bYT-wc^EH$0ACLs26t~%P1|QUQCgLgi(5edNJ40`u*)7 zX73WmDm7((h0VdIfqqYa}`eH95zuhPm~flhb@=P%cVqS*g$Ja<}xXf zStq^ron-z_O5_}NT{2&n68Ylgv1EQMC323NP0X`NBImd-i1`bW$T{v?V*ZvS@`1cY z%-2XF=eWnj{Fo$ij+-gR%#@Qj$9*B2zmO9-$L*5MyW~W^c)28-FUg6V17FDI7jh!! zz!i#lg_6iQ@T6issU&g^yrY=!D2bc{KcnW)Xd>sp5^64?iJSv>QS&aE$T{#FHJ_u2 zj04+uvmM%`eB2dK&C`|O=}HuT@hru2mSW_1uHrvebT$_#!3)IliQb{cl6x!NkI&*dCDaL$PBe&Q0YJ25=V`(Gm=xLvV5rnq<-w|JfK zje$+h?-bkb6qgs(QD-7cNfPT4Ooz#63S%v{et*f34Gj|uD3)MMXu*rUyJ=WkY;LuW zzhQR|D0WV5c8)u+de{wbcAn$Tr;{h$E$p}g+FwoDSCbSrg0N^OfpjhvyzaJ*2B zUZ}=0mq@QIQd=xiqd8uwCazSIMYlC!z1m51Tf3L3eMPr5X0O_gNuOTZr$+8mV>mvp zwmYtNWWobdtHzvA+i`qd?QmU972Vnnm1?T!)^>iNc4t0O>Zn_DZ_he51X#Zq^(sc` z%yM<8aQ_6`PsIDoiyI#iGt&m34Q1mrF&1vEY+Ngwxs@)LgUaQ0 z+)AI5jpt-Dw;<tZpBwp<4S7gR=k`BmD6_Iil3pzGt|tiI9rkfcR3gx zqPZG=cUhZpSMLj(qAzc#==Klzw)f*V&l=ektpQ>A8u$4cXEGM)Gyl@3)+?6J{|9yT zSsGb%;;&=9pspEM2lvStJN7x!efEmMH5;M%`&EbiYCXPXa9VXZt=3~(0!-;x!+>M@ z9Q$$xTqx0nk}qe#V=_G^`|=6=Ri?knzI?*wDs-;m%O_}yLboWse1dK%^p@hwC+MX@ zUn;(Qf(j`uq`qu|tlwXHXCuwDx3gZmhUqoz$|dI!rjM{IZ}=RE&XHVs!>c7)ExB?@ zm_+C#;>smqIibsmE0=_FLd%IOmxQx~o+Yka67CXum$-6Cm?+bUvMbX^upW?Uk?hJP zp-QGzvMV2`Sqhz{xblJ8q|i-@D<7z<3caeh@_~A)(5H$kAE*VCE}*V#pkRea=|<|x zIr#{sN2n{~Wb5~t0cr>GgSrlVTMZopJX0e%)<~XgVAAv(e<&$A)f+s8GbsEFisicR zJn}t{f;hg0bk~pz$2XDgCdaI$zYZES*bfL>N$;&BgH2_+ za$-=6?_Mnc!b=+dlBO~fpPpqk?(Q?Iz<(fm=^y{n=jY(XmMechsNp}T9hhkw5INMZ z%>wfcARNJINAO^#@(0Wb4H|uadMXe~P`?tC#rnxO5Bl52*rqw}@4G|`tiKtXtv6S@ zq&mR!g``U%>CK+Ybo%y(e;v2+g^4>w+MgmRoK??~z_X+|#}`Q01u;PS2GQLhj*QN_ zPzUaBVfqBSbD5ei(fN`)m#H$DmdWm1yWddg4aJ@F>>mpKLvd%E04@=wi>N#2+0B%0 zrtX|)zoYa!>dtxgT?Pr(^{j&r>OKklDhn1OhvneIaunA>$7KIwa&wN4%fZJ*`YGA> zlpMtAmt@@~*@fe)vhFI!gV${_oaoS3g)tUm%Z7aL>1y+(?+f7PO4PR!4PtJA?ia2)p+cH(wBaYtqhEH~m? z%_4DJORXcV){!_i=avKDRtHENV{OZg_*Pd*9GgnZ=6S0c634aFpH%lJbzmGnEamc) zH$zVifF6}9-Ak1;rhamk45=4!{e!9?0=HG{mLhw$lp=5l>$DL$Gp;4tVdQieIWv!m zz#**D4dl#5fM`#U(-Y*(Mu2FuvD0kq%tnA{tFXf=?8rudXlt?4TI|g6UhK3NJF^iX za473^2Rk#pPqayr(!XU3yM+b%h6mzA2*~JSGB%vQ9T8 zXXY^x?WyGSRB~qOkZ5y>(_G@rW`Mw6HuS*v|e^*c7kYoWT!o{Gm|L-hq6vrWM{^z1P*1L{*s-U9U*Wi z>r|{bGdn`yP}b?R;>;$Jz@eWGL$t2NMQ>WF`naL!)pE~WK&P*l= zM87*-pw3JtiS`54|3Gb+Atu_dRR1frVaq0%Z>oPnZ5W3U?FH4p5b;D+KT#FvvsC>o z)rKvj2wdpbFHvpSvWdV&W_^ij!UwmYQvNqfmj=TwQ9qbAOx(4{*h|KtVqs|PULLU#hI|fa0azMgHjk{ z!wMUPofof3-9Wk<$dS>9mn5tX>-SR+P{&u%2Un2~BY>SkA3Q=nOd>2!o97JNfJp>I z#9{AM*q2GbhyLLOUoA*}0Wx|T^*D{vSw$n_FVo9uAGd_2dB%IDFoOZ=AH|;%8+sa< zPs29H`%E4A4KB`}JABq8Jv0obUd6qcD8c1P-0LA8z(fh+2c+(^r8Fi=a9SaCzbK_K zQ2}RL>Q*K7W1<2V+vF}wi#q83Y0E2alW-mZL_7~MP$tabMW-CLDycs{W6jCQalE<|+;Q7|huDrav^X76L4 z0v9YL?U#}irZ@E3auT?lH0QXOgcXaoqSh1Ldg93FqozHsIMZvT<;3?5>Gg&TWC~=o zW5(^IGp#HEHLp7b)bJWLk+JmX^G~AA-2d|yY=*y)!rw@- zOt*YG_)Z}~9M2}Y*~Eq8c|p&1V=-mi_({XL8hq1q{&vK8+FN0Y-MZ!;!STO62W?$dlhoNzfuV*&>CT69j8&dl>V&MNI5;%!8=R7fm zgiR5zpv)z@xx|st$8|6M!J($c{jICi`3maJ)DmbP)cGOm&eh^{+<7|g&c~+&cP_!* znOcOieB5g%?#~uUm7U|AjWJw;>c^&D_1jynlbv{74Ged3R$<9|vcRnmNq;n1F z&I~nll2pyoOCn;4_op|h zGc%R2v8F1;suMG1;B%?8RCQ*i%(6R1Z>Y}9G=Y9ql`7SVnWpire4CFMRcZ@!P%1Sm zm0B^M#&SC7yOBqSSk7{EWs(c0?~rsmI37Q_RnxVPe|ZBlei_xfj2f^VJpwy=zB5S> z+tC}pxYF!ovjsz+w~~~tq$eA^@i&XNudojr3WOb~_YRc7+`kEl56<@;+vs~ByoL=x zl*XoyjTVTQ(P$JlwBMy}W0E+bYD=$;qo+-UrWIpDF>b^npurC!O|Fmt76Hv3=nA{M zR@QYHp8|puhKvY-UX5&9a+-sKLnDsrI@A@An}eHxJRCd(N1mx@BDlAhUy6Ky4h_2q@kmUO)*B2?9!T zND@#dhfV@YaYzwRSBI_w8ss#{$VV{SDO*4}b#weUZFt?`0?MzOFQ8F%M+s<5{V}yF zUayUJ9Us7J`NZ`T0Zm19ry}9W8K~|I5zj^PTx8(#Hy_FKk%4XEfmJ~AB4l8;*|O0s z7b62(%2;?=-hm8^mo1KzdWv4OF=9@4kTo3Mdv zs3TZDf(^`=fIo!gE7-vOuLoFufDPRLnkC7zBm?taECEFFmy&^t^*%}7CmGmM1`hEh z`GRC%))Q8#l3XbnxPSIal3z&%t|1GFTu2ODLvAJVR$^d64krpkK0ypzLsk;Gk{Gy# zd`;xn#K1feJtX>*KbH;M|Jx$VTVw-=GGr zpR1@`MGb5z1CBbCA5jCd@nEr4dAe#~OBFrb_mmf^2DVhO1SZKVRRh=W>s5KZYT)|4 zOqI)219MX$-dL6Qig8=VRr$DTU~Y{iFiF0y8n`{EROL$5!0dq~FiC!(8kk@AiSFcH z?=K!-d%t}(eMn^eu|2Hzzq<;w@X6}k+e4d=BbwzZP}S+rbUT}+_L-P^`D@?Nzf(}x z7iFJ|vWd+Nn=???U5#CXnLt{<&!fo{?8Ne^cgLRS^)Gn7TJfn?nzOn2)b~usO?^*Y z1Y0#-X*^x==aafXX}mzhixlwInsWMbC44zQ{+^V4Ed9+>&m4HeAvyDqoXc7`>BkT) zp_}0(5DHO9A&O>VJ*DlqK8qhJ4Z$97Q|oS1efW6qSB?AC=6n-;zuIZP+Lz;ls{28; z33J^nadXDgYIC+pZo!>St9==s`ea-?6nLgNw19@wBzC4Wtz($~)vszS2Wh2BdZ{vm z@$a- zjoq5qH6#e$uutl}Ps(5#U}hVHj&`YY2nZEwXoZ@{x-zrfgo(4ejr$1JHwV=^2UT4y zVUsc>`@)+a;EAb9_*8zfGRvj7%fG&!nrG<+axCQuZDxB^r%n&JYz;GeKngk_wPY{1 z#3cDvNI@KbC+WVETsS@<=}vGw`_u5EuReS>i&jKu5dlV-h#XXqLpO@x*U0qRW z1%zXg<1v1De17+PaXb1fI0A%9>{yBYm{pj+=FeN@rIo$^!7%-6%})_N{>v^vUEe8T z-zo8oasKtdDrmrSr3G~J81_AegIKeGwXyCr&#wsK1Xy>D5x~1v|OlvNDnzFgh@6}(zoNrJXZ&3W1IDvR8jkk%oT!D37Q%*mw_#IbF9G_79 zPH@b+04?w^dW3Qn_bw4IQ*n#G&{E@0@9$HeXkrpPqKQfHh$be%Bbt~5k7!~NJfew7 z@Q5ZR!6TZO1dnK95PJfew7 z@Q9WuB*7z^m;{e#ViG)}iAnH?CZ@I{nwZ*-XkuzRqKT>Ph$g1CBbu1nj%Z?PJEDoH z?T99(wj>w{ab3g#pl$H-9LS`44BtD-dor}t3>gYVq(iGWUfL<%Om&gwTS1jIi{ofPb+1cma4lOBYw)NaQJA0|=J@2o>J~~#YygVBA$JU1MrmRj` z{TQ!Vl&*2A62^_+G^N2bZVW&7-#g*sCm&f-W}ZTQPoY7~6dfuPfVXgu@_mt&t1)!n(1UH7G?|+c>i7c>e^zvWV9jXQ=XNz6&UeN%LzLGQ=zPL_+C=hU|6)b7lqDf;u<2t(`L^MP=ehTo-$%+*?! zI=%P6Hy>ofiw?_;56k{cFMEu_#Wak0m@9S_p84jh zicvt=gwr?SAxyimB>{}DuhCZ+-*?Hs+4vTJu(oSa=~aup-honfpq@-874N&|x5@X; z85oaJDZW(dzkegzH ztRHdMkAF{~rMrV2dHF{;@DXm#*ELUY$P+9i(0Y!ep5s_fe}ThZ;J+o@(oK>aIem^4 zI7e#E*G2QCkojVQt%Xw5LMfKhmq=kt#DrTbCEZHNk<-7I0>77<^L5irNq19n7GiCoL(dc7Rk-|x@d(QxI)Awa#+dV6G-XS!*%)h zNz`FGM-C|y6GrWkb$et-=A*+-mJ)cC``)mwQ9^Er372juQMZ&>=9@!G4khfin1Jc7 zqPwd&a{5yx@TtDx+a#VnU}qRJVsZ z^72P$;1SxK=}PdDXvlYBf~ON8;$niQ3siT3IeTCTewj z8{2@QAD#YzYFS&SXL@F#*Wj3^;Xqh|Q&ldzGj}~2x6if zI8koS8$MYMn=D6jJX^Mz&9iw}68q{F$c~I&x_WY(_-D-qf>jER5AMpG3(LM#!k1DH zKK|>aHtVGnhS{IMZ_SL&gg~Bm->_i(w&6FAe-)=jOo3vhD6kZ@ia?U#+2iuJNuy`-)LQG3vqVD?x2aPzuAFer|M3?zMRo zJhlqOuR##}0L2;@8`N%fTEGAP zMs2Z)2OPRDaIiGvs$_Rns?Y6DxolT1*XR1aoZ6Ms`fR?pIFFyuLbqu>#OrKOf;T8p zoRKyuo|_aS$6FNtElP8aw<*Ef#Pa1zi*lt6r|(vLcPl|0S15HVcx(a0?<=~KiVLTo zQFLcG-l~1tX28QgEMDqKl5&#tViL9W&Zmn;W%fD^geuafiexg;D%nar|3VGPYivoMD5zEHx(uF-NY+G7D-ykD< z1Nfns7GfjUdYdubjE!9Dy^-h}NjQ96O6XEz8yn{S-d|X^JKshXyG@ zwHFPE7NUd*Z*Q(N7wQaG!iD!mDv<)MmC{O}#V9cXic{i*lI@gsLR;D^?FH0P=_s_U zv(i}@vo1;(p`Dp(rYG;;V0Ey7hFK4*P4Q2(JnK9Gjj$de^lzl~Na5{ctj7p%7^ffi z0e{2C`j3S-OhMLDknrSmWIdhZUBesdD7|J0-Mor)SCKuFrClq(_+9#UMmSua+MvX4 zP}*}1vq=fuBxvD?J*aPV@X# zyN(nz@44Lg6!>?)8n$1J5+; zj(^0yKjI*ctFW#LyKwvndp^QO?(96l^`GDXj-O-y=i*}O1@?V`gE)Pnq?;(Ya6DPk zO&0MS$#afmA$;ge@ zbxC(!a^bjI@~oDO%yz;~fb_v#sR_sTB;R{d5XX-t-DAmx<09F!NH#LfqSsc)o-0IL zBKwxeL7e`DtouTC;kZn$UnU1|W4cS$?UG$MzN&a$RgB#Ex}ns+p#*SzOYy%YF1Btf zzPFViPQRn*?kFxC|EB1E6Y*2U^QmIw&fFhL{Xdidj$bPNFU7^zYsL4q62$4BQQc?M zh2v>dH%-I~sOJJ|Pn~!$7`r=jfgi=&yCc` zoDbOdrS&({0FKM3Zy8Uqpx1U$-7f0F>EBS@HzGblJ&#Z$b5<>jvHIW90FF<=P-Cfpx7I-D}6u1(7y!td@73sBpUi}2r->ZKu`X;*h)YoS62h=rD z4V|dgMhAV98r&p2=BPIiN>NHF>c#BkH+fz9Oy7Dx6<*RLzKO8Gwh6b}gu8Ly;APEGeUwE3wOYLKdd{ zKy4558zii7-+gC}xg7`O&raSZ5woC}U9w#tKE?A<_xWfbiyJsl;633&_kizUk_vJA zLY%@~xFQ@@Bxa^xi*;*xEc1bh)&ZlvT(>~`J|`VNC*7DYcVO|jV@Gyv`2+~ot*sN; zi@!D7#eZ{ZbqxGmL;BT_fy^!b_TTI7m5lo40<7Sc64O!=%qp@3Ir*(4CJ{%h6Qc;% zk)(AbnbE(!e!qL8uYa*5Jb6vv!%BVG(yjsxZ+||jZ%^o>A>PoLwaBtB8Mgx^^QC?{ zYE{l}u~)eMv9i(5!Uk`nxdN}C5N5$G(OiKKQ3&^jr{losID~t{B{;AIhw!1?iCgT% zk&MGF(OiMENC@-$EgcP9M?zRffO|;b0TRO3>{m(PRT9Eh7?u$XtRW$61ohfus(VcB znEQUXXvVr-pIR@6fp|lb-;f?`AdWZ}4xGB`VvD!Yv3;-NLEJDu#2F894&yCLbZq); zX$Uuj7p3%z(hzRws-*r^QZ_eSOXYq`a;r z{d_ubJ{`st^H;R@S2Tkw*28qbVLFs4Mka8;+}VEFf(*R-k|L9VqiLtgtG`)nk)icc zzx7fUbKP0L;rXVp*lx0KrTP6kjzTrE>$79!?Ty-y_EpTUIe4?NxD@nUb(v44Y6^W_hpZz*MY+t{p zQAOEstL+VTd?QBIER!6UiIFuIWygzRWXhkiRP0I-cc`D969vF?{N8!z>3T*CfYl(g%!**kr>bj5m!J?jOGU zkR_XhlRmrd-){130Wj?q-17?V&n6E-L~#EHIEypwEUE7-DT6cZ1*z`^DTBSw5;D}M zQX0sa_H(({=W;q{+AVU=EpmU(w3n5Bmz7M;w2zg(kChBQ5c6o-JUWQ=1N?c~eFN>s znf4IvcZg;(ragIW`_G3@@A?b|;(HnXt-Y~xYUHVBxlVzWTNA;!vNoNac=LNSKWPChULT-(4^RX4F*vw- zLVVW}BRj-Ddp<2;(8j#Xf55@#5`X_~UaVuqKX~N4y6xa^WBhMJJ0Bt4BV^BdcA>?d zont4gIR;GMI=;1VI$22K3&lY4&x!eSlEgG4(}=(_@y2*zQ|jG!O&QCu<8~-^SE6^N zdTh$A-+$he6}-4BWJu8ugJfu5IqFu9(wHsye$mVL+0)S~XkTc2s9-YoNpbt6WWIs2 zUuw0VCla}I@a2N`OQv6h`mPYu6%xWCIxj!IUGVuL1|N`ASISj&|Smu^iOxmy-5NU0Ca`hCdE-&FWxbINFh>vKXGL{W|7OIoINA z__-2wsYJcmq+A^`qpV~@k>%Q?9k#1o1z+5<1U{K& zxP;u9WhZb2-f$nevk`#{Mc6PEyEDrU7qGBlC3a_)oxms44CUCJS#|;+tTLRy?re9T zz!iAIFW8-_ECQcQGrZ=P4heiR%}~TI9TK<#Z`dNaGdo4#lWB&dk~^DG0=uUTu1Y>k zrNM|Koe~rG3+DmOpYK%niwt1OB+_wS#O0!Lf9;EPuyQ#A@^f?#oZ{T?Edh$9|~-^F@}k{+UDM!)@RLuAFkyjr9SwdNC+--zyS33_oVN2G@+o|^Jo)EU??J6LHw?ROj-kt*T_VyN# zkGGG28hJMoP!sPa0t)aB5Ky3Zpn!tCg9Q}o9V(y}-Yo>w(z~UAqP?R9)Y`kXfMUI4 z1=QBNt$-4}69v@4yMus|y^{r$>YXZ}KAwGqgNJ^e{RGtCv%i2cyfcL7vb?hdG_=9c z+7EF+fLnuH0e#ruLje^uC=k%-2BQV^QNxdFZ(u-xTf+$gf)BTThJ>>4;nry)E<`fy zcQHw{T;`U+LE*Rv$&jv;<5kE9oG-?_a5)DbbvB83C#nz9!bAf;#DGljbrunuck+zjaG4qT zz}H$heGdxVgTgpIfan2KN5p<0eHOj^Gj&GnkaBZ36o2U+C@!+@`1%Q=fCJQc0qcHfyg@_a2E8ra8MLzJ! z3lWFHSHU@ch>Tz*Mcm>c|CA&F6PgHClG7idI`r(+{r+Z1t&>HO1{1nzVu!nI9K zpMmQ@N*<19;yPf;IG&B`z(F*}b8sCnZ5$WkfI@8IzH}iDgRggpI05z~IWEFJ@HGz+ zhr%8u$0gWUg8lwiW%nK&Re6R1JbTV}&dJxL)nl5_vaAc|u$YA`n?w(ZtV1EDLQ)wh zOlNe|84)DfAaa|bLrZl834%zOq9PM(yr2Yi6tF}POhp*H#T(wBrmeLCRW2GtDk}6j z?R-4%zs~H8`OTLBgk-b(z0do;()Ar&wTWhXtGUCvoaYZ(8Ua)KAxmRB2>pnqapy^| zvoyAa&`()aSi@vqvnYhb>o6Bux(T^)dXp7mPPBA{968-(d0m#4uEAO-=`mf_rP7nT ztY6VvtWR`d2xHR!utL-qr6Yth=>wKVy^%g- z=|j?ASV`0$&2sWZ?=`XD`>XFhl2y@aWtt{%3(glP&=~GsSdZl!PuqS=1tx>V z5GJMDZH;;;{U=)^TuMJ+Yt%>SPCM+hGkovbY1g8cSGo~_U-}6!P-=RUt=2?7xR_~i;wK#=<<;s-OY^__<3lD==$OL zPCMFZ*U@|ILCDWY58oqyy_al_E+L-3V(V9=U$r&5hIsz2okV@vygO8Qw}?lc{;RD~ zZ>D=~jW92L&`zTM%)5Ytb`IfQ`cr!V>e14}5%#5z*dglE(h@x$E~U}WPp?!OGa%^uR23>zyi2)H)#2Vtx(RbI=ysLF zJ(zSn7lVF4g}4`!jxZ;K#&s<^ugs0DLY1fz6)~Q#Q}ye(dN@9BMn#P0k1CCOHhR6% zn7cuDDvf(Ldb6s+3Lf4KZB}&{C@tNzS^a|EqLLUeEuGt<^7K{}V&JrNv=zg-p1Gpc z+CC0VB5HDl!u&;Oz{23XTOmEI}+qS6>>&GQ~r z)x$X*3Zo|KFl~Z&Up=Y`!^P+~RT9%Dq%n;mPw!PBrcp>o7(Pa$qaU}x<_Z|ES5+lO zh46fzs^7=e&hdFOMuqTvztWg)L4T+;hMCd5N@LmueNa^$RKt09cTm+~0fuxF=Ht?z zsw5U-NXPSX=_4w{f(+>h^K6bpPG!|~qCzQrK zUivGgv4DfV71P+9l({QX2>iyGUwV-fVr{*2gbXl!hm*O(xqx2glwhqreWz1`j4-{z zDZ!e1dX=M*8K&1dN#u2S7rNHLT*N$mzmr6MM;aG?;=IENk>}xghZCV$f_~J|$oJ6e z9lc(9laof?hj*`=oEkJ!(9b#=`5$_lqtRSJ?{YF|Na9`XE~gr!=cF6ZiAwKrvKU1t zT|j3l{fd)8Lz8qhM%76-pmUY(aYBr)laA2IO26aOq9KZY*U{K^NWbT3jJl&ga5Oq! z>3xpI=sWsjC-X7q=qSWXs*x};cZRVWF!q@~;3Sbak_sm#)V6cig?^kz4ME@J6wWa6b8kSL|MxWmw8EIk65dFgRToYGs}5E**u2nkfW+igM& zihjZMkVvI>x*jt3G^PNcrQ7s#W0;{^i7scJzv@<^%b9-7)yU}6ue%xvSNaWCBePHM zbCbwFnsPpV-nwyf8U3M~MjleS2F+&l-`ykzY z(VRwq=4#|A=@V`ec}i2-$FM~gk39V!H;sIybPbx>=x^LC@|MyCG`G>G-4OXp=?Kkk z^kPpVk4Z1_^b+YdPa~hn^Hp9F`Aids!1`Pdk37BFOCzr-U4v#h`d%-K{HAmP&2#ix zFGQYGIzlrY-Qj8EJL!i!jpjP~VNWCPNk8Ewk@sZn@CgrdhV%4OUK;sN=^8ZS(VM&w zc~I#H&3W{*o<=^D-sWjE>(S478hKHAx0gg-)Wk(pZnuX=o_@(oBR?u#gXTW^RWC%I zR60VlAN`i6kuRn9dK%4t^gEtL-qiTW+~>AD{+kOv8ie%|e%aZaJKB%@enS2I{z54~ zB{a|(>fJek4@y*9#T=g3u^`l+YM|j8LQBC^Xg| zE7a^a3yt^33r+MV3QhJW3r+K<3AOkwLak-3XS)$Fl%s5>(Co6=Li5Vz3C%B?FSMY1 z!P!DsX>MWpLZQWpvc(DUxowHEHu}hp5tqKK*TsROHR_5rYKnOec;utcTK?5^B!z=^ zH`DH3XnuGdRb?;F-Mwcgs+qX5z1ONWx1jNm-=Q76#f?3(L&ipN<=SCQG@pO;_O7GL z_q~@uVK`pt{r_djMc5<~uk@zkIX*^5*KL_};<~Sr-y;%ptZ356^6I$<@c*&IZCJwa z?6LPhORb%L&Ko$m+nRE>^=tFz`ux_fF8=+t33G68AaTWk#1wPQ{`ro!=Vx8=#?Nu^ zm_79|dxp7B>bqtCg8Ta4lKWpS?Ya-FR&((f=hALGX3a4dd5C-3)0f*fn~Sn|l-2aT z_RZ$vCeEc@|A{@*T&%>SrlziOW|$ZL*o)v?_q5Y$Ubx4jqFUZ}XPF-qh=01%kGnUU zC*soFO7Di1-fZ(k7w6Kh-QeA5o@g*^$ZL7gn`OSy``+BXcl+p@;HR8a^pLH;yKKmzeZj;!0C2IPvn^qZdDT{yjLrl>x>+nOg%>-NP?k zURgepiJ;Yq0jm?k%`bdv;)JWl7nXg9Pdj6!&R7BeaoXKfyBnA<^i%iy6b&Ct{LIwx;zr8MBZ+DnMZXP+3K~VeC+Tmhb?Ktw zb@4cew!|;n64#hNa~v|Au-?7OykJ3|-fimSs-kaK_dLDw@sCp9hq;CVvx2hSH;Fl50+{P$ltWT6mh--{FCb5Z+lqfe(wE<3tx=2Cn`qsZIM zI&Qo!@kcKt%1oX1^zaoAe>rvLXnZ1W=R573c>;@9JT`8$FE>72v*3p9E1r29UzjK} zcgY@jl$Ez3fI4E0KV#svmtc-bqGVU%JY!Q)#qW@=OpE^2p2UEj#8C4+c;@_y&J`Cf zosMs<*VNUosq4+nRneU5XH1Eo?dQ&!I=6uTCUU8h!56Cz{q_YlEIYKSXsG#7P*haK z53~Gm7(bkP)3g~mu>Y{Z3CmWF>lN#YK@|fl(iO>yuwp<(s^a_~l$4g8ckU1UbAI&G MewiN!1{)22z&s!5xq%@ZhUP_%t1P{0RSUN@WS5y%P>p9n5FS`p=v3z92Y z?T;w>8+z+8w;b~$@*jHbsn^a*i4)faoH`|T#o@Q}9?ocx?(FQJC8Vv={Q{ymO$fP+ zZ-`#MJcC5NC{nFpLf!&H_))(P1}5XuZM8&hXZ_& ze4ji$3h(ai4wLRteE49Hw6@>Ix09XLYnjN$s57W*rPkODbPQn+$Y42guu4M>K+1M4pa{p5%fK8qMF_c0A6IsR;O!zdg z;N|@2UD%itW8u|Qc;MPb@S~btTWKln zsGU6omck3nKX^n-H`h*u*Kv$z52~_C*hm#f6A-Da2O-BIGe9NQ1feN11Fg$ub7UEX znT=wfI%{Tx>M#ot3PL>uS9u9kX}@_W{-$(xq;qB`x?rWL@*EV~b5+|Fr9sEKz~WeY z#nIC^V>4N(Lx42G=FI4fEvWU4=2~-&phs#mx7F(E`nTke!GBBm@f?`$5HZX1YCvA_ zBIMzq2FDsWBJQVw7s84h{7Kbd%;?AoeL!J!;e^6olv=${1{MlJ!G%)VzLzGKx%gid zyi0r4Jav%*_=%RlOYbIHf#=wh&AQQ*VkC4?c#RQ z=$s*Sqt~jX(O@GPX#?LecKjX6Ds9xOxo{9QdZ3lzIau%_I$sZ=fAZj6Wv}DFPAr`b z5Sn8Q;+<{(FDWBoR%Ewuu>bz-m;ATqOB>6}ck4Ni>;B4xm1~65e*?HYjKX3!qTbPZ zxQhF!`#1l(^XIRB{QP3+9=TV4Su7k1<{KoheSK$X`PAt%XV0BqX?)fAvT?KVdE<8D ai^lcFjSC-q_{o*a7eBuA(bZd@e)cy@#5&dh diff --git a/.cache/clangd/index/rws_service_provider_ros.hpp.11A527BD4315BF59.idx b/.cache/clangd/index/rws_service_provider_ros.hpp.11A527BD4315BF59.idx deleted file mode 100644 index 149975ab03367ea443a145c77b3cb84cc20dc2bb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 13240 zcmd5j33yXg);X`s3nf4RE!)G#zI3Mxr5jz+q-h({onmWA(=;t9NmG-wP>LW3Qb4wk zrEIbYh`?Ye!nA;hg1{&O!!|1G03zxPpn}NYApdzyPhN0lzW<;3{}29rK<+vB+;i?d z_pG-iJ5{CH5hjr+N>e9Vj1Il0L?V&nU%SI*^6!EJ;gg-8lVh~im<+~Do3+MNYP4l% zr^}GeV6_=_b|*u-PEuwv8>54RgU4Ad#^7?>q!PU` zc!Je7-d?3Q7=r~VrN$cF1bc8vwaHxCim>UcOr<)zMW-( z<8(Hoz1r-+ilOx1tkq1FSl*b;ttGqJRDzvFu&L5ut}b=<0BtCt;b<*`bQZl~92SH+ z6P6~nGHexs#{JI=c)QKu>~Dg_;lCFs|3gu2{gJM!t>e;R;q-qe zSlCpnDxF=}lTxs8a%s|9?{VH^al5& z+=_B@E=g6D&S6CpG*wEljci-q)}pjxuuX6S#XeIf%({UFH2D&}Vf=5<_UaOyMDS?$ zwy+iPq#6VgQ4IoQv7!d;I%`>3D>;Fct&p3J1X?H9sv{8;bR0y=UcanV{4V57S{mdK^qZH zw9&ZrOQ=V8$ffWnu&w&8G1^RJwK~16yxM}@PHTlyskayEsD(wEx4jZ~~oiqRH;~=ToLilf$Gpn&SR| zNcg=Fuot4+z9drNfeAnD2CnU~=*o{4IivEB^x4XCTiF5pGGLcMCl^hJ#a$N-4jhvx zXVQ>nK5+A47$3n#a4rhpw`PsfANbRGIg^1Di>2IRX(+!5*iF#eMbq7{zGKa%U(Wk7 zfHXecd;<7TCbXMtzW?kU;QO#*q@2;<{MRh^H5<;a0d@`WE*k%{7rwGDx>qb`1|ZEr zFYcgM06z`bX&~|$@yq%1-*(^HOU}e2%{$)QJKlc$9AM|b^DaJ#?Jc)9SCn~nWQL(; zK7havAg1lhMWfzzrSi<_l#LykM5NgV0sCM?+m}dlX=By?)wkBmnLLzrN6OuihV#3D z-R-t#&1}h~pD#0GiV;9Wel>Txi4k?a#a>qOacpGaIH8c8V zlO66Ke;{WPkm6TQ?pIHLej+6C$2u2274 zgq%?z&0TNqF5c2YU>CaGQgQ#z@sGa^Ss`ZzBF$Rh)}C%2mNSt^ zbH;-^gEwSg4I-C`2j)%S>a+XFnK4N5sg(Ov8p}5V+X#bQTft&EM>T*OaQND)#4q!^6RA6&&oG^!ZN@}_z>@qUakK~ z+By9dcz9KJvswRc>{23?>mp}{Bh7vfZokJ+zL+f* zxvbf={BqHA>1dNfk>U|>k5G=1Rf-gE=M-O)_~hUXCLzV=-rVQj{`@>(=efz*dhEcE zfst<>mopJav)O~&>=DQpu|?u7Z@<&H?5$OAnB>d|q`2Y1-N2ocv1Ov1Ms0~lyY1GQ za%PA?0o)Dn5(m$Gr`E^4#VAH0{MJ4Up(=V!7Xd~OOH$BOe|8&^yX%I2lBIk zods?*_ewk5p49%LoC!jjFBt9%W)Ppt=8AT3Oj-By<*QyAIg^YO3s`Oe`r%?=7rXi4 znO$SXGw-WU$(b0WY4YTnJcsgD)+*}u%)Wy`2l|ZmkuzCHu|~?Rkp}Xcf!*x3moF=3 z?_9Ta<;0Fm7@oQXv@KBF_T@VDg%hi8pSbWdD`!R`pBtXs4UA9KY_(|nSB70bv}y95 z?Q$j?Dc+HC???mqEx>MZ+wb+$XL=1xU4K^2_#@4BhTD!Fl+LD$T)ujgntkb=hoN#N z94W4PaaS=%%m8+V8<%g5yQg1~9o!{nv`AAgCQ-q+*4ei?UHBI=W9gA7o za%DOr^egkOvLAaQ zbzEdzJO!8z7dxIi74XVxM9&1(Owf|WVYLdL87R1pNp=b9gG zSuNpk^&H5W0|k`1yKL;UdHjPFjktOm#7=`WO8YW?It-r<$pm*f*3z>4_+Ppp2UEOB zMLtf|2p+;&gU~Uk1i=ZR^dNN4$bG(+x36FBF5`0pbCZs=IhKsi8=My_LiyqOspPsc zeoW99g$NZ4D^O9Qm+^)Eg$W{L7-mpWijnc9{-p^bR2EXEr0^!=%l*pZMW`;QPC)@j z#!ntHIZlM81Wrk!L?Gj*4xSn-Lh~SW9;8s{mGSc-U_K;@@In~25LA?aW&9%WUjzvv zycoh3gPMYej9&tQOCU*vmx2E>NFei*@eMGr0is2C1%$4E6iP8NekBB~ghYaSMtya@ zQ~Tq7c)6xwrZ~DY8DHUF5lK+5Jmu`H++KrQ4J&gdyhw({d82beCjz9CroNn7HxCrHzy~YKJs-YqBFD^qbVBDD&+61O^JU1yQ9`{ z`_t`6UlmyuPq8;(!kga@`cqUnqRnb^78NxChciBYyK#3sqNjsuI%tV+pr5p9<3-P9 zIH8HtC@Ca{jF&bKdN5(Xi8)k4MwV84p4*Xm9nn>ZRcUk*@?bordEkJ%0iD&1vR4JI~1Diw+{tTDMJ7(nHx3^ND!9t@zQ zBEv2LE3+Z$wgy6ZbQSyIz2v*7h|ocyeiW!wR|-ZpyfjHLu!^XPM6x?-O;A71zJ&Bc z>`?#CE`%m18sUV{dJvknk7#GV;hOlUFi<-CkEc*@wlZ5w)}!6$X#R8EXa0z;R#c~v zpJf!xS({QfvIkn8HbR?Cet=#PoS`8oqqM`vyXsT7;#yUtDxR_cvBoV3?F?;zd==3` z4@2mjcFO%0qkMi>)RQ_?OL`K_A$&DNyPJdm8W<*;!y0&T4d_I8Jp`?XaCh?v+yG&s zd2E3E4NxS)n_%cB2o}v{6Xb1zLJ{5!5t|{#-F(8gK(xF0By9t=yZHoehcME=U{3kl zp-6-qA*>OiM009{qDC-?a1)GZf|2g#HR3%O>26-JyCI3}A*bfb{A+WMR-o>qlu;UT zzg%sX!QU*3^}>7G3+!I#K*fd(?TXz89mvpf4`!?w{9V9tT%Qn?kVr)hMFYGfp^cC6yshwRZ(O0}M z?X84AopT_4k~%4iIvjKM=QAIVKVE|9xsWs$(kSG<>>uUWwkY!Z$umYdW|Uau6ebm>Q6RxWCaE+{ zEM&?P%TvYDWpe!F6tP&DI&!K?EKlZxVm_pc<;WsPS_ElyRYJLuyaY62xzPZz4UjCB z7b`)r64I%haQy!6cXOH>?0D>HpqU0alq73r-931+V2w9U)GBMWWU3RolwQ-Ej2H5s zQl-qGC`1RrYY-ZLx&-n!L_52EnyC9|UXX%27>8`s3UwN#QF;Tw!0dbgAo|HmZzOc> zu!BK*Yn(NiENk+mwY%PwM~+8ytSUBx>gre0?wl^F9dr)Sszg;9ZIYzmZiF`j;!WR- zPwP{`)}0H=H|&8>jF4_MF6kfF3U39pW_spP{o|i{TTs$;$ea!@lKN(8BmKYJ_M;Fn z=7MG}Y8Y*U$iG zKHG{-s+ikmr$N9%$7*W zPR824PQH84x()eTN;U6x1!7V<5eFC-juFLPb1#zEwYErZ10LU^ZuTQYoo%W6cmLqCI>~w5k!#* z*9z}Ow3eAyDN4S7kc$Vf$Jv#noThK4EvYdUoIrF-6MIKUub=BszX#9V z4AIS?AW9iNyd<~4D0-9GXU%=7zUg)j5~hcxC(@l_ZVlAL5VSw0->@xT92Xj>ddRMa zLNa)Y{C`%$G!2?U{jvj8=F%{9F0ih98)qQy3cK)DuzY0b4#Kehe3gHK#D*bd^(TjMX z*pS#5GHHC8@QaHe=;M{MH?>UjS&eIJV`>$&_V9BJhS%4h9U){obzYWRrpp*JhR%u& zyrwYEEz@aA^C&@Jlb&9lOZJ3qdFteBx;kvc)l;)5(h80DsQECOtX^oeHH#q6J=1BI zK)!pXQ#C+_d!`$;5=K*Op&P-QaJ~f6T^!LJ|NYHboqZ zOe^ZUPFbfB^*tqdO1h};d5}5}GDUqa1ocA55cRzn(iTG&?Nx@)W=YE+Rn+$iNL>M$ zr0?U^$M08m4K6~BD54aJ6e~{j==;Oi4SR$FOq;7Mq*!=n#NOuGS2i3)HJOK*YH3?6wq$KJZ5bbS_tQrZ^hH?gZuK8t64Hb|QXfy~FUM*tXPz4IE~1m-lT>sna#*wq=j$zPfo>T0 zCcM=W`qE+J?|vF{G!nO94Y9`1!SFS}uPTC|%T2%A^TvY-T~Stie7uU1B{fCJ()qYc zOt0KHmw)2sDZ!9ufMy2dP~y1S$@H$Z-QNZXXGzqj(OIsQJh;T~_H4o+6fq(~L2s8r zKn!SxNHHMphi?0!9~EcU?r)7fh`;oQd!HCOF`hyL28w{%D1s<3;wFXHW!fU`2+__b zWtzCT!fWfSJ~uky7Bj|V=*cX;k$>`5_($Htd(}EfUI#f8|EaS?M$UIB}J3-FvfFKp}ZAb;77$=bJt0_uj@oB;An81qV>ZDU+#eq6xlA?HE1i%;L{AgqEWSgPYd{x<2-z`^Ycv~A6|rPi{pxu$wYq%X(xM4y2*s==Rouv zP*GSF%IfgBkU%gw2g(!NURZq@vbCq!GpQ7@8O{367`5p+R6_I;{DmTW zIpCBxMRtkgIdRxQ9QG53oy6hu;;^GQ#9t<$&kHn=NPNX%UvVh>D5LGul?D1}MMu)zqNF?I$f4jqGnl%sy{3jzfGt+3RHW`d*Hfy!1*l5d0 z%@pa2igdObyUt)X87+>+g#vWKyWil6cA#D0eQ?broq0<)^n=HBtd#OFpX0@A&&AL*f z#c0zztTvsYvhqJNgLhj6R#S3sm@@nsL)%A|La?_7Fiwtlg$b|ys6q}+Z{%a*ot!B3woaMUJ9?~@^)7y$`^w=txu=uc*@Xdh9VlY<~JDY-EAPe2d zuZv~>N20r18eL^~lcd91=Yfq_D;<2B5?HD?>kST*!F3*+!OV9n&aVfiRM~AVF2lHx zc>FIgD$r@yu72g0nW~KjY=cBUZ!WqJ4+P&Xj4LE|K|-K%1Nrdb20jRNZ;6-Yob1f3 zPJV-XhU-GPS*obAQs=PhD)c6c2z#>b>D~2y7Y1u?H&AHWbUf7!H0aIdBE6yfXJ~s> zkxsDHPX zqAP54%@H~cCn#iU5q7>p|BPLM&3U#NR&*6?-3hL=+Kp}?3Nz|)KV9^$?c&&4$*aXR zz#gNU2?^aiZp{bk(H(Lr`~hs2zN?KkQ^{njG~_toO*Lwi>^}d zDEki_4!ynn-$>5(z=f{j?Fb_eA?U*J{<_5y#zF|Ec(fx6mY@$JdF50Zi(N>3>%hKG z&xbnHQSoddxZWWiutxj8k@*wojI&I3$1jsi7L&uIH=AlvCa(__D-tmW{(Sr|cPqZ? z&-Cmel5~P!Crs}C67}I9Yw*)|T`7)1{!M$!aq6AW;1c&-|}VuJtEGLBIb zM;IIC?V@{aUYMdk@~4X&lS1@1VB27%i({zIqW;xee!S?#0C5B}!9!g1F%7%G>)wo5 zj?oZ(1F#$52^WX&`AeVLSKOY?F;5c5Twv#dutwyM7cYJ}bo&U7i6M>#U>o3Z*BY{Z z6*qr7qoiklCJ?o882k@|wEN4&quzVfa_($GTYn}Fc@BWz0f_AW5_m4RRUTe{a}&p8 zlBB)B?seO3a)apd4_BCJ91}nsd2F7rlN9e>3zl8ovz%kHiM|8a9WdG@BV8jOUNr9W zn;hdy9BFKtmq33edfD^dN?(qV5`88+Q_x1vjoo&*bMh|7#1g%Rtr6xIJiDhoV_XBn zF+oJ1#7+`!tT3_EIOdHLD>x>L=-Ywa4&z)qnC77n|JC2plVh~R(E@CX+l}ay{#UO* z_xEs)krBr-V3)bw$n-G-i!z?%m>i|0HxQ+UM)-E{Dz5EW# z03(tF_6{7;^^d5p(+5EUb9Fa5^zG429HXKY>e>2%E(uMOng^OkO^@c7u|$`$(#Kr% zwK2VNLtZ_n8WYx5UHTS;cmQy-$}jhty{{CW<&LtVPh|xr0Xoj*QCj;FwgRZv}R%+a5le(XeOZ z_I0!RGr@S$4$yYM^zJX$NiUshxpnH&4=l$-(<%Hek28 z?eqHCb0fwjZaU8~PZ5WP)d(wm`cq=YpLpjJl$It-Q&U2qWQ>dQNtl-OJn^Y{Z^^gA zkvlpfI*!7H=g0joobjt)kLc$?^*m@v;{!%WkDWW^a~`*#2vSJN`Na~Yk20JfZi)Hc zE9*txIJ*JT8z7%@?4Y($zb(JJb|=oB3(<2yL+M#8nFo{Rfr8*c@9p2;eDW`YaD}qC zG8K6+RSb9tXQe>Lph5u&e1Smd;SmSDDz;v~GE^+d^v{ex-t9nQN!Em{XaULz%Sj~n z6iadga^(V)7o4Y}v@Dk7`{qv(prYU+6(tI>#Nca~B0$Ce|<=tDAvi#)z%SZ^61WuqE z9F@}2V)vgJfat22DkX)M(H|weauj&=2Ksst~q=B^E53-=^1O?lq3*>Wx9>cln1a%sPgW%?< zbC%yNdIr%8LA?;tD9?m%Dv22%IAksoYBV*ORQN>{SM|KGEA2X>tum{IPC_1xCwErI zbn>{<_ugRSmifpZ6&IC2mD!Yxs(#aV@7##!smiIz6!WN*#+c`Ab_k%tRV>*7(j6eDQd=x(2U$BLQo$#d>;msyFqTS4v1AW; z?}4$DPQ;SEFlsMMRCgEq$`dW@8@CnTp(29E2m4T&w;;3u z@>N9hod=;a`zjAt7`Yb*qn^~kTGA754q+`Y+1(s`H$bpp4jUkE1Ly>JBLr-OFn9Ct z-wdIGd2EK<%}^-7ZSYhZ1PbQT2H9;;Ai!H8d@D%Z%_nRdOm;V)`0b!}Hy{5U5K8*z z%_(;W6bf)VgtkMJU{38&*bW8(-UX4nAlBWyBKJV7yLmTf$aoODmKJuSL^}sBty$On!0wvSAHjPeq2SESuTLYzDECu;eND|7C5YV0%2`@6)tW)Y*OE`i z@%c}oQlwH8qJ!Wy@C`g&0{I)FoqanI>fT%$Aoo5RgUcky6Eu`Yshh{Z>}=(U|Cy%G zrVRGn#UQ^W#-bq0dggNL-VIztIijU1X)4v#^_s8G7S0}j0ntjCQbU_0DYzTH|EIO- zoAKys`?v2|R{C-$gkXept8q#HIG6AIY0h(LC-nEfA6bEt=0Vy#$RqVF)JFJz^y;^K z#8?c;iy@ortl`A$-J0ysASCEix>V}>7r)kfhUwh>D~MhI+69nJ1;mS<%=%{ECD+gZ z=R@>-&`>GI_Y9Ms2L-{)v_q=T-tptNk}ge`lb0>O6dmyS?~^8WMU63?;Nu=O#vA}2 ziW;OmJR$#fK__fF(?^>-@23`=FAJ8%kROR9@xJj91g+`)Ba0*F}v$+UaE z9Ew;7DuSDR57p1PU0Z;gj8(^`lLL`8qHO282uUaPAc21laiRA&-d_Jg-DQ+FGjyhm zlATy$^S4O}YMFg{&ytpavnb1v?8v5MyJ7#D(+6KYT8(H;vL>6NBN+)w;vZH>Qmdpb zd)+G^y@lM;7^#Akv{CI@9M(E^F`{S6XKF~~#!E7WS(1YXMT9|)Y!)nJs+~?!!){K@_F2%^KFMV`O4<` za@CzM1FB{t5JZs) z=kjktG?%U)(fm^op?CYwlNWt+HwzD7i?Jz5IlI4@_foYn{}iID5~|YZKK2|Mcq37} zHwn=uxha`yH2TK1`DY|rn<@@OJ7158K;aSz{G$<}>CFfuiu1vU2nQnjT)*JCs1wh< z4<_#eIdO{dp+(UFDf9+&(3&-M(e7KB$fya`$mmWnxB4eZ2|6r&GWeAbPx1}aLdaMM z1!V9P{c&6TI}}Mj((C#6ul1a~q=#5CDSnccGCnUmyaQw;Ta5MlsKek#1^tn^9)2}X z4B3TZ%u!|;CBY+2btjJP-}Nk_gZ+ZTsj7S9(yiR_?VpAqx<*!`rVxGj^!B=jE&JzrtjD>tq_gBS_t;}=3=1}$kK{9*IxF2R)1~G0%vME7elb%$PMfQYkd174#T^%;!>N)8YY5B%GWhvy4)$@&Z@^Z*_&ve>V zkn5i5RI4G?J=3MEg&c}4bR&2Z&KEzri{rYJ`)(X;;(NEk#KH{n6FM96^Y4GeeIl>$ z*6i$8zeaCZ z|0*d#bOw~=d`l#0?~mDk>)KOyR-nE!6`4u2C$S_aDJMhFcb+;gRnT{lx+qo9w=uz} z74%)JtW6g5U9YH567<~&iH(pZ=zAHcmqDta@0Flg3F)*~F+Q8cH$kGH?`BABhBVUm z$*PlgEQ13JQ6uqD@iK}Pr-qIG+q9QE`2s8@E2V&9;kn2I9kc6SK7nc~4=#@(%SJo* zHAfIcX&=?ZKd6$DsB1v9^Bt84=l6%sSa+qQ7s`s3MQg~mFTC`ls&Nr)LRq>Xos@En zSTfybdN@HJhDN`x{=-y0O-zrN9!KbprfDrNoQZ5lv@A}hqEnH>qE$FwYiSE~!?-v8 zb(YYVj~RD-|MZCn+=3;@BBg`jYk-e6oS-YacXT%1tr?86V&h^}lq{(!!X=##y0qxk z&o1Pix^ad#$#NTcjN!+WC}B zgd1ynZC^O*vjMn8?bBL4nZ*~}JDbDa?9IPdwSuA*GAaI3XNe0rUz};7ubzDK*2kBA zvf_+LZDcNGu$zY`$=~U_g||kt+?-4n^|dHt^5a4F&k?-jKiV|Oc@RyP6N(P)p zLPByvHs$7T=H7{#b0F1*=y-X2GF|^ShZp|7GWxU<(Nnckb18&;`|QQqwZotF=e;*2 zGsn$)vvLaEyf-~B-_3i|i}KyPH_e#m=Dph5TsQAcsn2ou-i$^laQEKyWsvXgy_qXv zs=N0lH9?lU_hvLh0eLTV!l+;8dp+s*cH1A~KkLKs4xorpD5z|r3qyYX^`5xzO?vO< zapfPY(N^|>$3E~9jH&}XI>3t@=iY{akMDl_*a}=$7o$^~M4~5zA^&5J?#~b!h(sfWVIN^QSQw5Lh9iVwFJVZ3 k41yT`4@9~@-ZT)21_{G{!f?1S^bm%_gkfJ{C>DnQ0!v2UNdN!< diff --git a/.cache/clangd/index/rws_state_publisher_ros.cpp.1AEA19B09DBBB081.idx b/.cache/clangd/index/rws_state_publisher_ros.cpp.1AEA19B09DBBB081.idx deleted file mode 100644 index e220525d5e8b78a117848e2bb62a93ce5bcedaea..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6158 zcmcgw30PBC7Jgt@n?T4$NWvBZ_<+X~WRb{XBw-OkAc+D4H4VuFqFFEt2smxEwPLku zTWuZJ>eSYbwzaEW-0GBCT9+1EwXL02>r$;+vDPkHofGB0VA}aQ)0uDhG`#b_bN_SB zJ@=k-g0`}(ELezPrRK_+Hp*>eU>L@R|1P)FA`XEE?+-zkot93@N!T1_s;DhJ9V3(z zH5#4Xps21k)MyOVl@ooCUZbuoH7FZv0IsQ`ajmLc)$nUr*QnF0)W62{6np2u233t> zVztU}YjI`GBvq+*4MtRw?G777wmExRj1<}Ba87r17)=yuY-ur=sZK+ei*z|nH$|tz zm3{M}-RLxT8J(2DVs}%{RMVKHb0Cj;fMR?O@Zv&N9SGV15oJlzB)^3cjxVl|#%7zh6%H{AlO%!3aIE!wJ zKhxx}w_4grd#A-lc33@aZIqd8ba+Y~whk*erlv@DyTxfXfT!+mvfE@c-v*ehMtd7+ zwX~48p0ctt$7GJdz$0@}o86P1o|TW?X7IN*{P#6ryIpSB<(t`{+H3}!tIb8{;CBuD zYPqw^Ww06T#x~0NM`<8taO4mA0E@weKe*Uw?68>sn;p1C;IbKvX0yfqUokma9Pa;= z;NQ7kUL9|eAnR_*(BWyZT3qdv(*Rd8(|gZJM~9mPfowBcjc~6_zPAa-1h*PW4VNiB7dOeg2eWhB3c}s!UxXEgv>~6XIx0cA| zSgXZK$w~6}Pv5^2@Nhl(SLMcL?C5|ip4kqu|3B^is~r5l{qVRgR*Tz0x&HS%@Owwi zZLz_@GePxfF`A}BkLaW_9OZ20~4?_)KO52Rfb1SY|HmVlL($_wNP==Dyj)paov!vbfd zeHqlpSP;a-Gh;JTkXa^9CX#7BNs*`+AyuSQkiK`iG~HMv1#!&nd1h=+00XZgsub5= zaXs+d*E<%3mIU27^Nm#*0Zd#Kqsri24=cF)a1|@`fyeaSA8z0SoLZBrMI>QQXLaeW z-kS<=QFsv-!R#T_B!1ijav5_yUnn5(cmq~y0e4C`|T~@LAkViG*aTkMK}r%QdtmPPEyX; z_33l_m$AOR%E>%XH|B}?1ZYbcQZ~}&^|J4J`pv=T04@tJi$JhImDhXU=Ie*3DJhw1+BGP8!d4+i+qFBg6OF)BCMXlrOxHt|t^raCX_FGt5(Gn- z@wr((DK9>6gp{9@pX+;9AS%f4NlKA&gj6G{p{4kU*#+}M_Z|Zek_1UfXi5ChoF^JC z4c-{uaReuPdWc+ma>=Q{+YF=s#0>%io#5olPmk>zTK9}!JSor2ima}BDhGU$MoH;SL1qKOZBGSTtVQd^YKCc0|<)h_9-zUpfJ!+60Am)*OUmY$E_cKYV zp8jIz&oyHLnYb`e$VDdsoDXcK?`;+)e>tZv?1JCg?9bn4>@dnGfYajBGSfCK7Pd@T zbZMMY_UBpmA8iJ|^7Habkzew-q4%Z-8;9ULdT$Ma8F;E9l~w|2a%w$#H(|}H$;*DM zngL7|{EB1*D=L;^!G=Bge(p>pE}!3Uwe~?jxOCk2tG24#zd@ z9l)#tRuKxkBJro#z5OK@A(>H0Q6z#PAquG)t!3ir{B(N5>lU3(N*BG}08AR0CU?Vk z*v6v!d(P>?RNHM7dy&^b6U&I0^Z}DL4i2on2C#y!NI;a6pRZlb{bnNta6UJmhNl>p zHEv$_ncOd?#w`I6FIkUYf~<)dVgcfYLl$V@AIp;9Aq!6Y9V(d5k<2ou)hWH!=@?nKv5XT1hS4bc}6S@7XID zIZT2oqiG&HtKfn;)Q`J;!xqu|>N`V$WMn$&A2knFXM|#dPwK_PiF)%@N{lEZ~4z>a%YuUw=nPwUIu^r zs=hh$ZtMjHPDB&J0^QVgn!(Fs8F+!PAjWE}$f%q>u#@Y_?y z-PODOCorCyol9TsNBa&Q_{$@EfAPZHT)G4=9h&jO@#$ZT1(+AXi$aZH*|D@;6Lvg# zcG%Uo7Mz{G=WD~WE1!8|HN|zW@{3?i*}~G|!L^?ONiDNhfZ|;{6nf`tAN82wNbxdw z<%k=kI-b=h@i}|~N$bl>BQjQe$@Md^;Y6#(xXb+x7^thPt3w8!dabvE{Ojhoyw2Nr zPDJwj+zb6Hk3`M|5*4A!Mq}BQg#lS(2anl6o6INaj{PEeVALbx`tidi(e-?({)M3W zPGzB2TS(Hi=ar?q1^q9Vd^N0{+WS;==Bo?Wyqfpo^4<^6RSd&uzqanrx_jG-O-}$x z0Z}jx`TbhivYF3KIDLe{z}aFpj!q)XBvpbYpCqgm-sO`d)sj{uy{>=qe)34}KHyD> zOrdYy_8W!S=dxA|4SRviq2362U|}qJ=m81lXY`VZCj=$XOgn?_-+P=PUjTPSQY@K- z>@xAHgsKcQ{_b4XyQlxPE%$&ItP)lQQrh{%gyq3&6So3fC@2&mFLovG>}Xk~JPQ@9 zA+dq(TMWEO+CvyhgU!9tu!@64Sh`xXh)47 zJoCvqfTJR!q$s8Xwkd^U4zs*1N0X-+kJ{M>gNDl1%?@v~A35}XIO*Isic>+tn=##>+H{KZfE6a4ITS^GH-WJXXTs6-Aj z@ibmq9GW)1*wx(nRi(fiT!tirZpz0(7&~RWCvorEKmo_MwlT1ggX|t}`SJ7kR~RpV zlCV@bq7mdo=Sb0agA-Kl(9fR_?Duo-#J9F*j;B7j5KfvvBFOL=5XK4#pCpNt#3SjX zr+sVc+?-%w;&FIFbcauV+_x>e{iiA~9L!_V@KFKl=;WDla84$aC89nJ!!5r)4h^@b z4o!B=SwGDV(Pt8w^!R;-ol_UJ|MU)k>zH-)L~u4KW6r6h4DWQ^z-gen=egp?KiIu* z>-jt2j)t(qkh^e4MFNRW5{iYfK1sro(BD8{k`Ty*$U_DWU&f{AfoGuW>xB)kYQJx}BKAwdxAx0P`zg+R2&g=~oSs*QF3o>@ z_vAZ{09;&HT!mag-?#(AhremxYI#stq$wmSZ&yN=+G!rQQn4`RJuhFW@{}I;~RjZY%vA9ZI zpqyEz)m4|*>Wa%N%hcuS3awIGtf|PcTRL=xPJ`KIrHw|1&d}ZtW~=jOYKzNibm|J_ zj54)uWN~pti8|lC1|y59Hk*Z}TJ2rUdYbC6+2=Xh^#+>KH#h5y^a5RngL2pncSXC+ zF?r;n1K7IXWFq+JccbjI`4Zo6ByXNu$Z0b5Hbg zgU#AvYNf0TOctu$>}qYLja0qOm2b1Oo58(unsT<8>_#2<>+GaD4Hn})fWfS{wo+zO zGd1#*I$53~Pr<-1V@|8pC6lFQV)q#Qr|E8XnaoD7JpUWZOjd^zHsJ0;y49kyI9eUd z_WZO}@8x#bV~gIZZ>8-&mj)66j{Hm?U@^GxGZ)+S?Iz=YlYtQehefA18co*!ipkb& zbN;6UKUQ(>cka!B-FDKtc2~36W3}w-`w?jLSw?R_=pLYILuKwS4T~3qP zx<`VVni`X$r1h$ z;aGrskiyT^^W2wLQ~VANmWW|QU}#{}-46^KeSiDwNX^sz$yacn1X$0(ImyX_-DGe7yHZx8EXUp66+lqVpwY=VlVl0A|#Ryjs0N+_Z{?`o23rXa~T%-EJ; z#P*G25v63QQkU`>K6iaM9+2ldd*PdFiE(T~JyA`#Y`tRfoYQpyzkW*F`B85;z=;)! z)rchU`P7b@Tfa&KI43BFhhXk-*gF^0Ltpr_39b*Ss z|A{SNpedp$l7W})3I4_Aoo0Y@L^)Cfi~S19A3t#CGk`<>=bLsTwZR4yFPB5)qgN7^hxz!!vjBvFJ&fTXBPyPpUcI#Ul!1$cpoVY(fla`aOY z*ft3%$wM%N8J(W$kust)#z>iQndzQ)S;8#BBdLU{F;a!Ff{~(w7iTRG*gps!#Nlyq zXi4;mw2gIF2kwk!9KkW49HBOxef*ryy&C~1K~fu!PJ+aDXaPS`*aMXOBEH7|_zd1_ zo7;Qiiu*4VMsDT`6q^77Q#<}>cN2*pl z(|H({)bs0^tg(s4@J41g*n|$(F&i9z{rM?9!<%04iYMWPMImLS&!vG+l28eg6l8W> z(A_q&^W2mG)_4A+a`mQ3yhfN541Uz&Sz=L1twcu_opl|@fte!6{`Uhd2wuV3!HRr!z?oImyJwS8)5A&_KD&X|Ts z)ce->@4l|O1~4a!lY;^;iv2cn|K7YSu$iH8p%j8)LzI$ow3bcC!evats~$ZcClkI= z2TU5NCcVyYmfx9`2X55_s^7NI+(+F88aR5yq#akXb)bL4_W&!yl`)8N=I<-l@xI(j z1DwgrWZ+r)RrT98eX8(^seZ?};8)D2uEMT~SRx#8!y)t0@eyUip_g)x{%+4KueFWr z|$d)_w5?Mvao7&S+T1P0boI26%C|_3jXUP(C{VNXGUv%Tsd&ich1?!9mFm$!3}{ zizo;w7$a3iR0>e2&YHoZzr1?J1xyXRhKUGvy%N^ams|2{fVqKOX2Q5mo&CBbH$&~- z`c#VhY-I;! zGXtXQ;jffJ&Gk~~OM+&B0a3CDahuqLq^@_eOF~;Ve+g?ZncEr4Yb z88f)L7f4TASVDh*t1GL2fwb?Ru>Y-?=dOJ+n%SY+o0&c@^(6hOhbLL^-Pzr6K7^4% zB{In-$|K8_Xzk*`b8&yV-zOd@-32*vE5Wb_qH<&W-~S~S;M^&>8Ay9+VRz%ID}L@N zQzNQLLh!QnbC1xeil+gtl2@q_ykc?I>KEtVnCrFUkL7hy_RF8l_hk_>o{V4Om@rs+ z|DyX?1i>f5^K7<@DNV<}Wf5cqDOmp$toX~!GS$=1B^<~o|^TOQw9btpiN~`%*1|~Iyio%sCL?@ zNmQP%)c(P@c7ZC}tu3IK-t*d%d+@!l=A9nZR{w1vr#)fG=|5(?{7m;pmx@MVl&`)I zQ-Ar^>K8WxNfwzk75V*o!K#JZr=LH@Vi8;sHwm3YxRaFP4IW8QDVXDt#AV_ZB)y^C zvV=O8egJqALK2wDd;3oIfX2a^&R(v7o0p!5mMTao&i0|;ABOiGTOQJwKIpDdDwSet^e>NnE}1&174u5U`(2wpKDzEV?oLxd zRxo99uzLKofeXhs0UR0}DnT(Fw9Lv*Im&U598HF18X9MR9nclGY_qwC{n$(IMhdt}1eLU&nZE4%3 zFxVM94=+XzvWaAVaum94e7?J}<#aLb4vr8L%upWmXYG>mw#rVaV>O z=5IcWevS19P!i+|#teeAh%^cMZgA!+%L}IxA6fxN3K!#qhe;4AAU%>eL>!Hzv#z$j z#HDF|5D!0$FF?h5_HfTzliR*6b;EvqHUpo)IVWZ=RDc&!fixBkWVpqK*G8dR?71T| z9S>}tYlSf7q@1~DpI_a(q&M?6s!|3XtP00=|@mAXivK zEw45lg#l7bt;8eMht)IQv4}=qBXbdF5jwt(>90e*f2{tx`G&~rgnVVa9`_*~wj2T~ z3@T*qtHW29KfPz>gku2bX6Ke7SI{?ZpPLhbEF;@)kKeE6~ZQoNOnxZ9a)F!~HQ)CnFH3y)cgX-(v#XgXzJKz- zj>ldcjP!~EB^B=XW82i7;r>IL7xkG&wNbaW(`LQfarnE0gK|G4yFW&LlF$P-j>zX; zo3^g=*~0P3Nis~vyujcOv}O`Sp-ei?XFSW-&p#j#kHur~Xk3KH!4Z$dqk<-|d0|{m PXh`tHhY6hR7Ng;xAQ#1}zP@Ie|w{ew2Xlu)TJ`s7bhBS;k=Le=_%M9-bg*=(?)7V*NK zxqHsJ-#O!>DduGdy&8y5W z7D|Mc%Z5M44b!oi8;p$nNpYo9;5KbLY(&@fs#jxr#ecX=nLg+FGrUesrVCVyJ!s5v zy*z6>R;ci4-L?!~GpJ?Ru2JI^uKOOhEyt)Zm-#gCe8a5Q|I!&w=>Du5*fnNwQOV9~ zy?#}hcx5m6y9CyK!nk4b0p&CQduV=$2ds8AVYzQM$n^M7xT#X#nxj55Y&T&3v}l#> zn$E1%XxSCa>$CCi$o`K)hix|MII#xI%Z5C>dLU* zZtkI4d7A{c_H@Voh2dkjsB&i;Q8M{VUnqzot~jioRb>x9r*Bhb73{q|y@R1>+WUX| z=Chw3eX7tYZ(4f~C|hD%HaG41*sGr}{(4|gl{?^kZZua6Mbm!w^}lH6&)%`3%1N;2 zGx@$yH0=jZO6r2Md`XqB1-rIiyFV07`C0GT zaeMmZ0ad;R5VE&rCqvOhSp88eJa_KKm2O$W3es}AyJ`2?G@p`ziZ!OBM92^Z&U|=c z$LnvEl5I&PyDNJuMoTKWn{#(!^+`n=)%Ia6x#;-hlOOzkK}sqqE!B@mNHqiyJfj*J zmf|6^s77e;7ObLr_u+|)&nU_lpoZFq!ybYdTY4e(-Vb}ehmh&M^Z?e3?1Q(U9zhBh zKbh!`U7iB(%;roFR$hvaovyLY;{s$NJ&7P#7J!KUAjrWtpI+Vh%B8K~-K+L$Se;wA zX{G)7uRaBJUd?aC432!%bDSQVIU_0 z3O^qBc6EF8yA-Ii{n zVys035!4E;ctJ!T1VuqmT7#Ds+VrKALVeLEFGYy3=Zs>n5Ii_6mAJtS-p7s1`T32;bW~hewurfV(BZ3f%TTDJsD@#=ibHEu_C0DDwo)@)(^mt}SM+-Qy2)@u_GjF{a!iG?Nw!bb z>uc)7)4brH8ffN(b;ITZl}`WfrRhN$n9f?tQeSV7>CwT)A=xs>Ctsu;_ zQjl>dZl;@uJj)GQcGvPh8(Sfc7g(OF7;2y@WRkk zK27LBN88N7mw&2r@7&PgTSb0-j0m}6t}ir1U_TS^^ezj#>3Mmx$ag}#)LR+|O%(6{ z7oUld_ENr77B(g~ZiwRY$lG7f|9;$CW`Mr#))(G!WEGhAujEe9t=$sKmGjsGw`AWei+mao^0(*5LlYq^|14ErKEHLbhv#5|j-HOKLYB|=L~-9dKqq;iVudL# z6*7c{bDtjF_TER;bSy38cjRxwYH6WxOW`h@J}pSQq;FUES3OOueD+mP$U$*b)nryR5E2m=|*jw1+;1t4rc2(tgf7nZlbb!8J| zm&B5U)47$K7TaF=?n`hN#o{LH;IYqokEn;IPqUJ#TsM|H{>~U~sw`GTL!q3Y;E^nE-oB?;fKRKvO??y?bnON58}rmyHG9+VV4L7du;85 z_@=F{hZUhJ2;vaBT&LLP?|s~FqC9MCP1N-(hdOz!lOKLZ}@6bwiWqS>c6zEX)-VO~z5iX&5+} zGIYjJ8LS&ZBq8f@Mqor$QLt#pszP=IMpGlIL8ykNCK6a%t~0^j5Tj#l5NkGzh4Drw zOUe3#J}lKTMjR`^0bZm}%!MhU|dD-3ASFt96FB1W!A37U{(w2aOt z1x1Kqjftun6BiUIAuBOc2XRYOlgYFqi-M^1*J!J&uVvu5k|8O{>10;OHf&?? zkeEnI1iOSKFAZ9Tr>;OD^5Xxx$`R93oFbtp(7ZX*Bo`}|jMO`zRea-Zv@EZuuBl~~ zj5Ig^wmL`=h>+OHRw_-j^XO=gwmeB3ymZ7@&6oy-|B;o+t2 zqBF~;;DZQE6G<(ZSZ5Ff<(uAruyK0Vb4+L8^-9FDk|sl8*`zAr)>usqV%_Tkfl!!t zc6IUo0N>?ZH$e&qd|nst?)L-Pe_4(m^mKUorjkSbp|Hm{l^*U4dYtZjy4%z4?CA>g zL0>QL^>uf7d>((;8TJPJty(g}i^F0^d;RM@ zE+PXALL|b+1x?BT+@XsNtVIP8^Pax$KrkFate1sVr=X~jIx zCK1i^1SYr!)Rby^%L*Et7qEsiDy>L@Vz3ex6FN}RiiTmDk?F{aP&6QAfElyd{s0yc zvC(d?3!eJ0VhBSlnG=YWv!F$+idYzaYFZO9E6G~xq+HklVNp58DT8v7OC{2=7?!wx zHSJQ9sRTIb!<-S9HHinWjbUzBOiGgoVgjZPmyjb|_N~6bR%fe2;GNVOQ_?jx^^Itf z!BZwbl9m(FG+93baT)pz%3&(Nu_T{2SM*%bPVYs&8i)uq{qMryLIJ{O0zSf%HspkC zz{zJLjlroYg9E&BF(DxU&cq3eX^Z{9yuI{3`!(AmbCfXfCZi=Pg|(%YjlZ@2#5@#+%?n024H^ta)hFg z7YE0k9vo*XAGY5|T&Nn~-;WhIv_29DB_nQPYo$7svN`;LAwk}5-Wz~P$j zsx==u8=u|t(Xq-CtCo}@7WUmG?m6Zox3A%-&do-s^!i_fhY#&KcZSv8)6&zH3*O$} z(w|$E#TGTnyU#yZRBVqI$1ACKl)1=arb!qyt~*h&_px&ie17Q8YpXt(QEU%g8gf#u zVtbei*VEO7bGO)kQ2PA4Gp+XSh22Xj*=py@_(c;d`E2=oYVN`}SKrn5(TiWrEVc(r zgE^*Rdv9rP-YVb2>U~=L=;oH|!EwHnpF{O7{rKKhHyq!2UjdqyJ@~VcMPrMbimZ0u zJYNOXM4>R#VnTqX0GKZIT~3*-_HaYkM_24t?x{O0Rh9yb*CWRxt2fL(R)7e_V6nx- z-h^YJ`5_y1#cJ=H-`g9ZAJ>=1+0XUouU!2(xn}X+9narC^A#wL zdx4vw*mrhrM`!VWY%Cyc>)4M!-1T|)4+{|Ke0lex#cjL`J1jiyKc<(_}-yozssom{+69Wb4M#9^)Gzu`*fPZ6e6RPB7O5+FP5k8ysr@) zClet%nGxFh=^y?X-tfuyfb6ok=Fu_w<1O~vc7J>9$^zoqUU_HiTF&r8-QiB^FM0f} zdms4j+Xrrb_mYEc2Yz*AT+{wP1v_h4{hVwBNB{iS!_Ma5_G|>B&TB8;_UmUxZ+Xnx zvgq*jKYW)cV7xwOV%aZXv!Zx;oYLI?b%GgF?XPng5#09pL=7@(^nq>GH%D~X=WZ>^Uy6L zhmLj@keSEYZytJ}?H`9B0(Z5$jW#yz8YnqA8)?ZO|Ei_oX#H)+3kd9q^({ur6Mx@C zifG3U>gu!G-oB`5MGO_7>4g`0Z*-4}3lKT9{^$qW-1DC-K;-3FqxOStWBDG#!5Jz(->{-)RO-9jGIBe!h9)!ym2NP`wARs8lJ{w9;0)TBYVz zZxyGX*xS8f7RYwa=(JKV-a8cSSabQ8E=XqnAxwL0hQ++1&}so@*ntizdu-RE!T&_Y zstSmJq5+OLa=)3-8?uDTsa`nZEPZ*a_`>)F6h2>U|I35hcE7v00Gmj|34ydETyJ%b zyfl+X_T!*0sK`ERe?VOQd&h5QHZ?m?Q*HynuhqnIST0>!W0_+un|pToy!jQ?msBsS eUS7T8!gJ1Du=xB%l~w00TyjzE1uL10(SHFz>pk%R diff --git a/.cache/clangd/index/utilities.cpp.8466B813AD21AFA5.idx b/.cache/clangd/index/utilities.cpp.8466B813AD21AFA5.idx deleted file mode 100644 index c2a1397de4e20c96c8104c9312e347616403b490..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 5560 zcmb_f4R93Y8U6wXgyVupK#=ovkpRZzvLvJ=cZB3Fcb9OGyG!ma1Po=nxBJ~?$=>dD zcP}BvA80!uwpH3f2N8d8styG^j9Nz+v|tOhmd+S-{6VMcbVQ3t2epx^Xy4t-cew~Cs1FcTpU@86Kb8f!ubO@n``rU;*!;YI&3Q)^?2fa8=~({M7S zsgx#DSk>5=D5zZ&OL4L!VNMfdN$0SXBFAJ+r)r8Uidb2wQsIsWrDCNAD-~ul<&Tfl z64YUPm@lWaE-ZlrM3LsSw1Rnx$10}?DZ_^x*99_O%sFl-Fr#3QmoTq;S({=NHc2VH zDwAX-Hh~o?E-O?QEAgTrB@82aT%4RtrX_)64ePyv*7fD~E3y{#{FveV7=bq|vl1on zSki>JfE5}nc1vs$8!QOeOlho=z#3#T8lbFYN!HB{fyrn>63c0g5+q)a4r1@^!eB`O zn9Wo#D;O*s7bHQ$VjrdBPk_n6#lRv13>DTx_hc*M9Rt?U+FF+)_d-2*r&CEof=SF^ zMS*~XIF**55%AbOQDLUgbtV0kPQW@aREGsQMY*}0D(SCsLf)#DaiMn~)MtSK(@2~R z;l)G3F7;VqUv1=?ipxB{e7flq)&ww_Y=HTYJqA{m~07D zU15w&%5~VjK@vo6?D)aQ*N2`J`UX*#BDd$&odYs4s9SJ-R&Xb9-~?USE^Dy(P+o109S% z(Awe)_<~V))E^2iQg6_r^ACpn`2Uqw!x(>4Y z=`J~m>4b7)jKy@XtaPg>mcuj~i!nUzVR}_sRXF3Q$ZA#Q1r`D)3NWa&AaP=v$H?9R zzpN<26K~KI7XIo(WmmBnhj&S~r=_%td3!u98H;WN(bzLE*a}cnvLL~momF6uz!{cT zTH;wrv-6k}RiLCL1+!e2J~Va?Y5}BP5XSaQ+k*&)>~XbE(%21lSrYq@UC4AHvdhS> zU{y{l9Jcdk<^6fq1n(x{pip zBM6+xN(ovNVsz%MvZ`WH#Ucc8@yilYx~#0S290p|rEtg6g2<1;`5UMSFgQ>ELlGyE zOj1p#+46k7*U{=Z`{mo30U#idZy5t9LkQneSz%KG|6LHs7*LZ8%kzTtoh%twU7p4G zs)^HiX-yCXO~7h}KIF8V(r6e?I>Cx83>P|&{Y%5QI?Z!=lh*erIZf1Zh zUA7QdWMlGS{W?vY=qGmjyU@)^T7+*LX3Nry;B;s!N8O(rtb*_Lr3VWr+aG13{s5?rd4(d_I&eYie5W%Tk<*FvMUOaVi7V&=5qKIhu88X^Y;n#QsPv%h zhZbX`o&7pMalpb!(_cRuUsaBw1vqM6b1KvY75ZL0U0QfzcC7l-3MWE?4E?FdjYMw@ z5;`}(su6x^2Mvn~Z{ToBLvYUt@jk|Yxfd>ea@!LI>>3TjS0UFWNLZf|xZs%-tX3>> z81={k58uFj$=GT5{GE1eebY~VCBJGxHC4#rwR#uV)?4crqsgWT;|eOP3u+6>_uM$J z>b~CuiVzJF)w8Orj0Zyc=QR8*dA9nl7e5OW7oiH^J1=vV8ILS~<88&)_I&d85er%d zd|`r6TI-qMDFqLcOla{Bz{A0hg)=+f?O$j?bs({B!a7^6dxF~r5);Rx`XwN7x^CW~ zv!C^+iqImEa7}lW8;`7yPagW<+^ma>ONx*k_@F$+cx3qsj;r)!gbFwRHrhAv;LLFr zM_Zt+Et|X}x;FYFaw-L;7$B25*=X|m<^cN9_`kP#Rs39`Shm)_ugWC zZ=A^yYz>Bql*titg&N7}nyH%{TMJLTHQwTAncXsznLY|rwR zau4r5@yPg>pg8U;+!X13_wwy%BJlMnWQ$Su&6^rJ1HG=yjBl%azRX|W-=En+k%9X*oobl)4%w!#h4fWQI(_5) zC#R+F-CF~J>l-1nnGxD@;V=J=wtf6FAiK=2%gGx3#U{tDeLo&tpGQ91XWg5)h1P;l zcQ(KV2e;jR|M9J+zwdbK`XjEVe|KiclH2oB?Zbwa^_dKIY}xwp%Kz=1k;&jOQ|OO> z;@dCme9}@k=atRBgdMCSLqdh=gvCZqckexP4=&br=Mmv<=N%X7-mRT6YJ?wX@=Pt? z^=5G%mL8+G-{id8+W@Euiv$;e{IQGvO=^AnM!h+vcFZEp@%RJJy*B08O=p12HnA%R zGEXddbZ7s-+2wg4^JLSG4S#UG^9p3(p6hmz!6s7!CD-ppQu3$1sH-|#x$Ar$i5*>0 zr_~+(SGQh72kRuEK6~dI*VbN_KzUet{v_j%@0W2NDg!IdzIUg0`ZIZ`yg2E!M&FBKo1epeorUU~KD4+i(VxfCpUkvDsPzJBrjpEtJ6-4DIE-nxD+ zskFt>ZSBsU{%J}dJ=oedN!P9R){`jS9*8$Dx#4pUfSG#u?s_FjpUs8+5FX{eLma%j{|q^d&`!GPo!Xx z)khLOZ&g}#Z2nza%<^T*P#Ccmm%W% diff --git a/.cache/clangd/index/utilities.hpp.62390E5A28AD6DA6.idx b/.cache/clangd/index/utilities.hpp.62390E5A28AD6DA6.idx deleted file mode 100644 index a9efc8864328041068e3035df8dcffab8bd71982..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1768 zcma)6L5mzk7_HIWBs-2~%t8VYp^#C~*gjNJvxN{q=O2?y9k> zddAHrBzV$`Ab1cw`5U}sLB$aK4<-l6MF<`}CT|h#UY_xV;~_N6}6phlot^*Y^3_MhVV2_MAk)TAH~fi8;36bfP*gN_s* zIt`gvK&eunk)cSV0PzB1t8#hB6w9d^>mX->4M5REDw;A8XIu;%iS-r9JTC-~m}4Jv zlRlrnHD$E*1yAY=c$aqz-9NZQfu2aL*01Q_1bU;&PAua7B%)sy* zWML>5v2};u$0;C_!kFuH%(&ZvgbQvU+o3l9DwvsEToz?8blY0*O*?a8POML#HmQ__bTs=xws2tX+`#1mQw90Zs@6RkQWZ?5dV?PJ#OP5Q7p)07+QbY=I9k9BKPO4#Yc z{;ax~_UG)tXD8rL%8WiYvKwoqWJ&6ZzQh!K2uj;2Mfm_n(Z26T_IEUn_*Rv-rmNbm z1k)C1dtgo_>o&Fn6j9;k`$vucw>||O!1WrL-+98q5c_H;!}klrGj2F&-zU}|iTst$ z`yGVfzr%F;o&Vs9{1A_f$n<^)Y^$-D$xxGoXW)CDm&zQxfw~ql@WxVI)k7A6hdMzF zqhPE(j#08Kb4xJD9na)DwwqB_#3lZj&6(k9r3V+(Dso~<>NDkwb)IqjqW9^!g39G- zTCH?ABsfw$*$G@qV;r|?#;Ogh#{k|%QOX4bERJ!kf}sKpA_6j!JjR=MCl3?6beq3^ zvibSf@?L|yvgB@I(rmxhK1-Gs7GJ0xd8yW{-TGqrjnTh<{L&!DDnxIww}yzr3#8sa z#NI#r&u<^@o@$U+D@1p(`#K^Hy-1c{MudVy-=0ycEjbl7GB+PB@7?Y%z57!R&97>W zX8WV|mC959$Kl1}>i&IP?yhtRi_YbO;zaM z?*07N-`_ttXC+DdWF`6gLUCvB;s=NA@edo*58?~e4 Is9h+Z$Fh)dZvX%Q diff --git a/.cache/clangd/index/utilities.hpp.F418EFD6A6E9D646.idx b/.cache/clangd/index/utilities.hpp.F418EFD6A6E9D646.idx deleted file mode 100644 index dff9eaa3b97e7093ca1ec35ea69fe99f3a819d4d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2284 zcma)7L2D#M6t0Ph*~C%fj_!gY6cUpS%uZ)_MWKacmaKsgc3CqadvKwt>3%(3Zg*t58^>VJbF+N1mCNfo=nUnn}Hd6s=oT(_rCXD z_14Dv`mbjgTZ=aCW?;o6V{8t;#%j4UjSuvh<+qz!Ld>sP3t8J5ZWRY(MKhHq;ev-M z&mpu@<+LNXR!wDT)oPWdpcf6_y4BzYbQg4Oc9w6%hfhg!zz0#4+XQk%po>I~pP$ zfeE#2yBI1az>z2%Su`L#hlqmQZVN3ku6riPL@rvOd8{-~L>{FwZ#fQ<6{;-j;-!%p&J9g51hjg7%Q{PA)QVTcp)x&B; zzOOr&Uj_kaje2CvJ2|!iCU;y%U~&fyv;&&V!3Ii%?H7O)-4Ysj!wL)6MVQDO_|+)7 zxPf*W-qv8yQ#64ZV%J~?juf}Q5DXo1t%*%0RXP4Hak6B{ z$uGzn)HvJ?(@sRaOOO#8bT25RU?E2GKdEvQ`iLk>CCA|%h9)mA%5{nAzZhVzErY_dG9A8F(%IPE&x_ zQ~Hi+ix51F6GYGrdd8FJt4LF~1g*^R4DMvwq^|Dck8F-~S}i$!K%+w!Oe=HQJtRU$ zJ)9}LDlF)j^o_c9cD{%ff#=+zj8)elTuYd4~dQfK1l--+_RaRbDxx!{9rzcCZPn9Yq(Y5dWTiL%qG4bpZ z1B5s0RS?nt_x?wfm%9J__I;V1D;Tz?wwG{!=JAOqpGJoLzvUmF{l2$YX3rIf&8f{7 z5pibfvGa3?&=8yZBWg-BPDK&AG4sZ^8O(iLDpyt)S1%Tt8{f2Vp3@H>;_~MF<|{>* zLJ*RWkb>lE@6&hv&#$c_dV6`hUZ9Foh$c}5`lkoq{rT6Izr2p<6}Iwx5%TBB&JX)H n-<&2T6RYK7Swkww4Xn92PY;#G%U{iXQSGjm&a$(#(Et1g4__Ws diff --git a/.cache/clangd/index/visibility_control.h.F5187384E0A565C2.idx b/.cache/clangd/index/visibility_control.h.F5187384E0A565C2.idx deleted file mode 100644 index b28bc37255e1e25e11c3d7ca85e6269bdfc6f86a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 326 zcmWIYbaS&~WMFVk@vO*AElFfyU|>`WgATsruDKjUtq%uA^Kd+=HKSwWvp|~2QTgJcu0RAvrtpET3 From a88ce61f2a320f84b2575637061daddf776847e6 Mon Sep 17 00:00:00 2001 From: Souphis Date: Wed, 6 Apr 2022 10:33:51 +0200 Subject: [PATCH 06/27] Add rws client launch and minor clean up --- ...tem_position_only.cpp.3EF1087217BBE2B8.idx | Bin 0 -> 12738 bytes ...tem_position_only.hpp.8A2B130C31B29B26.idx | Bin 0 -> 3718 bytes .../index/mapping.cpp.986C71284B0266B6.idx | Bin 0 -> 22072 bytes .../index/mapping.hpp.A89898448F05C4B9.idx | Bin 0 -> 10102 bytes .../index/rws_client.cpp.EFFF1D4EFBF2C97C.idx | Bin 0 -> 2836 bytes .../index/rws_client.hpp.96A4BFF4DFB820B8.idx | Bin 0 -> 1214 bytes .../rws_client_node.cpp.D12E88785A409E56.idx | Bin 0 -> 2614 bytes ...vice_provider_ros.cpp.3D58FEF4D583A6ED.idx | Bin 0 -> 60906 bytes ...vice_provider_ros.hpp.313ACA2CCCC7D4F1.idx | Bin 0 -> 13132 bytes ...ate_publisher_ros.cpp.3FFEFC4AE6422D83.idx | Bin 0 -> 6314 bytes ...ate_publisher_ros.hpp.BDDAB2FE4A654F70.idx | Bin 0 -> 2050 bytes .../index/utilities.cpp.BC8AB2AD8B37CB17.idx | Bin 0 -> 6130 bytes .../index/utilities.hpp.2C3FAE4039E1F841.idx | Bin 0 -> 2302 bytes .../visibility_control.h.6BF9DD9BAF8E623B.idx | Bin 0 -> 326 bytes abb.repos | 6 ++- abb_bringup/launch/abb_rws_client.launch.py | 45 ++++++++++++++++++ .../abb_hardware_interface/mapping.hpp | 3 ++ .../rws_service_provider_ros.hpp | 4 -- .../rws_state_publisher_ros.hpp | 3 ++ .../abb_hardware_interface/utilities.hpp | 2 + abb_hardware_interface/src/mapping.cpp | 34 ++----------- .../src/rws_service_provider_ros.cpp | 1 - 22 files changed, 61 insertions(+), 37 deletions(-) create mode 100644 .cache/clangd/index/abb_system_position_only.cpp.3EF1087217BBE2B8.idx create mode 100644 .cache/clangd/index/abb_system_position_only.hpp.8A2B130C31B29B26.idx create mode 100644 .cache/clangd/index/mapping.cpp.986C71284B0266B6.idx create mode 100644 .cache/clangd/index/mapping.hpp.A89898448F05C4B9.idx create mode 100644 .cache/clangd/index/rws_client.cpp.EFFF1D4EFBF2C97C.idx create mode 100644 .cache/clangd/index/rws_client.hpp.96A4BFF4DFB820B8.idx create mode 100644 .cache/clangd/index/rws_client_node.cpp.D12E88785A409E56.idx create mode 100644 .cache/clangd/index/rws_service_provider_ros.cpp.3D58FEF4D583A6ED.idx create mode 100644 .cache/clangd/index/rws_service_provider_ros.hpp.313ACA2CCCC7D4F1.idx create mode 100644 .cache/clangd/index/rws_state_publisher_ros.cpp.3FFEFC4AE6422D83.idx create mode 100644 .cache/clangd/index/rws_state_publisher_ros.hpp.BDDAB2FE4A654F70.idx create mode 100644 .cache/clangd/index/utilities.cpp.BC8AB2AD8B37CB17.idx create mode 100644 .cache/clangd/index/utilities.hpp.2C3FAE4039E1F841.idx create mode 100644 .cache/clangd/index/visibility_control.h.6BF9DD9BAF8E623B.idx create mode 100644 abb_bringup/launch/abb_rws_client.launch.py diff --git a/.cache/clangd/index/abb_system_position_only.cpp.3EF1087217BBE2B8.idx b/.cache/clangd/index/abb_system_position_only.cpp.3EF1087217BBE2B8.idx new file mode 100644 index 0000000000000000000000000000000000000000..8e1f46d914d081043a80500a4dac364a4a340edb GIT binary patch literal 12738 zcmd^Gd0bP+_P-OZ$Z`W=i-E92c7YIxmqow@FhGzsfG7pikX#@V63ilC>kkzvExLEAqEfMx>eJW0s04+KZ8-PPPKzy=pUg_rB~0T^uijQikes%9*zm8 zrsU=p6v~scvgA3r@+@fz(^Qz7ElrhAotXohbEa9^Ws-Esj7OUbW)>7mvL9_P%#cZv zr&_m9m82yXWfjV0*~M~cc3zewTar_lTqw=WnW(R+lPepP8l9F>sSI*uZ7p0@mReLO z%_@*fa*|WBBy#h^(wt05D*X%`peQewS1I(WI)$E+tF=Z-U!hP^a>PEq%|2Rm9WC3RT|Yg?XbpLg17^xaesKbPM3JOuLq=YK9e&TScMk;mM z3U#GOJ6ByJs@0e(D=C#|rp}bAtEtsMMzblAu}ZC1$sy;)22q2uMm4NKsZnSvMH+Rv z$owr@92pfEg+UHg6Dzf*@bKt3Z1{@5rpI!VTBCZ5x_SPf-oiO2!3lS&G(JiV^IK~hgC zqpZFrBw)Yp{(hq)IVGiF(5CZ-_L~d0n=#}-;d4}dtxj*0D|Iyxyeh_{8c+}Pl}0O1 zYrrbt))Pdc-?tDXfON^)qJ2IN zo`W7(tsQcw27_FqHb4tfD52m7*{zi8sY=*J>E*PuhV~hSLEzIEp9_^sf2X4n2IGbb z8;lh&muRRd*8>c5^nE@q z=k-*Dp*#e`Mj1}dzYuvM-v%fBV*TO{#vOT%m_9cOCj}xw)Y;$vWE0>v0e{2?L3RRGMp9e&QQ^|(H6dN zGS)WMib}Liw4$ciPO+lWSZQo#mMlEWB3qoCX*-k0^p)9`S+szYDqLkXavfl;18gL9 zoNNcS?ZAbhI{@ARoEh2-G=|;{Si7yC?*VuZa7HK(x_z8;EN#mJD85#Z+6pp}*#v#} z;`k-Ew(J_gvI!R4JiZjGy8xkCY**|!Q}AHk%^Azj1n+z9DX+Ue@la&zfy;W}hGZR5 zUDPW+UvL6qjs_62bz)H2h(bz-?uCvM$hm~Qx#5Qx^|E;A+GyCI(FAE$KSP_<&(LP| zGqhRV3~g37qJ=G@H#a%(9Y(NLqp^fuGT;8j2o?e9W#6#s;aDyNDi7m1AxIK1Gr?8^ zCxmBm;xUI$8%o^aFb@}xF(~j8&puTL=v4{MOu8*Ou zb^=Z(a7UBV>8{7iz!L@hyfLzY=9bc3aL@d3z8G0l-k$CHqLqthLncE#Lj(6ZoImhd z#xXL#>1waQ{XzyD-3q3)f&!Et6xd5%uc0_?k8G+i$2H{g%A`?Hc(Tzlc1ggj&2Raz z_QRcws&+)&5~Oytmd)&>aa5xtnwcOMfzgWqJN?1KzNQ^LW2YJ?b^RbHlY%lq94!C8y##3vdFtgfR3_HK5^v1 z)q<8-XyT26#wcs>`!51w1b%{C4t$q`NYsx`K^9JtlR>@(4Nz2KPhGi-iAFHY%S+~u zN(o<407YDsTqHq~C&-fU5)o1sL6#Mi6(g#0!KxLr!Os7Ms!MQ6@I}o8IoWBlg+lh? z>M&S-p|;)ew#!<=gTcZjz;bRQ$Ot^bfteuME!uLzBgj~{SSu>gEzyda;x@&KN^?rH zoJ0vS+cukE=A7v{(~qIbyvi>Y^;aR2GKmLxj^h>yXe6T-yPU2@xHD(*d{)y%o4^ z1)dDO8#wK@e!d5AdH@%N6y5j}uc`mOHx~v8(PWVXu~b{7aXGcPcMaVh7$Kn2td@l8!v5gw?BCi>TZV542x+IFcN&Tr2Q zS*+qza0mYW>soWv^O1kQY1hSN$MC@%BiXg6`P9@C8x5l^*2YZ#7Q~_A=KyZ z$TQz>#z{H{S#j-|{Lh;Mj^Kl*%F`Fc7}c1!4kzhE`}S8qjOlLi*PDwGS=?*$%ECiQ zb879|azC@^?yE57(y_C7U-7NGZ3}PWL#NRR{iQQMwu^cf6(ja&UYlkLKHq_p=F{lI zr-E*GYCl?z4^_R?Z$EK++qG&PPMS}rv#4S>oy~h;IB7ne3YN9yFIf;DxuBzuV|rm% z97GHqz>#lTaJBe@PXztvV6IV=Q6xo%+^Y7zx7|HD!tR%e!SK4v@Jh>{t)~2T^`v#- zgbjP<+?_pwy=?3D=Ld98f71`EqOv5J4CQ+`sTFHeP=<%YoDTk`p|IALrz(i`IxNIt zi1hLEXF{ZaE8wHrFLWCdM3Wd3EE-!BjC8+Z@;s6L`k6WK1SyIW#UtN>lR9^u$3Wxt z$iH3LzX~U7J!-kr`S^D&g-PK!IfpmL^A3LGdcZ&kgi;f5Zvr0oD}J7kf*nc6$;H59 zG2q_pY$>_2MDs09HUnNW@Z1?hmH54q{VsAQFjuDw>nKxSb1v-glz(o&GL)S5hsaN# z@9Y?BHn0!ocD?7~3DV34rt63xI(}|1G#eN(EoWY9*SD9=2DZxo{L4ShQQ{j?@00!e zU0k5s<7e>;n7vndR#`cYF5uY(1juo0+;wOZkh!Rsx)jm zQ}6Tc^!b;dK>Y&zVy%GYEf6t4D+(z}K+t;O__mC>eP`c?PG}?GZUliy&YNFU$j%wN z--aElfowG>MjczzQk^0;eCalV6|gNg=o#YNjPWq^^1b+0@%kvpJ_<@N1PQdQ@-r3N zot|%Ll3s3sA{2TEEr{NszG-u3$~%QnOENE6Ao3ybRPJ8vi%#VPSsqoMfJ_3F{{gxm zK*8drHtzws`$>BUg#xbve$RkmS=m5Y^WHIuRF$%CFJ!P6aC-p{B`*Yd2yhPp9=g5g zPWb29lKW@-;J}!`m{7DHOac8T2O|m%hTgz@MTY#rK81(mod@?`g&Qp8lv*~puN6d( z?>komo9m_Z`N)}|ikgkX;1wE^Nv;P$>%jzsFM`|x+_r!aM8ER0bfIBV5nXWG0f-&I z19kK!ByJ+YRO6vrjhPaYgSdsfPnvAGlY%Tn)F&Vo=yQEUD@Z`eQE#K@f`G3d55?!t z_IE~8?2qkP_teR28UH0e_xH3l^?RpW`qUmLx$)d$lu^T*z&O8TWTfyWFiH@Qj1<-- z;zA{;E&-|Z(0qmpOAgCK7fm=>&#MnZ8^qxTd95G}Z4e!l(2?%-he_gV(Hm|J?F?<$ z?7UD1)IfREuRAAXC2GloO(k=+&R)r9~=cSW0`p;`%bpx@NahJY1wIZ zi=kf2dF7T|_}Kr<_~2h3Z|{Lx?FLvkaAcs{3+#J=J3}7;*a6^(&`Cqv{t$3S^szlJ z&3D~5Ybu2H9KShMX>>F2YX(6`LhpRK)VVa~9ES#LYJCP0`Az@lH`(9 zw1sz9ob`_nt;9yK^ZQp;^%J*F&t^f%3@`8G6c|yyWXIdJjQ8%7SGHR_;y0c~FAXU>YCfW??;0+?b1GO{bd9t3d?P0UZK}ZZM8<4F>>m z0E|Pffgq0pucIIiRW!fAO-Byq<&TD5Ak-<8hXUpo=f6)meo)`_h{rm6xU}MelzSEK zq}Hd_>YbX!z-KY@P7TWEEM-VkcKoFW{OV*ydThyqRNG$`m;dTJ71ojW>(fPsMO$ZU zVPG`+83P!xn}SVY>Nng5?noDXK`X&;2?#(+AjqX4cqs_$W`BOgnbddP*s))Br~EE| z1jF~%Hzrn{^26~kIeFUtX-|YioLmX)R{}o5;yq33S@~0L&pZN}AD7;4yAgRN7sp{> zbBBi}gjO8hMLEIiD29en4PHkf^y2W%At(6q5JK;dUmw`++i-O@L?7*zP)ZN0nXm|j zsGlyqkQp&>l#YI;a8op+=cOQgDTqdTy}$azz7>1U`HWz_>M4zamKuBm(;%Y1#Lypu zKY-NM@4S+~s%5E-czg^t9<^hbnE47{YuCX4hJpEtLIKMLA7wk*&fdY%E6^**E5OUo gE5u9SHP*}Da}2?D@^E)`c5~tQ@W*k3dEVIn0n-YS#Q*>R literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/abb_system_position_only.hpp.8A2B130C31B29B26.idx b/.cache/clangd/index/abb_system_position_only.hpp.8A2B130C31B29B26.idx new file mode 100644 index 0000000000000000000000000000000000000000..a599263f6c4ac5b2c57ba4c54bda73babe66fb51 GIT binary patch literal 3718 zcmd53 zbIEGLP8K&QN4*5)xu6FL$xr-PAtcUGP5N-+CeI`0i*Z%Es7kUJfCCV_cHe z5GO^6Dr~w{z@n(E$|vi)1d;bK3=@%}JflcG@ra->eUiLEiIZ>{EsJ<8)Tb~)jI0$! zU8DJw`xNl289A{hJPN@jjr-)jI#&~MUYVdfA(>ZuqG%b zag`yRXS!LD z%kB01e%#s~MK*Hg%012Gk6FlY5m|~!#uarJP?S~83w&aXC`1KSnPj6VAC=_9Bp~fw z8|$6~)XQ_KB%`RLy?;YtR%Jto2wH1<$(v4-g_xisnPcVvJltzL4C477AuKp=XMIAv~3Tz9r@!`&Weju5gnWnEY}B=seLUVPxkEHwH4p` zuiEjPRAd>Tss<>AZm>4w83^azGpuXRzHB?5O%M*Z!%KT|Jr2WOeRRumNA%JfD=sA- zS{`T#=!0Qjx^_{^trNBH+wm;2zMpdUQwwQ-uD{qotT}mo12n^ zD>pwu*VWW5H|&Fs!$Z%+_oQcFDh1K5bk|&cfCxzrGT)^~OBHDauN`e5mN9P_K|S3-hmn%5w$bjIc==!$Sa*6{Iq!Z7qT~lnK_^a*JN+4v#`k{OU}s! zKY#QkL3_)*)zGD7fhW7p{r1)%h4oDUy?RAn#ZNCTO2Y)5;mrZGg|5q}%Ypg>SBNK_ zBV!S)f9!)le_ge80r6BLZSU}RL>;sS9dH<6YqE((69{1cVYcJEI`A<; z`@Mc2Bz2&z{5i|{weyME)#Pdi^y|Wvlg>Uzq`k@MSm*}akOP#k&`r202X;7_-g=o?b}5@m)vE`^Jhg9V zSJ~64@7`8a2#fSlBQ^N_++MILzWdQHh}xEEYk)pN-AI%gy8->px%WnHyf)+~Iki|@ zoIn{cV_N4r98yA!5~d#F`hM|+S&gr36w@vAJUp)$JXz=(T$41b#kEN@AND29>T!M2 ztPwXFvkTQ}*D`E{JG35T1acwSn@6i2J~Fbj{kB@jyvX*E0E%2yBU!svS5na7_QHIvNb$aH$S-a);))ESu1S~;Nm9Jlj9DgY< zQBOhR5c%4v3~L2&Xv63;69j~eLq;MrwKGhSK2h_|hSHXc2lFzsvI`0wGm2*BSZ(&) wy!>g?QI3hze(jAtxga2vZ;IKbXfwq;Q!Fq=@=Fq)Ob`$%G{r1aoNkJL0ZRa%@c;k- literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/mapping.cpp.986C71284B0266B6.idx b/.cache/clangd/index/mapping.cpp.986C71284B0266B6.idx new file mode 100644 index 0000000000000000000000000000000000000000..97f9179fdd694cc0419336880bc62a2aca009bbe GIT binary patch literal 22072 zcmc(H2UwKH_V=E%Do9&oMNk)9MMcW8qGCbWfPjjEC}2;-6;?oL?t+TZ7;Io8v7oVg zjUe6xOJYNlSg=wwB6dMhA!;OvvBVP1H?!;P`@RNC$oKqjo*T3Cn=@z5oH=b~UT;`X zpFSOjibVd=K~oYmDe49yk;t0-t4qtU@XB~_a!PmN1V=^mLPk4hqA z;u7N$W8^8Z8abg#)yxn>NgEP*8weGer}XN~htN|6hxcqSj6LAIp(6HYsJ8 zTC0(V(|rh0N5#e^YUF;=(Tbo%{r;$<^g4Ri261HnUv}uNVudHDwJCkIab%CRWakqS z)QQo03mWzo3*yneE@7fBE+&zf3$dj)7}Bf3ddo|R)h10QHWTgbtxZi#iA&H#YP8xU ztvqg=-uBo;aXNWw;)KMc$;6KTW`S>A-~YfR)N+GUIL9ZcqodU+YG*n9Q=XERtdWn? zCMD?IlN!O>bgWI%MKT6-Ltay~cCyafJD5xmKv~!AvUJwJ>+3zlBXYgVM#=nd6Hh&M zY@}A592Xs#po{s}k|vQbmzYv-H5!J$Nr|C)=JiwIn*@7L1-?g!h;-GNTjK^w(1b+{nb^MNOkC|p3q`80l1@$RxfFV?BCx zlhn>H0)rA$G}>|MD2=x_PlSIO5&rcGjaL7*6_UjMjumn{rb~zf&S#Jw~O}~5kk%AACA$7ut0XuHVihD*v8X$ zWE}zs4+`!1b-PefJ)zMyNEE2cHuOXWTObsFvjx^o_ukO|+TQC4^eY*dnjmj)IO*0Q z2S@UzC6Nfri>iA12yzARnu6XkTCc%Zhjbn%p*6e~4C|1TXSjs8Zo}2DnrEnlux>-u zM=wL5>P3%>DtUWDOE__=@RY4Tv{QJ(=6Q0TOd|F7uGcle!8)@F?$wrF0 zoY+OAP(*9vCTX;agrsPVPmG(JNDZt8I_z&rVaBS5)l*}9vL{$uXk`@q+xK-!2W^$bc{$5q>N2U z&?t3DsmZZ%I_2af?F3yiDTkG`vPn*ioUBvEkwQluAFqs6YojNVOVmhmgJ`IkNmo>S zYP9CP*yyxTdZwf%>ZJeiHh#lIieY3<@~37>idIejORl|B6go}(IPyC&Ns*eEs?$U( z#-%3eZ*B#k{xV%dWF%;El3rScS{s)VOWImZbZTO>Ix$5Nt%-`)5hOKHt05P{>ap<} zMHJau0!=2w8ik=&B_vTI#W-CWxq6?XNJ@-P6DeXuia1@GE=7|dQY48KL>N%LZI{jA+1lg^=oam|Z zpKiwccp;^Eb=>lxQAC-PoT4OdtBg^{(|i%d37o3aD#ykpDx*j^^bb)_(DWgvGo6xd zaa26L8ulPQp?r;@N0Nw`5_wpl3-I@a$^^7qsY?8x_L{BR5{UAlQ2a<63COH)Z|>Ha+<_VTGw#H z^6NR6sHpxUHT4|IG*-{yOsnrdTwrcSz4Ny9U99My4D^kRjG8jV)06DZShX%LikwgB z)sD)^pSN!$DQY80_Ki!?2|IWj>Q6Q_NHmUky|+^N?p(lSB4Z*Ufh8_FJ~Bp=sL@g* zp@oY+R~adYX(?$#UyXXil897~`3!+upgkJX>YlnTVxttVE*Sr(g6LI2vZ($c`+uw$ zopzFv+`2~UVj|fKa((xR%V=-j8jgnUh+(JbCkFM=!uw>yS2gY%$|qx@{6|ZEpLt(P znns(aDVNC<)vi--@;_w{rH(kTMxF33s+4HWlqgMd$~)<3G!T&@fc|UHtkK%2D;kcC zb#!t@P**3ti__zVyAyI}KzQq?BAJo9I2GwzuX3UOH%))+hsN;hO-W90k#8VnLE6w_ zF;}EN3BH>D)h9M0{@IUw)svPmcCA<>5}Wjljfh+)wGd^&cu^)?0n01kk^w_4hq{Ow zH|Xu&a22EjWB}OLUS99;Q;#YO(Lz1t0kk@RO){VmtO}tCq4jJjSq_saY0HQI{pHi& zZ`w1`HQ0C!T4ca_XuKXQ2&uBU`BF%sq>dc}e>~iHr8gtpiB>x)*L`5MPtR3hXR;Wy zl+-6}s_*W`%4>{t3CNZ}s|<*h#kL|mySFimpGxWcz6x4W@L*vCqsvFLe6-Af9bmQt zED2@D7M9B(m6G=DZ8zFv=G~=?bUrkn53&r1Y#u2iggu-r5UVzczGwfjZP~A!v7IS4ohc@Q-Uid#`Xza_YQ{t;xxDk{kyCqTGui{- zdH@s|upC^MgM#o?b!a+q29@Bf_lxxh`!+hvDD%NFA6jR?EO49!tqJ7^F4jrYDdjo$ zU%b5GyirXX!Eqy{oa#80(sgTXIw6hHU8t3Mt)4ZJZ2Thqn#P-sZ<_%FOb4_jR6W}@ zU@~5L?yyLrelm&8ybBz6QGN@-aiM-@Uss#tPbkOg4+?)?n9$-sjB*oNY(hx}y_D6j!aOIRx?glq!5YFd*!NIy1Z6skqPU-d>vRBr^|%x=(rtQGplC~ z4Q9-l)ss?YypR^`6;C^K-Mf+OJ7|yz3!vo!X!CWcYERddgXW5tRt8`AEbK2+!u||M z&pDa58MP&G0iRj}xj z=D$2RbdEAv0S+sml`#xu z!WOjLf)ZvV=FNs)_%&+5O3LIBs2)KWV`4u0YQGHyFDKHTC+PVEdl{od&pRg;MrYih zJ&RDa2#2sSmcN;8o9&l6LN5}wsYO>d#@c>Q!Rg~G?^u#Cwb-H-<*bJQzoOl*=)eOW zpxpxj@CVxcApoAE-E#pjQ`};vSZ?(COqeaUn=N+W0hwaEOaZV^Y`0JVEETs{DwZ3K zJrlCUcG+SF99U4X29V3+?uTo6&7Ep$H{KXv@M~lgf0T zcKOTqP*u%A)f|jqO0@avPIu2kmsGST3*ECgJF+P$`eVp_#V@pHmDqEYSj9w>YQhum zo%nee?U{$Fc^o%pEl6C;ko}lz5z@=(aTz_C0XP3JZ-jMCUVqA@yR5qti}WlriU|ut zR^+kRhE29%Q|8EIPwI#f~gj$Va>7Iqg34Si5J)wXjjC)kx?1af z+Sq%a_L@t_tU!wuC}EN~_3WOq*gO9jop=$LEdq06;?9KiC|i#XOtEcyPyOBBwfAI7 zngz|Wz>Y_{0nIj`IU{Xnd4BNE-+j}CO7av`PdR^Wx3BMTmrZ{xrcBDgt{mF(7FvV7 zYA}c`w0+gh$Nj6LyEP)DUG2IWH<~oNTXk>2_MJ3)S@q&KeXV@?%>b(aezTudKV#E* zSn~8?%a*pJ(rgEp?V#j^yu&CtjJ9kuJ1q3=Uo(F65lUJBZ41DK=QPDADaNMEXw_qZeKhLB6IrP%T*JRt{5d9j5@lZu z5ydcurfZM3LjRTkf$`+T}58w0aV!DbiLH;GU&-i%s zM-QJpKHo9-RN*J5W<91oYe2RJ+J1KSmoo$UN8Igrb<}t6p5?6@5cWqwdK6mn*dGJw zF#&J^{V#Cyks%kc_eIVJJFlJl(Eo6}HI;QUwB8I(#yW;<4oV8J33Jmf?ObhE?X~Yh zNf$!1g#x2phi2Idsg%IiL;?!#ba96eh3k7)II`86u)2?#y`gLo>sjIzrpXFK5Sc)w^uBlUeG z?DND8^TZ}BkPzToal>ypz`K*x;)|VYNO?t5wPYJK&ovP(os z_km;|*z!!g1YJr{$xNJOY8q?}hXq~~TnA0oK~tWk<$`T4*t0$I`BUy(ro1?pl;iY>N^CCq$+Mus)J`eP4!+H(XO zAK~I(|FeE0x3)VSO@%%M0jD68r;6(+yN=FG6`@yu8uL8o_asUh<`&kOxeIBI?>N3Y zJ4+0n{YA!0+ZAgmSt-a$1rg^O_P)kNfWcWmIk~kc7;ZsGhqw*t#p5`_Z3Mshk=sZ7 zrrJ%-Z))5${APk%LN6u_;XKi8BEOmHmdbCYxux-&)7_@?o9W<|4t!t^xXs~!FwuP9 z3oR-}iODqiV4DvPJTKe|c3Ytp3lN0j04ffk7qjfJ4|eVPuUl+0s;B+nvLBQ@w=6|T zDOawA4SMQ$%+6e&UAKT_3p8O)N5`V`esp1hF}!i$_X!&7EXp-U+%QLM&TN1H`C{{Y zag*846u;hk-XJ%kziD2xDO;7)2>Z$UxvA3`)68M6GD0bdK`ek zJd3LYn@VtH&Oj(`fXxj7Py;qK0^ly#+!X-7fXy!g;CHb3T>v}=o5up+8Q44%058Gj zr2v?THZzeg*j%)kD*)!B&3plng*I6NUh9+g$s^3RFfB1M? zd%F=`1`KcY?S^vdwQJFQE!w;|cxOh3+nbU{dd)a|d4Pq!tT+tP!-8_F9988Q%D8^G zPa5xL?K_y3TRqzJ=*V`NG=19m@SA>Z{P@klHi7(RP@5orGo($3vH6kX^<^$Y>}1p| z)GGB*=EkGr;y=&#{c$tJzZRQ+&6&$+?SxSeoD#pH=5iRi9~R__a+H>Hxngw2z31tF z?Ho;+RDr4r!kKlj71DFN;d+UMN_Lo|J%-yPW6$wP6$68(FQ(iQR0$z0OpLXv$n5j- z(h-XL%6yGQsU|QX()--%bSmgRaM>qt(h`)Ea85d|dGtkXhoXZ97m(zFjlc!k@8z5{ z#yMx~!hRut(Afez1qQJ_iBWenpK+wiV2b|&?!SPFtuZ2HB#n6H0=M@-Hfn(SXCM+Ls?|sFwhSog=U|RsqSSTbwF}5s58B70(Ry(Rk`1&5C z^HqX-CG=#gOKf5$tNFJ74|H{_!DTflc!@F}8|GtUR(BAJt!T0p&5v$$S@g@j0oRf@ z1a0g#x@x!^=?QNg-kw=7X-;S}!I>?VG#7&XLU3SNngENyevtsk0{bihungqOpdC-u z*&xpr0LwwXTmY;9`3eEB2|8>71<#;1L)*=QAe#qm^8~;aXuCxKYy*#N(3zK@_JGG8 z=*(12*0LAe_kt%6C;-<2fyp0+{)Yu6LLsOM!JoIYMc4x6yE zEm{70v{)|yHlW1@0k9jJ?#AXUlaV0>Xj6c8JYXN%>=OX{(PqB@IEi*AIeR8Nim+Lc zpqwp6+hT0NES^x5W4m&6W!^%7bJ*$}7a|F80bMVkl1Fh7T`qD3Z}NYK?0@)R*(&Ob zCqZ@+cDDaf+o=x7Mzdv4z_7~5#nI)w?OT}%LioMufk?y}`-z~`;Go7;EB5t)s?8J%-0_+es+aYej09|o~ z+oBEyk0_G>S%5Jnr#9U^K6Lf)aGDm&P*H|HEMcY|Y3F+X;)S!6c^7Ub!Q`uh-O4vqO{Y<07btdt7tbAzW5eTU$=jF{XmSE2Ek-zB zyR~ogq$!>LlXT$9yy;Z1@38TAXv+*^ijQct^}|mt)7f5t>IIj?(nh|Ff1Wk_h2bK( z%Ngj#+nF-xRtDZY;4Ju_6?j`YbT5aVJc^qry@}1(4w30@q4bsjs77hE0H{G}4F^oM zU6D0Epic^2#4fbng);x92ZyF@>2!4J$MUIH+PA5p+C2kyX9Pxc6T9C;KQ`~QSs!?A zdT{G6%H$9>KZNaA)jMs@u?@?UZXcse7D2N`f`j{dG+WOd+^5~WUHBqHGJ$TzMzGxo z4!rpHCD?rlt=I(xq1cIvo#@3BKK*d%hS6zLP4x;#&ljj-HNlM3zm8q97#~M_d^-8` zWx038*=fzE1fRB|_ziHs!KKYlD{71PPI>ywActZjc=6=ei4Aw6C7YIv-GwH*P{MS^ zxYJ66zE!b0WX`DRLq1s6buOK)YrC$!7+uEfeiM$C<=a~j#pR++F3MO&CctL2*(?C^ z&?Zj+Y(bkX0-zGzD!E4j!s8ltxQ5-?J`vzLx?blV8VFE@ovN@mkK!ge-Nep3;1;&O zgJZR~KHn}ualss#EF$CQxqZQW2v^MtELZOtTH?H z&(IFZ^`XX?1!h@-!~F)7ZQu^~nfFZ<17f;#GK3aMp5O?!51sdM)!l;MV}{j^=&mQ- z1MT;Kf)_$gqU0ntVkL*MO}M8onSVpi-_V<>>a*N)tMBALxI+DMH^_H`d&K_p;Xmif zw4WDl-1+hFktb=-U2J?8n=@{U@7E~PH_RSGl{Zl}F^nm1$*twb$IjifoyvY5r02no z7lv+QkK5dhO!kivk2~L1=&S3w=sp*Fv!X4#%Jrb{51Z~%=DA{%T(MMR9yVauveP@i zShD8mwDL9$sMjq4+a=JFS3xZWyQSd3F31VRCUo0`p3GNP6}K7npe0cW>Cvb(19_G- z2UK%lAX~%gZbSSNKM2$xb!Up(%oMvb8(OU!^lY)sM-8Z8HQ-(YzD(pb`@jA1aeg~5 zYtnN9q$dP7oF_qgQUDZzv`7FHgS1!xlz_BE0F;8XQ~;a;=_vtl8lWY1Fm6@Yg|YtL#|`b>w+i9D)g`7W?B0v zbj<3HX3wB1`$+ZCaHjS3lS4lA3XKmiBlvG9{|%MQ90~9cEv)#)svEL0;f&j%*$iDQL-DQERW?JzP@COcv^QV`~e6*0Hb+a&tR)F zf@-u3TbH3bE5dTO$yx_U_r+7)JqGv3oaf|LhBmYE%Dqfu%noe41Dmh|*;k!HYwbmw zE9sc!V$bE=+v3-jpZ_&xcA)--Z9dq}2YcSxYXR6TfEMgco{U|C9oC>5E9t+^tGaye z%5V)`@JR?hDY$vRg0d^z&3nG?Vxy>gjpUTH5Tu3R$XoC^?0$~3`}|Kj9k?|u<02*P z(W!^=@J^Z`okEOFwwLrl(ePCXOM8Uy3VK}Oo<6_vwy&{ucxXyFE(eF@f|s8>w9MmP ze!jKOPK(^W^#&z92C`#2>sscz znWx53kxql`G$?sHRE5D+7|9Hs2|y<{e0jqr{yu2ZPYI#zk5eZ5L9$=)6jF*VrQB1< z_mc*^+-0Ane|5bBsyo~V4nHg%@{PCikk9Cf(?OLE5iFe?{A_b%C-=VFX-`n6pimYz z4nA%CY{~~^`lpcskQ6{uUMwg^*J5tkL#n}dodOfSFf23pG(-xPDXZd6d4+C4KGMz> z8pGS0&rxzM#6BgW#?k8-1n__hD7}C!nTm*j7g2hV1CHcI40_zSQc0~P9~AlE#j8XP zV8a7w$x3)aaS%-oqJ%wi9`Beqa?S7w;pchN41gHY9DgjUpUeyBN4tU)W0JY#%D**0;*L?x-2)rH%fT!T~Q~FB3}AeK$u>J+*`S~Yn4r(^n!|ya@u@@wJ1retR-HOnY zE%&mf_Eewcvwowb*bS~gB)b*z@M{d&i5|wp?YQ$hxm)`Kb zS9&!$O^>e^d#)GzvI6nej3Y8d+JdK)`C2ev3)Z~UxeXn+p%crLY)9yOEqRP5-#YTt zyB(Ws7kr+y7j5@)pC>V<^cmdn@gsjM*l&lH%o2$p`@nu5v}D^!fc;>7=D3{da5-2m7w9k#9r8FG-d!^H#~Q6wB@MY-(PAq$WiJ)? zl#4A)f}-@{vjk)%f&#D-11oVb+p~KI7JVOldqXz0`*~u|dE%a|Fsj|L?wTy;&SBa! zAKmA3=kZ@|EP9l4dW!zA@7KxCSk2yFnLJJ1Gf7QlF9W+WaN?QDE$n#<`?6^t_J7cP z=dDIhDf2mE&pBdmHtnNsP0C6pjwql^&O*Rh=+9$Pjds=CTPX8H8cq%0`!d(~quEM_ zP5GtCR5dwhm4o)|iRwwael09oUDCgv-39l%-0Rts@jG^8h0oXb%tZH@XnYcTwrPiR z#?TfYP;RHN@hR>(?|H|@7PCxq;tZ9Fa|Lu3R4UF@0-ze4s|COvaK0k|YQecy0Ne-X z`vTw*I6o2qPr>=A0C)k;F9bk3I;SIFusP^FM*z%2=XnBP5jrmt0E^Liu>iUT*Yvm3RDHVmKr^9uOQo4}$z4xUui1$cCT6@H04?8Oh7< zzaDA*)d2ko_ZS2o6FkgZMA=2|JyWZRSJVF^Rq}UWbo1$t`9S|P{4u{g$+z*dVGhg%(E^TAl)?KwoA-MT?>8A@{AU*L_dM=5`3u_dNE`HyBLH!2=kBlCv85uP)a%9ZNF(cI@$BqaY7&>%F_@Ice!5@u^8#ZqEhob)n DqT&@2 literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/mapping.hpp.A89898448F05C4B9.idx b/.cache/clangd/index/mapping.hpp.A89898448F05C4B9.idx new file mode 100644 index 0000000000000000000000000000000000000000..dc1b39ceba63249c3bcc1ebb9f181abc63c1cfdc GIT binary patch literal 10102 zcmc&(4{#LK8Q&L(`NIW*X-fE$xbi0?gyaY`0!M)G=YUuVe-evS<=DI1Bunmg&)q!& z*3^t(>{#0b_Iq#d+k1D} zyBrrsGbHT2@ArN0`~SYTx4n7826et5tP3{p3(KZ7Q4oY;_%%#jdA1xL=ue?|i(gmd zc5$;5F+}gi&7xsSrYxG8xP42jsLK&uHe?mn6iuxw1b9T!rEnY-mLhCfm(8fIicv*1 zm-$RFpaGAfDr$#lcFH24B685;sw)(ew%xvFYx8nNOKOm1 z(2g`2#Nm=PR1Kv=g>->jN|8u0W|nzor>=EF&ICOkJ*t{YSoX=fuIZxE&TPddTPnRM}&=)p3#;vIaZB8|_cB93f z%86T;@a$ZeO0f(bm{PH1_l-x#h-PH%Ip9s@wyi+QD(xKg$}C99Mns8;`lV} z*8F?Mt8AJu+NSG?g{fy} zdMe8uVV@C`;$RPRHyrK!5ZJ7mvfeHQWRHha;YvHgxGl7^KAnYdu#aJ3JYq)J2P2N6 z#!mU{ZQCmcOc?uM>X2X@)al)$O0Mgu6Wd`mq;+(_N;P+fiQ|*nEt@4{5;SXw1O&an zSS%^VP8>KXmTulIDIqyHdUy(JRL!qssH~d%y?PIvu!bqd9d1oi@Ru9@D)~{dr&<_` zF*ZyvHfsXOfQg=|j029~%;2((mos3n+b7!u`)&q|cDrDV*k@8PCM7I$B%ifR2%r9m zf`H=jbi-f^wcqKsz^}3pnKl16jEMh*7zKWEy*mo)miqV3xE*!(yd%({<1z4oPJabXcydGJG4n z0!VUD8gAyn*d?8ll$Z@k&Co$pE^z_uoVd(tE>QvKoT#jOS&gcZUKdx1mDZ=kjiZUT zY<6j3QsAfJ4tphV*#8M~sQ&+CzFQ=U~tS9h{zr^EL3GuN`=g&@k@phfcc7EO;*iW z$HgtsDd|2_mlV@TBya&;2LWvs+Tl*&al74}T3B`)S~SwB818OO?=m8AHFVRej;OwF z!|jhMp&yhX>oiS#fk-471L@^9;gyMxzDuaf`vTw)Os|IU2a3C5TzSuWFPDFa;V(ZohFdD|{ zQvk=s@5k1s*pa~~^pwB{*?LNK79_l{v7p$?tWVgQ1a{!Z{1N*mRp5_!!A=yx*dO*+ zO%Q|$c`G{Ge22vM9MC`_E`Db%g?%mARS_T@#Uk(DP8JM!ILrw$`2>?wJ1tMS z0Wd4~-`@0ef%{Dk(>1H>8j!MVcHxFLK&(01eCU}E?`z`_$4KEZQUsVqGm1i60JCxJ zv|V|3z55`C@lW^90>tt;u8lVW!uP^WPv@*(Z*YhqQZq#A0JEgLB)k(gBotHit)zF*AAXv}Y< z5?0Qiz$D!B=$=>Pde1{Hp##0^&G%A^8!NA3h$l}Kzc}%s2QP3k2Fc_>=C{SOrfS}-BNJSsH7BH);i<@@<=I;yN zYw(a)c)NQldMIM)wfWvwK)iaXq~VbRw?Q0b)VL+TWiB9A%$vw``RAwQKbj(ayqDXj zpH%d-eVP_ref>=!<-+RchVKi{c$~u=C9b1n3dpG|E7-FcFmG-7e8k*zc@2j#XPD)H z@XVdO={tb<&+UOTgLhuNkVA}+{1N7v>%<(UjV`wv@8`zrg%q$l!2~FJzwlQF*F<*` zmvoL)og<4ddy30``^?~<1};vZ1o0fHM1o5iCgL!uw8J8e5OIW5qB2-^u#r`6xE0nK z5Ud(Q0u~q$tinP<<=OKeU4J3C6qIY6);I@~5{nJ+w8#*R6$Z;zWg!8}3JA2EaCys_ zw|9T~#0OfAOY+uum)Hp{wJd5`hGE_=+}rf(jMr}lP#-DnBjt7$fpxW~NdubOTHrkq zmWzK3y7uPe_U25&)NX6Jdj2~PH0CnG!rq+4NVw^h^TmCa_iqQ$17!IC*=8rPG(>WT zNI4ce{txPZrdh4m{ zp9Pp%ZPwZe2mZ@FMheiOy0`2fFU>ws0v3#rsu8jRL*0F5Tg}Ud&-MU+KdJ2}4R-2F zgCuv56k!Xv$JU?J2jb4B}mTf;3Mz53aY3C{ z9U(PXxVRm7(rV=B%cmY0`pc6KRILPlv(%i<=TY@BQj2+ni4Xi%lSh6u7zkEpN5ZL} zwQc>V;0-qj?jyB*q=B!#+|#58s}BtZ30B`n3CI8htJxy~lM4v6!{ai>8kT8W$7S?9 zEL*)C32)44>i^-%+C9{DRsI^@b-71KKDrKL4g6N0M}G7b5NLD9WlSMhwmLczK0mT< zfw<`YDX`xFsTd&DXt@h|L+cRPg`w8vkVNAPBdy`14*~ke`neS!1c8yPkN)`T?)am$ ccG2(q)ql@FoaYbtcHeUAE@4-kcuV~8|CYXxt^fc4 literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/rws_client.cpp.EFFF1D4EFBF2C97C.idx b/.cache/clangd/index/rws_client.cpp.EFFF1D4EFBF2C97C.idx new file mode 100644 index 0000000000000000000000000000000000000000..de8d4dcf92ac73ce8713483cc673e77b2b1c1a9e GIT binary patch literal 2836 zcmcgue{2&~9KV&e*XxdMv|U>UY0!`6LQB*tr7$#C~xbeb%0FaTg4*qkQ)**=|n@7AIhea!r)jAt8+W*`eA+>|Lk1#$k<4p&(787pBm-|2AlPR zd}?45DXNJ%6x%@yrJ(TN5m2p9;Nvf_vSvCZzTE%XMle_Zi%!t6}1`-)w zm;tAA+xeu8p+K4|>lMfux>YSJ1~;ywy+&1(ASV_ILRAyS4NlPvQ&d&1EFyVaL{LyP z6QZJRq-c_A$#7mY29l;pk#6)&FaC*dlmesJC;o;LCKBMA;Q|KJ{>I(kz$syjG%03vZ$FrhLUPvjin(dN@cO2LLlMRV%0b{ zhQRK=R>CF{1&T&ZGsOv@Yif-GB?>4;%`jnw0y+f{#N|U01hRtqXV)_(=~_`KaoRqm z!c|qPRDv=$rdvt9QdMz?S;(1X1<3-A*{pFjsUpu(NUErnI8`ZdGppXdSWm2n!m-Ky zCC!RPdpA3znkF_o(?i;N$?-2nL^vfZjz)bP%~rpi-gmw zCWj}ND~YOzCr)aV&oU5KP&7`$Z^UF)+zV5R3XNt0JQmzs&X`UOkB%g#eNgt%YPgKY z>pSr{g-1w(l1UXYZ=B=qf8gemBx;oa^VYmI4e&DBWx>(?LyIYAj7BCKmZb)8-w@LCl z{4^n8LBJ8HOa9pBPxrie6gXHwyJ>%epkqTvfq)*$R-PX zE}xG;)+VPmO}^)3Y~Cm6L<8dK@~k6L@6^Q?JD*>))HWKVcMvrTJTcFDB0ahI-3zBy zf3Uj6IV)lQ%4_t;cLsmP<#DZYbrb8IZ@-0h9Y4GWTQ}!3!tftfVEZvU1K!o-iRoiD z5iASZ=(dIZZ@hB)($>2yoIH3q@#&du*gdir_m*UDo%0vZZ{B_cr@}By zC$VCIm+{sm>zi+X*}i!LkBx$k;BrEV9rT5Uh;-0%V`_~xbsPJov-EDl^zxRj<6mFB zY+$UP@rQ^t?j{qcODDoFg$51;4>+8F0Zb3UIzgMSEkqI{P|UdTCfk-{Md&QGaw||CP%Z z&c0x`ZH=qWboIA8Ti~tCA>6j$ir`9OeQWcp*FU*-{wF&MnyH8C1YX+PB>8DSLm)T` zI#8FUUcZ~@JbLOo?9Q{%vyB9fpeow4i09Z?g@0SXvEbRUI~U`Z9MN@D)ZUtT){zB8 z;eQk=hsCAfu@=Vyr^`)y7;of}$g0T7NLS?1$g;@t$ck_)yD%77%u{zXA F{Q=R4#X|r9 literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/rws_client.hpp.96A4BFF4DFB820B8.idx b/.cache/clangd/index/rws_client.hpp.96A4BFF4DFB820B8.idx new file mode 100644 index 0000000000000000000000000000000000000000..e2e0641a7595d0513a405da06a2e97b1771542e2 GIT binary patch literal 1214 zcmcgrOK1~87@pn6>}DI*O$dENsa^zoFk1?Gh|+^KfeHcJ9z4l1*-WyF`(kE7tRmim zUet>qc+r-Ccq$5F4?cP*MT+Rbg9?fi1bY#D9@W`RXXB$6FD_(e@_+yTf8Y1-?95cT zd^Z8WWNqq{izsAAps^pJ*xn(sL-@=bpPh7UFpDLyqo*mBa ziIy1OnJiZ>Kl$-m5`{h>r<3XJ(E?K4dO;Sf&SHM8azY*uh0UI_Dysc)hvxdbuSX{i zlvJ^wG2}*ba>R3{Tc z n94!Lk{kcC5cJj{1diTrR8=}0>V_pgyQsSI>jEi*dSofrV6)oaqDFGoI$EIY4` z@ByUdjFM6Lz-LpX`!3Qh3M}c6dYC8iT}b`L#D~O~!U=H!+&jw-J@fFxD`!?$?k%1R z1?*Nwc~2%l%M5b?FJ3lMt_)wA4H?1A;urZ_#l$_NCb;9qLL6oqR|i(Veo zGjq?EbH4N4bIzR^i1+tLIE12Vd{oDl>_G?x;WjNsg4M8aE^tB~v8Sv}8>a3o=tnGQ$#~ z7G^oeiBLteRlFb?lPQy=%rMtaF8+yc2nj=w6P|d~Vluo5C6-`fEeC6A2sX7%tO_}s zDi$&59Iz-e8QO>$phaU+tspaE6~Ja#wW%soOHi?*nSj`oVOc52Sq%#cv=*QeIAg)- zKFx!Rf`pt|rj|S^7*s1GA&&%NmQ4%mNHCDVFqDreSWpS;o?Fj|V$dAPi*$tOVo|g6 zd8~@Vh8;EZq6QL^ShNa+sS;?m%3@j3)j5Eo$uuu&Br8s>)~%0pMmiB_Q@iuj4u{um zMsqX%T?ex^(bRcrzJPFd0GyG)d0o=YyfYP3t-p5mzlO7tDd{qm^O#*P4HN`~T&D&I z1_{?0%;X|bZ=?cK1g0*@s!He$F&SCI`nLoNIfago(Fsi@!J62+Iu1Tj zS<7?Pod3xF`|rK@P4{PDb#u`f%fHIs;qva<7~j|W_}8C;=EfzBysN@~vmrOJW&0SU z(9_3c&s z`8{>to}PGb{Ndxr4!`lJlRW5cc9Vbg%E1HW{+fD#o2r}YT#|EJ_I+~nqlxn#P|?P< z&r-3%*E&mu-#;A!D*S+)~Q)B8^FzrX<0uc_bUs(>leWT%oa<)-K?!p>vr>Tnkb zt({(0@Xe>r*IW>OK2sU)Sc~AFt2uEkLVLxcN>A0|YHtk}S`}IyS{Yg%x;3;SbW5o9 XCSR?;sj)uL5Ug9)yk<$;(wotr6O@+m literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/rws_service_provider_ros.cpp.3D58FEF4D583A6ED.idx b/.cache/clangd/index/rws_service_provider_ros.cpp.3D58FEF4D583A6ED.idx new file mode 100644 index 0000000000000000000000000000000000000000..3db966fb404a2b878c32d1a8c742071af6fff9ad GIT binary patch literal 60906 zcmeFad0Z67);~;FS9f)oVMmk!L=gwvMQ)jDF zRf)0D(LX)3uxOta`%z|kUMjY*u&|~7=H}&OOw-W6nEx>t(sD9Jrso(kv(wVU2KoA0 z7$PIObm^9q(ymjdl=v=jRcj_+9adty|FsGk4%=We~aB}H}q z&%Yw&Rsi2b&iTpYL^t-B|a=Cb5zQJ(F2BMXQij5 z<)#c6KAgTbv3>WX*iPM2qT<^{bc#x;eKrx84E+KIygHsUCqrNF??`Ft~x3^ zXK3#5)B)*gYXANz!?RLG<*FH3xp}F>hN**7bJ9ko=A@@&WaXvj3^W(Y$Qm$gL|Xbk zRZVWrfVY+AWakFF{mcJbeaRMvWcp6}-}I02a#HF4GqN)B47usU2GYN0WgA9hjmS+; zGYlM&H6Sk|JL@k$4o}TVrNfw>Lw_Bf{kFA+)SQgG!4&7Dr;W%;OU=qNq@@oSmP>yb zk(HC4I$&^W|6%Ed0d#2TPorqzbc1>Hvj)*311t;!b4O?8rG8|{&Kfq_!Z66fkdZq& zH!nTY!jNrY$VsQ&mop&Ukd~1X_SgP24#>_Lm@!Dr8kv!)4j(pR(4h1*wO96t_Su=k zhtVc>PFM2=XXK=%&^G6dR!0xWO#90Z1BRt$4N`|?^jB;D);z%IZ}hjIZA%Lqlr_TF zw|S7oU*Gs&jbQ%~8N<^4n?C<19tQ?6vqbu!%#_UBL1wO~9r}O#_W$^J&Zyj!%+##Z zLFqaF+iGZs(1!dk+dvIMwUNYBbM(n+HJqc<3{EfU*xjg9O!I)ql*XY@Xz>zNO!pkv1%4P; z{kXq=r1^)xex&&q_K{|knN4R+Zc6sRfp4D&nDrKMJzy?d3*YttgXSJ!2wKd3dDkc0 z54C+_{(*kefb2}FZqnXX!S@IKww&6}8Inzn1ZwR89-f_>&Ous#dMa(gTl(7;(!Xa9 zH}^!{UuaLgD?|zJ%DlA@{$m$X3o>Ki=#;213D!C;g>A*!6U zd@DHpF(lj;b))pV#Pu#|X;>hT1%i8BnPx*j5)=Md|DguyEi6(lWm(uD>ZQ4c`jnTdpOYrdV8kaSgq1i$ZCc0@1ZV^f7cN-B~T2U8PAg zuWz1Zi{7Ut_9?FWlt9C3fvgrh>fV$P*Iw7(>&`=46imxhAlC}yYv@EeIk6IBLuY>B z8s%$?I?xhFvFlOnXUHU(?2CF-ZORp%AA4zw;%JE)>{^3;4Y?$j)zRm(%^MQErXX7s zMoY{RTxSUZh5!=4#-?BFp!6nXhiBWOeze3^#dWI^Vpt`RRf1PtOWwDP)c#_~!nP=x zmbpe;uMt1PJb}y;SX)w}4A*as|Gkwh>O{*_%dXY5cc%$t8rQoYG_h-2bI*T)Eox57 zEE8Op2?j$;(y~F_o6=SX$GZ+5{h=+2q$TEK*ZJ7TFo+CdeLHB3c;n`gixX^7Z(8E2 z;(Ar_H>?xLI>Du`mXEe{ZnzDVyV;_4w9Hx2^(-Bs_sRRLmXG#NALW{#*w_}O&=N-# z*P}|PVU0l62;OzIeDdRr;r-)sB5hG1EmMeG3z46pJ!#Lr`SX;j($o#1g|;Yxme?e@ zZjzcBMw8KYb#)X5&bJ%Z=z~yO6hKRC6I{0m%?v>#$g!@(f-osLVC~r=Thx`7s35Kt z#MkhZK)w>#C@!2gE1=b@qxQDQM9b_GUH6I241Gu+R?E_r^RM-D>`1w(6)o{vaD7eR zVfezLIaM*F@aEpbtHy(s${@&%I5y=Tpl{d%vUCC6-0TUutd=(<`o7^&Rf`-|_b&z@+DTGA4?1=rhxk0FeNvA*AY z^UL=;%=_b>Eox6oyb)dB(9uaFX{^MyhwYrw+kLph7A4UVPl@YO5@uK=kVS&NuHQNwnGmgC8{8stOu{+n>qF%Jb z8pU;u;%8VPkQH28Zk;~k;uTwb))ocPGV77+ddk<)B%0Oo^Xu5etE>MAutnjt#7~mz zPgItEMm}RD?xk-Ve_eZEt1aqIOH5T>Ow8M_RQMy;q8?VGOkDPGr3kIRHkxZX9~>GV{KZR&_uQwxBq*suObJ zkTY`TkSlWKkUMhcP-E1XLte;>Lwcm=kT3G(kP#U<)EqVEP)pR3LqRBrLm?=HLt!Y4 zLndV6PySv=3{FZ}>OdKwOm0>tM}fu{pTx)c zRj(UH312J0Un{XN*>IZ|CvRD}OrnHiNOKH1fmW8MEO(5^SpNql%vV~?SE9kpQ7oM- zzV5s@of3}7;YZ|nc!x4+Zqn#eE9=oAK8f57sTxg(g+L!ty)Cfibx|6la%F&+fLF5ny*z)6Svc( z5hy~-GtaCxx6Ur1?X40zRtbrqQMBrPA?Usk&TzG$sTS-3YZ^`6b!u{hK6Gfl7yZ8% zTfywp{1UrZKK#Q?N~l0RDp0?=p;=UaaNo=xZ|G3m#m2ih00gX7eTsdaVk3`3p5kyG zcY2Du*5TiW$JzKDdP#@kSHb#Mp?=#9z0Z0jtsr^$+<%yy*C{3&ui*m8(48|^2 zOGUX4nu7qWnU127>{sv#~rIJA>%O>RK$X#m*pl zv08!U3hWG`m)3{n>)07YFIHb-`6YIS9>?k&NuDD)g9(h)HIlqWat5;it9vAQkK_y{ z8dfh$@@2^xxEQN7l3XJ>0~cd;xhyZ2oxvo)>M2=1B|F2c#p**@ekeNwmt%Dbk*5%6 z;Bu_4B=Sn)3|vn8pUC@&GjKUpFA(_xaRx32$BJ@{b(nP`%u365J{C+~tA!aye;nlD zN?Dh5Cw;*QvRZn2Mp?|`hV1%^=(`k za&U2I#E_GV6Nj8#oH^v`;>sa+7k3Udc4^EZFBdNk>0R_3@^$g$kkQ4+q2?~lIn>gn zC5M7sf;bf762hS{moN^QTudBl@6w(_(Js*(igk(QP$!p89O~lIg+qxhi5%+FppP5t zvwjWwaVVuh3Wo-`4B(y{=rWK)L)?ZmX0>FxWpZe^+i(u$y5(|cq}xaijdmaH$!Zzv zK9)lh1h)wSS9X%%Hi^g61nX&n1ABUdpxYq09}yfT4|)Ieb}bc=xC=@{=>qpV}>mlpF{Nx(%nbyo{z_^ z$=;q7uB9SUH&JxISmo6CPLHgvS}G!S#iIMvyBddlKcxw^?L=Lv=)Qct?#h)V<>CSkm2 z4_9|yxVExajFyT>-CFEE2Cx0HCMSsMk_xP=!0ua&UqyX>9`B;{Vcm7?eq;L64h5e>YA>tmWoK-8p(Zc-@_xm$jLpYr6N+d zM{@tf;L-0<)AgTesfg5FmfTlle$+rs&@R?e5vi+@+*{@9e%d_(dC{3J>z2#zep1^s zpX)n!YpICTos!)Pe!5??A?wSvS}G!S4`ufrnlU2>jtpy|r6N){g}9GCHuv+vY5Hwc z7ZTk{;_iK}@^FY}tD&_2iEbZpAHT@$Qq@;ZWm+mCbr*y_a3N*p*hcAvE=IKI%-h7x8=?z5#PApPtXP5PtB!IPO(s6HpHo|8CmB(>^v zrPXvL4%`;IrB8;GWgXs275`S;aVt&)wL`~{YC0Uq@Gcy*3x_jYjy2`j930)vD(ObY8FqeXdm>3Fwhv4fm#B{(Hiu*R(&F(C!#gzbE7_Gq8pwH>|W3&%j zLq}2L7Nd*U8uU4>52Gj88uYnV&6iNVWDP?}nMFb?C2P>?c>5PML+*C` z+{w+%fi|m|MQP?hn|;ipG;^TMd1g_XInd@2vnb6RXfugflx7aJS;{O*GY8siXBH)O zfRN1*W>K0s(B?L?D9s#bQ-kU(N;3!AEMgX=nFDP$F^kg7fi{PkMQP?Zn#;FEZ}s>Bo`rI0|Pn z`V=yr;&Bx+R-tevv+p6FdnknAaiVdY7|vw)1kq=L7{c%uqVWr!zC<)G5yP2`Uncr2 z6GIp-5{*SXeT!(^B8D>^uub&YCWbJ)T{Ldz=|70ZAO0HU@;M@gFr9H!G#=&YS486# zF`Vg;YogCJF@)i2(O4~pGoA8W^m#6ZFgzU_r{i!Cby{^M_L+%87@mcVvv~S9*!T?& zXF8|^`;_1ihSy-@8lL_gHh%Y4Zt%`ehmtz~M}XUBy0EaR|fLu<;sC zug1n|K5FnB`#i@XOy|A8#uq$&n&dxCGO>v~UGkeQg)%%t@}I%ezmbgJNa0LJmPkG& zQV7F4CF4#hoaxNnlFx1_gy9R4@q!c%I!3Erl6)>nAq-ba#!8<4N;1BZ!kLbJE&05b zLKuD{8Q<{qrLu9U9L{ubk?d0>hcH|$8;f~*x$IXihcX>~Og0{q!x=sy`<#$N7(OW* zPxAD8vhkiA&UE?%+2?^A!tgJ$@fV&xkr*eEaHjJo6Q9W>gyDQ*%;)LF#8^zinN9FD z@%fsBFuZ~oSMc;*#JG!uGn-)#@!3N{7~V^adwKd9Vmw2_nN4wy_?#ml44)^)^E~|q zX>x%as-oS};d%y}wq17+$9|S*NrBzrgG#c&}H27~ZZl*{-yJB~EHXD&D0^5W@$R zCI^)kuv|+WEXBJ*31ax1(&U`d0u~FY1*LeOSArP6t~9x>w16c^t$IW8zM%v$d{1d| zPiXBzpZ-KSw+|=pRc7rO2fe89;S`87f%5U7m-E8mt>; znn_xmpf$GZ6 zbP$I^qC+^;CAtfT5~CA2G$48ahla-t@5k!QjmhQE$e58F8XY&9v$@B{jpfh;A!dTW zmA!-_E}>+mjVn=TB}!oUF^YYR-e=nQH`M+&)RW-?F}gtP!?f>o(KKD`&hS|=`mET8 zX~T1(>73Y|;X7i~9kDmlhE-zQDlv)S1ycJ3QcouB7fN9Zr9_4|NfDc*WG3x5OQD;k z1cool9WKg!nRL7)x4R_wV7OY2u9o{SY4}VwJ(IgLJd4E4BK?^3n@u8SlVpb15z{)- zok_d(BxF75!f*xYP(k`K>2`>;J4AW_)&>7uX`?yjL%BaJI;<{2YW9Dk--wC8S=7xC zO*LXCz%JdRrX(b}cvBX?C8ghzvOqhzoc$($;}5$YQeM6&*k2Spnc4YRuzxIgGP5!t z+2DP2$}h>!cwlhK9K=oju2P)*-A~Ia<|&FTkozJsT%L?$+airzl5n(qPI7 z)Zhg2VrJ}jveS2R6HvqMN8($04r-Iugod&kS##k&JB?jk?`YL}ntB{+plQG%7mW*t z8fqGH$V217Ay17bhrBi39P-ilaLAxBaL8Zd&!HBY790xH1ac@?6U?DdO(=)jYT9xr zLKDHEC`}ZHVl*)v>Zs|+p?FO^hY~ai97@t8aVXs?-44b>s}8mr%%Nd6!?;jswoNvN za%^%qG{R;Cheo-Ka%Xjpu^Ur2{#x}@yH7bZQLvfFhhy^vn|y}due2=c`Q&tsCszC5 zKJ}qWtoFnGIFy1@I5bT_(*!G4_U}cof9FN8Mx7Te$~Amwqynl6CsyI!;2C*b>hP6Q zr$?cba1^H=#Y4cw^0?Rc?3NEAJBgUCvOAnajv$oi`l948TXF@ujMxN(inJ zBAHIRFL>P-{26{CXr2g83_lYz&lvXl>EM8hj{AbB@Lz_kmm%jBE8pus`1QnL)JMeD zm$37c&Gk+s7gkU9s{W=${%^%4e@lVCm%`s=fc{UH!o8m!UhX=i<0q79=b_+vC=v`U z8lOa73z0v=%aLX|a$=QFicj@`5)GjawdxmIm3v_U3AE`wY$7-~4U;Sh#A277SGbC4%j(tC*aFjmrMh!2Mh z8HS;Z=AY(2kf9bsTX1g=92Cga89X?cdtd0FP>$Aia9fTRF*t%lQG=qmk}*SKxVCg0 z(vd^)8Sz}p64Da}v6dyJC2{Rc&rHu|w85E!IW#P5*lTF^T+ffn z8I{ML8#8=N4nv=2fBGRq6NOgnNEUh zqLTNxQ~N;(T_;2U>rh=SgdP+kfOWL$6(RJB5WzxK)k0{s5W&p$0u)++B3P(u1qxk( zBA^B470S>(C<0VG70W2}9*STw%n4%X1TlieESHI)%ftv4queHjZWANG2cm|N7?GCV-+wQ}BxX9z(Z%%QhTYfjYL^|Ir_+T%NgqXa6p& zWQ(L0+}i`Y26A-ErfU7qDL2&Mlo~u3=0jj=$3Df4Z;hRWkOLW>DTmFJBN?6}N6z8P7s_#kass2zmxJc>OSMI^rbxC2dQjR3eD2$> zw`hyD;2v9W3e4!%T?^K(=-_scS_dV9XNh27qHeS3y;<}J(b9Tm@ei|hin5u*Ju|$a zD_|zl=ko=>d?5q~mhX0Of`=5`R2H4biwz`mE`RV{9LZ$H1MKzy>luE8y&hqIhO4or z8apxk0&89{9BgRxTcvYr^SZ%C6uc2dGGV$Id2L4i4DUjkUC4>yy-2f{;o$YF;`(_H zH0NeN#r99JC%iGF;cq_YNe!5*AhQ{o8C2b(q)QNn7m_i8Z}#;~0x^Wir`24c#7vjsF;u!ZfX<^Y$x zO>qRP%Pjt!%M@=W{>l_nnG(-%xuPvsbi6opKB;(vIHY@Q6w^s19&o#uuPo%0!$JQ7 zEADUCwKm)M-_3Q6FjPNW`Ks&Ge*p`@1p3<%`1jh=6Y)pj*q^_=+|G)c#l&!pw1V|k zs**_JUD6xY8fc;i39ly6EYW7F(sioRlO@I!D)EI%4@dx^l36hpDS<5UWsPE3qqKss zBXz2kHd~eUOuX(>y6#hYGVys->2XwfA9MjVvz6vom0*^rQl&JnQi35`qopSwwE9g6 zgG7|}FTyX6S|6>U0)MlZw3+R!jnugqcjMXSO^-)p`y;X^sB5}zBikQkI7%r<3G3~5 zhSqRi2|llMf~G_rUPQ{OBcD=&WgE-3pxvXd_YR-e_hWM)wMLAu5qp3K(cw{L;??A{ zLlv$1o#6N#pWeI^Iqu}slkXFo`^1s;`7>hsjMQU&{)*VYBJ~*_r`V5EI9#A;3KUy5 zCi4`ld5S%ZNzB&kS!YgnSfSCX1MmP_Xt-7#hzD|Lh&;re(K6*s4h@%wb0}BN<FR(e1*s>ClOpWST+LmW?85F~ zm}=Ftn4HD#%+-8^$s_CzMj744Dv>WFcQCE#@}NYDC3og(9+${*$(^~DPbKnHa%ZmP ze3{Ib-N8cEs=H*eOLk{77L(OizS3 z#$i*DX)3DQVo3KJA=7dc$2e>kGVMZfjKhv2({U8XIIIeps!$x`uyLYkoEXPAY>8-E zBF2H?OI;Pwv_*^q>s71%Aew#<;~0ls5lvUbI2PQf7ERS+9OJm@*fbr-F^>BNo4&zu zjN`t;rtfeZ>&VO4bQ#Anj;qF|Y8=NnZkiM^P3pur?i_)0RplHwQ#E|pD7(p>^qZpM(4-@bNKRw za_d65Ju5$7_L?vIGrUyRER~%YE|xXL48s6Ztu#^ao5=f&wWsyK9O*Rk_K$;mo}Ndw z%uzY~sN5a81{9}E^_oPENFJ<@A4=q*`hyYotKj5+E{33qVMJ2(Znq)YFq%Q}n+ccvjE zhiHcZOe+*pSuTXK$v9VVp3C-nbV;*1xHUg^4Xy8u(CLkk1aiE~^gQd1r~8_{(w9=o zOKH%DZnu-hE;J=|xl;APtCdf(soy&pSx=_tPkgpe!Y?k-eS7<{^?vNM`QVI)%k8BK zy4_y3{$6(aZQ2>-$n(+5=sc3Ge~_I5Ujz?qZ!^;aK8X&8L2n3x7F)hM^a#2JrUfk) zqmOCLiq)QcR99?9RTE#`&YrZ`8KvbJ=HOC+uCzSMaKiDfhCXl3FDNGJIbOyHAU} zJ3fVOh?F89^5q{(agU`0Mt>>=J>~P|UrUu@WKlKF(enAqLtujLi zo}nawZPM+%sJ)r#wlf^45!KI<yt%OcfA{Z`I!V8s1Fo|gVTWLL431_%Si7QgN@@8x78l?+wwkB^?`tfFK z#6BekW*=oVC3L?M!SGQf=BN@6lZUE6CE}P8!|+w5^HrrAZ`O9MQo8YGZNhI#GT21j zMqZ!s)3n1wDC;j1dM^`FL31Vbu*$uEF~FI2`~|`Kf>1wf#e$2T`CW(59>CVqaQz#5 z9J@a0bN82|16>w)-}gI4Yd9{%9~XLnZtK3W>k@|ttJ7%>*OYqKl*X)0cNNFGiU+i* zM`~fOb;XxMn*8&zpTCce`1d|K0_+3ITk-mMPM+2t00)Ay=lNTqI?qW+0!VpiHzte=Wa%t~8<^((N6S!w&Qejhe5EA1lIU&JO*N9Jv# z`X|(Idw2GhdE2NypWlSFQqr%KOw39vmHbPk7-prNmh`736SE-BNY-bhrnWyRHXq&B zYR%h9^)Dn72z|2}wtgu!1vPBmW~yH-o0x@hSk@nwO<<~+x0&jzWD~RECJ_AuVq#X@ zGNNBbOw5YgLHu`+7-q$tBKlLr1Xdh`Y$FvUq8m>J&5V)()nf2ip)*R^ZF9?_Y z9dZ5ljJWoBTJyZA&BCv#^4x&>Zb0cEGWyOsKhAQ=;#q(5mh<0&nIL)@d5#E`RN8DQC6OwrKI^CgnH0$NSx0S<$p*PT>!?bZRLb>PM?IIxbGbh2s5ykpA@!l7s8}In z1F6q6-C;rwllq|PEZ?1ETi1~d>)G{dJM<&UGfzePr=lBlOp12hwW6Y9eW)jSLI^$~ zL^9jxwBU7G@MpME&{PUe3||#AR~d$uQsx`sH-cNru01Xn8j|v3&+RBOGM6^wrPSl4 z)C+6@u-WMI4fG9ynQpEy z<1`q`RQbrj*5ALLO$o0_@N3cyT)@;p7Gv%|w^08Dq8J+g_o~>x*Q!|Rr$6_-6;NnC ztL}ypd_(CBu5ka*p+4XA9ya^q3qh6AFaITL_Ur?9>qN^$TQ@^WbAB_%obgkjNKxUEs_iK2CmBFs_epK*zYp= zU3LM#8U8McX#O~i%CupbHek+?7!R(k?AeEOj8eyvxnt{p@JmlaY#g%rlL z()W_@_fjCkN2GuwJpH)jbzJgi^b3;ag5<<-rKG83c<{<^bw@h)Q)nOan_!1D9Jkzb z{#+jY`L@vSwlEOf#-Z8;8T$txw`@eEvJkvMh=(yXpXwHTNQh_t=QSbtnh?)q=yM_X zxeyN(nNM{Ko`K>)p_@;23toldng6*D1@A-gU`(1%bqhYtGJ(yfx&_}y@k~oj6oV&< z@oWT(#o%Hwo{eCs7+fmGGyn6L7<^2OXa47PG5ER|&-~99V(<$w9+ZdqRJY*SIG$U zyhn;>9Cuj?zAVMFfvk~&YovIlb(hP*%jI~cbx+B`r`Wl+=2P8*AIkBJW2cbdDI}h8 z>`D^6lEgEP-A97=k$A?j7fA305)T|ZtmTlF)hDN>&~?*`LfeZ%6dUNrLfgke6dUM# z)HWYQv4Ji^ZHrJ88|YFLQ_2r?0d8A>qgY3;!fjXKDAv(sxNRAZVjW$H+g9Qz*3nOK z+ow2+b@VHuc}46%6%I?hFtKLnvHp~`*T~6hGtri@r1xM%stQH`L0^|riKzFYoyJBPy zJ%H5}$YBL?WOxs9*n=E_^)b!%b-0Hdfz`1(L3EfPIs&U>b(!d}OmqZR$LcoGVVmd( ztd426ufq}15m=q>-Vq(HiH^YPboY+v@LY5RR>$;w9*3FO5k>&hY+r{G>oLqMSD-Ng4i{t=B4(jVg=@9 z=C&^QWb?vwx-@k{=y*a%1jeQ^SO_}JAMABS&|DGhfj+z_c6reIH+xdOd`W0{NoWED znusDa{7q;AGs5i6xlKWhVMfqJdDN&FdBF_$&^I`5?d-09&^dZs=y_a7g^F^bFOUl< zpSGb*bB%UQ1j~W0APCXN_=X-AOvmZ^*tBJsY;`=aF=-RoIv{32`tV|7ZsoQ3$53n-r z2)XAa`2%1@YG=sF&*T(fMXFUuuh}FOSdnH+kc9Q57qBALs-)*3@&T}7?l<0rV?&cH zX~&c*!KF%f;DNkJe_Frp^;)2W#bV>dVoUgfyzNi#Pc5Bic0$Uf)N*Ms%&HNN+lO>n z)U%sF_dQE3&q$#V$sF;1&t^Go-T$OdED%~R5ZZzq9P!ibXK~?yQPgbf(YQz3O;3f} zyY?sdrQ1D)dh>(;C^j;4&y(~%hsRMaScp3=#EBp`wCWN}{{%8zgoBFsbG%BhrUcsq zedOe)2Tt@}YEC8oTLdJ>7S(4pQICrxzV#e%)H;_@XwS`p#)bb2_Sz)uUs9vw_s8r z?UNe8SR(|$@X(k$^2tX=9*5-f2l?frPWh1TY7JARJ2qiQBl6^sKJPfWr=llViEW@61uY!CD?$;+KNkC?tbe zqGKo|JQk9fSjPjSLioD7PZo=~Z1#wm5C(wOh28{4}c2%{rhhdH&hXd? zZJV!n`g08(@e4wO3qoU93dVFP*lQa0ho#`Lg||%(R^KA}&70|v<6h8tW3MjTy2LhU zC?#wY`fL-@!2J6p?$^`(MmIf232*4iv5*482fan7n77`W%Y>-Cg9v8gCwIQ>y>8Ux zNwjIpkZu`j3THG>I|w(sg#F-*26&)5O%JfJtOtBb5xt2Eh;#>0Q|mU2W@l&Dl%aZd z^*GePt^tQ!>|8k1(5@keJnTF;oT_A^o z?SeTJY8T3(wsvhf6k!*^p(wj34#n8TaHykQM-Ii?#d9dZE`dWyc1avccSzT>9vtj2 zm_x(r4fA2N?0VT8%Bh#bp%L{)aA=grs5%j^RmapHB~NXrBrxH4v5mbM8x;AOKRB^?uVOhVlj zq}zgyNvPL?^jgpXi<U3HnX+6?02~~ll3Zw&NLhT_WT|zo$e?3OhV|sl1 zyE~q!L=&X~Q3uwGd1s2WTGX*=y-$?(i8^p)XtIzfofUPUJ!zJeDBTft%szV~N^e9R zlaTYVG#~4jgxrj!%~%JM+~ zNzyUZ#O_Fs?YnRAUiL3*yO`U65x+v?I{a7ta)v}J+ zkF$t0i|CmBxQqEh6-25aIe}lkaO3X^o;|@_nl!ZB=w&rqV10McT)22s)}rM-?5I zHRg8he*`k+dYsuUgQ19L{Z^qZmsyY4g1(LIe;J*|8f*Ir$Hds)d?yXxA*t44o7 zb#36dsaQ21URAwx*^{*mulz{`{@cT=9vrX=|D<<*V@ShU+~G*{%Nc*Pg}8Rxfn`TN zJTk@#&bqkweee5Mrlg5**2TT$&5j#qPoD#4T{I8=Y?pWJ&QLh(V$s?{`(OPR(3aKS z;BxTI&3>L27VUtuE+*cb{^NTk#t-4Fi^@csDO2j1tl_MSE#=CfT_ab}`f6`**&Q%7 z|7Lre)^OIv^r_p9+Z-JIEu3}X|9;ov_j?ZR3TIt34EI~OF(8b-zxD=~p$-9am;apO z3TIuE{dDMyaeoGT!C4m{ewZ}N_sfsA!-k>7xjT1{UDv?@&bqMecX&bh^draNtP9Ii z;$FYG#}qj0Vos;U6AO|x^Wm(E3C|u6zue95132sA%l7(qhRQ73f3-Kb+)7z~!*bt& zJ#f~=9kpykvCYpj;jD{UFDK=Fe1CoooOR*gS+4%^ESip2?F}xG&k8?W+RmX8&bnB< z>1V&`Nk7v5slCBPx4vZlO{^bPW0l&bqLAU^C-0Yme=pce}8`Yt%1< zs_%1BlXH?0<|@o#s=kx-NdX|BE#F-b2nzS}?UU}0KGJ&*eg3Z85Al5lCA=f=MSxPMRDa+roW!3S1>Mk;o1+M4|ylofcO44 zhw}ZMmhdmpXr8we_PrFz@DVBU2v0vQ1s&&)3%?|3 zE=l%KeufoVJl}WPPc#OXnUKkyyZe)r@RO9nOq*L$$6Hb_z%!1vx)s~wVGW&4E3wZ? zs)pX(r8YCZ{>anM{mkO+5bAme^#o&aW{TrwWyx&|O88#1|DK(bJS+KO)V98}D=6U( zvcH3Tz?_`*_3ziWm)!2tHU;$$+yv?$*aXx+C__;Hpg}K`oPIbYul zY2v%+4CSRC)I->}Nx|Atlm{x_`h_rGD4zyA%Z{QYlO z6hE@LlH>~pazhRZX{|&4B{cl+1Z*{{ef2$i-`CHwv%HQgS zRsL2ttn#WJ@FcUk|=LCd}3WPdh> zIwZBH33pqlWX<{Zy9?lu^$m61yYpo1a&X8dH&3$(3;%r)0vCRjEtStE>8}A{ZL%<oPzhYkVhV&rUw@ z3MBI49(%mUUCx^h5_x#1k2{^qNTK!DUa2`L_D$b)zpPyd5*cl3`oYk}C5|AGm#nmC zHpQdWcOa3EMPHQ{_U!c>B(mY<(A?+AofAPKTl#!kWVF0A3ncQr@=XDO>86iCBF7wB zRpat7i8_e2S84{Qj``%1ubaIDi99Dia&*&!D(#QjD>X?E>})?bMFoj`b6!ooik@*n z^W;~Df?jU&q?|Ue%fR<*drateOc)3; ztOdT|%kI5=kVFZ^NK=e#Ay@?}fC{xwjh}|Wi|B^7x3{;0Py^$g77Nq|a}IeH)A@j0pGIjJ?!7mYr# zdDD`7T+wuadZCL+vch&aM*hKM7~W{5b#Yz8iX+5ESC zHRi>&n^Gs3&HtT!wP<^c&^sux6XmTU(xiw4fnl~}$Gj7}*B%&23F}endNc$^5JsBL zH&4AMH{V_huCIk=FyEFnT+w}D$tAO+zfDNoCiDW1TDG^+XT8_m6Lfy85u?|Lona`= zYeqrq`FpUoiJEPqJI^Xu*qtUIh%ILG zcZ+=`hJ7VQGWt9*XdZvp*fLSGOtfe8^P+lQ420=GzfaU$6YUwkE2?+JKyW|krd`qh z0Ud^4H_lzYs33!GOA~`0{q^oJ&2!P7(HBWH-#if93A#;9qJKDCECm(+_3kW9iDb{p zZ;@JT;qS`YEopX3_TY}tB~h9FsSDcC0JPlVDu3714LR(F90~3Qy^TZ;y2al;^+47< zknI`$xvV~y1Hm29s=v!EewRZS{!cx|8jSgW-_s7^f^SGLjqyeP(~vy z3i-RL=994bB$Ck=k)TEV-Bn)`&DX@9(Kis9Pag==m2S%;EjICYS#2djTlu@J_7Ke; zV$aGSChB1l2)a|N{zzK<$lq;sj07Fy@3uNeH0OvtlwWS~XL#(71v}}CStZ%8lDuG` zmPfa@_FH(v;a{L?{*HM4dq%ugyw_{{_J(s$Qr?;+HJBxNKuluAro`?65zm4tVJ=FX zi+Y3cu=2o-IVIxQ)>PG;k@RPz7LWsF-m#&7DYbwd8!M~3U3_@lvmUMCCuzt}QZ9rm zVBXUja{O}Y*4-`Xx}EDq*%y@6s$Uxn?rag6>q<3Rx2pi()}TnS&FiQz#b9A$lB+ zX!=5oW%{5h7Wx+4)}hs+>uS*e{I=$S z>zrlXLMGB;B?A4^hVk2GF<>*Zf!22TWRc@n{$`(Gs^mD8&6)KrceTr&{%1SdKBs6W zu6@gd*kwXbR$r0OzDP&}y#7|x!&2{!Bk5zsLUggv83^WctAbYWm(H#eH0uO=po7Av zEe_R(a#r6R(e;j4XZ686pv64&9(6esmUNqf>utdYzJKHA`|Xlv+nJkDDcV$u9?Tvo zm265S52pWj5Styu1IGJX$FZNZ)~sJmcZ95!1J=r6jFC3TZX0Ah!<%H^O>!W^TjhYQ zeECwjb*bE*(RaySyJUZc%jNgVS<*7~3uVnQ*@@9l%9@i5Z!(N)-~aJTvln{|CmzGS zVMcAbJMOEI>AjCrLKW^?h0|ebZQf&76&t^`BPG;`J!`~Nn6vPI+J|lRZMi;tBf7p3 z>-uo>tp~Fs%+xn@%}O>n{_Vl!?ul z@c3SA@;$?lWk3_-P6*_Lpl4FAN+4B&9!A^T0#YOB;SJ^+M#wy*XHst?A{&vONxjc8 z`JB({T!_g+tY=bcD<)g{v$Kw4a-7d6yowg+yWKjzdgF@Hz3 zod1q${c};R()4b3H%+{pKxgAk5`2?%f)t$6Y4`4CKicvsqT3<_U5VfZ5)sow8r?RF zjX>msrA(()fL@$b zWtCyIzFgmhmDI_)`V6_rZVeb}Bsbzv6S)ajvZ>ru$4WMnn{mib_T%zwRavb&`VgxD zasc=CR&pz@&en2k?tN|KHXJQn4(Dj?_(pA5RKcofIzDo|;#b4WeKz{FlY|H2;WX%b7b=!`LyuekjFLT$M8+$brbnB zT!l1M$cf=6$n6QzGh_D|@_2^)7=DR-U-H3~SIFxX@@MpMqGp`v#PAoQ<_jLr5Zz{o zdS*P&7CmN*ehhyl`hLX+Tjq&g^F)6}Um|Ljh)xU_iJBrFpBLTEi+X0fToE-_L??#t zif(sBJ=jj>;7Y>>Vl##xiC&LHe}=0?O||I6@FK}=k)#L7Vh*mjE#+~su|@J@#?($pvr}?nxKehjl=aN`zAAfMmHimLA^YCogD+psZgYs9IR}NrqmcM9JfHZ^=Yungh}R81ZNL z4AGn+P7I$Xn)3|r)Gqtod)TQ1RHj%VD+drvJ3|{p3~%{~`AV{R0-47Sl;0V1yYZP; zVGk)`8V;R?+d)$O&ZHGzs25uu^VF(+-1{_xinMA!_kJ8oaZlmUG@;%!p-y9&_Zxd` z5PTuHW8QD|eq)c*$QQ08Gw(O{xQ~3{N-}yTrRXtH^o1+QsJ|n66pOx7?`j%Vl4?6K#B^f=kk9b@lzHlYk z?(o1#Z%p_l<*o5btMN+RHl*F%0-6O!9BM=fB|>6}&>QTh-PuWf^EW-}M*SCkw4Pg# zTaRMaqaMsx*nlE7pss-TxYT=p{14e5Q+@ff6!5bY#zGHOl3SIeXZXJ4d!Iix@}U&) zkT3sOYW-Mh&&ofQyq-$_48M{zuOugi-$ppz1TNA)kKO6UFg~;t5I5d)qW_ zUUKo6`MTA7IV@j}hG59vHuui-+O@Eh63XO`WpW~@;=MJY0lzd~_}kxkQO=+{VHF;9 zA*{lKa}2BS;4;E0JOs926&~DhScM1g8&=^V-UF-fpgUm|9&{zF!b9K-R^fp=U=<$5 z8dl+9h+!2TbS139gKmRWc+f@vXx(lf+4VA3H^_YH)e<>!3A<7Tj3H{qrTe6F5zoiS z^)af8K<$^lIQkO~nMRA*bhYWrME)!xd6qB$HmK~+YxK#PWWVp}B%Oyk&O?dJrC*4G z7NT&5S0K#_wrPI<=azn>-0Oc!+qVG6FTg!up!OGzIb5;h+s`P$vYlldytvF{6TSP` z@(B9#Q~dr@JOBo&?1z;Pi$?A~LnC?%v2h^|fQrn!>3mjUBacH?@!M5b;ZCb?SD=?& z{(ss#_wXpHG>vnrPF1A{ik%Dy-HF|F(-ABTV_ta@7aHLcb@%km?zI8 zzd6;n>OQAVo%6o$cjZ^D)}C`pw%n7?+>-;Zk5}Q2eE+4}#G{;x9%0)E(O({!-LW-8qB!OHpSKYt&Zc4Xd$Q z&e>fwbH&D&8@`1TG1=%d+32TE#Gaom%$rtnDE%iJ_Q2y>K26lW(}sShjZwcX$A&#* zwmy<3#)tJGhxL)F^Ex){=c@G=ROfYU*n^6U;i_{vHtd0AM!xD?jt%?yDszKu*@J8zyfT6GSr(pv-8SVL)|wby!nuQf_dlvF3gk9$O$5v&hPGh?Qi^?hLP z;ED~^e_7!4p_TfemHKdXE3ZB`9-kDK#HO9^YxY8V| zI{W^)r~T=1!yDY+EW4kqSMiS}>wTQjcIGQ@j@ssQQaw0XuU8a&+->=%C6|Xjj?pS7 zJBLl1F32Y?$Y-e2SIeww*+=omqqh#a(YfdaqbBRj()X4g^%l4E9X6s4b4%PE zBkB&f#4RzSmT*hlMKkImx4=!cqNZAI>bu2OR57=}ZL*>^aSL3f6;(+VxR2LS^4U7peUvFtJT&Z8pQTkgZ5a%)FAfh@%3NtKCp2rPQ(!- zbc8aaD*mjVm zm}&*4T4D8`KA(K@uy`$Z9u_yh70tdC{w`~OeJJ?!YB#1MGPpvT**{l6-N7Dzt(n^`YS;arP;<56c3-Sm=LJC6lF$(L>X_n)`U&NsjVU9GPURbTe;dRz8^mCB?{Ikj57~t? zL3&sUOu<>-%lJB}`ka%|53+nSgE-Rr3I{`bf24o}96m;`4dUnp~N)u1QGzH%^qE&lKG;_35Z zfa;`GBWIQsmlip}zm2uV^}A}veIt8KDemRWS{4gyv3O9;T8F#~HM}4DMM$rAo^?;fJ%fzd? z`>O6yLCEc^6N3BdC8Bw~IOOHCy7{8@^oAju0RVE&j?qkxURwnR#(tTBW)OnUD z^5C9fc+>&}W}Sw6h2c?CY>530f4LD*Q*4+A40omBp+&e`hWnP`p+&g2O!r%+N8SJ9 z^O^2_rbpeEOB8W%S5qu3OjVYeqB~&#=`u z`t3`@gSuvSW!Hi-glft@>fAXMp1ZtHWz9~lTfM39_P<5r`6|TI6=Hz;Q7LmFp6`fm z9nl|F-=4EwXf356@P>({5iz9^^*`g&=MVqtK=naq`QxlH*lLu=?Sgeg5`I?+0=nI?e;x53tWPNA#K_`la{d_WoxT=1Hx7jAH4eQ@)w3szo{fRkO<+EMG3;N?@-Z27qj0AOJ z)PM2#aq;6isc*C)&R@(~qyF*d-%6Y?J@OCJ@%S1mTw`@r)}Zt6UF|ja>m7+`sI&r= zB-5^5Y?My-oo|eWH$>JOqNf@IFFy3qvecdCNi3)3j#tVr{ETYZWinHY*}#Rz!QXjCRSt^U9Ye?m9URZ;QOQ z#b`C0UJ6gX(?6xp6f{(5feNztUYc1wq^QaM&Unw|B2X?`s{z-s^u})&?G#^{)#b|K zl?~?O844mg6hzbquK)G1g`e-LD8IZ_mx&K}9$+$##xaeV#3R}l?N?tjY_h(ljGFtJ zGm7!WF!K7mjQl=7qo6OyD9#thsI9LpqXb_9qhwz)qf}oiqcmR{qYPgLqt3q0j52+h zjJo=|GRpR4Gs^MhFv|7iGV1N?&8V-hFQWmm1M0VhVI++m$Y^lvU`BbqJodPJUp}Le z{*f)|%#ZPpVKm-9p3wyV1V$766B$ivIjKG>42Ig4FEJ_*{sO^{ohJO#IKL{QvBypC zVWBXvpRRhQlR|7@!a`gm3>0uDE)fAt&ee|@MmEu|M5J==1`RIpauHb0k6$jr(BxA4 zO3?+Ad(M5Zqe@&V>{1a)yjs}M@Di^P_8QJ>g%^AFYQrAaTG0Z%Np&5E6Us#r=ge}E zMZ8%AHj5zV@Me)lyj@t^h0VDQdMEKt(P*c5ka(A{cZo>i-NN3@d5^I7aNaAt&=@Fz z0aAuV{AVITT^1cqLmdguImpW;t`q^(mEaskelGDb5qC_q;hcUh6eh{IKub9$}F;M}8@oZ%9;*f#F6sr{<3uX4UF?CYFw2>S--o5Bl?hZ1;T zZYtuDH>$2f4yWPL#W@E;X5uMY0GBe(VF;UvXJ~QAE9IO%L(AaY19_#yGc_AUYKUiP zHZG0Cg_;eaH1TZB#-);Yj^>3%MF~_SHbmnWY6&z~U#O)m)H-m^!Ja8`krpVT3}u;E zq=m7EO6|p3T(Q=Mb9%9s!MR7VmP=fs*)U8KFVpO0oR@1h_GGDjg=Vkd{3p!|jg1o6 zNQ7R*|5-~=b0mk;{;YN2oP%5p;xa8zrUf~Nk&{7Ou36=p%{jSTOX2+Ua;+=pUzBUV zB;KSo+N3>5yjin1YmvlTG#fb_#9K9cE9Y&fdabokf+5@sXaOXJ(7n?>EsSVg;tI{K z&?1QsXf~2Wh(FhCMDG$G)NCY+5LaqmXp)p534#I51AQdjo1M@?Fq;ye(!9`1a!!W% zl=zGmfPRv57-m%BYR!h8lK30V{)Y1<%?nMG5=7zNOY=Z)skT2H4#B)id_(g>f5|x+ zW>(_cT5ISrId_D)mG}oO0DUIsFwCyRFY7k+n#2XVUBG#&ZbQFG?XT!wXt09*XRL+=yDFj zAWdARXO-b0^~aa#earNxiQm_4gzgf5pxZE16K~LMgzyrV>t1N$lpqcg1HA?OA?g;- z;RM8~an9VKXAys>2N18uIsBoXM!a8d0e=bSg#G;aKGJQ(u~GXcy8Q{~PjwsdY}8(% zd!gA=f<3IY=pN{C)!nbdA()?uztnB$bBRysHq6k(r*$the@gHtVT<-aze{T$7xfU# z(!@1-4D`I56JVYuzM==9@8ukZnVR^zZbR=&d{eh?a=xW|p*d87Ly45@_{lPX)?Oyd zG=!yd&Os11ae?$8Je_l>0H%dA|1s$Cg?GNe+LH_*Or3KWLD|HwLLMYLDUGNjNr@|z zZK%CarWeW#&OHicF7a$>Bb=RhuCx)nP5hd)5!OyTPkN!LRDw!eA7wlgKeV<~B-5}C z$TD{cUdFGN32Obv;k5O#1LvIevL|u5^pwk3 z&Y^M?3s~Q8l(yxGgEDcm3~ZJ`&f(26jTmu`+u_0bdwFq3QWUpCwxRYNGJS{4;M`+} z%q89_?VU1`_(N%b$a%N4cXQq&z0kxeL99e(eEb0l;CDC;G4ixlctGZ$d=&9P=|QYK z=MX+6@gW&N%sl5X%1aR=svEl~Y751YOvRxF0JR^N>BnUT=N_m5Kzu^lh^;3+DQ%Ri zB0eQ;#Ml#`mR@LnmEafSiHyG}6KL)8qD;FeJ8;fH1$E*Y>8X*ioI|LnPJBfMuE-$g zFexk+9dqG|VzepPu+lg;U`xfWh(hE(q z5;RM=Z#^#?v1%>O;SfBz#8ZvHR3pea4394HEF(C}c$D~6Bl1<_0pi(4Bs{#tbBxG2 zoaY%fJiXNZy5WV!S_!PNHg0&}ub{Q&H;oX&EQpsH9{4RdhY)T-Tw(;^zu+83*ah*s zh7CUk@k+y9$+^_CP;k}8Q07y%SJ z;~YkECGlaS9RiSuj~Mn5Ba-;2VWT)2ag||LaXxO?D3(U;Ck!t%@k$UcArB9pqXHZb zCpn7oyE%PNzIUgc!&&EyZp77w2MTh|p=u+M_>$2YigL~!FOi%a0$(F|nZMp;BMFLg zI{vbeb(z0jtyQk%|zn4X6w0>vW%)$X2-ddstkd)8AK2>9sjzS^g4gN*UhZg`Rgq(+ajo$j$dH5 zUtp$leqw>ygLsh{SVZ+=QRT@DFQWW1l)^F75cEvPFEO(qwI*I_+Dpwy;$qV-=3HXh zC7hR;UU)K;Aw$CM7eopq?MB_%+~O{bM6SoAn|%L zh?GgrN$|vT&Vr+mxZG@u6iUwR;hE?B1RRINo6P_`^qj+RAQJB|b6|TQ-ep>FBocpU zTJYQxBTgETpDOPYd!J?;QZT9gQ!@@Jn8X#P4UazYXQmB@Bk|{^4bMLDLDLIQj55Sv zK45y_hg0%BheHS-B0gz);g92-j4&eNuguo)%W>|Aa3bQb%>ev!oWlq!BL2p-;in_6 zF>Qnw5&zY+;jbgUYX#NV4<`0qF;Bm9W?Z)R)w@i=!x z7!vV4GXQ@c=P<&Nh+na6`1OdVTlRF$Gb|haJ!+q6dEq%yh9mTM%L6|jX@Oq1LI_tP zUSN6Q@8g_|uqEO}R%`hEICn(&67ic>0RBJDVT3UemsmFZfW+@uHo}>Rms>Xcfy65; zFFaDpAO)F><$+(2_KMe9A%r;*ud}@H4{}aMxD)YuD*!(s=P<&ah&Nj{{Ds6@EF0lZ z#9J*JenaAImKUBaW!S>{m*s)~P{~Uj4k0Xx_+!fpKO*O3ghvrqSONGGIfoG@Mf`>qu*s>8WMSR4v;a?;^YI)%yQwFlj6aKPc)o&j?)1pygv@5#aM~!$BS5rpKUCkNA zxMCQ2U0z0hm!DD46=W3WieuE))s|6$D}hn6E16NME0s~2D~(ZxD}zyIS7%0%mxcm2p-;Ru!&%YKXH5OoiH`Ap65 zb2*n|(Xhk}E-_Qo#q^4d{%FFUeY>!`jV1PlT06Chjg&&IO);&yJDgF>ZAe%mFV^~~ z{)kyC(#+UoLciT4U~uV_wuN|>iO-xTIe&T}+# zj>e9!%eSS+*A*NguGGv*etccNEw$I>+Y;9m93d{(&2pW+UWIN}aIVX@rQ_@JZHebe zbDm_6UnR{|oa^*%bo^;)p62bhrFolkUA`?HUuu}827CT3hPj1vUBMAL{+?mp~oG|J9uNZG*lUO_C;Dz_>Qu%$iQ-%x{m@#1`c@{tOKZv>^+$k!qZ(oqV&yA2#=X z5e*kazYAiB+IFqoI(^&tPM>v0!+Uz(d-`a#UVrtE$A7oj{m0NxK9}dKv{7m!$nm+n zP^-PDHd36LUHOIjIJGh1)a1%Pq>obz-;U2^*ady8T8PFVZR9OBMyrJjq#hX0uQNue zg$AeQ)$n8Hcr_74El)H5x;aiw><~d`jd;!ajhZMqK9}cKTQ8`INh9Pp58q>rR}+D& zpKtkMOXir%80($eb-KfbMcsJxGH2W_*BZ&{4%Ja-rQV@C=4(yo%>PC2f<`!1rz66r zBeGSMDpj2da-mb2b&B+o4HK&)VyYvOloILs^8H!oBOY?3t9M1;yQ06^{Jrr}W#-h9 zN8UgKmQ1(HkXkiWY7abhlei`sN-WY4b=_j-iv;z=clz`m(5vIDFLBspJ$AD0r!QxT z8N0;vs|(+qC9WpxcJG;o7uu%x-KO_f+Z{hNK00Rnt(UwwOAwKih%QRk;RLq@my0A~ zh(Jn3Q(}ld))4=YWH%~^SmDG|PZLi~69d(Ic1(=DSDFLV4U$tED5uo?rQ*NMulUco ztIovU9~bYBi~r!b_@mvv!>RJZ87(l!_eUquFR!V;DWm58=8R(eF^s%^FC)L-&nV~* zGK%xZF>32?%P7I0z$n?D%qZ2L$|%jB#wf#|!KkypGows@CZn$Yu8gw%*^F}hIgE1s zxr}=Ido$|m@5?C9pT{WQpU-Gy%aQdyWz6wgj$t&u<# zRxdGvR<1y>W1*FsM*L%JWcHO=V`pH5gXn8J>AD&vLgckmL@Qm_j|sEixt=#R69+oG z;d)42&|nJJyOrs=ihoT0-H0u-*H>bog6yoEXRtzMwiyP;_KRGjeb045rm2YBEus`F zMHOD*k+?@#eqx1)sh|wXdyh0-IXh)WK8D%~`D}$8rgm-`yf|$15NCEc;l;cO9r0h0 zc;nA&6aUsHAytOj#wRogsi|Xw25sq|@$}CG`e)vlp`#OlF`-sM)1_fr5q867{$_z@ mEtMrHTRr*?mhRO zdv+l!MWILt76|0pl;;gPo5ocj5QyQg)n?J(><0txlQlIvTW6`z7wR%BrV71QXUR&> z7HA3z)Rs!Cy0A>IGuk2}{|WJ%%Yd%XWYMXu_6@CS!EAk*F4EuMzu08Z`CCop=3>3o zztUtWwVE}BI)9Fh*{H6x`WKYz%e39FMPt@$)mDRAqt)t-YJ;`N>TfYw_1ZFZkj>-%1Nx23jZRVO|2_3fJ|&Qy|KvpR1X7( z`2Ten`(s;72$}^i-~Ftuhom`DgAn2hON0rm`}fMXl9Y3oUxHO>Z(jVJTS6I-OPx0aI^!f}A-= z`m`Ji$NOnG7LM;zaV$LJC+t{w#!uF<@O+=RV{u~rq#X;#`sr9Rc<-Vj@M4vETd~@r zvzC|HAY;(}o4K0RQfN=tP1d09L9xc7t<*rNpoiqcGMlRf^v1%na;?24_>F148u|Bp z*?)<3Pf4RT_Y_HL$aVhv2jLFOUGz7(LCxc+VoYWmR}}ddY05N(HhrN(dX~a6t~RoN zJ$ArytHnW8I3_3_{`g1u+pWm4?{5=T=nA3e68yT9=|()}>bo%x2iy(uZqW(koRt&! zIMj0_j+=e4J&xPy3!UR>H_FK_1ZK0^W>On8dZPd;z@Ftj)kQZ3GJGeHFA>$;tP@zM zDJv_`6qf!9Z7nZQ3pitRuIRcEkBfmL;l;o~1`|losy5A@-A#_5u^V!d5l3qWyJf_K zoQ!w~FTrDaq~?U^c2eDI_`1dp@_B&(>TJGRhZ@9Uzgvk33=tRN$86;3$19*=3G^`EA>8>n^9>#ermp3)ojHoc}yKNom%^4LfV z1k{_K9{=kD!`FQ%R~G@>L3}$%WY3pC$hC&x(`(H7!Hw6xH;Ac37r}GeX=Xb;nr$R> zBkAj)@%;UO#&MEdnV3oeng+r&kU%zo4qzMH{{L>{biU5trKo4J5LP-WX=10}-CSDIqV#L%WnE#SyzNACgW)1us z+i?4jC9_@oPyry914MFwMD=_*Xp;9{GoCw}w5bmj2Q>SL?>-XV^TpF#*<^le?d=U> zYBKQpPRM*G3}JT@dbiVwRds?ZKVGHs#gsqLEOlX)x_GlWbPj)-RK{(|vTN=iP5g^}zQLT@2s94E>5ND%!^VssT#=|FRpX0Fn{>`Fqf zB>Y*_iIQtK7X3X`OvMAuJ$L3Fyiz@(>z!U{)~J55kG=|M7E_~vW<6on6A2qahYWIX z(r%4NV~VThh^YvmSmnyBa`k45=ptUWMe|%f{p^E}7mKMZptvGrt_TCz?S$S=hB|h6 zeordfK^+|?rX~W-c^Bq9yih)!&+qd5;a4h|+N_acYAR5i6f!4;(QGTBTgf=bF7s{_ zH{BaRtNT#Npf8tpJ^~&Wzp+BAMFQ!6) z=8y|>$YlbXN9XaotlPZm>da>*fliJGik}JdGw_L{<9LcK*|V+-JhI^hWkB(iO9~>S(ChWB?F%<$dTV0r~E)q7E&gEZu$2YtFuyM^&y_gCEikmLXO*n~$ z*6@6Gr4_jJ+F_~@Q{#Z*3&MOsyjdwN4L`)?BO|u)*>^6?Apey=2C=Q6$ z|9xE9nInBDC1^oANoXfIJzox*Lx!{sLtL`NV#*J8`Ich7r6g#Vu?Gm#9hKJBJ?8SL~~E;d1r3#PsEf2Xf9IBMQSXYPN(yF@Im6dAFqDqrV>+f zpjb{b%fSvC2;Jahhv)X@mQsI8J|m_gfu`M+X?LB#me3`4Q8#@WT)5&lA==1LMAJX#Rygop)f-ozHADcp_40hc4m&yb0 zEbV<1Gb$my60!1NxePsyh)s|rL?P7sZz*ftPrUaTa8t=t$rxNP%)_Q! zaK|k@PkdgsclP%~fI2)ZJQm%H=O=wGobjE%7SIccVj)RG$@d)^b?n?J@AGhkxPZ7Q zbQ2<0<}C|FNL*j`aNAk|1FLIDW(}E+al8Mf;eRZB(7X#)S4USXG2n~X`4i_SAk_bZ z&dya`f9(&ewXs?SS~q4PZ~=SnfmguP117kX1JOgm4tg23+_*YO#HLHq(rLpgyt3Jmcgc8brGI3CIm%vWG=5wU6?bsP_A0yK%}*hFlB zcR?%!i)(CLcUI^tVLWIS9?0_%wa zL$8QkN_>`*I38{w!3`uC-G+!=MkLEfJP$V#pGFdgswZM!C1YMCkvzPD1g#)R7+geb z6Y*^#GK7aje155K?=Ek6SZ$zIif<-jbw0WEB%<#baWQFym+DS5 zpbaWRPG(Qago!6;hdtfIZN?jPdGl8O@D0#c=TzsT_Kkn|V{ZTVU26cXP1a`O*(ZE? zy7KJtn;C#srYWbOd%#t&JC~^9-oEtis=_<(?*Qu3u+ms`#J-iUeLMEUh$282B^PC4 zhU0rI{oO6QI${AmUok%o_mp@G+ctgT`UgNKNs|)MI|h^r_mAC~VE|F9f>g0+-y$~E zH#GvGKugpT`3nKhz}keQgbefzfvY0U8TZsy19~w@UQ9AD7=><_EgkDWa3M@smDX&` zCd0Jlt`~M^+yHc`tW=5jKy!v$+mmm+ckJnhZ&PyPVxSL=4Nbx%FD|RR_pG*EEr8BV z%vGTS#7rHY-JYi7Ht`Q9R)7Bc%Q8<9q?UtLlHr(jir@{U%_I>YRRlpiZw)EL_$~rh zAGMCiF$##lRYbH98Tt+p1h>H($q0;lA_zf)Hj&{NokWoCj@?51FcTI*svfnK$T5o- zL1HLtB`KIQiXh!&wv*AAiHabMFgwX;j4&c77>4gA2`f~!IhjmHPHz4UNQyptyp z*8SxSFiuTOO+)QTJ80Yg>AaIZfHup`O0=-_=`XKOnin$|G%qDIB@1l;EW%%@LMUD9 z`R?A@lvY?P3zNlSNWiV(2wY`@2S6(YG*`|bI=ffmTLzuDVF1V}S(1iw;?yBzC5d!a z2cKpV$g4v$nbu6yJiM0pttBDO>LFQ2f_e2=N2abLGkLg$OlTqgyt=fIoEDPD!y8HH zMiS+$J|UY(q_g_OZz0Lf>Lb}of>HjQI!)b5X7X?=32r43ygId#nXROdhqsgP?Igxo zy~1~r7-#j0-c90BAF?a1HC(ShQ3A3LNeoe;`AtsiKkm!MXg7Gb4nlVjPs}_-pjY%h z;)#kj`AB;6xUYS?V0~0XlngT*^ak)qTt$hGgasv_xiZp$zEn0g-3kXzo}NB76}UHv+6OG--0K>voqgKh1#CvJ?d4iol*6DKgp!Gyia#0eAtOmL;8 z1AV=I(3wB<&j-dOijs8nY6a1y-txw{PXMh_sFHM$aVzE<}^-;~E(yjtP zFCpg=;jHvkh<5d#bI(IK1ZZu5wwL`lG4GvM z{N&6LDQqK`%as^Ju^9kv+1?32`s$`H;s$u`rhvXgT9SZzRefds-q*xorGO4ogr#GO zJzx3F*_l;iF92F5lPU3#$OTTrH4kua{H8p*dj_rT%ZgqAF)IQ>k{sILDx8oWfc)O-E!nCO`{=5d(O9Q1+v>*{1 z;}a8x&`S58j)y&H8x2H@h;$KA;n}%FC~PrNAiT=wPxD{6H#ZLs8JQfJiKc^k2)ymB z6y%P=feEgE;y`yUy|=bz-WA|y2sX$t%!yc|#2AIpnyS<7^=tgj0xz@5oP%NZwa%5N z5594v0?-PTA_x5}hx_Saw*Z|oGi5f$@=a}7IYIG1L;yNLnvjU9x%po9$G1<7 zeiqORau(#{`=YJG0qt!dJmR*Ei{*;@A%!4}+>l&3rhiZk`%RM~gx|25YY^eu9U*VZ zOt1Vy25Un?LgeUu!5905N)bYj1Z%n05w69@2Q=3&LUfztMR~!u4<^I$jZ$MGil*($ z7gtp1rk?`zoTND!_!{kh>US$8ZSN#N>*P8W=4SW}dvl#8+#53uK-=3(IDu{wCb*sw zqOqj}zQo>7!ihJ-g*PsE)*gU+x0A?rB1cLQ^j;G7kW_5T95hXyQQLMW8weG_3K_mA z#8gRA6hd!BjSSrOaTixIEhbruNgk>@dVM$+*Q7%3huwa6^15qey^DwqiVsS|NYC*O z-9u!^TLgLg@B_pb6ZyjnJ$x&l8@LS1@ado;PoA5J zK9;M%Q|rhS)OxPsRxKqt&Jiwc8JX%F;S{fubms_{+C-+HXTcYNm#{Yj@hy(4yY}5W z*u>Rr(^95op`GB}fSzj%BK4o^>Q;8X*JmA2*O25Il8#RO{e(>?H{8}HfmqGKW*MqC zD7$1%6he4d*wo%j#BEQG>b!G(!u>`NYq&AwN#_OIK$Hz66VEDwCRuzVN#O;%f~2e< z87SDU@~->F0sb>VA~6v$GIR>329NkI|Mdf0hLtioB@bQRx$rmlSIvL@1c<39utB2LP|g*hmG&M67yXOM4?1 zH@)`7g{h}*o#8ZgfoefE#)r@P>UWxY{e3id6WI(U-sF10gDcN2?!66W1o`q zd%o=?jQ4w;WMC&5iP_in`>oMO;K%adH>w$Y%qrHvzqfOkG4~p)2_2qrVPYJ-hE| zn2@XFIT(JwU3fp@g*VeJfR2&JsPO5(ee0z|=IGOjfX+?Jor-?q`vsTgHV;`K;Vd^b zeTtLiPR^R?WVx9+)153gGk?01ZY`IyrB+uD$GwaE8XUolQ zATyjTcTyvn>}D}f9^$cwc%jiee68QJZSNjygl+Src?qbXKLzv>Ef#Lp!}=N$ zSwj@)Qn|c2WC@8w7!3pXbN>&3{2#Gi+g=H-oekR>lZ+XdZ&-9?8t#`iu*)exdI9{@ zkTs9MRB!Br3IxOW;Rt>>kROWp;WPYjI6v&m51-|S_-iA8;eM5*=fmJYAQ;IH`}0HY ze>HkO18^V^2>GE0KOD>td-1~|{Lq~rdh)}e{E$sw-gF}2Z)ZPbhK(3G+|9$C7WV2b m^6b-B+^_$DXP)&MIB4*Yp^U(dU(tsj!jDSe#|sAn!T$iZUSRJ4 literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/rws_state_publisher_ros.cpp.3FFEFC4AE6422D83.idx b/.cache/clangd/index/rws_state_publisher_ros.cpp.3FFEFC4AE6422D83.idx new file mode 100644 index 0000000000000000000000000000000000000000..eaf28cb2952db6b7513fb641f4a142f08ec80d8b GIT binary patch literal 6314 zcmcgw33yXg7Je=1YSN}nn!YCKmZmKNXeVKFnCXHxg#sf~ z<7#SjdP8wlm7%)EP*pL`3+Zb#6(t5$V>Q6ll`O7Rm#G_m3F{hldbQ@4xV~JgE>;c2 zRqE2>2~~Q7R#R`N(9~9`HR@`8vA&|Fy1;4cG?=f&)#YQwF?71iU_CCnO(sG!;%HkxudJRR*87uD%-PH}Y@O*Ca}X)$!z4V^B^Vt2WX zRx8zRbecPjPTF9xyJ=@Dqhzt0tR6G{yJ%ca(@j#R!gaad-G=$G-q6xFbS#WziNt46gYH6eF(=0Zs!|G{kqs>&K!&Bn0by&eg4NbY* zEl#rme0FzHT_&6PHo#;x+S@3rrG>inl%7G3Bu8T4o4KIP?olYxbFkYj{;LeOcq~@) zuf+U!EJp>vlmy*oGuT{hOjX=U{cl_MUGD638Ei(ov5j{AQ5pycIPwR5fW_d#A6)D- zc38~+O$2TcxNHWa*=(`@S4@r;hxsY>8sOxTOjn^C z9c~H)s?BIM!tpbCW9e}@sTPZ!GC_MR(HN)Dr4}pgy2)m;T4=kQgfl|@h5^!nY3p@5 z#(FI>uC38w&<$(!dgx;M3XK|Ls*&;X7H?kOzgm))hqZzOc@*{AW%_#}Gg$P$a+D~W zv7-Z82H6fl`hVK}wPgLj{qVRgR*Tz0yZ-kP_>Gdm+!h;Ds0n69i_tU%b9LET?t-D6 za_!8~?`J<+!}q7sFfu`sFhUs}6di>HGb0{;E}iCYSxyN%dDsXHBSRuW;%u? z-^JEE(U*2nJoAFPi8IJG)ei%3GAN$=EMy)PBug3tm1g82iHZ=F$J_$r7? z^8NWiXop-<6eSXSC0v9{ypl9n%JWL{2)Rf(Gb1LdY#YHPQ-V`?h@4B-ht&)8lMVN3 zs}fH|=+5>N@3psp2W7Id;YcYmF3gdCkWPo)WhP~gTBn%PyOj6M)kyL{-N+~B5uh#O z$oNQG*v-G|nK%2N2e>q}Gz`Hab$0jto4y?jB*~oQ_}=uxFTaqKd06z&M_1+*)6Wg# zl3Dp#KXi5Ch%qJTz_1_qbID!*CIYg~Fx%ia-?TLU& zkku!nN{|Iym?n%B_W-4^Tv+oaq3JD=t$01DqVG&u>^dR9MWIDeh%#yQrvcF(PctO3 zA*LY?!CbOQ+!XJXCdEx+olDMrxNgC+u8&|zqp*>U8kcO2YG$*+B@H42o8aWj&y4CB zSo^Hceo~&D8D3TSbSC&Di;%HFL1z6zZ?=&gr$z;vhh51U-rgFb=ko6d?J`MOBGMZ1 zGiO8J@wpAaoi{v>==pf*%Et`y1H@eFZ>vHjp*|)l^)sLE{Hc1RKbOS)aRI6XaNfU} zJ-6vt-piSFAs2ksW_PkuMPFk8*!I6b1;8$IzjvB4`}A}+ocvH&3G$+ zd_?QIuVJl&Om3a~<^UsWG6RRmkYiAuhmGtJl{>ebe9LQU@5)7Li zSC|m=?mc{f3r7`ZBkeh5-OWoc1~OAdC((^S@Z8mt57Fs)PXJs;)~OM^U{>z(jZ?2o z_R097q8XI){3lZbIHW?L5H9=aOxDa&>t+tA6e^>(uk4wf*M+^vA&F=L&(%#@Tho7e z6o<^kb7QQ=a%IJ=zMUMh8n2Gwez-)}zP$O+BX3U}eOLGPAHjH5MizUtAL}`I;Lnfl z{h5IUS!@elGBEY~<5NB#1+Xwo7=Z@C(qn16#_o9P?4YY}%|APD&sT=$Ry_O0Dq7%P z>9d2?r3*?5``3I5B(>aH5!&yXf#5q|`*4OCN=m2{mLYDC>V#IW6crgoAZcA`Ntkl^ z7Xlvx>rb@S79J;z;-$AW;+Q40J8q zyudGgRR1v>Xj3^9JF&M=2ZlW=sUI_F5*^Q%>R$|~pQg%Zv~h~f`vhEMgl@G!wUR(F4-?MG`#wUR!m&hHB{C=%;>GbEvo<73ikbDV$ z1gb>1lT?bDyb@lE-{qC0Rnk@@y{>=i0qRKBKHyCWPhn5q_8a*b=hBxC40?ggq1gy| z;9)%W(gPCQpV3P$nGle`GVKg_VDE8G-h4PK(n9HYWS2`;CR8fX^>^pe?mfM)ZN3-0 z;1%)8kbXGhCQ)mi9Z4T%lx+~SZ;vL?1ya>z+3lh`Zy z+Z&&|J96_R6)+KT1bgLs=WieFJDKBRnzag7#XP)iT;0yP#hN`w=7l$B9b?WYl}@o| z^zVy4myI6YhWP~L-5F~?JiO{Lrqfgt)$B1jpdB`*|IEj00gecZkfA*tuuaS#d6>tH zoSN*KF=(8<-*2dB-Q-|~{m@JA2jkCuy+{?g+Xp^4!##KV=w($to*X_e$Xap#R6Ur~ zj?`A6cpbj}&KT>K$UpmNe>~#sb$R=_NXU$+NK}Cwz5TGW^+oZ zk{!y&f;ce)68J#IZ-wjUCSpz?P z*0mo;{xW&;qD5kyNDg8o*<5!YfI`rSV8Q>1p4ZIwvy_n1qo+9G&5lAN6d@ zX#cU2fdhqH7CtKC9i1>e51fQABQftrw&bU&0aUz4!b7_lD&SP;b+!G z>_5E&;5u#{dm}iTq?~;!Ny*%<8zLLn>3Od3iT8K!+j{;EIHN)Q5aceLQL#wsm2e3j z>y@NDDfZltO(`5VTe?f~fcqs;yc|^xWB;*#skM5ih%E z?w)h*Ip6utxwBJyCnm0>2-#)qeb_NWElCLJgf9&P>(c~m*qWNIR6;E@?{8FXi`LCx zs$3yjwW@G^ z_pb?wSM|cb1JLq`@sp$b4n$ESPrGefg)1xENrmh9XoEDg><%VW3!#ZWT zy4^6E9b3oTnvH))_J5Q*YP0I&#HuhaYjAje$Yw~XX||?^mL8WA=r$Xr=Hs6op{7e= z0;9QPEq}-Zme!%YL4!Dr-am3Te3V-icGcV(S#^lPR*B<h7+1 ztx-im*vJPeX+Ct#wyT;xOXvZoTH@elpX}H-KYI8!k>8jgLP0L{M}i3KH2_Om7IxFK zN=f89z}_eI4M!rj4_y8Ji(ejprrgPIT6tFpJ*l2tY*)r#`)c9JeZwN(3FqaV@>C>Z z`#m@O)_d;sol7Er9oS1-O8t?D?fZ{$;=H|hQRGFi7xxt(j6`fd_3d`SNL;=-#dACn za_zaENRV_BKPPZsr;-a>uYYAwyuHQg8YBvo|hv^Bh)?=kwjMJuqkJ zG!Im)FvVpehA{D#kB@G909>4;fWV`%VZtfG4S%!{cHf8PBQ#LoBU2eCM$8N36o2ISdcyWNeqJcAqZ;(2HF44v&%!TUfc}cePUlPmf@Cf zT55aYoAaP9iKWem;NU0H5$*8oDV8!*=)#o8pM2?o_n(;WU^Hf=u2nQ<V{xPm}fd?uQN*WWx^d-*+X1WJLfqH&?^(7DCr*i(R_I8wX= zLoPh`$eGh8jy($M{I>ik7XI1b56fHYKW+lGG$0KlID7&CHdYvWvHI%;`R(L!@RkSV zQ3Q{{ppUDOkifLHjer}cA})ZydyuNEtTYqN1%K4IHsFR3;mci#$KE<5pGc)Pq%+C3 Sc9Lls+gsa}OU)E*E$ts6#*B6V literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/utilities.cpp.BC8AB2AD8B37CB17.idx b/.cache/clangd/index/utilities.cpp.BC8AB2AD8B37CB17.idx new file mode 100644 index 0000000000000000000000000000000000000000..6871fe0033b4cb9ab57ee169d5e1b2f80831272e GIT binary patch literal 6130 zcmb_f3ve678D1wgaTGb27;uOQIYXY24(*k?z#H zQ*75f650~_BD4)19)S|3fzkv@fuST5G64#uly(R(5FX_*9b6hhI-%4sK%oDgys{j} zi3Qczr`v!3=l4H$74)^X9w|r2E%^qM*boX4LZ$Gp8=72S0x#raVJ?qoGLAAX!@$Xu zp)-ccVBHWR30aRb0wb!5f<;4C6|y5Rni^3JLNzosk-*wAoeB1Y7#(Yyux7JZ7+-Xv zl&p{I!%{V4#IXV#;6++A(i)Z+3G1RJr%W4alrT)P!hjYH1G|DHV&w9apb1Gv8_@Zr zpa?OnF;P`x;({V2WF=>TTm1NqGEtc)To`ngxZCC9D{7 zRK^+y8aFCJ5}RAZUqjGh*nn70hG$%}q7t=ZSn`IP#A@1LWJMz0f$sxx44O28@_-1LN*i%a9e`{|cDt5__>!2%ng;&JQ6{ZG z89;DTRRjb#UO*eLM!m;Ijysr3pnQM~8Cbj;LyafnvhMV*=9YjZNEUu%wf!2S4?6Dy3?WUSc<( z8raUX0z!&9Pz{-Z^qAP2k&a2}BqlRsf)c|_|0-KegRQ2vnt|sEhCq_l$t;&`*v8;N zF_D%??Glz87_-gMM6=ad9$Vo7Rwh8*V>^~{9|pjG^eMos%91s z*V&j>gLxY6M9z>|9zNPG zI@5YZ^gNzN!5O8)tSs%QOwIS0I*^G#L`hCRGVLV^vj%^|W+$hQhq7 zqk|80@*TdGaZz5tK|-^|j3-ZpRVWOAr46!!Wj)5GmSugjB5_jp@f-5p^* z=PEN)Rz8L?V1j;Rke1hLi}21Q!=HX#ko6dfmWUlrYH( zX$L$lHM%C6N;OrlGha@puLrR`U=yBr(9i_C)MRbX8St1Da^@R2ht< z<%Bc^=FbRpqM8*)N6;G$q7bA(e<1_zDH#e{?a4JVGHm)12dA}gE- z1JUglHsV$}fpv}~Sxm@qZ?HjEaFbNpRMgSg*5(Z&I16}pXCRQ7NW3=~>0porlPMfUCXY>;+4B4-H_?TecO z&AUP%Jpv+|Q1&Lyn_*|~k0=UQ*g5XZJu;oNjCI@;eVmiAIArYqYI#!j zvg)U*3r-UgP&i{>wp@=$!O&2|C3P+E$2D>=(BN)`QwGZ1op=*|^SA*5x#H0cIE)Mo zzbDLVD(NCPkNC_TRm5nMDoaQoN=8QDXH)4@SF~RHGxb#~TC)l{+bY^tI+`k)R-)O3 zvkD8ovAV!fP`&fJhc^7`7yc5o5;#_uudXv62$7#*@LBat{Vgwj?k_7rb+GR|+gW8k zviqB_FS~ftr|%xLA{Xo@i;^oG-9_Ciz{2daW;8T{g}ookM{a&^c$pP714pDNve3~{ z)Ugmaii>8p*nwljaml`;pAV->P(5(C=eeuRN7lxtcYk=S{KU$|C8!qmJw={5<|DhW z;i%5dMyU9@UxtSc?K*FU)!FUnZq5ep>~r*GS0%9p4f5^_4;BK$b+u$V9j zn~ZBtl?}smZIkV6iEDmOw3Y|U0Jvpmf4=eX+@uQm^*MZ}FF+Ydu zUGmXAE3ZGk^WHo(Eq&nU!wW_it}d`T{pa}0s3uwpGc9HbPzZpj$$uGTvO2?cVLx55 zTe&B1w^Ug2FkXx757)1seJl?VT7!iav-ZXv3(X7Js4G@y@4Vie6<@(O(7ndax3-S_ zd-N%Qu77@i1tr@rI{xg&vxMW8lamnQLfPa(;@5>bs0buJ5bhdZb#vW0oZaqj@A%%t zRQ7VcIh=i5U+&7?mz7&1-m~Mm`)0lj$?=@;VQB5U+P9;#_&+t|0b2|E(FeOe>-te1 zBJD5jUXc9c#eM)vw#X&4T0^tFk0o*G4d7GzvUZk+7}}reI$wM3H6TY8N9rl}2H~c@ zJv(2w=V7=1#rxL2^4ljiV^T4Ug{j;3nmNzyXYT&bYh!wAo?P=S_nuuhWO{t>;IZEisQdn&nL=|% z$|JSUfBOe?n!*$!qm)+q<~v^~P2X{E12|45LS`}}wDpre{wuuxGN$LLSC zG~T-VJEK?R5zqGWJ7QOJMgZ~-H}XKyV{hJb|M%WHaML@N9&A4F>my^D_WwE9Ud8I? zW+FKHm%kl$tqE?=L@?sI`jTzGd3xmLN3D(php+o7%wU2Hb=7JPHoCg)-hH>@GGj*` z9`3N;@QLHS)#skn!gsa0=T_hPc3B>p9^$rNX}`_W1gIrzlFbzIhfesm=xe(-lj4}$ zUrvkT;k%xFea=%?9sx3L#p@_CkF0v|=HWv}+w(x?(bk&=?{EI+VTiy}>1n2oO}hqC zPR>S}^2fe()E%w8^>`kEJ-*IiI3EAUMv}xvY^Sb1v+b>mS1*sDJTyK30`H6NQE?t3 zht?f^f179C6M2ZdG;5^spoiHH&~{$XSw|6n<%_4+Bp#f1OCFjIzk1-q(VcIv0ZnbF zEqi{xapHp?x2&(+1GT7BD3vtRR;OB_W>;?(rXSziwSE@Jw$Es{QZL>;6m45|*%xjA zGxrdtJvPH)UQuYapk~`&XTKa+toU`_KiuHf6|8AzEX)SVO zHxT?*PY}5!EN7WxEtz|E={fVtDyu51D=)2FT4}3XR=K=#1#|9s=P$f)L3zam^A}%S Ka}m4f67)Yv#I)%E literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/utilities.hpp.2C3FAE4039E1F841.idx b/.cache/clangd/index/utilities.hpp.2C3FAE4039E1F841.idx new file mode 100644 index 0000000000000000000000000000000000000000..f05e52ac0172914f9b367efaf30597ed17a8556a GIT binary patch literal 2302 zcma)7O=u)V6t0Ph`Ehi!i7u!Jg~t3qb~>9C#TGG>tigagtQpujxX{#ezn(6)yQ`_H z&TNQ_;>nXBC}CT5b&kTgxzSMPoAd*7?x z-rC%}H$liouyrE=%|;0!)A+Bnwu)8kThax5c9NSV;EY#NRm9|KC{8Q zTt`F0*A60@^1OrcJRaD{ETuevRP&I7bTH!elqF!d3}4M;2Q=35e|Zifr^1BoY3XU6 zfXFrFX<*nP_ih9jNg9>AjN2UudCE1!yVR&ZL>4PWp$pwM%s2XdxpaR~?P(oJ(Zy~A zt}An_F98pvL_R#Ed5Si`;*N6!7I$Evt00XyXrPGcq5+0ci%FnO%`{wQe#BFt^&mLE zg>ovINl>UMieL<}tI&Z1%`FzZzCzZTXfht|4%XckBBp32FpP~zCnq~KXUwFG>yf9* zvrI^AugTjG8eF=G3Zk9l zk=LL`;f5dQf$^?^49Fn6UP%QTF;M?WoinMAkTRvDIK2JTMvKL{y$ddm%H`e|%@54f z&1E{bx9Xy86`nE{F?R=2oVPYVJSG-=u?MzI8S40(OGU~eXrJTNp4yncEcY<7Y3;F9 zj*Fu6NBm(998<}%xv@@BM2S0|KjyeU^*-nnte1!tVPn|j64q|xT$(v@-CXmSYn(9G zC59jI-MO{K8ba`CF>B4W6Jq&p8;|Ue{_XCWR%0=}JBfrm2G?<%NF?AWk!KNCPFKk5 zDq}u4n8?dgud5u6QnEOs*4bJe2LCsfk6$)r%L_9bF6=;9dR z?Vv%1hTdS_A=`cRYEhQ;Gv`Y75BkrpuH&EcqEon>6tm`8X>GFJ9F`j>f(HEl*lW#W zL4a($;!g8{>V~Q+fCO z*{65@`Td6~d8|aV##&2=n0#=g`UoQS|K@*v^5@<{l{{J^8e@&85HT_Kz_~MskPxb$ z2C`KqZ5Fnp-}!fT|C{FItKTIs{XwNVv%au?zU0*WHoJ08-noOzjk(5iWtzQPkAL~` z=fC_>nVMOgSab^3gp@onw&7RC{@VHIZTHhluV9eYN^7k|mBA2gxR&UjZ-0OH-eQVhTzD0wOl3=VrKHA4b(H{W!5~3-^>@Uzr6R_{#Vh+>{)WQ HTqWc`0CpsY literal 0 HcmV?d00001 diff --git a/.cache/clangd/index/visibility_control.h.6BF9DD9BAF8E623B.idx b/.cache/clangd/index/visibility_control.h.6BF9DD9BAF8E623B.idx new file mode 100644 index 0000000000000000000000000000000000000000..e53cb5072c0ef3a46d5981ddcd504162b1099bc7 GIT binary patch literal 326 zcmWIYbaS&~WMFVk@vO*AElFfyU|>`WgATsrtqFr3D$8 z#roy>McKs#iOH$@iAhQE1$pu1#rnlX$zWblez6glk&#%GQl40p8lRb0l3J7oQk|KX zoKuDKjUtq%uA^Kd+=HKSwWvp|~2QTgJcu05COM+yDRo literal 0 HcmV?d00001 diff --git a/abb.repos b/abb.repos index b8faa6e..3c315a8 100644 --- a/abb.repos +++ b/abb.repos @@ -10,4 +10,8 @@ repositories: abb_egm_rws_managers: type: git url: https://github.com/ros-industrial/abb_egm_rws_managers.git - version: master \ No newline at end of file + version: master + abb_ros2_msgs + type: git + url: https://github.com/gbartyzel/abb_ros2_msgs.git + version: rolling diff --git a/abb_bringup/launch/abb_rws_client.launch.py b/abb_bringup/launch/abb_rws_client.launch.py new file mode 100644 index 0000000..e2f9f99 --- /dev/null +++ b/abb_bringup/launch/abb_rws_client.launch.py @@ -0,0 +1,45 @@ +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + + +def launch_setup(context, *args, **kwargs): + robot_ip = LaunchConfiguration("robot_ip") + robot_port = LaunchConfiguration("robot_port") + robot_nickname = LaunchConfiguration("robot_nickname") + polling_rate = LaunchConfiguration("polling_rate") + no_connection_timeout = LaunchConfiguration("no_connection_timeout") + + return [ + Node( + package="abb_hardware_interface", + executable="rws_client", + name="rws_client", + output="screen", + parameters=[ + { + "robot_ip": robot_ip, + "robot_port": int(robot_port.perform(context)), + "robot_nickname": robot_nickname, + "polling_rate": float(polling_rate.perform(context)), + "no_connection_timeout": bool( + no_connection_timeout.perform(context) + ), + } + ], + ) + ] + + +def generate_launch_description(): + return LaunchDescription( + [ + DeclareLaunchArgument("robot_ip"), + DeclareLaunchArgument("robot_port"), + DeclareLaunchArgument("robot_nickname"), + DeclareLaunchArgument("polling_rate"), + DeclareLaunchArgument("no_connection_timeout"), + OpaqueFunction(function=launch_setup), + ] + ) diff --git a/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp b/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp index 3d01b62..02cf4b9 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp @@ -37,6 +37,9 @@ #ifndef ABB_HARDWARE_INTERFACE__MAPPING_HPP_ #define ABB_HARDWARE_INTERFACE__MAPPING_HPP_ +#include +#include + #include #include diff --git a/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp b/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp index 9d47d24..b66f65a 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp @@ -5,21 +5,17 @@ #include "abb_hardware_interface/rws_client.hpp" // SYSMTEM - #include #include // ROS - #include // ABB MSG - #include #include // ABB SRV - #include #include #include diff --git a/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp b/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp index e33e2e8..251ae62 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp @@ -3,6 +3,9 @@ #include "abb_hardware_interface/rws_client.hpp" +// SYSTEM +#include + // ROS #include diff --git a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp b/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp index aac080d..8651b7c 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp @@ -40,6 +40,8 @@ #ifndef ABB_HARDWARE_INTERFACE__UTILITIES_HPP__ #define ABB_HARDWARE_INTERFACE__UTILITIES_HPP__ +#include + #include namespace abb diff --git a/abb_hardware_interface/src/mapping.cpp b/abb_hardware_interface/src/mapping.cpp index 85fd502..2f15e60 100644 --- a/abb_hardware_interface/src/mapping.cpp +++ b/abb_hardware_interface/src/mapping.cpp @@ -34,6 +34,8 @@ *********************************************************************************************************************** */ +#include "abb_hardware_interface/mapping.hpp" + // System #include #include @@ -41,27 +43,15 @@ // ABB INTERFACES #include +#include #include #include #include -#include "abb_hardware_interface/mapping.hpp" - -namespace { -/** - * \brief Name for ROS logging in the 'mapping' context. - */ -constexpr char ROS_LOG_MAPPING[]{"mapping"}; -} // namespace - namespace abb { namespace robot { namespace utilities { -/*********************************************************************************************************************** - * Utility function definitions (mapping from RWS to ROS representations) - */ - uint8_t map(const rws::RWSInterface::RAPIDTaskExecutionState state) { switch (state) { case rws::RWSInterface::UNKNOWN: @@ -91,7 +81,6 @@ uint8_t map(const rws::RWSInterface::RAPIDTaskExecutionState state) { } uint8_t map_state_machine_state(const rws::RAPIDNum& state) { - // Note: Inspect the StateMachine Add-In's RAPID implementation to see defined states. switch (static_cast(state.value)) { case 0: return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_IDLE; @@ -116,7 +105,6 @@ uint8_t map_state_machine_state(const rws::RAPIDNum& state) { } uint8_t map_state_machine_egm_action(const rws::RAPIDNum& action) { - // Note: Inspect the StateMachine Add-In's RAPID implementation to see defined EGM actions. switch (static_cast(action.value)) { case 0: return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_NONE; @@ -229,10 +217,6 @@ abb_rapid_sm_addin_msgs::msg::EGMSettings map(const rws::RWSStateMachineInterfac return ros_egm_settings; } -/*********************************************************************************************************************** - * Utility function definitions (mapping from ROS to RWS representations) - */ - unsigned int map_state_machine_sg_command(const unsigned int command) { switch (command) { case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_NONE: @@ -379,10 +363,6 @@ rws::RWSStateMachineInterface::EGMSettings map(const abb_rapid_sm_addin_msgs::ms return rws_egm_settings; } -/*********************************************************************************************************************** - * Utility function definitions (mapping from EGM to ROS representations) - */ - uint8_t map(egm::wrapper::Status::EGMState state) { switch (state) { case egm::wrapper::Status::EGM_ERROR: @@ -438,10 +418,6 @@ uint8_t map(egm::wrapper::Status::RAPIDExecutionState state) { } } -/*********************************************************************************************************************** - * Utility template function definitions - */ - template std::string map_vector_to_string(const std::vector& vector) { std::stringstream ss{}; @@ -462,10 +438,6 @@ std::string map_vector_to_string(const std::vector& vector) { return ss.str(); } -/*********************************************************************************************************************** - * Utility template function instantiations - */ - template std::string map_vector_to_string(const std::vector& vector); template std::string map_vector_to_string(const std::vector& vector); template std::string map_vector_to_string(const std::vector& vector); diff --git a/abb_hardware_interface/src/rws_service_provider_ros.cpp b/abb_hardware_interface/src/rws_service_provider_ros.cpp index 949076a..c76ed74 100644 --- a/abb_hardware_interface/src/rws_service_provider_ros.cpp +++ b/abb_hardware_interface/src/rws_service_provider_ros.cpp @@ -20,7 +20,6 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node core_services_.push_back(node_->create_service( "~/get_robot_controller_description", std::bind(&RWSServiceProviderROS::get_rc_description, this, std::placeholders::_1, std::placeholders::_2))); - core_services_.push_back(node_->create_service( "~/get_file_contents", std::bind(&RWSServiceProviderROS::get_file_contents, this, std::placeholders::_1, std::placeholders::_2))); From 1fe13f64d75a08108f72f7c0fde9c0108c34bfa0 Mon Sep 17 00:00:00 2001 From: Souphis Date: Wed, 6 Apr 2022 10:34:15 +0200 Subject: [PATCH 07/27] Remove .cache --- ...ystem_position_only.cpp.3EF1087217BBE2B8.idx | Bin 12738 -> 0 bytes ...ystem_position_only.hpp.8A2B130C31B29B26.idx | Bin 3718 -> 0 bytes .../index/mapping.cpp.986C71284B0266B6.idx | Bin 22072 -> 0 bytes .../index/mapping.hpp.A89898448F05C4B9.idx | Bin 10102 -> 0 bytes .../index/rws_client.cpp.EFFF1D4EFBF2C97C.idx | Bin 2836 -> 0 bytes .../index/rws_client.hpp.96A4BFF4DFB820B8.idx | Bin 1214 -> 0 bytes .../rws_client_node.cpp.D12E88785A409E56.idx | Bin 2614 -> 0 bytes ...ervice_provider_ros.cpp.3D58FEF4D583A6ED.idx | Bin 60906 -> 0 bytes ...ervice_provider_ros.hpp.313ACA2CCCC7D4F1.idx | Bin 13132 -> 0 bytes ...state_publisher_ros.cpp.3FFEFC4AE6422D83.idx | Bin 6314 -> 0 bytes ...state_publisher_ros.hpp.BDDAB2FE4A654F70.idx | Bin 2050 -> 0 bytes .../index/utilities.cpp.BC8AB2AD8B37CB17.idx | Bin 6130 -> 0 bytes .../index/utilities.hpp.2C3FAE4039E1F841.idx | Bin 2302 -> 0 bytes .../visibility_control.h.6BF9DD9BAF8E623B.idx | Bin 326 -> 0 bytes 14 files changed, 0 insertions(+), 0 deletions(-) delete mode 100644 .cache/clangd/index/abb_system_position_only.cpp.3EF1087217BBE2B8.idx delete mode 100644 .cache/clangd/index/abb_system_position_only.hpp.8A2B130C31B29B26.idx delete mode 100644 .cache/clangd/index/mapping.cpp.986C71284B0266B6.idx delete mode 100644 .cache/clangd/index/mapping.hpp.A89898448F05C4B9.idx delete mode 100644 .cache/clangd/index/rws_client.cpp.EFFF1D4EFBF2C97C.idx delete mode 100644 .cache/clangd/index/rws_client.hpp.96A4BFF4DFB820B8.idx delete mode 100644 .cache/clangd/index/rws_client_node.cpp.D12E88785A409E56.idx delete mode 100644 .cache/clangd/index/rws_service_provider_ros.cpp.3D58FEF4D583A6ED.idx delete mode 100644 .cache/clangd/index/rws_service_provider_ros.hpp.313ACA2CCCC7D4F1.idx delete mode 100644 .cache/clangd/index/rws_state_publisher_ros.cpp.3FFEFC4AE6422D83.idx delete mode 100644 .cache/clangd/index/rws_state_publisher_ros.hpp.BDDAB2FE4A654F70.idx delete mode 100644 .cache/clangd/index/utilities.cpp.BC8AB2AD8B37CB17.idx delete mode 100644 .cache/clangd/index/utilities.hpp.2C3FAE4039E1F841.idx delete mode 100644 .cache/clangd/index/visibility_control.h.6BF9DD9BAF8E623B.idx diff --git a/.cache/clangd/index/abb_system_position_only.cpp.3EF1087217BBE2B8.idx b/.cache/clangd/index/abb_system_position_only.cpp.3EF1087217BBE2B8.idx deleted file mode 100644 index 8e1f46d914d081043a80500a4dac364a4a340edb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 12738 zcmd^Gd0bP+_P-OZ$Z`W=i-E92c7YIxmqow@FhGzsfG7pikX#@V63ilC>kkzvExLEAqEfMx>eJW0s04+KZ8-PPPKzy=pUg_rB~0T^uijQikes%9*zm8 zrsU=p6v~scvgA3r@+@fz(^Qz7ElrhAotXohbEa9^Ws-Esj7OUbW)>7mvL9_P%#cZv zr&_m9m82yXWfjV0*~M~cc3zewTar_lTqw=WnW(R+lPepP8l9F>sSI*uZ7p0@mReLO z%_@*fa*|WBBy#h^(wt05D*X%`peQewS1I(WI)$E+tF=Z-U!hP^a>PEq%|2Rm9WC3RT|Yg?XbpLg17^xaesKbPM3JOuLq=YK9e&TScMk;mM z3U#GOJ6ByJs@0e(D=C#|rp}bAtEtsMMzblAu}ZC1$sy;)22q2uMm4NKsZnSvMH+Rv z$owr@92pfEg+UHg6Dzf*@bKt3Z1{@5rpI!VTBCZ5x_SPf-oiO2!3lS&G(JiV^IK~hgC zqpZFrBw)Yp{(hq)IVGiF(5CZ-_L~d0n=#}-;d4}dtxj*0D|Iyxyeh_{8c+}Pl}0O1 zYrrbt))Pdc-?tDXfON^)qJ2IN zo`W7(tsQcw27_FqHb4tfD52m7*{zi8sY=*J>E*PuhV~hSLEzIEp9_^sf2X4n2IGbb z8;lh&muRRd*8>c5^nE@q z=k-*Dp*#e`Mj1}dzYuvM-v%fBV*TO{#vOT%m_9cOCj}xw)Y;$vWE0>v0e{2?L3RRGMp9e&QQ^|(H6dN zGS)WMib}Liw4$ciPO+lWSZQo#mMlEWB3qoCX*-k0^p)9`S+szYDqLkXavfl;18gL9 zoNNcS?ZAbhI{@ARoEh2-G=|;{Si7yC?*VuZa7HK(x_z8;EN#mJD85#Z+6pp}*#v#} z;`k-Ew(J_gvI!R4JiZjGy8xkCY**|!Q}AHk%^Azj1n+z9DX+Ue@la&zfy;W}hGZR5 zUDPW+UvL6qjs_62bz)H2h(bz-?uCvM$hm~Qx#5Qx^|E;A+GyCI(FAE$KSP_<&(LP| zGqhRV3~g37qJ=G@H#a%(9Y(NLqp^fuGT;8j2o?e9W#6#s;aDyNDi7m1AxIK1Gr?8^ zCxmBm;xUI$8%o^aFb@}xF(~j8&puTL=v4{MOu8*Ou zb^=Z(a7UBV>8{7iz!L@hyfLzY=9bc3aL@d3z8G0l-k$CHqLqthLncE#Lj(6ZoImhd z#xXL#>1waQ{XzyD-3q3)f&!Et6xd5%uc0_?k8G+i$2H{g%A`?Hc(Tzlc1ggj&2Raz z_QRcws&+)&5~Oytmd)&>aa5xtnwcOMfzgWqJN?1KzNQ^LW2YJ?b^RbHlY%lq94!C8y##3vdFtgfR3_HK5^v1 z)q<8-XyT26#wcs>`!51w1b%{C4t$q`NYsx`K^9JtlR>@(4Nz2KPhGi-iAFHY%S+~u zN(o<407YDsTqHq~C&-fU5)o1sL6#Mi6(g#0!KxLr!Os7Ms!MQ6@I}o8IoWBlg+lh? z>M&S-p|;)ew#!<=gTcZjz;bRQ$Ot^bfteuME!uLzBgj~{SSu>gEzyda;x@&KN^?rH zoJ0vS+cukE=A7v{(~qIbyvi>Y^;aR2GKmLxj^h>yXe6T-yPU2@xHD(*d{)y%o4^ z1)dDO8#wK@e!d5AdH@%N6y5j}uc`mOHx~v8(PWVXu~b{7aXGcPcMaVh7$Kn2td@l8!v5gw?BCi>TZV542x+IFcN&Tr2Q zS*+qza0mYW>soWv^O1kQY1hSN$MC@%BiXg6`P9@C8x5l^*2YZ#7Q~_A=KyZ z$TQz>#z{H{S#j-|{Lh;Mj^Kl*%F`Fc7}c1!4kzhE`}S8qjOlLi*PDwGS=?*$%ECiQ zb879|azC@^?yE57(y_C7U-7NGZ3}PWL#NRR{iQQMwu^cf6(ja&UYlkLKHq_p=F{lI zr-E*GYCl?z4^_R?Z$EK++qG&PPMS}rv#4S>oy~h;IB7ne3YN9yFIf;DxuBzuV|rm% z97GHqz>#lTaJBe@PXztvV6IV=Q6xo%+^Y7zx7|HD!tR%e!SK4v@Jh>{t)~2T^`v#- zgbjP<+?_pwy=?3D=Ld98f71`EqOv5J4CQ+`sTFHeP=<%YoDTk`p|IALrz(i`IxNIt zi1hLEXF{ZaE8wHrFLWCdM3Wd3EE-!BjC8+Z@;s6L`k6WK1SyIW#UtN>lR9^u$3Wxt z$iH3LzX~U7J!-kr`S^D&g-PK!IfpmL^A3LGdcZ&kgi;f5Zvr0oD}J7kf*nc6$;H59 zG2q_pY$>_2MDs09HUnNW@Z1?hmH54q{VsAQFjuDw>nKxSb1v-glz(o&GL)S5hsaN# z@9Y?BHn0!ocD?7~3DV34rt63xI(}|1G#eN(EoWY9*SD9=2DZxo{L4ShQQ{j?@00!e zU0k5s<7e>;n7vndR#`cYF5uY(1juo0+;wOZkh!Rsx)jm zQ}6Tc^!b;dK>Y&zVy%GYEf6t4D+(z}K+t;O__mC>eP`c?PG}?GZUliy&YNFU$j%wN z--aElfowG>MjczzQk^0;eCalV6|gNg=o#YNjPWq^^1b+0@%kvpJ_<@N1PQdQ@-r3N zot|%Ll3s3sA{2TEEr{NszG-u3$~%QnOENE6Ao3ybRPJ8vi%#VPSsqoMfJ_3F{{gxm zK*8drHtzws`$>BUg#xbve$RkmS=m5Y^WHIuRF$%CFJ!P6aC-p{B`*Yd2yhPp9=g5g zPWb29lKW@-;J}!`m{7DHOac8T2O|m%hTgz@MTY#rK81(mod@?`g&Qp8lv*~puN6d( z?>komo9m_Z`N)}|ikgkX;1wE^Nv;P$>%jzsFM`|x+_r!aM8ER0bfIBV5nXWG0f-&I z19kK!ByJ+YRO6vrjhPaYgSdsfPnvAGlY%Tn)F&Vo=yQEUD@Z`eQE#K@f`G3d55?!t z_IE~8?2qkP_teR28UH0e_xH3l^?RpW`qUmLx$)d$lu^T*z&O8TWTfyWFiH@Qj1<-- z;zA{;E&-|Z(0qmpOAgCK7fm=>&#MnZ8^qxTd95G}Z4e!l(2?%-he_gV(Hm|J?F?<$ z?7UD1)IfREuRAAXC2GloO(k=+&R)r9~=cSW0`p;`%bpx@NahJY1wIZ zi=kf2dF7T|_}Kr<_~2h3Z|{Lx?FLvkaAcs{3+#J=J3}7;*a6^(&`Cqv{t$3S^szlJ z&3D~5Ybu2H9KShMX>>F2YX(6`LhpRK)VVa~9ES#LYJCP0`Az@lH`(9 zw1sz9ob`_nt;9yK^ZQp;^%J*F&t^f%3@`8G6c|yyWXIdJjQ8%7SGHR_;y0c~FAXU>YCfW??;0+?b1GO{bd9t3d?P0UZK}ZZM8<4F>>m z0E|Pffgq0pucIIiRW!fAO-Byq<&TD5Ak-<8hXUpo=f6)meo)`_h{rm6xU}MelzSEK zq}Hd_>YbX!z-KY@P7TWEEM-VkcKoFW{OV*ydThyqRNG$`m;dTJ71ojW>(fPsMO$ZU zVPG`+83P!xn}SVY>Nng5?noDXK`X&;2?#(+AjqX4cqs_$W`BOgnbddP*s))Br~EE| z1jF~%Hzrn{^26~kIeFUtX-|YioLmX)R{}o5;yq33S@~0L&pZN}AD7;4yAgRN7sp{> zbBBi}gjO8hMLEIiD29en4PHkf^y2W%At(6q5JK;dUmw`++i-O@L?7*zP)ZN0nXm|j zsGlyqkQp&>l#YI;a8op+=cOQgDTqdTy}$azz7>1U`HWz_>M4zamKuBm(;%Y1#Lypu zKY-NM@4S+~s%5E-czg^t9<^hbnE47{YuCX4hJpEtLIKMLA7wk*&fdY%E6^**E5OUo gE5u9SHP*}Da}2?D@^E)`c5~tQ@W*k3dEVIn0n-YS#Q*>R diff --git a/.cache/clangd/index/abb_system_position_only.hpp.8A2B130C31B29B26.idx b/.cache/clangd/index/abb_system_position_only.hpp.8A2B130C31B29B26.idx deleted file mode 100644 index a599263f6c4ac5b2c57ba4c54bda73babe66fb51..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 3718 zcmd53 zbIEGLP8K&QN4*5)xu6FL$xr-PAtcUGP5N-+CeI`0i*Z%Es7kUJfCCV_cHe z5GO^6Dr~w{z@n(E$|vi)1d;bK3=@%}JflcG@ra->eUiLEiIZ>{EsJ<8)Tb~)jI0$! zU8DJw`xNl289A{hJPN@jjr-)jI#&~MUYVdfA(>ZuqG%b zag`yRXS!LD z%kB01e%#s~MK*Hg%012Gk6FlY5m|~!#uarJP?S~83w&aXC`1KSnPj6VAC=_9Bp~fw z8|$6~)XQ_KB%`RLy?;YtR%Jto2wH1<$(v4-g_xisnPcVvJltzL4C477AuKp=XMIAv~3Tz9r@!`&Weju5gnWnEY}B=seLUVPxkEHwH4p` zuiEjPRAd>Tss<>AZm>4w83^azGpuXRzHB?5O%M*Z!%KT|Jr2WOeRRumNA%JfD=sA- zS{`T#=!0Qjx^_{^trNBH+wm;2zMpdUQwwQ-uD{qotT}mo12n^ zD>pwu*VWW5H|&Fs!$Z%+_oQcFDh1K5bk|&cfCxzrGT)^~OBHDauN`e5mN9P_K|S3-hmn%5w$bjIc==!$Sa*6{Iq!Z7qT~lnK_^a*JN+4v#`k{OU}s! zKY#QkL3_)*)zGD7fhW7p{r1)%h4oDUy?RAn#ZNCTO2Y)5;mrZGg|5q}%Ypg>SBNK_ zBV!S)f9!)le_ge80r6BLZSU}RL>;sS9dH<6YqE((69{1cVYcJEI`A<; z`@Mc2Bz2&z{5i|{weyME)#Pdi^y|Wvlg>Uzq`k@MSm*}akOP#k&`r202X;7_-g=o?b}5@m)vE`^Jhg9V zSJ~64@7`8a2#fSlBQ^N_++MILzWdQHh}xEEYk)pN-AI%gy8->px%WnHyf)+~Iki|@ zoIn{cV_N4r98yA!5~d#F`hM|+S&gr36w@vAJUp)$JXz=(T$41b#kEN@AND29>T!M2 ztPwXFvkTQ}*D`E{JG35T1acwSn@6i2J~Fbj{kB@jyvX*E0E%2yBU!svS5na7_QHIvNb$aH$S-a);))ESu1S~;Nm9Jlj9DgY< zQBOhR5c%4v3~L2&Xv63;69j~eLq;MrwKGhSK2h_|hSHXc2lFzsvI`0wGm2*BSZ(&) wy!>g?QI3hze(jAtxga2vZ;IKbXfwq;Q!Fq=@=Fq)Ob`$%G{r1aoNkJL0ZRa%@c;k- diff --git a/.cache/clangd/index/mapping.cpp.986C71284B0266B6.idx b/.cache/clangd/index/mapping.cpp.986C71284B0266B6.idx deleted file mode 100644 index 97f9179fdd694cc0419336880bc62a2aca009bbe..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 22072 zcmc(H2UwKH_V=E%Do9&oMNk)9MMcW8qGCbWfPjjEC}2;-6;?oL?t+TZ7;Io8v7oVg zjUe6xOJYNlSg=wwB6dMhA!;OvvBVP1H?!;P`@RNC$oKqjo*T3Cn=@z5oH=b~UT;`X zpFSOjibVd=K~oYmDe49yk;t0-t4qtU@XB~_a!PmN1V=^mLPk4hqA z;u7N$W8^8Z8abg#)yxn>NgEP*8weGer}XN~htN|6hxcqSj6LAIp(6HYsJ8 zTC0(V(|rh0N5#e^YUF;=(Tbo%{r;$<^g4Ri261HnUv}uNVudHDwJCkIab%CRWakqS z)QQo03mWzo3*yneE@7fBE+&zf3$dj)7}Bf3ddo|R)h10QHWTgbtxZi#iA&H#YP8xU ztvqg=-uBo;aXNWw;)KMc$;6KTW`S>A-~YfR)N+GUIL9ZcqodU+YG*n9Q=XERtdWn? zCMD?IlN!O>bgWI%MKT6-Ltay~cCyafJD5xmKv~!AvUJwJ>+3zlBXYgVM#=nd6Hh&M zY@}A592Xs#po{s}k|vQbmzYv-H5!J$Nr|C)=JiwIn*@7L1-?g!h;-GNTjK^w(1b+{nb^MNOkC|p3q`80l1@$RxfFV?BCx zlhn>H0)rA$G}>|MD2=x_PlSIO5&rcGjaL7*6_UjMjumn{rb~zf&S#Jw~O}~5kk%AACA$7ut0XuHVihD*v8X$ zWE}zs4+`!1b-PefJ)zMyNEE2cHuOXWTObsFvjx^o_ukO|+TQC4^eY*dnjmj)IO*0Q z2S@UzC6Nfri>iA12yzARnu6XkTCc%Zhjbn%p*6e~4C|1TXSjs8Zo}2DnrEnlux>-u zM=wL5>P3%>DtUWDOE__=@RY4Tv{QJ(=6Q0TOd|F7uGcle!8)@F?$wrF0 zoY+OAP(*9vCTX;agrsPVPmG(JNDZt8I_z&rVaBS5)l*}9vL{$uXk`@q+xK-!2W^$bc{$5q>N2U z&?t3DsmZZ%I_2af?F3yiDTkG`vPn*ioUBvEkwQluAFqs6YojNVOVmhmgJ`IkNmo>S zYP9CP*yyxTdZwf%>ZJeiHh#lIieY3<@~37>idIejORl|B6go}(IPyC&Ns*eEs?$U( z#-%3eZ*B#k{xV%dWF%;El3rScS{s)VOWImZbZTO>Ix$5Nt%-`)5hOKHt05P{>ap<} zMHJau0!=2w8ik=&B_vTI#W-CWxq6?XNJ@-P6DeXuia1@GE=7|dQY48KL>N%LZI{jA+1lg^=oam|Z zpKiwccp;^Eb=>lxQAC-PoT4OdtBg^{(|i%d37o3aD#ykpDx*j^^bb)_(DWgvGo6xd zaa26L8ulPQp?r;@N0Nw`5_wpl3-I@a$^^7qsY?8x_L{BR5{UAlQ2a<63COH)Z|>Ha+<_VTGw#H z^6NR6sHpxUHT4|IG*-{yOsnrdTwrcSz4Ny9U99My4D^kRjG8jV)06DZShX%LikwgB z)sD)^pSN!$DQY80_Ki!?2|IWj>Q6Q_NHmUky|+^N?p(lSB4Z*Ufh8_FJ~Bp=sL@g* zp@oY+R~adYX(?$#UyXXil897~`3!+upgkJX>YlnTVxttVE*Sr(g6LI2vZ($c`+uw$ zopzFv+`2~UVj|fKa((xR%V=-j8jgnUh+(JbCkFM=!uw>yS2gY%$|qx@{6|ZEpLt(P znns(aDVNC<)vi--@;_w{rH(kTMxF33s+4HWlqgMd$~)<3G!T&@fc|UHtkK%2D;kcC zb#!t@P**3ti__zVyAyI}KzQq?BAJo9I2GwzuX3UOH%))+hsN;hO-W90k#8VnLE6w_ zF;}EN3BH>D)h9M0{@IUw)svPmcCA<>5}Wjljfh+)wGd^&cu^)?0n01kk^w_4hq{Ow zH|Xu&a22EjWB}OLUS99;Q;#YO(Lz1t0kk@RO){VmtO}tCq4jJjSq_saY0HQI{pHi& zZ`w1`HQ0C!T4ca_XuKXQ2&uBU`BF%sq>dc}e>~iHr8gtpiB>x)*L`5MPtR3hXR;Wy zl+-6}s_*W`%4>{t3CNZ}s|<*h#kL|mySFimpGxWcz6x4W@L*vCqsvFLe6-Af9bmQt zED2@D7M9B(m6G=DZ8zFv=G~=?bUrkn53&r1Y#u2iggu-r5UVzczGwfjZP~A!v7IS4ohc@Q-Uid#`Xza_YQ{t;xxDk{kyCqTGui{- zdH@s|upC^MgM#o?b!a+q29@Bf_lxxh`!+hvDD%NFA6jR?EO49!tqJ7^F4jrYDdjo$ zU%b5GyirXX!Eqy{oa#80(sgTXIw6hHU8t3Mt)4ZJZ2Thqn#P-sZ<_%FOb4_jR6W}@ zU@~5L?yyLrelm&8ybBz6QGN@-aiM-@Uss#tPbkOg4+?)?n9$-sjB*oNY(hx}y_D6j!aOIRx?glq!5YFd*!NIy1Z6skqPU-d>vRBr^|%x=(rtQGplC~ z4Q9-l)ss?YypR^`6;C^K-Mf+OJ7|yz3!vo!X!CWcYERddgXW5tRt8`AEbK2+!u||M z&pDa58MP&G0iRj}xj z=D$2RbdEAv0S+sml`#xu z!WOjLf)ZvV=FNs)_%&+5O3LIBs2)KWV`4u0YQGHyFDKHTC+PVEdl{od&pRg;MrYih zJ&RDa2#2sSmcN;8o9&l6LN5}wsYO>d#@c>Q!Rg~G?^u#Cwb-H-<*bJQzoOl*=)eOW zpxpxj@CVxcApoAE-E#pjQ`};vSZ?(COqeaUn=N+W0hwaEOaZV^Y`0JVEETs{DwZ3K zJrlCUcG+SF99U4X29V3+?uTo6&7Ep$H{KXv@M~lgf0T zcKOTqP*u%A)f|jqO0@avPIu2kmsGST3*ECgJF+P$`eVp_#V@pHmDqEYSj9w>YQhum zo%nee?U{$Fc^o%pEl6C;ko}lz5z@=(aTz_C0XP3JZ-jMCUVqA@yR5qti}WlriU|ut zR^+kRhE29%Q|8EIPwI#f~gj$Va>7Iqg34Si5J)wXjjC)kx?1af z+Sq%a_L@t_tU!wuC}EN~_3WOq*gO9jop=$LEdq06;?9KiC|i#XOtEcyPyOBBwfAI7 zngz|Wz>Y_{0nIj`IU{Xnd4BNE-+j}CO7av`PdR^Wx3BMTmrZ{xrcBDgt{mF(7FvV7 zYA}c`w0+gh$Nj6LyEP)DUG2IWH<~oNTXk>2_MJ3)S@q&KeXV@?%>b(aezTudKV#E* zSn~8?%a*pJ(rgEp?V#j^yu&CtjJ9kuJ1q3=Uo(F65lUJBZ41DK=QPDADaNMEXw_qZeKhLB6IrP%T*JRt{5d9j5@lZu z5ydcurfZM3LjRTkf$`+T}58w0aV!DbiLH;GU&-i%s zM-QJpKHo9-RN*J5W<91oYe2RJ+J1KSmoo$UN8Igrb<}t6p5?6@5cWqwdK6mn*dGJw zF#&J^{V#Cyks%kc_eIVJJFlJl(Eo6}HI;QUwB8I(#yW;<4oV8J33Jmf?ObhE?X~Yh zNf$!1g#x2phi2Idsg%IiL;?!#ba96eh3k7)II`86u)2?#y`gLo>sjIzrpXFK5Sc)w^uBlUeG z?DND8^TZ}BkPzToal>ypz`K*x;)|VYNO?t5wPYJK&ovP(os z_km;|*z!!g1YJr{$xNJOY8q?}hXq~~TnA0oK~tWk<$`T4*t0$I`BUy(ro1?pl;iY>N^CCq$+Mus)J`eP4!+H(XO zAK~I(|FeE0x3)VSO@%%M0jD68r;6(+yN=FG6`@yu8uL8o_asUh<`&kOxeIBI?>N3Y zJ4+0n{YA!0+ZAgmSt-a$1rg^O_P)kNfWcWmIk~kc7;ZsGhqw*t#p5`_Z3Mshk=sZ7 zrrJ%-Z))5${APk%LN6u_;XKi8BEOmHmdbCYxux-&)7_@?o9W<|4t!t^xXs~!FwuP9 z3oR-}iODqiV4DvPJTKe|c3Ytp3lN0j04ffk7qjfJ4|eVPuUl+0s;B+nvLBQ@w=6|T zDOawA4SMQ$%+6e&UAKT_3p8O)N5`V`esp1hF}!i$_X!&7EXp-U+%QLM&TN1H`C{{Y zag*846u;hk-XJ%kziD2xDO;7)2>Z$UxvA3`)68M6GD0bdK`ek zJd3LYn@VtH&Oj(`fXxj7Py;qK0^ly#+!X-7fXy!g;CHb3T>v}=o5up+8Q44%058Gj zr2v?THZzeg*j%)kD*)!B&3plng*I6NUh9+g$s^3RFfB1M? zd%F=`1`KcY?S^vdwQJFQE!w;|cxOh3+nbU{dd)a|d4Pq!tT+tP!-8_F9988Q%D8^G zPa5xL?K_y3TRqzJ=*V`NG=19m@SA>Z{P@klHi7(RP@5orGo($3vH6kX^<^$Y>}1p| z)GGB*=EkGr;y=&#{c$tJzZRQ+&6&$+?SxSeoD#pH=5iRi9~R__a+H>Hxngw2z31tF z?Ho;+RDr4r!kKlj71DFN;d+UMN_Lo|J%-yPW6$wP6$68(FQ(iQR0$z0OpLXv$n5j- z(h-XL%6yGQsU|QX()--%bSmgRaM>qt(h`)Ea85d|dGtkXhoXZ97m(zFjlc!k@8z5{ z#yMx~!hRut(Afez1qQJ_iBWenpK+wiV2b|&?!SPFtuZ2HB#n6H0=M@-Hfn(SXCM+Ls?|sFwhSog=U|RsqSSTbwF}5s58B70(Ry(Rk`1&5C z^HqX-CG=#gOKf5$tNFJ74|H{_!DTflc!@F}8|GtUR(BAJt!T0p&5v$$S@g@j0oRf@ z1a0g#x@x!^=?QNg-kw=7X-;S}!I>?VG#7&XLU3SNngENyevtsk0{bihungqOpdC-u z*&xpr0LwwXTmY;9`3eEB2|8>71<#;1L)*=QAe#qm^8~;aXuCxKYy*#N(3zK@_JGG8 z=*(12*0LAe_kt%6C;-<2fyp0+{)Yu6LLsOM!JoIYMc4x6yE zEm{70v{)|yHlW1@0k9jJ?#AXUlaV0>Xj6c8JYXN%>=OX{(PqB@IEi*AIeR8Nim+Lc zpqwp6+hT0NES^x5W4m&6W!^%7bJ*$}7a|F80bMVkl1Fh7T`qD3Z}NYK?0@)R*(&Ob zCqZ@+cDDaf+o=x7Mzdv4z_7~5#nI)w?OT}%LioMufk?y}`-z~`;Go7;EB5t)s?8J%-0_+es+aYej09|o~ z+oBEyk0_G>S%5Jnr#9U^K6Lf)aGDm&P*H|HEMcY|Y3F+X;)S!6c^7Ub!Q`uh-O4vqO{Y<07btdt7tbAzW5eTU$=jF{XmSE2Ek-zB zyR~ogq$!>LlXT$9yy;Z1@38TAXv+*^ijQct^}|mt)7f5t>IIj?(nh|Ff1Wk_h2bK( z%Ngj#+nF-xRtDZY;4Ju_6?j`YbT5aVJc^qry@}1(4w30@q4bsjs77hE0H{G}4F^oM zU6D0Epic^2#4fbng);x92ZyF@>2!4J$MUIH+PA5p+C2kyX9Pxc6T9C;KQ`~QSs!?A zdT{G6%H$9>KZNaA)jMs@u?@?UZXcse7D2N`f`j{dG+WOd+^5~WUHBqHGJ$TzMzGxo z4!rpHCD?rlt=I(xq1cIvo#@3BKK*d%hS6zLP4x;#&ljj-HNlM3zm8q97#~M_d^-8` zWx038*=fzE1fRB|_ziHs!KKYlD{71PPI>ywActZjc=6=ei4Aw6C7YIv-GwH*P{MS^ zxYJ66zE!b0WX`DRLq1s6buOK)YrC$!7+uEfeiM$C<=a~j#pR++F3MO&CctL2*(?C^ z&?Zj+Y(bkX0-zGzD!E4j!s8ltxQ5-?J`vzLx?blV8VFE@ovN@mkK!ge-Nep3;1;&O zgJZR~KHn}ualss#EF$CQxqZQW2v^MtELZOtTH?H z&(IFZ^`XX?1!h@-!~F)7ZQu^~nfFZ<17f;#GK3aMp5O?!51sdM)!l;MV}{j^=&mQ- z1MT;Kf)_$gqU0ntVkL*MO}M8onSVpi-_V<>>a*N)tMBALxI+DMH^_H`d&K_p;Xmif zw4WDl-1+hFktb=-U2J?8n=@{U@7E~PH_RSGl{Zl}F^nm1$*twb$IjifoyvY5r02no z7lv+QkK5dhO!kivk2~L1=&S3w=sp*Fv!X4#%Jrb{51Z~%=DA{%T(MMR9yVauveP@i zShD8mwDL9$sMjq4+a=JFS3xZWyQSd3F31VRCUo0`p3GNP6}K7npe0cW>Cvb(19_G- z2UK%lAX~%gZbSSNKM2$xb!Up(%oMvb8(OU!^lY)sM-8Z8HQ-(YzD(pb`@jA1aeg~5 zYtnN9q$dP7oF_qgQUDZzv`7FHgS1!xlz_BE0F;8XQ~;a;=_vtl8lWY1Fm6@Yg|YtL#|`b>w+i9D)g`7W?B0v zbj<3HX3wB1`$+ZCaHjS3lS4lA3XKmiBlvG9{|%MQ90~9cEv)#)svEL0;f&j%*$iDQL-DQERW?JzP@COcv^QV`~e6*0Hb+a&tR)F zf@-u3TbH3bE5dTO$yx_U_r+7)JqGv3oaf|LhBmYE%Dqfu%noe41Dmh|*;k!HYwbmw zE9sc!V$bE=+v3-jpZ_&xcA)--Z9dq}2YcSxYXR6TfEMgco{U|C9oC>5E9t+^tGaye z%5V)`@JR?hDY$vRg0d^z&3nG?Vxy>gjpUTH5Tu3R$XoC^?0$~3`}|Kj9k?|u<02*P z(W!^=@J^Z`okEOFwwLrl(ePCXOM8Uy3VK}Oo<6_vwy&{ucxXyFE(eF@f|s8>w9MmP ze!jKOPK(^W^#&z92C`#2>sscz znWx53kxql`G$?sHRE5D+7|9Hs2|y<{e0jqr{yu2ZPYI#zk5eZ5L9$=)6jF*VrQB1< z_mc*^+-0Ane|5bBsyo~V4nHg%@{PCikk9Cf(?OLE5iFe?{A_b%C-=VFX-`n6pimYz z4nA%CY{~~^`lpcskQ6{uUMwg^*J5tkL#n}dodOfSFf23pG(-xPDXZd6d4+C4KGMz> z8pGS0&rxzM#6BgW#?k8-1n__hD7}C!nTm*j7g2hV1CHcI40_zSQc0~P9~AlE#j8XP zV8a7w$x3)aaS%-oqJ%wi9`Beqa?S7w;pchN41gHY9DgjUpUeyBN4tU)W0JY#%D**0;*L?x-2)rH%fT!T~Q~FB3}AeK$u>J+*`S~Yn4r(^n!|ya@u@@wJ1retR-HOnY zE%&mf_Eewcvwowb*bS~gB)b*z@M{d&i5|wp?YQ$hxm)`Kb zS9&!$O^>e^d#)GzvI6nej3Y8d+JdK)`C2ev3)Z~UxeXn+p%crLY)9yOEqRP5-#YTt zyB(Ws7kr+y7j5@)pC>V<^cmdn@gsjM*l&lH%o2$p`@nu5v}D^!fc;>7=D3{da5-2m7w9k#9r8FG-d!^H#~Q6wB@MY-(PAq$WiJ)? zl#4A)f}-@{vjk)%f&#D-11oVb+p~KI7JVOldqXz0`*~u|dE%a|Fsj|L?wTy;&SBa! zAKmA3=kZ@|EP9l4dW!zA@7KxCSk2yFnLJJ1Gf7QlF9W+WaN?QDE$n#<`?6^t_J7cP z=dDIhDf2mE&pBdmHtnNsP0C6pjwql^&O*Rh=+9$Pjds=CTPX8H8cq%0`!d(~quEM_ zP5GtCR5dwhm4o)|iRwwael09oUDCgv-39l%-0Rts@jG^8h0oXb%tZH@XnYcTwrPiR z#?TfYP;RHN@hR>(?|H|@7PCxq;tZ9Fa|Lu3R4UF@0-ze4s|COvaK0k|YQecy0Ne-X z`vTw*I6o2qPr>=A0C)k;F9bk3I;SIFusP^FM*z%2=XnBP5jrmt0E^Liu>iUT*Yvm3RDHVmKr^9uOQo4}$z4xUui1$cCT6@H04?8Oh7< zzaDA*)d2ko_ZS2o6FkgZMA=2|JyWZRSJVF^Rq}UWbo1$t`9S|P{4u{g$+z*dVGhg%(E^TAl)?KwoA-MT?>8A@{AU*L_dM=5`3u_dNE`HyBLH!2=kBlCv85uP)a%9ZNF(cI@$BqaY7&>%F_@Ice!5@u^8#ZqEhob)n DqT&@2 diff --git a/.cache/clangd/index/mapping.hpp.A89898448F05C4B9.idx b/.cache/clangd/index/mapping.hpp.A89898448F05C4B9.idx deleted file mode 100644 index dc1b39ceba63249c3bcc1ebb9f181abc63c1cfdc..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 10102 zcmc&(4{#LK8Q&L(`NIW*X-fE$xbi0?gyaY`0!M)G=YUuVe-evS<=DI1Bunmg&)q!& z*3^t(>{#0b_Iq#d+k1D} zyBrrsGbHT2@ArN0`~SYTx4n7826et5tP3{p3(KZ7Q4oY;_%%#jdA1xL=ue?|i(gmd zc5$;5F+}gi&7xsSrYxG8xP42jsLK&uHe?mn6iuxw1b9T!rEnY-mLhCfm(8fIicv*1 zm-$RFpaGAfDr$#lcFH24B685;sw)(ew%xvFYx8nNOKOm1 z(2g`2#Nm=PR1Kv=g>->jN|8u0W|nzor>=EF&ICOkJ*t{YSoX=fuIZxE&TPddTPnRM}&=)p3#;vIaZB8|_cB93f z%86T;@a$ZeO0f(bm{PH1_l-x#h-PH%Ip9s@wyi+QD(xKg$}C99Mns8;`lV} z*8F?Mt8AJu+NSG?g{fy} zdMe8uVV@C`;$RPRHyrK!5ZJ7mvfeHQWRHha;YvHgxGl7^KAnYdu#aJ3JYq)J2P2N6 z#!mU{ZQCmcOc?uM>X2X@)al)$O0Mgu6Wd`mq;+(_N;P+fiQ|*nEt@4{5;SXw1O&an zSS%^VP8>KXmTulIDIqyHdUy(JRL!qssH~d%y?PIvu!bqd9d1oi@Ru9@D)~{dr&<_` zF*ZyvHfsXOfQg=|j029~%;2((mos3n+b7!u`)&q|cDrDV*k@8PCM7I$B%ifR2%r9m zf`H=jbi-f^wcqKsz^}3pnKl16jEMh*7zKWEy*mo)miqV3xE*!(yd%({<1z4oPJabXcydGJG4n z0!VUD8gAyn*d?8ll$Z@k&Co$pE^z_uoVd(tE>QvKoT#jOS&gcZUKdx1mDZ=kjiZUT zY<6j3QsAfJ4tphV*#8M~sQ&+CzFQ=U~tS9h{zr^EL3GuN`=g&@k@phfcc7EO;*iW z$HgtsDd|2_mlV@TBya&;2LWvs+Tl*&al74}T3B`)S~SwB818OO?=m8AHFVRej;OwF z!|jhMp&yhX>oiS#fk-471L@^9;gyMxzDuaf`vTw)Os|IU2a3C5TzSuWFPDFa;V(ZohFdD|{ zQvk=s@5k1s*pa~~^pwB{*?LNK79_l{v7p$?tWVgQ1a{!Z{1N*mRp5_!!A=yx*dO*+ zO%Q|$c`G{Ge22vM9MC`_E`Db%g?%mARS_T@#Uk(DP8JM!ILrw$`2>?wJ1tMS z0Wd4~-`@0ef%{Dk(>1H>8j!MVcHxFLK&(01eCU}E?`z`_$4KEZQUsVqGm1i60JCxJ zv|V|3z55`C@lW^90>tt;u8lVW!uP^WPv@*(Z*YhqQZq#A0JEgLB)k(gBotHit)zF*AAXv}Y< z5?0Qiz$D!B=$=>Pde1{Hp##0^&G%A^8!NA3h$l}Kzc}%s2QP3k2Fc_>=C{SOrfS}-BNJSsH7BH);i<@@<=I;yN zYw(a)c)NQldMIM)wfWvwK)iaXq~VbRw?Q0b)VL+TWiB9A%$vw``RAwQKbj(ayqDXj zpH%d-eVP_ref>=!<-+RchVKi{c$~u=C9b1n3dpG|E7-FcFmG-7e8k*zc@2j#XPD)H z@XVdO={tb<&+UOTgLhuNkVA}+{1N7v>%<(UjV`wv@8`zrg%q$l!2~FJzwlQF*F<*` zmvoL)og<4ddy30``^?~<1};vZ1o0fHM1o5iCgL!uw8J8e5OIW5qB2-^u#r`6xE0nK z5Ud(Q0u~q$tinP<<=OKeU4J3C6qIY6);I@~5{nJ+w8#*R6$Z;zWg!8}3JA2EaCys_ zw|9T~#0OfAOY+uum)Hp{wJd5`hGE_=+}rf(jMr}lP#-DnBjt7$fpxW~NdubOTHrkq zmWzK3y7uPe_U25&)NX6Jdj2~PH0CnG!rq+4NVw^h^TmCa_iqQ$17!IC*=8rPG(>WT zNI4ce{txPZrdh4m{ zp9Pp%ZPwZe2mZ@FMheiOy0`2fFU>ws0v3#rsu8jRL*0F5Tg}Ud&-MU+KdJ2}4R-2F zgCuv56k!Xv$JU?J2jb4B}mTf;3Mz53aY3C{ z9U(PXxVRm7(rV=B%cmY0`pc6KRILPlv(%i<=TY@BQj2+ni4Xi%lSh6u7zkEpN5ZL} zwQc>V;0-qj?jyB*q=B!#+|#58s}BtZ30B`n3CI8htJxy~lM4v6!{ai>8kT8W$7S?9 zEL*)C32)44>i^-%+C9{DRsI^@b-71KKDrKL4g6N0M}G7b5NLD9WlSMhwmLczK0mT< zfw<`YDX`xFsTd&DXt@h|L+cRPg`w8vkVNAPBdy`14*~ke`neS!1c8yPkN)`T?)am$ ccG2(q)ql@FoaYbtcHeUAE@4-kcuV~8|CYXxt^fc4 diff --git a/.cache/clangd/index/rws_client.cpp.EFFF1D4EFBF2C97C.idx b/.cache/clangd/index/rws_client.cpp.EFFF1D4EFBF2C97C.idx deleted file mode 100644 index de8d4dcf92ac73ce8713483cc673e77b2b1c1a9e..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2836 zcmcgue{2&~9KV&e*XxdMv|U>UY0!`6LQB*tr7$#C~xbeb%0FaTg4*qkQ)**=|n@7AIhea!r)jAt8+W*`eA+>|Lk1#$k<4p&(787pBm-|2AlPR zd}?45DXNJ%6x%@yrJ(TN5m2p9;Nvf_vSvCZzTE%XMle_Zi%!t6}1`-)w zm;tAA+xeu8p+K4|>lMfux>YSJ1~;ywy+&1(ASV_ILRAyS4NlPvQ&d&1EFyVaL{LyP z6QZJRq-c_A$#7mY29l;pk#6)&FaC*dlmesJC;o;LCKBMA;Q|KJ{>I(kz$syjG%03vZ$FrhLUPvjin(dN@cO2LLlMRV%0b{ zhQRK=R>CF{1&T&ZGsOv@Yif-GB?>4;%`jnw0y+f{#N|U01hRtqXV)_(=~_`KaoRqm z!c|qPRDv=$rdvt9QdMz?S;(1X1<3-A*{pFjsUpu(NUErnI8`ZdGppXdSWm2n!m-Ky zCC!RPdpA3znkF_o(?i;N$?-2nL^vfZjz)bP%~rpi-gmw zCWj}ND~YOzCr)aV&oU5KP&7`$Z^UF)+zV5R3XNt0JQmzs&X`UOkB%g#eNgt%YPgKY z>pSr{g-1w(l1UXYZ=B=qf8gemBx;oa^VYmI4e&DBWx>(?LyIYAj7BCKmZb)8-w@LCl z{4^n8LBJ8HOa9pBPxrie6gXHwyJ>%epkqTvfq)*$R-PX zE}xG;)+VPmO}^)3Y~Cm6L<8dK@~k6L@6^Q?JD*>))HWKVcMvrTJTcFDB0ahI-3zBy zf3Uj6IV)lQ%4_t;cLsmP<#DZYbrb8IZ@-0h9Y4GWTQ}!3!tftfVEZvU1K!o-iRoiD z5iASZ=(dIZZ@hB)($>2yoIH3q@#&du*gdir_m*UDo%0vZZ{B_cr@}By zC$VCIm+{sm>zi+X*}i!LkBx$k;BrEV9rT5Uh;-0%V`_~xbsPJov-EDl^zxRj<6mFB zY+$UP@rQ^t?j{qcODDoFg$51;4>+8F0Zb3UIzgMSEkqI{P|UdTCfk-{Md&QGaw||CP%Z z&c0x`ZH=qWboIA8Ti~tCA>6j$ir`9OeQWcp*FU*-{wF&MnyH8C1YX+PB>8DSLm)T` zI#8FUUcZ~@JbLOo?9Q{%vyB9fpeow4i09Z?g@0SXvEbRUI~U`Z9MN@D)ZUtT){zB8 z;eQk=hsCAfu@=Vyr^`)y7;of}$g0T7NLS?1$g;@t$ck_)yD%77%u{zXA F{Q=R4#X|r9 diff --git a/.cache/clangd/index/rws_client.hpp.96A4BFF4DFB820B8.idx b/.cache/clangd/index/rws_client.hpp.96A4BFF4DFB820B8.idx deleted file mode 100644 index e2e0641a7595d0513a405da06a2e97b1771542e2..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1214 zcmcgrOK1~87@pn6>}DI*O$dENsa^zoFk1?Gh|+^KfeHcJ9z4l1*-WyF`(kE7tRmim zUet>qc+r-Ccq$5F4?cP*MT+Rbg9?fi1bY#D9@W`RXXB$6FD_(e@_+yTf8Y1-?95cT zd^Z8WWNqq{izsAAps^pJ*xn(sL-@=bpPh7UFpDLyqo*mBa ziIy1OnJiZ>Kl$-m5`{h>r<3XJ(E?K4dO;Sf&SHM8azY*uh0UI_Dysc)hvxdbuSX{i zlvJ^wG2}*ba>R3{Tc z n94!Lk{kcC5cJj{1diTrR8=}0>V_pgyQsSI>jEi*dSofrV6)oaqDFGoI$EIY4` z@ByUdjFM6Lz-LpX`!3Qh3M}c6dYC8iT}b`L#D~O~!U=H!+&jw-J@fFxD`!?$?k%1R z1?*Nwc~2%l%M5b?FJ3lMt_)wA4H?1A;urZ_#l$_NCb;9qLL6oqR|i(Veo zGjq?EbH4N4bIzR^i1+tLIE12Vd{oDl>_G?x;WjNsg4M8aE^tB~v8Sv}8>a3o=tnGQ$#~ z7G^oeiBLteRlFb?lPQy=%rMtaF8+yc2nj=w6P|d~Vluo5C6-`fEeC6A2sX7%tO_}s zDi$&59Iz-e8QO>$phaU+tspaE6~Ja#wW%soOHi?*nSj`oVOc52Sq%#cv=*QeIAg)- zKFx!Rf`pt|rj|S^7*s1GA&&%NmQ4%mNHCDVFqDreSWpS;o?Fj|V$dAPi*$tOVo|g6 zd8~@Vh8;EZq6QL^ShNa+sS;?m%3@j3)j5Eo$uuu&Br8s>)~%0pMmiB_Q@iuj4u{um zMsqX%T?ex^(bRcrzJPFd0GyG)d0o=YyfYP3t-p5mzlO7tDd{qm^O#*P4HN`~T&D&I z1_{?0%;X|bZ=?cK1g0*@s!He$F&SCI`nLoNIfago(Fsi@!J62+Iu1Tj zS<7?Pod3xF`|rK@P4{PDb#u`f%fHIs;qva<7~j|W_}8C;=EfzBysN@~vmrOJW&0SU z(9_3c&s z`8{>to}PGb{Ndxr4!`lJlRW5cc9Vbg%E1HW{+fD#o2r}YT#|EJ_I+~nqlxn#P|?P< z&r-3%*E&mu-#;A!D*S+)~Q)B8^FzrX<0uc_bUs(>leWT%oa<)-K?!p>vr>Tnkb zt({(0@Xe>r*IW>OK2sU)Sc~AFt2uEkLVLxcN>A0|YHtk}S`}IyS{Yg%x;3;SbW5o9 XCSR?;sj)uL5Ug9)yk<$;(wotr6O@+m diff --git a/.cache/clangd/index/rws_service_provider_ros.cpp.3D58FEF4D583A6ED.idx b/.cache/clangd/index/rws_service_provider_ros.cpp.3D58FEF4D583A6ED.idx deleted file mode 100644 index 3db966fb404a2b878c32d1a8c742071af6fff9ad..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 60906 zcmeFad0Z67);~;FS9f)oVMmk!L=gwvMQ)jDF zRf)0D(LX)3uxOta`%z|kUMjY*u&|~7=H}&OOw-W6nEx>t(sD9Jrso(kv(wVU2KoA0 z7$PIObm^9q(ymjdl=v=jRcj_+9adty|FsGk4%=We~aB}H}q z&%Yw&Rsi2b&iTpYL^t-B|a=Cb5zQJ(F2BMXQij5 z<)#c6KAgTbv3>WX*iPM2qT<^{bc#x;eKrx84E+KIygHsUCqrNF??`Ft~x3^ zXK3#5)B)*gYXANz!?RLG<*FH3xp}F>hN**7bJ9ko=A@@&WaXvj3^W(Y$Qm$gL|Xbk zRZVWrfVY+AWakFF{mcJbeaRMvWcp6}-}I02a#HF4GqN)B47usU2GYN0WgA9hjmS+; zGYlM&H6Sk|JL@k$4o}TVrNfw>Lw_Bf{kFA+)SQgG!4&7Dr;W%;OU=qNq@@oSmP>yb zk(HC4I$&^W|6%Ed0d#2TPorqzbc1>Hvj)*311t;!b4O?8rG8|{&Kfq_!Z66fkdZq& zH!nTY!jNrY$VsQ&mop&Ukd~1X_SgP24#>_Lm@!Dr8kv!)4j(pR(4h1*wO96t_Su=k zhtVc>PFM2=XXK=%&^G6dR!0xWO#90Z1BRt$4N`|?^jB;D);z%IZ}hjIZA%Lqlr_TF zw|S7oU*Gs&jbQ%~8N<^4n?C<19tQ?6vqbu!%#_UBL1wO~9r}O#_W$^J&Zyj!%+##Z zLFqaF+iGZs(1!dk+dvIMwUNYBbM(n+HJqc<3{EfU*xjg9O!I)ql*XY@Xz>zNO!pkv1%4P; z{kXq=r1^)xex&&q_K{|knN4R+Zc6sRfp4D&nDrKMJzy?d3*YttgXSJ!2wKd3dDkc0 z54C+_{(*kefb2}FZqnXX!S@IKww&6}8Inzn1ZwR89-f_>&Ous#dMa(gTl(7;(!Xa9 zH}^!{UuaLgD?|zJ%DlA@{$m$X3o>Ki=#;213D!C;g>A*!6U zd@DHpF(lj;b))pV#Pu#|X;>hT1%i8BnPx*j5)=Md|DguyEi6(lWm(uD>ZQ4c`jnTdpOYrdV8kaSgq1i$ZCc0@1ZV^f7cN-B~T2U8PAg zuWz1Zi{7Ut_9?FWlt9C3fvgrh>fV$P*Iw7(>&`=46imxhAlC}yYv@EeIk6IBLuY>B z8s%$?I?xhFvFlOnXUHU(?2CF-ZORp%AA4zw;%JE)>{^3;4Y?$j)zRm(%^MQErXX7s zMoY{RTxSUZh5!=4#-?BFp!6nXhiBWOeze3^#dWI^Vpt`RRf1PtOWwDP)c#_~!nP=x zmbpe;uMt1PJb}y;SX)w}4A*as|Gkwh>O{*_%dXY5cc%$t8rQoYG_h-2bI*T)Eox57 zEE8Op2?j$;(y~F_o6=SX$GZ+5{h=+2q$TEK*ZJ7TFo+CdeLHB3c;n`gixX^7Z(8E2 z;(Ar_H>?xLI>Du`mXEe{ZnzDVyV;_4w9Hx2^(-Bs_sRRLmXG#NALW{#*w_}O&=N-# z*P}|PVU0l62;OzIeDdRr;r-)sB5hG1EmMeG3z46pJ!#Lr`SX;j($o#1g|;Yxme?e@ zZjzcBMw8KYb#)X5&bJ%Z=z~yO6hKRC6I{0m%?v>#$g!@(f-osLVC~r=Thx`7s35Kt z#MkhZK)w>#C@!2gE1=b@qxQDQM9b_GUH6I241Gu+R?E_r^RM-D>`1w(6)o{vaD7eR zVfezLIaM*F@aEpbtHy(s${@&%I5y=Tpl{d%vUCC6-0TUutd=(<`o7^&Rf`-|_b&z@+DTGA4?1=rhxk0FeNvA*AY z^UL=;%=_b>Eox6oyb)dB(9uaFX{^MyhwYrw+kLph7A4UVPl@YO5@uK=kVS&NuHQNwnGmgC8{8stOu{+n>qF%Jb z8pU;u;%8VPkQH28Zk;~k;uTwb))ocPGV77+ddk<)B%0Oo^Xu5etE>MAutnjt#7~mz zPgItEMm}RD?xk-Ve_eZEt1aqIOH5T>Ow8M_RQMy;q8?VGOkDPGr3kIRHkxZX9~>GV{KZR&_uQwxBq*suObJ zkTY`TkSlWKkUMhcP-E1XLte;>Lwcm=kT3G(kP#U<)EqVEP)pR3LqRBrLm?=HLt!Y4 zLndV6PySv=3{FZ}>OdKwOm0>tM}fu{pTx)c zRj(UH312J0Un{XN*>IZ|CvRD}OrnHiNOKH1fmW8MEO(5^SpNql%vV~?SE9kpQ7oM- zzV5s@of3}7;YZ|nc!x4+Zqn#eE9=oAK8f57sTxg(g+L!ty)Cfibx|6la%F&+fLF5ny*z)6Svc( z5hy~-GtaCxx6Ur1?X40zRtbrqQMBrPA?Usk&TzG$sTS-3YZ^`6b!u{hK6Gfl7yZ8% zTfywp{1UrZKK#Q?N~l0RDp0?=p;=UaaNo=xZ|G3m#m2ih00gX7eTsdaVk3`3p5kyG zcY2Du*5TiW$JzKDdP#@kSHb#Mp?=#9z0Z0jtsr^$+<%yy*C{3&ui*m8(48|^2 zOGUX4nu7qWnU127>{sv#~rIJA>%O>RK$X#m*pl zv08!U3hWG`m)3{n>)07YFIHb-`6YIS9>?k&NuDD)g9(h)HIlqWat5;it9vAQkK_y{ z8dfh$@@2^xxEQN7l3XJ>0~cd;xhyZ2oxvo)>M2=1B|F2c#p**@ekeNwmt%Dbk*5%6 z;Bu_4B=Sn)3|vn8pUC@&GjKUpFA(_xaRx32$BJ@{b(nP`%u365J{C+~tA!aye;nlD zN?Dh5Cw;*QvRZn2Mp?|`hV1%^=(`k za&U2I#E_GV6Nj8#oH^v`;>sa+7k3Udc4^EZFBdNk>0R_3@^$g$kkQ4+q2?~lIn>gn zC5M7sf;bf762hS{moN^QTudBl@6w(_(Js*(igk(QP$!p89O~lIg+qxhi5%+FppP5t zvwjWwaVVuh3Wo-`4B(y{=rWK)L)?ZmX0>FxWpZe^+i(u$y5(|cq}xaijdmaH$!Zzv zK9)lh1h)wSS9X%%Hi^g61nX&n1ABUdpxYq09}yfT4|)Ieb}bc=xC=@{=>qpV}>mlpF{Nx(%nbyo{z_^ z$=;q7uB9SUH&JxISmo6CPLHgvS}G!S#iIMvyBddlKcxw^?L=Lv=)Qct?#h)V<>CSkm2 z4_9|yxVExajFyT>-CFEE2Cx0HCMSsMk_xP=!0ua&UqyX>9`B;{Vcm7?eq;L64h5e>YA>tmWoK-8p(Zc-@_xm$jLpYr6N+d zM{@tf;L-0<)AgTesfg5FmfTlle$+rs&@R?e5vi+@+*{@9e%d_(dC{3J>z2#zep1^s zpX)n!YpICTos!)Pe!5??A?wSvS}G!S4`ufrnlU2>jtpy|r6N){g}9GCHuv+vY5Hwc z7ZTk{;_iK}@^FY}tD&_2iEbZpAHT@$Qq@;ZWm+mCbr*y_a3N*p*hcAvE=IKI%-h7x8=?z5#PApPtXP5PtB!IPO(s6HpHo|8CmB(>^v zrPXvL4%`;IrB8;GWgXs275`S;aVt&)wL`~{YC0Uq@Gcy*3x_jYjy2`j930)vD(ObY8FqeXdm>3Fwhv4fm#B{(Hiu*R(&F(C!#gzbE7_Gq8pwH>|W3&%j zLq}2L7Nd*U8uU4>52Gj88uYnV&6iNVWDP?}nMFb?C2P>?c>5PML+*C` z+{w+%fi|m|MQP?hn|;ipG;^TMd1g_XInd@2vnb6RXfugflx7aJS;{O*GY8siXBH)O zfRN1*W>K0s(B?L?D9s#bQ-kU(N;3!AEMgX=nFDP$F^kg7fi{PkMQP?Zn#;FEZ}s>Bo`rI0|Pn z`V=yr;&Bx+R-tevv+p6FdnknAaiVdY7|vw)1kq=L7{c%uqVWr!zC<)G5yP2`Uncr2 z6GIp-5{*SXeT!(^B8D>^uub&YCWbJ)T{Ldz=|70ZAO0HU@;M@gFr9H!G#=&YS486# zF`Vg;YogCJF@)i2(O4~pGoA8W^m#6ZFgzU_r{i!Cby{^M_L+%87@mcVvv~S9*!T?& zXF8|^`;_1ihSy-@8lL_gHh%Y4Zt%`ehmtz~M}XUBy0EaR|fLu<;sC zug1n|K5FnB`#i@XOy|A8#uq$&n&dxCGO>v~UGkeQg)%%t@}I%ezmbgJNa0LJmPkG& zQV7F4CF4#hoaxNnlFx1_gy9R4@q!c%I!3Erl6)>nAq-ba#!8<4N;1BZ!kLbJE&05b zLKuD{8Q<{qrLu9U9L{ubk?d0>hcH|$8;f~*x$IXihcX>~Og0{q!x=sy`<#$N7(OW* zPxAD8vhkiA&UE?%+2?^A!tgJ$@fV&xkr*eEaHjJo6Q9W>gyDQ*%;)LF#8^zinN9FD z@%fsBFuZ~oSMc;*#JG!uGn-)#@!3N{7~V^adwKd9Vmw2_nN4wy_?#ml44)^)^E~|q zX>x%as-oS};d%y}wq17+$9|S*NrBzrgG#c&}H27~ZZl*{-yJB~EHXD&D0^5W@$R zCI^)kuv|+WEXBJ*31ax1(&U`d0u~FY1*LeOSArP6t~9x>w16c^t$IW8zM%v$d{1d| zPiXBzpZ-KSw+|=pRc7rO2fe89;S`87f%5U7m-E8mt>; znn_xmpf$GZ6 zbP$I^qC+^;CAtfT5~CA2G$48ahla-t@5k!QjmhQE$e58F8XY&9v$@B{jpfh;A!dTW zmA!-_E}>+mjVn=TB}!oUF^YYR-e=nQH`M+&)RW-?F}gtP!?f>o(KKD`&hS|=`mET8 zX~T1(>73Y|;X7i~9kDmlhE-zQDlv)S1ycJ3QcouB7fN9Zr9_4|NfDc*WG3x5OQD;k z1cool9WKg!nRL7)x4R_wV7OY2u9o{SY4}VwJ(IgLJd4E4BK?^3n@u8SlVpb15z{)- zok_d(BxF75!f*xYP(k`K>2`>;J4AW_)&>7uX`?yjL%BaJI;<{2YW9Dk--wC8S=7xC zO*LXCz%JdRrX(b}cvBX?C8ghzvOqhzoc$($;}5$YQeM6&*k2Spnc4YRuzxIgGP5!t z+2DP2$}h>!cwlhK9K=oju2P)*-A~Ia<|&FTkozJsT%L?$+airzl5n(qPI7 z)Zhg2VrJ}jveS2R6HvqMN8($04r-Iugod&kS##k&JB?jk?`YL}ntB{+plQG%7mW*t z8fqGH$V217Ay17bhrBi39P-ilaLAxBaL8Zd&!HBY790xH1ac@?6U?DdO(=)jYT9xr zLKDHEC`}ZHVl*)v>Zs|+p?FO^hY~ai97@t8aVXs?-44b>s}8mr%%Nd6!?;jswoNvN za%^%qG{R;Cheo-Ka%Xjpu^Ur2{#x}@yH7bZQLvfFhhy^vn|y}due2=c`Q&tsCszC5 zKJ}qWtoFnGIFy1@I5bT_(*!G4_U}cof9FN8Mx7Te$~Amwqynl6CsyI!;2C*b>hP6Q zr$?cba1^H=#Y4cw^0?Rc?3NEAJBgUCvOAnajv$oi`l948TXF@ujMxN(inJ zBAHIRFL>P-{26{CXr2g83_lYz&lvXl>EM8hj{AbB@Lz_kmm%jBE8pus`1QnL)JMeD zm$37c&Gk+s7gkU9s{W=${%^%4e@lVCm%`s=fc{UH!o8m!UhX=i<0q79=b_+vC=v`U z8lOa73z0v=%aLX|a$=QFicj@`5)GjawdxmIm3v_U3AE`wY$7-~4U;Sh#A277SGbC4%j(tC*aFjmrMh!2Mh z8HS;Z=AY(2kf9bsTX1g=92Cga89X?cdtd0FP>$Aia9fTRF*t%lQG=qmk}*SKxVCg0 z(vd^)8Sz}p64Da}v6dyJC2{Rc&rHu|w85E!IW#P5*lTF^T+ffn z8I{ML8#8=N4nv=2fBGRq6NOgnNEUh zqLTNxQ~N;(T_;2U>rh=SgdP+kfOWL$6(RJB5WzxK)k0{s5W&p$0u)++B3P(u1qxk( zBA^B470S>(C<0VG70W2}9*STw%n4%X1TlieESHI)%ftv4queHjZWANG2cm|N7?GCV-+wQ}BxX9z(Z%%QhTYfjYL^|Ir_+T%NgqXa6p& zWQ(L0+}i`Y26A-ErfU7qDL2&Mlo~u3=0jj=$3Df4Z;hRWkOLW>DTmFJBN?6}N6z8P7s_#kass2zmxJc>OSMI^rbxC2dQjR3eD2$> zw`hyD;2v9W3e4!%T?^K(=-_scS_dV9XNh27qHeS3y;<}J(b9Tm@ei|hin5u*Ju|$a zD_|zl=ko=>d?5q~mhX0Of`=5`R2H4biwz`mE`RV{9LZ$H1MKzy>luE8y&hqIhO4or z8apxk0&89{9BgRxTcvYr^SZ%C6uc2dGGV$Id2L4i4DUjkUC4>yy-2f{;o$YF;`(_H zH0NeN#r99JC%iGF;cq_YNe!5*AhQ{o8C2b(q)QNn7m_i8Z}#;~0x^Wir`24c#7vjsF;u!ZfX<^Y$x zO>qRP%Pjt!%M@=W{>l_nnG(-%xuPvsbi6opKB;(vIHY@Q6w^s19&o#uuPo%0!$JQ7 zEADUCwKm)M-_3Q6FjPNW`Ks&Ge*p`@1p3<%`1jh=6Y)pj*q^_=+|G)c#l&!pw1V|k zs**_JUD6xY8fc;i39ly6EYW7F(sioRlO@I!D)EI%4@dx^l36hpDS<5UWsPE3qqKss zBXz2kHd~eUOuX(>y6#hYGVys->2XwfA9MjVvz6vom0*^rQl&JnQi35`qopSwwE9g6 zgG7|}FTyX6S|6>U0)MlZw3+R!jnugqcjMXSO^-)p`y;X^sB5}zBikQkI7%r<3G3~5 zhSqRi2|llMf~G_rUPQ{OBcD=&WgE-3pxvXd_YR-e_hWM)wMLAu5qp3K(cw{L;??A{ zLlv$1o#6N#pWeI^Iqu}slkXFo`^1s;`7>hsjMQU&{)*VYBJ~*_r`V5EI9#A;3KUy5 zCi4`ld5S%ZNzB&kS!YgnSfSCX1MmP_Xt-7#hzD|Lh&;re(K6*s4h@%wb0}BN<FR(e1*s>ClOpWST+LmW?85F~ zm}=Ftn4HD#%+-8^$s_CzMj744Dv>WFcQCE#@}NYDC3og(9+${*$(^~DPbKnHa%ZmP ze3{Ib-N8cEs=H*eOLk{77L(OizS3 z#$i*DX)3DQVo3KJA=7dc$2e>kGVMZfjKhv2({U8XIIIeps!$x`uyLYkoEXPAY>8-E zBF2H?OI;Pwv_*^q>s71%Aew#<;~0ls5lvUbI2PQf7ERS+9OJm@*fbr-F^>BNo4&zu zjN`t;rtfeZ>&VO4bQ#Anj;qF|Y8=NnZkiM^P3pur?i_)0RplHwQ#E|pD7(p>^qZpM(4-@bNKRw za_d65Ju5$7_L?vIGrUyRER~%YE|xXL48s6Ztu#^ao5=f&wWsyK9O*Rk_K$;mo}Ndw z%uzY~sN5a81{9}E^_oPENFJ<@A4=q*`hyYotKj5+E{33qVMJ2(Znq)YFq%Q}n+ccvjE zhiHcZOe+*pSuTXK$v9VVp3C-nbV;*1xHUg^4Xy8u(CLkk1aiE~^gQd1r~8_{(w9=o zOKH%DZnu-hE;J=|xl;APtCdf(soy&pSx=_tPkgpe!Y?k-eS7<{^?vNM`QVI)%k8BK zy4_y3{$6(aZQ2>-$n(+5=sc3Ge~_I5Ujz?qZ!^;aK8X&8L2n3x7F)hM^a#2JrUfk) zqmOCLiq)QcR99?9RTE#`&YrZ`8KvbJ=HOC+uCzSMaKiDfhCXl3FDNGJIbOyHAU} zJ3fVOh?F89^5q{(agU`0Mt>>=J>~P|UrUu@WKlKF(enAqLtujLi zo}nawZPM+%sJ)r#wlf^45!KI<yt%OcfA{Z`I!V8s1Fo|gVTWLL431_%Si7QgN@@8x78l?+wwkB^?`tfFK z#6BekW*=oVC3L?M!SGQf=BN@6lZUE6CE}P8!|+w5^HrrAZ`O9MQo8YGZNhI#GT21j zMqZ!s)3n1wDC;j1dM^`FL31Vbu*$uEF~FI2`~|`Kf>1wf#e$2T`CW(59>CVqaQz#5 z9J@a0bN82|16>w)-}gI4Yd9{%9~XLnZtK3W>k@|ttJ7%>*OYqKl*X)0cNNFGiU+i* zM`~fOb;XxMn*8&zpTCce`1d|K0_+3ITk-mMPM+2t00)Ay=lNTqI?qW+0!VpiHzte=Wa%t~8<^((N6S!w&Qejhe5EA1lIU&JO*N9Jv# z`X|(Idw2GhdE2NypWlSFQqr%KOw39vmHbPk7-prNmh`736SE-BNY-bhrnWyRHXq&B zYR%h9^)Dn72z|2}wtgu!1vPBmW~yH-o0x@hSk@nwO<<~+x0&jzWD~RECJ_AuVq#X@ zGNNBbOw5YgLHu`+7-q$tBKlLr1Xdh`Y$FvUq8m>J&5V)()nf2ip)*R^ZF9?_Y z9dZ5ljJWoBTJyZA&BCv#^4x&>Zb0cEGWyOsKhAQ=;#q(5mh<0&nIL)@d5#E`RN8DQC6OwrKI^CgnH0$NSx0S<$p*PT>!?bZRLb>PM?IIxbGbh2s5ykpA@!l7s8}In z1F6q6-C;rwllq|PEZ?1ETi1~d>)G{dJM<&UGfzePr=lBlOp12hwW6Y9eW)jSLI^$~ zL^9jxwBU7G@MpME&{PUe3||#AR~d$uQsx`sH-cNru01Xn8j|v3&+RBOGM6^wrPSl4 z)C+6@u-WMI4fG9ynQpEy z<1`q`RQbrj*5ALLO$o0_@N3cyT)@;p7Gv%|w^08Dq8J+g_o~>x*Q!|Rr$6_-6;NnC ztL}ypd_(CBu5ka*p+4XA9ya^q3qh6AFaITL_Ur?9>qN^$TQ@^WbAB_%obgkjNKxUEs_iK2CmBFs_epK*zYp= zU3LM#8U8McX#O~i%CupbHek+?7!R(k?AeEOj8eyvxnt{p@JmlaY#g%rlL z()W_@_fjCkN2GuwJpH)jbzJgi^b3;ag5<<-rKG83c<{<^bw@h)Q)nOan_!1D9Jkzb z{#+jY`L@vSwlEOf#-Z8;8T$txw`@eEvJkvMh=(yXpXwHTNQh_t=QSbtnh?)q=yM_X zxeyN(nNM{Ko`K>)p_@;23toldng6*D1@A-gU`(1%bqhYtGJ(yfx&_}y@k~oj6oV&< z@oWT(#o%Hwo{eCs7+fmGGyn6L7<^2OXa47PG5ER|&-~99V(<$w9+ZdqRJY*SIG$U zyhn;>9Cuj?zAVMFfvk~&YovIlb(hP*%jI~cbx+B`r`Wl+=2P8*AIkBJW2cbdDI}h8 z>`D^6lEgEP-A97=k$A?j7fA305)T|ZtmTlF)hDN>&~?*`LfeZ%6dUNrLfgke6dUM# z)HWYQv4Ji^ZHrJ88|YFLQ_2r?0d8A>qgY3;!fjXKDAv(sxNRAZVjW$H+g9Qz*3nOK z+ow2+b@VHuc}46%6%I?hFtKLnvHp~`*T~6hGtri@r1xM%stQH`L0^|riKzFYoyJBPy zJ%H5}$YBL?WOxs9*n=E_^)b!%b-0Hdfz`1(L3EfPIs&U>b(!d}OmqZR$LcoGVVmd( ztd426ufq}15m=q>-Vq(HiH^YPboY+v@LY5RR>$;w9*3FO5k>&hY+r{G>oLqMSD-Ng4i{t=B4(jVg=@9 z=C&^QWb?vwx-@k{=y*a%1jeQ^SO_}JAMABS&|DGhfj+z_c6reIH+xdOd`W0{NoWED znusDa{7q;AGs5i6xlKWhVMfqJdDN&FdBF_$&^I`5?d-09&^dZs=y_a7g^F^bFOUl< zpSGb*bB%UQ1j~W0APCXN_=X-AOvmZ^*tBJsY;`=aF=-RoIv{32`tV|7ZsoQ3$53n-r z2)XAa`2%1@YG=sF&*T(fMXFUuuh}FOSdnH+kc9Q57qBALs-)*3@&T}7?l<0rV?&cH zX~&c*!KF%f;DNkJe_Frp^;)2W#bV>dVoUgfyzNi#Pc5Bic0$Uf)N*Ms%&HNN+lO>n z)U%sF_dQE3&q$#V$sF;1&t^Go-T$OdED%~R5ZZzq9P!ibXK~?yQPgbf(YQz3O;3f} zyY?sdrQ1D)dh>(;C^j;4&y(~%hsRMaScp3=#EBp`wCWN}{{%8zgoBFsbG%BhrUcsq zedOe)2Tt@}YEC8oTLdJ>7S(4pQICrxzV#e%)H;_@XwS`p#)bb2_Sz)uUs9vw_s8r z?UNe8SR(|$@X(k$^2tX=9*5-f2l?frPWh1TY7JARJ2qiQBl6^sKJPfWr=llViEW@61uY!CD?$;+KNkC?tbe zqGKo|JQk9fSjPjSLioD7PZo=~Z1#wm5C(wOh28{4}c2%{rhhdH&hXd? zZJV!n`g08(@e4wO3qoU93dVFP*lQa0ho#`Lg||%(R^KA}&70|v<6h8tW3MjTy2LhU zC?#wY`fL-@!2J6p?$^`(MmIf232*4iv5*482fan7n77`W%Y>-Cg9v8gCwIQ>y>8Ux zNwjIpkZu`j3THG>I|w(sg#F-*26&)5O%JfJtOtBb5xt2Eh;#>0Q|mU2W@l&Dl%aZd z^*GePt^tQ!>|8k1(5@keJnTF;oT_A^o z?SeTJY8T3(wsvhf6k!*^p(wj34#n8TaHykQM-Ii?#d9dZE`dWyc1avccSzT>9vtj2 zm_x(r4fA2N?0VT8%Bh#bp%L{)aA=grs5%j^RmapHB~NXrBrxH4v5mbM8x;AOKRB^?uVOhVlj zq}zgyNvPL?^jgpXi<U3HnX+6?02~~ll3Zw&NLhT_WT|zo$e?3OhV|sl1 zyE~q!L=&X~Q3uwGd1s2WTGX*=y-$?(i8^p)XtIzfofUPUJ!zJeDBTft%szV~N^e9R zlaTYVG#~4jgxrj!%~%JM+~ zNzyUZ#O_Fs?YnRAUiL3*yO`U65x+v?I{a7ta)v}J+ zkF$t0i|CmBxQqEh6-25aIe}lkaO3X^o;|@_nl!ZB=w&rqV10McT)22s)}rM-?5I zHRg8he*`k+dYsuUgQ19L{Z^qZmsyY4g1(LIe;J*|8f*Ir$Hds)d?yXxA*t44o7 zb#36dsaQ21URAwx*^{*mulz{`{@cT=9vrX=|D<<*V@ShU+~G*{%Nc*Pg}8Rxfn`TN zJTk@#&bqkweee5Mrlg5**2TT$&5j#qPoD#4T{I8=Y?pWJ&QLh(V$s?{`(OPR(3aKS z;BxTI&3>L27VUtuE+*cb{^NTk#t-4Fi^@csDO2j1tl_MSE#=CfT_ab}`f6`**&Q%7 z|7Lre)^OIv^r_p9+Z-JIEu3}X|9;ov_j?ZR3TIt34EI~OF(8b-zxD=~p$-9am;apO z3TIuE{dDMyaeoGT!C4m{ewZ}N_sfsA!-k>7xjT1{UDv?@&bqMecX&bh^draNtP9Ii z;$FYG#}qj0Vos;U6AO|x^Wm(E3C|u6zue95132sA%l7(qhRQ73f3-Kb+)7z~!*bt& zJ#f~=9kpykvCYpj;jD{UFDK=Fe1CoooOR*gS+4%^ESip2?F}xG&k8?W+RmX8&bnB< z>1V&`Nk7v5slCBPx4vZlO{^bPW0l&bqLAU^C-0Yme=pce}8`Yt%1< zs_%1BlXH?0<|@o#s=kx-NdX|BE#F-b2nzS}?UU}0KGJ&*eg3Z85Al5lCA=f=MSxPMRDa+roW!3S1>Mk;o1+M4|ylofcO44 zhw}ZMmhdmpXr8we_PrFz@DVBU2v0vQ1s&&)3%?|3 zE=l%KeufoVJl}WPPc#OXnUKkyyZe)r@RO9nOq*L$$6Hb_z%!1vx)s~wVGW&4E3wZ? zs)pX(r8YCZ{>anM{mkO+5bAme^#o&aW{TrwWyx&|O88#1|DK(bJS+KO)V98}D=6U( zvcH3Tz?_`*_3ziWm)!2tHU;$$+yv?$*aXx+C__;Hpg}K`oPIbYul zY2v%+4CSRC)I->}Nx|Atlm{x_`h_rGD4zyA%Z{QYlO z6hE@LlH>~pazhRZX{|&4B{cl+1Z*{{ef2$i-`CHwv%HQgS zRsL2ttn#WJ@FcUk|=LCd}3WPdh> zIwZBH33pqlWX<{Zy9?lu^$m61yYpo1a&X8dH&3$(3;%r)0vCRjEtStE>8}A{ZL%<oPzhYkVhV&rUw@ z3MBI49(%mUUCx^h5_x#1k2{^qNTK!DUa2`L_D$b)zpPyd5*cl3`oYk}C5|AGm#nmC zHpQdWcOa3EMPHQ{_U!c>B(mY<(A?+AofAPKTl#!kWVF0A3ncQr@=XDO>86iCBF7wB zRpat7i8_e2S84{Qj``%1ubaIDi99Dia&*&!D(#QjD>X?E>})?bMFoj`b6!ooik@*n z^W;~Df?jU&q?|Ue%fR<*drateOc)3; ztOdT|%kI5=kVFZ^NK=e#Ay@?}fC{xwjh}|Wi|B^7x3{;0Py^$g77Nq|a}IeH)A@j0pGIjJ?!7mYr# zdDD`7T+wuadZCL+vch&aM*hKM7~W{5b#Yz8iX+5ESC zHRi>&n^Gs3&HtT!wP<^c&^sux6XmTU(xiw4fnl~}$Gj7}*B%&23F}endNc$^5JsBL zH&4AMH{V_huCIk=FyEFnT+w}D$tAO+zfDNoCiDW1TDG^+XT8_m6Lfy85u?|Lona`= zYeqrq`FpUoiJEPqJI^Xu*qtUIh%ILG zcZ+=`hJ7VQGWt9*XdZvp*fLSGOtfe8^P+lQ420=GzfaU$6YUwkE2?+JKyW|krd`qh z0Ud^4H_lzYs33!GOA~`0{q^oJ&2!P7(HBWH-#if93A#;9qJKDCECm(+_3kW9iDb{p zZ;@JT;qS`YEopX3_TY}tB~h9FsSDcC0JPlVDu3714LR(F90~3Qy^TZ;y2al;^+47< zknI`$xvV~y1Hm29s=v!EewRZS{!cx|8jSgW-_s7^f^SGLjqyeP(~vy z3i-RL=994bB$Ck=k)TEV-Bn)`&DX@9(Kis9Pag==m2S%;EjICYS#2djTlu@J_7Ke; zV$aGSChB1l2)a|N{zzK<$lq;sj07Fy@3uNeH0OvtlwWS~XL#(71v}}CStZ%8lDuG` zmPfa@_FH(v;a{L?{*HM4dq%ugyw_{{_J(s$Qr?;+HJBxNKuluAro`?65zm4tVJ=FX zi+Y3cu=2o-IVIxQ)>PG;k@RPz7LWsF-m#&7DYbwd8!M~3U3_@lvmUMCCuzt}QZ9rm zVBXUja{O}Y*4-`Xx}EDq*%y@6s$Uxn?rag6>q<3Rx2pi()}TnS&FiQz#b9A$lB+ zX!=5oW%{5h7Wx+4)}hs+>uS*e{I=$S z>zrlXLMGB;B?A4^hVk2GF<>*Zf!22TWRc@n{$`(Gs^mD8&6)KrceTr&{%1SdKBs6W zu6@gd*kwXbR$r0OzDP&}y#7|x!&2{!Bk5zsLUggv83^WctAbYWm(H#eH0uO=po7Av zEe_R(a#r6R(e;j4XZ686pv64&9(6esmUNqf>utdYzJKHA`|Xlv+nJkDDcV$u9?Tvo zm265S52pWj5Styu1IGJX$FZNZ)~sJmcZ95!1J=r6jFC3TZX0Ah!<%H^O>!W^TjhYQ zeECwjb*bE*(RaySyJUZc%jNgVS<*7~3uVnQ*@@9l%9@i5Z!(N)-~aJTvln{|CmzGS zVMcAbJMOEI>AjCrLKW^?h0|ebZQf&76&t^`BPG;`J!`~Nn6vPI+J|lRZMi;tBf7p3 z>-uo>tp~Fs%+xn@%}O>n{_Vl!?ul z@c3SA@;$?lWk3_-P6*_Lpl4FAN+4B&9!A^T0#YOB;SJ^+M#wy*XHst?A{&vONxjc8 z`JB({T!_g+tY=bcD<)g{v$Kw4a-7d6yowg+yWKjzdgF@Hz3 zod1q${c};R()4b3H%+{pKxgAk5`2?%f)t$6Y4`4CKicvsqT3<_U5VfZ5)sow8r?RF zjX>msrA(()fL@$b zWtCyIzFgmhmDI_)`V6_rZVeb}Bsbzv6S)ajvZ>ru$4WMnn{mib_T%zwRavb&`VgxD zasc=CR&pz@&en2k?tN|KHXJQn4(Dj?_(pA5RKcofIzDo|;#b4WeKz{FlY|H2;WX%b7b=!`LyuekjFLT$M8+$brbnB zT!l1M$cf=6$n6QzGh_D|@_2^)7=DR-U-H3~SIFxX@@MpMqGp`v#PAoQ<_jLr5Zz{o zdS*P&7CmN*ehhyl`hLX+Tjq&g^F)6}Um|Ljh)xU_iJBrFpBLTEi+X0fToE-_L??#t zif(sBJ=jj>;7Y>>Vl##xiC&LHe}=0?O||I6@FK}=k)#L7Vh*mjE#+~su|@J@#?($pvr}?nxKehjl=aN`zAAfMmHimLA^YCogD+psZgYs9IR}NrqmcM9JfHZ^=Yungh}R81ZNL z4AGn+P7I$Xn)3|r)Gqtod)TQ1RHj%VD+drvJ3|{p3~%{~`AV{R0-47Sl;0V1yYZP; zVGk)`8V;R?+d)$O&ZHGzs25uu^VF(+-1{_xinMA!_kJ8oaZlmUG@;%!p-y9&_Zxd` z5PTuHW8QD|eq)c*$QQ08Gw(O{xQ~3{N-}yTrRXtH^o1+QsJ|n66pOx7?`j%Vl4?6K#B^f=kk9b@lzHlYk z?(o1#Z%p_l<*o5btMN+RHl*F%0-6O!9BM=fB|>6}&>QTh-PuWf^EW-}M*SCkw4Pg# zTaRMaqaMsx*nlE7pss-TxYT=p{14e5Q+@ff6!5bY#zGHOl3SIeXZXJ4d!Iix@}U&) zkT3sOYW-Mh&&ofQyq-$_48M{zuOugi-$ppz1TNA)kKO6UFg~;t5I5d)qW_ zUUKo6`MTA7IV@j}hG59vHuui-+O@Eh63XO`WpW~@;=MJY0lzd~_}kxkQO=+{VHF;9 zA*{lKa}2BS;4;E0JOs926&~DhScM1g8&=^V-UF-fpgUm|9&{zF!b9K-R^fp=U=<$5 z8dl+9h+!2TbS139gKmRWc+f@vXx(lf+4VA3H^_YH)e<>!3A<7Tj3H{qrTe6F5zoiS z^)af8K<$^lIQkO~nMRA*bhYWrME)!xd6qB$HmK~+YxK#PWWVp}B%Oyk&O?dJrC*4G z7NT&5S0K#_wrPI<=azn>-0Oc!+qVG6FTg!up!OGzIb5;h+s`P$vYlldytvF{6TSP` z@(B9#Q~dr@JOBo&?1z;Pi$?A~LnC?%v2h^|fQrn!>3mjUBacH?@!M5b;ZCb?SD=?& z{(ss#_wXpHG>vnrPF1A{ik%Dy-HF|F(-ABTV_ta@7aHLcb@%km?zI8 zzd6;n>OQAVo%6o$cjZ^D)}C`pw%n7?+>-;Zk5}Q2eE+4}#G{;x9%0)E(O({!-LW-8qB!OHpSKYt&Zc4Xd$Q z&e>fwbH&D&8@`1TG1=%d+32TE#Gaom%$rtnDE%iJ_Q2y>K26lW(}sShjZwcX$A&#* zwmy<3#)tJGhxL)F^Ex){=c@G=ROfYU*n^6U;i_{vHtd0AM!xD?jt%?yDszKu*@J8zyfT6GSr(pv-8SVL)|wby!nuQf_dlvF3gk9$O$5v&hPGh?Qi^?hLP z;ED~^e_7!4p_TfemHKdXE3ZB`9-kDK#HO9^YxY8V| zI{W^)r~T=1!yDY+EW4kqSMiS}>wTQjcIGQ@j@ssQQaw0XuU8a&+->=%C6|Xjj?pS7 zJBLl1F32Y?$Y-e2SIeww*+=omqqh#a(YfdaqbBRj()X4g^%l4E9X6s4b4%PE zBkB&f#4RzSmT*hlMKkImx4=!cqNZAI>bu2OR57=}ZL*>^aSL3f6;(+VxR2LS^4U7peUvFtJT&Z8pQTkgZ5a%)FAfh@%3NtKCp2rPQ(!- zbc8aaD*mjVm zm}&*4T4D8`KA(K@uy`$Z9u_yh70tdC{w`~OeJJ?!YB#1MGPpvT**{l6-N7Dzt(n^`YS;arP;<56c3-Sm=LJC6lF$(L>X_n)`U&NsjVU9GPURbTe;dRz8^mCB?{Ikj57~t? zL3&sUOu<>-%lJB}`ka%|53+nSgE-Rr3I{`bf24o}96m;`4dUnp~N)u1QGzH%^qE&lKG;_35Z zfa;`GBWIQsmlip}zm2uV^}A}veIt8KDemRWS{4gyv3O9;T8F#~HM}4DMM$rAo^?;fJ%fzd? z`>O6yLCEc^6N3BdC8Bw~IOOHCy7{8@^oAju0RVE&j?qkxURwnR#(tTBW)OnUD z^5C9fc+>&}W}Sw6h2c?CY>530f4LD*Q*4+A40omBp+&e`hWnP`p+&g2O!r%+N8SJ9 z^O^2_rbpeEOB8W%S5qu3OjVYeqB~&#=`u z`t3`@gSuvSW!Hi-glft@>fAXMp1ZtHWz9~lTfM39_P<5r`6|TI6=Hz;Q7LmFp6`fm z9nl|F-=4EwXf356@P>({5iz9^^*`g&=MVqtK=naq`QxlH*lLu=?Sgeg5`I?+0=nI?e;x53tWPNA#K_`la{d_WoxT=1Hx7jAH4eQ@)w3szo{fRkO<+EMG3;N?@-Z27qj0AOJ z)PM2#aq;6isc*C)&R@(~qyF*d-%6Y?J@OCJ@%S1mTw`@r)}Zt6UF|ja>m7+`sI&r= zB-5^5Y?My-oo|eWH$>JOqNf@IFFy3qvecdCNi3)3j#tVr{ETYZWinHY*}#Rz!QXjCRSt^U9Ye?m9URZ;QOQ z#b`C0UJ6gX(?6xp6f{(5feNztUYc1wq^QaM&Unw|B2X?`s{z-s^u})&?G#^{)#b|K zl?~?O844mg6hzbquK)G1g`e-LD8IZ_mx&K}9$+$##xaeV#3R}l?N?tjY_h(ljGFtJ zGm7!WF!K7mjQl=7qo6OyD9#thsI9LpqXb_9qhwz)qf}oiqcmR{qYPgLqt3q0j52+h zjJo=|GRpR4Gs^MhFv|7iGV1N?&8V-hFQWmm1M0VhVI++m$Y^lvU`BbqJodPJUp}Le z{*f)|%#ZPpVKm-9p3wyV1V$766B$ivIjKG>42Ig4FEJ_*{sO^{ohJO#IKL{QvBypC zVWBXvpRRhQlR|7@!a`gm3>0uDE)fAt&ee|@MmEu|M5J==1`RIpauHb0k6$jr(BxA4 zO3?+Ad(M5Zqe@&V>{1a)yjs}M@Di^P_8QJ>g%^AFYQrAaTG0Z%Np&5E6Us#r=ge}E zMZ8%AHj5zV@Me)lyj@t^h0VDQdMEKt(P*c5ka(A{cZo>i-NN3@d5^I7aNaAt&=@Fz z0aAuV{AVITT^1cqLmdguImpW;t`q^(mEaskelGDb5qC_q;hcUh6eh{IKub9$}F;M}8@oZ%9;*f#F6sr{<3uX4UF?CYFw2>S--o5Bl?hZ1;T zZYtuDH>$2f4yWPL#W@E;X5uMY0GBe(VF;UvXJ~QAE9IO%L(AaY19_#yGc_AUYKUiP zHZG0Cg_;eaH1TZB#-);Yj^>3%MF~_SHbmnWY6&z~U#O)m)H-m^!Ja8`krpVT3}u;E zq=m7EO6|p3T(Q=Mb9%9s!MR7VmP=fs*)U8KFVpO0oR@1h_GGDjg=Vkd{3p!|jg1o6 zNQ7R*|5-~=b0mk;{;YN2oP%5p;xa8zrUf~Nk&{7Ou36=p%{jSTOX2+Ua;+=pUzBUV zB;KSo+N3>5yjin1YmvlTG#fb_#9K9cE9Y&fdabokf+5@sXaOXJ(7n?>EsSVg;tI{K z&?1QsXf~2Wh(FhCMDG$G)NCY+5LaqmXp)p534#I51AQdjo1M@?Fq;ye(!9`1a!!W% zl=zGmfPRv57-m%BYR!h8lK30V{)Y1<%?nMG5=7zNOY=Z)skT2H4#B)id_(g>f5|x+ zW>(_cT5ISrId_D)mG}oO0DUIsFwCyRFY7k+n#2XVUBG#&ZbQFG?XT!wXt09*XRL+=yDFj zAWdARXO-b0^~aa#earNxiQm_4gzgf5pxZE16K~LMgzyrV>t1N$lpqcg1HA?OA?g;- z;RM8~an9VKXAys>2N18uIsBoXM!a8d0e=bSg#G;aKGJQ(u~GXcy8Q{~PjwsdY}8(% zd!gA=f<3IY=pN{C)!nbdA()?uztnB$bBRysHq6k(r*$the@gHtVT<-aze{T$7xfU# z(!@1-4D`I56JVYuzM==9@8ukZnVR^zZbR=&d{eh?a=xW|p*d87Ly45@_{lPX)?Oyd zG=!yd&Os11ae?$8Je_l>0H%dA|1s$Cg?GNe+LH_*Or3KWLD|HwLLMYLDUGNjNr@|z zZK%CarWeW#&OHicF7a$>Bb=RhuCx)nP5hd)5!OyTPkN!LRDw!eA7wlgKeV<~B-5}C z$TD{cUdFGN32Obv;k5O#1LvIevL|u5^pwk3 z&Y^M?3s~Q8l(yxGgEDcm3~ZJ`&f(26jTmu`+u_0bdwFq3QWUpCwxRYNGJS{4;M`+} z%q89_?VU1`_(N%b$a%N4cXQq&z0kxeL99e(eEb0l;CDC;G4ixlctGZ$d=&9P=|QYK z=MX+6@gW&N%sl5X%1aR=svEl~Y751YOvRxF0JR^N>BnUT=N_m5Kzu^lh^;3+DQ%Ri zB0eQ;#Ml#`mR@LnmEafSiHyG}6KL)8qD;FeJ8;fH1$E*Y>8X*ioI|LnPJBfMuE-$g zFexk+9dqG|VzepPu+lg;U`xfWh(hE(q z5;RM=Z#^#?v1%>O;SfBz#8ZvHR3pea4394HEF(C}c$D~6Bl1<_0pi(4Bs{#tbBxG2 zoaY%fJiXNZy5WV!S_!PNHg0&}ub{Q&H;oX&EQpsH9{4RdhY)T-Tw(;^zu+83*ah*s zh7CUk@k+y9$+^_CP;k}8Q07y%SJ z;~YkECGlaS9RiSuj~Mn5Ba-;2VWT)2ag||LaXxO?D3(U;Ck!t%@k$UcArB9pqXHZb zCpn7oyE%PNzIUgc!&&EyZp77w2MTh|p=u+M_>$2YigL~!FOi%a0$(F|nZMp;BMFLg zI{vbeb(z0jtyQk%|zn4X6w0>vW%)$X2-ddstkd)8AK2>9sjzS^g4gN*UhZg`Rgq(+ajo$j$dH5 zUtp$leqw>ygLsh{SVZ+=QRT@DFQWW1l)^F75cEvPFEO(qwI*I_+Dpwy;$qV-=3HXh zC7hR;UU)K;Aw$CM7eopq?MB_%+~O{bM6SoAn|%L zh?GgrN$|vT&Vr+mxZG@u6iUwR;hE?B1RRINo6P_`^qj+RAQJB|b6|TQ-ep>FBocpU zTJYQxBTgETpDOPYd!J?;QZT9gQ!@@Jn8X#P4UazYXQmB@Bk|{^4bMLDLDLIQj55Sv zK45y_hg0%BheHS-B0gz);g92-j4&eNuguo)%W>|Aa3bQb%>ev!oWlq!BL2p-;in_6 zF>Qnw5&zY+;jbgUYX#NV4<`0qF;Bm9W?Z)R)w@i=!x z7!vV4GXQ@c=P<&Nh+na6`1OdVTlRF$Gb|haJ!+q6dEq%yh9mTM%L6|jX@Oq1LI_tP zUSN6Q@8g_|uqEO}R%`hEICn(&67ic>0RBJDVT3UemsmFZfW+@uHo}>Rms>Xcfy65; zFFaDpAO)F><$+(2_KMe9A%r;*ud}@H4{}aMxD)YuD*!(s=P<&ah&Nj{{Ds6@EF0lZ z#9J*JenaAImKUBaW!S>{m*s)~P{~Uj4k0Xx_+!fpKO*O3ghvrqSONGGIfoG@Mf`>qu*s>8WMSR4v;a?;^YI)%yQwFlj6aKPc)o&j?)1pygv@5#aM~!$BS5rpKUCkNA zxMCQ2U0z0hm!DD46=W3WieuE))s|6$D}hn6E16NME0s~2D~(ZxD}zyIS7%0%mxcm2p-;Ru!&%YKXH5OoiH`Ap65 zb2*n|(Xhk}E-_Qo#q^4d{%FFUeY>!`jV1PlT06Chjg&&IO);&yJDgF>ZAe%mFV^~~ z{)kyC(#+UoLciT4U~uV_wuN|>iO-xTIe&T}+# zj>e9!%eSS+*A*NguGGv*etccNEw$I>+Y;9m93d{(&2pW+UWIN}aIVX@rQ_@JZHebe zbDm_6UnR{|oa^*%bo^;)p62bhrFolkUA`?HUuu}827CT3hPj1vUBMAL{+?mp~oG|J9uNZG*lUO_C;Dz_>Qu%$iQ-%x{m@#1`c@{tOKZv>^+$k!qZ(oqV&yA2#=X z5e*kazYAiB+IFqoI(^&tPM>v0!+Uz(d-`a#UVrtE$A7oj{m0NxK9}dKv{7m!$nm+n zP^-PDHd36LUHOIjIJGh1)a1%Pq>obz-;U2^*ady8T8PFVZR9OBMyrJjq#hX0uQNue zg$AeQ)$n8Hcr_74El)H5x;aiw><~d`jd;!ajhZMqK9}cKTQ8`INh9Pp58q>rR}+D& zpKtkMOXir%80($eb-KfbMcsJxGH2W_*BZ&{4%Ja-rQV@C=4(yo%>PC2f<`!1rz66r zBeGSMDpj2da-mb2b&B+o4HK&)VyYvOloILs^8H!oBOY?3t9M1;yQ06^{Jrr}W#-h9 zN8UgKmQ1(HkXkiWY7abhlei`sN-WY4b=_j-iv;z=clz`m(5vIDFLBspJ$AD0r!QxT z8N0;vs|(+qC9WpxcJG;o7uu%x-KO_f+Z{hNK00Rnt(UwwOAwKih%QRk;RLq@my0A~ zh(Jn3Q(}ld))4=YWH%~^SmDG|PZLi~69d(Ic1(=DSDFLV4U$tED5uo?rQ*NMulUco ztIovU9~bYBi~r!b_@mvv!>RJZ87(l!_eUquFR!V;DWm58=8R(eF^s%^FC)L-&nV~* zGK%xZF>32?%P7I0z$n?D%qZ2L$|%jB#wf#|!KkypGows@CZn$Yu8gw%*^F}hIgE1s zxr}=Ido$|m@5?C9pT{WQpU-Gy%aQdyWz6wgj$t&u<# zRxdGvR<1y>W1*FsM*L%JWcHO=V`pH5gXn8J>AD&vLgckmL@Qm_j|sEixt=#R69+oG z;d)42&|nJJyOrs=ihoT0-H0u-*H>bog6yoEXRtzMwiyP;_KRGjeb045rm2YBEus`F zMHOD*k+?@#eqx1)sh|wXdyh0-IXh)WK8D%~`D}$8rgm-`yf|$15NCEc;l;cO9r0h0 zc;nA&6aUsHAytOj#wRogsi|Xw25sq|@$}CG`e)vlp`#OlF`-sM)1_fr5q867{$_z@ mEtMrHTRr*?mhRO zdv+l!MWILt76|0pl;;gPo5ocj5QyQg)n?J(><0txlQlIvTW6`z7wR%BrV71QXUR&> z7HA3z)Rs!Cy0A>IGuk2}{|WJ%%Yd%XWYMXu_6@CS!EAk*F4EuMzu08Z`CCop=3>3o zztUtWwVE}BI)9Fh*{H6x`WKYz%e39FMPt@$)mDRAqt)t-YJ;`N>TfYw_1ZFZkj>-%1Nx23jZRVO|2_3fJ|&Qy|KvpR1X7( z`2Ten`(s;72$}^i-~Ftuhom`DgAn2hON0rm`}fMXl9Y3oUxHO>Z(jVJTS6I-OPx0aI^!f}A-= z`m`Ji$NOnG7LM;zaV$LJC+t{w#!uF<@O+=RV{u~rq#X;#`sr9Rc<-Vj@M4vETd~@r zvzC|HAY;(}o4K0RQfN=tP1d09L9xc7t<*rNpoiqcGMlRf^v1%na;?24_>F148u|Bp z*?)<3Pf4RT_Y_HL$aVhv2jLFOUGz7(LCxc+VoYWmR}}ddY05N(HhrN(dX~a6t~RoN zJ$ArytHnW8I3_3_{`g1u+pWm4?{5=T=nA3e68yT9=|()}>bo%x2iy(uZqW(koRt&! zIMj0_j+=e4J&xPy3!UR>H_FK_1ZK0^W>On8dZPd;z@Ftj)kQZ3GJGeHFA>$;tP@zM zDJv_`6qf!9Z7nZQ3pitRuIRcEkBfmL;l;o~1`|losy5A@-A#_5u^V!d5l3qWyJf_K zoQ!w~FTrDaq~?U^c2eDI_`1dp@_B&(>TJGRhZ@9Uzgvk33=tRN$86;3$19*=3G^`EA>8>n^9>#ermp3)ojHoc}yKNom%^4LfV z1k{_K9{=kD!`FQ%R~G@>L3}$%WY3pC$hC&x(`(H7!Hw6xH;Ac37r}GeX=Xb;nr$R> zBkAj)@%;UO#&MEdnV3oeng+r&kU%zo4qzMH{{L>{biU5trKo4J5LP-WX=10}-CSDIqV#L%WnE#SyzNACgW)1us z+i?4jC9_@oPyry914MFwMD=_*Xp;9{GoCw}w5bmj2Q>SL?>-XV^TpF#*<^le?d=U> zYBKQpPRM*G3}JT@dbiVwRds?ZKVGHs#gsqLEOlX)x_GlWbPj)-RK{(|vTN=iP5g^}zQLT@2s94E>5ND%!^VssT#=|FRpX0Fn{>`Fqf zB>Y*_iIQtK7X3X`OvMAuJ$L3Fyiz@(>z!U{)~J55kG=|M7E_~vW<6on6A2qahYWIX z(r%4NV~VThh^YvmSmnyBa`k45=ptUWMe|%f{p^E}7mKMZptvGrt_TCz?S$S=hB|h6 zeordfK^+|?rX~W-c^Bq9yih)!&+qd5;a4h|+N_acYAR5i6f!4;(QGTBTgf=bF7s{_ zH{BaRtNT#Npf8tpJ^~&Wzp+BAMFQ!6) z=8y|>$YlbXN9XaotlPZm>da>*fliJGik}JdGw_L{<9LcK*|V+-JhI^hWkB(iO9~>S(ChWB?F%<$dTV0r~E)q7E&gEZu$2YtFuyM^&y_gCEikmLXO*n~$ z*6@6Gr4_jJ+F_~@Q{#Z*3&MOsyjdwN4L`)?BO|u)*>^6?Apey=2C=Q6$ z|9xE9nInBDC1^oANoXfIJzox*Lx!{sLtL`NV#*J8`Ich7r6g#Vu?Gm#9hKJBJ?8SL~~E;d1r3#PsEf2Xf9IBMQSXYPN(yF@Im6dAFqDqrV>+f zpjb{b%fSvC2;Jahhv)X@mQsI8J|m_gfu`M+X?LB#me3`4Q8#@WT)5&lA==1LMAJX#Rygop)f-ozHADcp_40hc4m&yb0 zEbV<1Gb$my60!1NxePsyh)s|rL?P7sZz*ftPrUaTa8t=t$rxNP%)_Q! zaK|k@PkdgsclP%~fI2)ZJQm%H=O=wGobjE%7SIccVj)RG$@d)^b?n?J@AGhkxPZ7Q zbQ2<0<}C|FNL*j`aNAk|1FLIDW(}E+al8Mf;eRZB(7X#)S4USXG2n~X`4i_SAk_bZ z&dya`f9(&ewXs?SS~q4PZ~=SnfmguP117kX1JOgm4tg23+_*YO#HLHq(rLpgyt3Jmcgc8brGI3CIm%vWG=5wU6?bsP_A0yK%}*hFlB zcR?%!i)(CLcUI^tVLWIS9?0_%wa zL$8QkN_>`*I38{w!3`uC-G+!=MkLEfJP$V#pGFdgswZM!C1YMCkvzPD1g#)R7+geb z6Y*^#GK7aje155K?=Ek6SZ$zIif<-jbw0WEB%<#baWQFym+DS5 zpbaWRPG(Qago!6;hdtfIZN?jPdGl8O@D0#c=TzsT_Kkn|V{ZTVU26cXP1a`O*(ZE? zy7KJtn;C#srYWbOd%#t&JC~^9-oEtis=_<(?*Qu3u+ms`#J-iUeLMEUh$282B^PC4 zhU0rI{oO6QI${AmUok%o_mp@G+ctgT`UgNKNs|)MI|h^r_mAC~VE|F9f>g0+-y$~E zH#GvGKugpT`3nKhz}keQgbefzfvY0U8TZsy19~w@UQ9AD7=><_EgkDWa3M@smDX&` zCd0Jlt`~M^+yHc`tW=5jKy!v$+mmm+ckJnhZ&PyPVxSL=4Nbx%FD|RR_pG*EEr8BV z%vGTS#7rHY-JYi7Ht`Q9R)7Bc%Q8<9q?UtLlHr(jir@{U%_I>YRRlpiZw)EL_$~rh zAGMCiF$##lRYbH98Tt+p1h>H($q0;lA_zf)Hj&{NokWoCj@?51FcTI*svfnK$T5o- zL1HLtB`KIQiXh!&wv*AAiHabMFgwX;j4&c77>4gA2`f~!IhjmHPHz4UNQyptyp z*8SxSFiuTOO+)QTJ80Yg>AaIZfHup`O0=-_=`XKOnin$|G%qDIB@1l;EW%%@LMUD9 z`R?A@lvY?P3zNlSNWiV(2wY`@2S6(YG*`|bI=ffmTLzuDVF1V}S(1iw;?yBzC5d!a z2cKpV$g4v$nbu6yJiM0pttBDO>LFQ2f_e2=N2abLGkLg$OlTqgyt=fIoEDPD!y8HH zMiS+$J|UY(q_g_OZz0Lf>Lb}of>HjQI!)b5X7X?=32r43ygId#nXROdhqsgP?Igxo zy~1~r7-#j0-c90BAF?a1HC(ShQ3A3LNeoe;`AtsiKkm!MXg7Gb4nlVjPs}_-pjY%h z;)#kj`AB;6xUYS?V0~0XlngT*^ak)qTt$hGgasv_xiZp$zEn0g-3kXzo}NB76}UHv+6OG--0K>voqgKh1#CvJ?d4iol*6DKgp!Gyia#0eAtOmL;8 z1AV=I(3wB<&j-dOijs8nY6a1y-txw{PXMh_sFHM$aVzE<}^-;~E(yjtP zFCpg=;jHvkh<5d#bI(IK1ZZu5wwL`lG4GvM z{N&6LDQqK`%as^Ju^9kv+1?32`s$`H;s$u`rhvXgT9SZzRefds-q*xorGO4ogr#GO zJzx3F*_l;iF92F5lPU3#$OTTrH4kua{H8p*dj_rT%ZgqAF)IQ>k{sILDx8oWfc)O-E!nCO`{=5d(O9Q1+v>*{1 z;}a8x&`S58j)y&H8x2H@h;$KA;n}%FC~PrNAiT=wPxD{6H#ZLs8JQfJiKc^k2)ymB z6y%P=feEgE;y`yUy|=bz-WA|y2sX$t%!yc|#2AIpnyS<7^=tgj0xz@5oP%NZwa%5N z5594v0?-PTA_x5}hx_Saw*Z|oGi5f$@=a}7IYIG1L;yNLnvjU9x%po9$G1<7 zeiqORau(#{`=YJG0qt!dJmR*Ei{*;@A%!4}+>l&3rhiZk`%RM~gx|25YY^eu9U*VZ zOt1Vy25Un?LgeUu!5905N)bYj1Z%n05w69@2Q=3&LUfztMR~!u4<^I$jZ$MGil*($ z7gtp1rk?`zoTND!_!{kh>US$8ZSN#N>*P8W=4SW}dvl#8+#53uK-=3(IDu{wCb*sw zqOqj}zQo>7!ihJ-g*PsE)*gU+x0A?rB1cLQ^j;G7kW_5T95hXyQQLMW8weG_3K_mA z#8gRA6hd!BjSSrOaTixIEhbruNgk>@dVM$+*Q7%3huwa6^15qey^DwqiVsS|NYC*O z-9u!^TLgLg@B_pb6ZyjnJ$x&l8@LS1@ado;PoA5J zK9;M%Q|rhS)OxPsRxKqt&Jiwc8JX%F;S{fubms_{+C-+HXTcYNm#{Yj@hy(4yY}5W z*u>Rr(^95op`GB}fSzj%BK4o^>Q;8X*JmA2*O25Il8#RO{e(>?H{8}HfmqGKW*MqC zD7$1%6he4d*wo%j#BEQG>b!G(!u>`NYq&AwN#_OIK$Hz66VEDwCRuzVN#O;%f~2e< z87SDU@~->F0sb>VA~6v$GIR>329NkI|Mdf0hLtioB@bQRx$rmlSIvL@1c<39utB2LP|g*hmG&M67yXOM4?1 zH@)`7g{h}*o#8ZgfoefE#)r@P>UWxY{e3id6WI(U-sF10gDcN2?!66W1o`q zd%o=?jQ4w;WMC&5iP_in`>oMO;K%adH>w$Y%qrHvzqfOkG4~p)2_2qrVPYJ-hE| zn2@XFIT(JwU3fp@g*VeJfR2&JsPO5(ee0z|=IGOjfX+?Jor-?q`vsTgHV;`K;Vd^b zeTtLiPR^R?WVx9+)153gGk?01ZY`IyrB+uD$GwaE8XUolQ zATyjTcTyvn>}D}f9^$cwc%jiee68QJZSNjygl+Src?qbXKLzv>Ef#Lp!}=N$ zSwj@)Qn|c2WC@8w7!3pXbN>&3{2#Gi+g=H-oekR>lZ+XdZ&-9?8t#`iu*)exdI9{@ zkTs9MRB!Br3IxOW;Rt>>kROWp;WPYjI6v&m51-|S_-iA8;eM5*=fmJYAQ;IH`}0HY ze>HkO18^V^2>GE0KOD>td-1~|{Lq~rdh)}e{E$sw-gF}2Z)ZPbhK(3G+|9$C7WV2b m^6b-B+^_$DXP)&MIB4*Yp^U(dU(tsj!jDSe#|sAn!T$iZUSRJ4 diff --git a/.cache/clangd/index/rws_state_publisher_ros.cpp.3FFEFC4AE6422D83.idx b/.cache/clangd/index/rws_state_publisher_ros.cpp.3FFEFC4AE6422D83.idx deleted file mode 100644 index eaf28cb2952db6b7513fb641f4a142f08ec80d8b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6314 zcmcgw33yXg7Je=1YSN}nn!YCKmZmKNXeVKFnCXHxg#sf~ z<7#SjdP8wlm7%)EP*pL`3+Zb#6(t5$V>Q6ll`O7Rm#G_m3F{hldbQ@4xV~JgE>;c2 zRqE2>2~~Q7R#R`N(9~9`HR@`8vA&|Fy1;4cG?=f&)#YQwF?71iU_CCnO(sG!;%HkxudJRR*87uD%-PH}Y@O*Ca}X)$!z4V^B^Vt2WX zRx8zRbecPjPTF9xyJ=@Dqhzt0tR6G{yJ%ca(@j#R!gaad-G=$G-q6xFbS#WziNt46gYH6eF(=0Zs!|G{kqs>&K!&Bn0by&eg4NbY* zEl#rme0FzHT_&6PHo#;x+S@3rrG>inl%7G3Bu8T4o4KIP?olYxbFkYj{;LeOcq~@) zuf+U!EJp>vlmy*oGuT{hOjX=U{cl_MUGD638Ei(ov5j{AQ5pycIPwR5fW_d#A6)D- zc38~+O$2TcxNHWa*=(`@S4@r;hxsY>8sOxTOjn^C z9c~H)s?BIM!tpbCW9e}@sTPZ!GC_MR(HN)Dr4}pgy2)m;T4=kQgfl|@h5^!nY3p@5 z#(FI>uC38w&<$(!dgx;M3XK|Ls*&;X7H?kOzgm))hqZzOc@*{AW%_#}Gg$P$a+D~W zv7-Z82H6fl`hVK}wPgLj{qVRgR*Tz0yZ-kP_>Gdm+!h;Ds0n69i_tU%b9LET?t-D6 za_!8~?`J<+!}q7sFfu`sFhUs}6di>HGb0{;E}iCYSxyN%dDsXHBSRuW;%u? z-^JEE(U*2nJoAFPi8IJG)ei%3GAN$=EMy)PBug3tm1g82iHZ=F$J_$r7? z^8NWiXop-<6eSXSC0v9{ypl9n%JWL{2)Rf(Gb1LdY#YHPQ-V`?h@4B-ht&)8lMVN3 zs}fH|=+5>N@3psp2W7Id;YcYmF3gdCkWPo)WhP~gTBn%PyOj6M)kyL{-N+~B5uh#O z$oNQG*v-G|nK%2N2e>q}Gz`Hab$0jto4y?jB*~oQ_}=uxFTaqKd06z&M_1+*)6Wg# zl3Dp#KXi5Ch%qJTz_1_qbID!*CIYg~Fx%ia-?TLU& zkku!nN{|Iym?n%B_W-4^Tv+oaq3JD=t$01DqVG&u>^dR9MWIDeh%#yQrvcF(PctO3 zA*LY?!CbOQ+!XJXCdEx+olDMrxNgC+u8&|zqp*>U8kcO2YG$*+B@H42o8aWj&y4CB zSo^Hceo~&D8D3TSbSC&Di;%HFL1z6zZ?=&gr$z;vhh51U-rgFb=ko6d?J`MOBGMZ1 zGiO8J@wpAaoi{v>==pf*%Et`y1H@eFZ>vHjp*|)l^)sLE{Hc1RKbOS)aRI6XaNfU} zJ-6vt-piSFAs2ksW_PkuMPFk8*!I6b1;8$IzjvB4`}A}+ocvH&3G$+ zd_?QIuVJl&Om3a~<^UsWG6RRmkYiAuhmGtJl{>ebe9LQU@5)7Li zSC|m=?mc{f3r7`ZBkeh5-OWoc1~OAdC((^S@Z8mt57Fs)PXJs;)~OM^U{>z(jZ?2o z_R097q8XI){3lZbIHW?L5H9=aOxDa&>t+tA6e^>(uk4wf*M+^vA&F=L&(%#@Tho7e z6o<^kb7QQ=a%IJ=zMUMh8n2Gwez-)}zP$O+BX3U}eOLGPAHjH5MizUtAL}`I;Lnfl z{h5IUS!@elGBEY~<5NB#1+Xwo7=Z@C(qn16#_o9P?4YY}%|APD&sT=$Ry_O0Dq7%P z>9d2?r3*?5``3I5B(>aH5!&yXf#5q|`*4OCN=m2{mLYDC>V#IW6crgoAZcA`Ntkl^ z7Xlvx>rb@S79J;z;-$AW;+Q40J8q zyudGgRR1v>Xj3^9JF&M=2ZlW=sUI_F5*^Q%>R$|~pQg%Zv~h~f`vhEMgl@G!wUR(F4-?MG`#wUR!m&hHB{C=%;>GbEvo<73ikbDV$ z1gb>1lT?bDyb@lE-{qC0Rnk@@y{>=i0qRKBKHyCWPhn5q_8a*b=hBxC40?ggq1gy| z;9)%W(gPCQpV3P$nGle`GVKg_VDE8G-h4PK(n9HYWS2`;CR8fX^>^pe?mfM)ZN3-0 z;1%)8kbXGhCQ)mi9Z4T%lx+~SZ;vL?1ya>z+3lh`Zy z+Z&&|J96_R6)+KT1bgLs=WieFJDKBRnzag7#XP)iT;0yP#hN`w=7l$B9b?WYl}@o| z^zVy4myI6YhWP~L-5F~?JiO{Lrqfgt)$B1jpdB`*|IEj00gecZkfA*tuuaS#d6>tH zoSN*KF=(8<-*2dB-Q-|~{m@JA2jkCuy+{?g+Xp^4!##KV=w($to*X_e$Xap#R6Ur~ zj?`A6cpbj}&KT>K$UpmNe>~#sb$R=_NXU$+NK}Cwz5TGW^+oZ zk{!y&f;ce)68J#IZ-wjUCSpz?P z*0mo;{xW&;qD5kyNDg8o*<5!YfI`rSV8Q>1p4ZIwvy_n1qo+9G&5lAN6d@ zX#cU2fdhqH7CtKC9i1>e51fQABQftrw&bU&0aUz4!b7_lD&SP;b+!G z>_5E&;5u#{dm}iTq?~;!Ny*%<8zLLn>3Od3iT8K!+j{;EIHN)Q5aceLQL#wsm2e3j z>y@NDDfZltO(`5VTe?f~fcqs;yc|^xWB;*#skM5ih%E z?w)h*Ip6utxwBJyCnm0>2-#)qeb_NWElCLJgf9&P>(c~m*qWNIR6;E@?{8FXi`LCx zs$3yjwW@G^ z_pb?wSM|cb1JLq`@sp$b4n$ESPrGefg)1xENrmh9XoEDg><%VW3!#ZWT zy4^6E9b3oTnvH))_J5Q*YP0I&#HuhaYjAje$Yw~XX||?^mL8WA=r$Xr=Hs6op{7e= z0;9QPEq}-Zme!%YL4!Dr-am3Te3V-icGcV(S#^lPR*B<h7+1 ztx-im*vJPeX+Ct#wyT;xOXvZoTH@elpX}H-KYI8!k>8jgLP0L{M}i3KH2_Om7IxFK zN=f89z}_eI4M!rj4_y8Ji(ejprrgPIT6tFpJ*l2tY*)r#`)c9JeZwN(3FqaV@>C>Z z`#m@O)_d;sol7Er9oS1-O8t?D?fZ{$;=H|hQRGFi7xxt(j6`fd_3d`SNL;=-#dACn za_zaENRV_BKPPZsr;-a>uYYAwyuHQg8YBvo|hv^Bh)?=kwjMJuqkJ zG!Im)FvVpehA{D#kB@G909>4;fWV`%VZtfG4S%!{cHf8PBQ#LoBU2eCM$8N36o2ISdcyWNeqJcAqZ;(2HF44v&%!TUfc}cePUlPmf@Cf zT55aYoAaP9iKWem;NU0H5$*8oDV8!*=)#o8pM2?o_n(;WU^Hf=u2nQ<V{xPm}fd?uQN*WWx^d-*+X1WJLfqH&?^(7DCr*i(R_I8wX= zLoPh`$eGh8jy($M{I>ik7XI1b56fHYKW+lGG$0KlID7&CHdYvWvHI%;`R(L!@RkSV zQ3Q{{ppUDOkifLHjer}cA})ZydyuNEtTYqN1%K4IHsFR3;mci#$KE<5pGc)Pq%+C3 Sc9Lls+gsa}OU)E*E$ts6#*B6V diff --git a/.cache/clangd/index/utilities.cpp.BC8AB2AD8B37CB17.idx b/.cache/clangd/index/utilities.cpp.BC8AB2AD8B37CB17.idx deleted file mode 100644 index 6871fe0033b4cb9ab57ee169d5e1b2f80831272e..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6130 zcmb_f3ve678D1wgaTGb27;uOQIYXY24(*k?z#H zQ*75f650~_BD4)19)S|3fzkv@fuST5G64#uly(R(5FX_*9b6hhI-%4sK%oDgys{j} zi3Qczr`v!3=l4H$74)^X9w|r2E%^qM*boX4LZ$Gp8=72S0x#raVJ?qoGLAAX!@$Xu zp)-ccVBHWR30aRb0wb!5f<;4C6|y5Rni^3JLNzosk-*wAoeB1Y7#(Yyux7JZ7+-Xv zl&p{I!%{V4#IXV#;6++A(i)Z+3G1RJr%W4alrT)P!hjYH1G|DHV&w9apb1Gv8_@Zr zpa?OnF;P`x;({V2WF=>TTm1NqGEtc)To`ngxZCC9D{7 zRK^+y8aFCJ5}RAZUqjGh*nn70hG$%}q7t=ZSn`IP#A@1LWJMz0f$sxx44O28@_-1LN*i%a9e`{|cDt5__>!2%ng;&JQ6{ZG z89;DTRRjb#UO*eLM!m;Ijysr3pnQM~8Cbj;LyafnvhMV*=9YjZNEUu%wf!2S4?6Dy3?WUSc<( z8raUX0z!&9Pz{-Z^qAP2k&a2}BqlRsf)c|_|0-KegRQ2vnt|sEhCq_l$t;&`*v8;N zF_D%??Glz87_-gMM6=ad9$Vo7Rwh8*V>^~{9|pjG^eMos%91s z*V&j>gLxY6M9z>|9zNPG zI@5YZ^gNzN!5O8)tSs%QOwIS0I*^G#L`hCRGVLV^vj%^|W+$hQhq7 zqk|80@*TdGaZz5tK|-^|j3-ZpRVWOAr46!!Wj)5GmSugjB5_jp@f-5p^* z=PEN)Rz8L?V1j;Rke1hLi}21Q!=HX#ko6dfmWUlrYH( zX$L$lHM%C6N;OrlGha@puLrR`U=yBr(9i_C)MRbX8St1Da^@R2ht< z<%Bc^=FbRpqM8*)N6;G$q7bA(e<1_zDH#e{?a4JVGHm)12dA}gE- z1JUglHsV$}fpv}~Sxm@qZ?HjEaFbNpRMgSg*5(Z&I16}pXCRQ7NW3=~>0porlPMfUCXY>;+4B4-H_?TecO z&AUP%Jpv+|Q1&Lyn_*|~k0=UQ*g5XZJu;oNjCI@;eVmiAIArYqYI#!j zvg)U*3r-UgP&i{>wp@=$!O&2|C3P+E$2D>=(BN)`QwGZ1op=*|^SA*5x#H0cIE)Mo zzbDLVD(NCPkNC_TRm5nMDoaQoN=8QDXH)4@SF~RHGxb#~TC)l{+bY^tI+`k)R-)O3 zvkD8ovAV!fP`&fJhc^7`7yc5o5;#_uudXv62$7#*@LBat{Vgwj?k_7rb+GR|+gW8k zviqB_FS~ftr|%xLA{Xo@i;^oG-9_Ciz{2daW;8T{g}ookM{a&^c$pP714pDNve3~{ z)Ugmaii>8p*nwljaml`;pAV->P(5(C=eeuRN7lxtcYk=S{KU$|C8!qmJw={5<|DhW z;i%5dMyU9@UxtSc?K*FU)!FUnZq5ep>~r*GS0%9p4f5^_4;BK$b+u$V9j zn~ZBtl?}smZIkV6iEDmOw3Y|U0Jvpmf4=eX+@uQm^*MZ}FF+Ydu zUGmXAE3ZGk^WHo(Eq&nU!wW_it}d`T{pa}0s3uwpGc9HbPzZpj$$uGTvO2?cVLx55 zTe&B1w^Ug2FkXx757)1seJl?VT7!iav-ZXv3(X7Js4G@y@4Vie6<@(O(7ndax3-S_ zd-N%Qu77@i1tr@rI{xg&vxMW8lamnQLfPa(;@5>bs0buJ5bhdZb#vW0oZaqj@A%%t zRQ7VcIh=i5U+&7?mz7&1-m~Mm`)0lj$?=@;VQB5U+P9;#_&+t|0b2|E(FeOe>-te1 zBJD5jUXc9c#eM)vw#X&4T0^tFk0o*G4d7GzvUZk+7}}reI$wM3H6TY8N9rl}2H~c@ zJv(2w=V7=1#rxL2^4ljiV^T4Ug{j;3nmNzyXYT&bYh!wAo?P=S_nuuhWO{t>;IZEisQdn&nL=|% z$|JSUfBOe?n!*$!qm)+q<~v^~P2X{E12|45LS`}}wDpre{wuuxGN$LLSC zG~T-VJEK?R5zqGWJ7QOJMgZ~-H}XKyV{hJb|M%WHaML@N9&A4F>my^D_WwE9Ud8I? zW+FKHm%kl$tqE?=L@?sI`jTzGd3xmLN3D(php+o7%wU2Hb=7JPHoCg)-hH>@GGj*` z9`3N;@QLHS)#skn!gsa0=T_hPc3B>p9^$rNX}`_W1gIrzlFbzIhfesm=xe(-lj4}$ zUrvkT;k%xFea=%?9sx3L#p@_CkF0v|=HWv}+w(x?(bk&=?{EI+VTiy}>1n2oO}hqC zPR>S}^2fe()E%w8^>`kEJ-*IiI3EAUMv}xvY^Sb1v+b>mS1*sDJTyK30`H6NQE?t3 zht?f^f179C6M2ZdG;5^spoiHH&~{$XSw|6n<%_4+Bp#f1OCFjIzk1-q(VcIv0ZnbF zEqi{xapHp?x2&(+1GT7BD3vtRR;OB_W>;?(rXSziwSE@Jw$Es{QZL>;6m45|*%xjA zGxrdtJvPH)UQuYapk~`&XTKa+toU`_KiuHf6|8AzEX)SVO zHxT?*PY}5!EN7WxEtz|E={fVtDyu51D=)2FT4}3XR=K=#1#|9s=P$f)L3zam^A}%S Ka}m4f67)Yv#I)%E diff --git a/.cache/clangd/index/utilities.hpp.2C3FAE4039E1F841.idx b/.cache/clangd/index/utilities.hpp.2C3FAE4039E1F841.idx deleted file mode 100644 index f05e52ac0172914f9b367efaf30597ed17a8556a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2302 zcma)7O=u)V6t0Ph`Ehi!i7u!Jg~t3qb~>9C#TGG>tigagtQpujxX{#ezn(6)yQ`_H z&TNQ_;>nXBC}CT5b&kTgxzSMPoAd*7?x z-rC%}H$liouyrE=%|;0!)A+Bnwu)8kThax5c9NSV;EY#NRm9|KC{8Q zTt`F0*A60@^1OrcJRaD{ETuevRP&I7bTH!elqF!d3}4M;2Q=35e|Zifr^1BoY3XU6 zfXFrFX<*nP_ih9jNg9>AjN2UudCE1!yVR&ZL>4PWp$pwM%s2XdxpaR~?P(oJ(Zy~A zt}An_F98pvL_R#Ed5Si`;*N6!7I$Evt00XyXrPGcq5+0ci%FnO%`{wQe#BFt^&mLE zg>ovINl>UMieL<}tI&Z1%`FzZzCzZTXfht|4%XckBBp32FpP~zCnq~KXUwFG>yf9* zvrI^AugTjG8eF=G3Zk9l zk=LL`;f5dQf$^?^49Fn6UP%QTF;M?WoinMAkTRvDIK2JTMvKL{y$ddm%H`e|%@54f z&1E{bx9Xy86`nE{F?R=2oVPYVJSG-=u?MzI8S40(OGU~eXrJTNp4yncEcY<7Y3;F9 zj*Fu6NBm(998<}%xv@@BM2S0|KjyeU^*-nnte1!tVPn|j64q|xT$(v@-CXmSYn(9G zC59jI-MO{K8ba`CF>B4W6Jq&p8;|Ue{_XCWR%0=}JBfrm2G?<%NF?AWk!KNCPFKk5 zDq}u4n8?dgud5u6QnEOs*4bJe2LCsfk6$)r%L_9bF6=;9dR z?Vv%1hTdS_A=`cRYEhQ;Gv`Y75BkrpuH&EcqEon>6tm`8X>GFJ9F`j>f(HEl*lW#W zL4a($;!g8{>V~Q+fCO z*{65@`Td6~d8|aV##&2=n0#=g`UoQS|K@*v^5@<{l{{J^8e@&85HT_Kz_~MskPxb$ z2C`KqZ5Fnp-}!fT|C{FItKTIs{XwNVv%au?zU0*WHoJ08-noOzjk(5iWtzQPkAL~` z=fC_>nVMOgSab^3gp@onw&7RC{@VHIZTHhluV9eYN^7k|mBA2gxR&UjZ-0OH-eQVhTzD0wOl3=VrKHA4b(H{W!5~3-^>@Uzr6R_{#Vh+>{)WQ HTqWc`0CpsY diff --git a/.cache/clangd/index/visibility_control.h.6BF9DD9BAF8E623B.idx b/.cache/clangd/index/visibility_control.h.6BF9DD9BAF8E623B.idx deleted file mode 100644 index e53cb5072c0ef3a46d5981ddcd504162b1099bc7..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 326 zcmWIYbaS&~WMFVk@vO*AElFfyU|>`WgATsrtqFr3D$8 z#roy>McKs#iOH$@iAhQE1$pu1#rnlX$zWblez6glk&#%GQl40p8lRb0l3J7oQk|KX zoKuDKjUtq%uA^Kd+=HKSwWvp|~2QTgJcu05COM+yDRo From beb38957e4283530ceff7d322bd520a30891788f Mon Sep 17 00:00:00 2001 From: Souphis Date: Wed, 6 Apr 2022 10:35:27 +0200 Subject: [PATCH 08/27] Add gitignore --- .gitignore | 2 ++ 1 file changed, 2 insertions(+) create mode 100644 .gitignore diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..b010b19 --- /dev/null +++ b/.gitignore @@ -0,0 +1,2 @@ +.cache/ +compile_commands.json From 5d1e412af41193514c8571d47d82913edd6103cc Mon Sep 17 00:00:00 2001 From: Souphis Date: Wed, 6 Apr 2022 11:54:10 +0200 Subject: [PATCH 09/27] Add license mentions --- .../abb_hardware_interface/mapping.hpp | 3 ++ .../abb_hardware_interface/rws_client.hpp | 46 ++++++++++++++++-- .../rws_service_provider_ros.hpp | 47 +++++++++++++++++-- .../rws_state_publisher_ros.hpp | 40 ++++++++++++++++ .../abb_hardware_interface/utilities.hpp | 7 +-- abb_hardware_interface/src/mapping.cpp | 3 ++ abb_hardware_interface/src/rws_client.cpp | 40 ++++++++++++++++ .../src/rws_service_provider_ros.cpp | 40 ++++++++++++++++ .../src/rws_state_publisher_ros.cpp | 40 ++++++++++++++++ abb_hardware_interface/src/utilities.cpp | 1 + 10 files changed, 257 insertions(+), 10 deletions(-) diff --git a/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp b/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp index 02cf4b9..992aecf 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp @@ -34,6 +34,9 @@ *********************************************************************************************************************** */ +// This file is a modified copy from +// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/mapping.h + #ifndef ABB_HARDWARE_INTERFACE__MAPPING_HPP_ #define ABB_HARDWARE_INTERFACE__MAPPING_HPP_ diff --git a/abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp b/abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp index 1ff3040..2b32838 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp @@ -1,5 +1,45 @@ -#ifndef ABB_HARDWARE_INTERFACE__RWS_CLIENT_HPP__ -#define ABB_HARDWARE_INTERFACE__RWS_CLIENT_HPP__ +/*********************************************************************************************************************** + * + * Copyright (c) 2020, ABB Schweiz AG + * 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 ABB 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 HOLDER 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. + * + *********************************************************************************************************************** + */ + +// This file is a modified copy from +// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/include/abb_rws_service_provider/ +// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/include/abb_rws_state_publisher/ + +#ifndef ABB_HARDWARE_INTERFACE__RWS_CLIENT_HPP_ +#define ABB_HARDWARE_INTERFACE__RWS_CLIENT_HPP_ // ROS #include @@ -26,4 +66,4 @@ class RWSClient { } // namespace abb_rws_client -#endif // ABB_HARDWARE_INTERFACE__RWS_CLIENT_HPP__ +#endif // ABB_HARDWARE_INTERFACE__RWS_CLIENT_HPP_ diff --git a/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp b/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp index b66f65a..e03e69d 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp @@ -1,6 +1,45 @@ -#ifndef ABB_HARDWARE_INTERFACE__RWS_SERCIVE_PROVIDER_ROS_HPP__ -#define ABB_HARDWARE_INTERFACE__RWS_SERCIVE_PROVIDER_ROS_HPP__ - +/*********************************************************************************************************************** + * + * Copyright (c) 2020, ABB Schweiz AG + * 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 ABB 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 HOLDER 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. + * + *********************************************************************************************************************** + */ +// +// This file is a modified copy from +// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/include/abb_rws_service_provider/ +// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/include/abb_rws_state_publisher/ + +#ifndef ABB_HARDWARE_INTERFACE__RWS_SERCIVE_PROVIDER_ROS_HPP_ +#define ABB_HARDWARE_INTERFACE__RWS_SERCIVE_PROVIDER_ROS_HPP_ #include "abb_hardware_interface/rws_client.hpp" @@ -188,4 +227,4 @@ class RWSServiceProviderROS : RWSClient { } // namespace abb_rws_client -#endif // ABB_HARDWARE_INTERFACE__RWS_SERCIVE_PROVIDER_ROS_HPP__ +#endif // ABB_HARDWARE_INTERFACE__RWS_SERCIVE_PROVIDER_ROS_HPP_ diff --git a/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp b/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp index 251ae62..cfb3a1a 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp @@ -1,3 +1,43 @@ +/*********************************************************************************************************************** + * + * Copyright (c) 2020, ABB Schweiz AG + * 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 ABB 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 HOLDER 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. + * + *********************************************************************************************************************** + */ + +// This file is a modified copy from +// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/include/abb_rws_service_provider/ +// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/include/abb_rws_state_publisher/ + #ifndef ABB_HARDWARE_INTERFACE__RWS_STATE_PUBLISHER_ROS_HPP_ #define ABB_HARDWARE_INTERFACE__RWS_STATE_PUBLISHER_ROS_HPP_ diff --git a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp b/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp index 8651b7c..18c7ea4 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp @@ -36,9 +36,10 @@ // This file is a modified copy from // https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/initialization.h +// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/verification.h -#ifndef ABB_HARDWARE_INTERFACE__UTILITIES_HPP__ -#define ABB_HARDWARE_INTERFACE__UTILITIES_HPP__ +#ifndef ABB_HARDWARE_INTERFACE__UTILITIES_HPP_ +#define ABB_HARDWARE_INTERFACE__UTILITIES_HPP_ #include @@ -90,4 +91,4 @@ bool verify_state_machine_add_in_presence(const SystemIndicators &system_indicat } // namespace robot } // namespace abb -#endif // ABB_HARDWARE_INTERFACE__UTILITIES_HPP__ +#endif // ABB_HARDWARE_INTERFACE__UTILITIES_HPP_ diff --git a/abb_hardware_interface/src/mapping.cpp b/abb_hardware_interface/src/mapping.cpp index 2f15e60..79c4d04 100644 --- a/abb_hardware_interface/src/mapping.cpp +++ b/abb_hardware_interface/src/mapping.cpp @@ -34,6 +34,9 @@ *********************************************************************************************************************** */ +// This file is a modified copy from +// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/mapping.cpp + #include "abb_hardware_interface/mapping.hpp" // System diff --git a/abb_hardware_interface/src/rws_client.cpp b/abb_hardware_interface/src/rws_client.cpp index 64f2339..d87950f 100644 --- a/abb_hardware_interface/src/rws_client.cpp +++ b/abb_hardware_interface/src/rws_client.cpp @@ -1,3 +1,43 @@ +/*********************************************************************************************************************** + * + * Copyright (c) 2020, ABB Schweiz AG + * 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 ABB 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 HOLDER 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. + * + *********************************************************************************************************************** + */ + +// This file is a modified copy from +// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/src +// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/src + #include "abb_hardware_interface/rws_client.hpp" #include "abb_hardware_interface/utilities.hpp" diff --git a/abb_hardware_interface/src/rws_service_provider_ros.cpp b/abb_hardware_interface/src/rws_service_provider_ros.cpp index c76ed74..45144bc 100644 --- a/abb_hardware_interface/src/rws_service_provider_ros.cpp +++ b/abb_hardware_interface/src/rws_service_provider_ros.cpp @@ -1,3 +1,43 @@ +/*********************************************************************************************************************** + * + * Copyright (c) 2020, ABB Schweiz AG + * 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 ABB 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 HOLDER 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. + * + *********************************************************************************************************************** + */ + +// This file is a modified copy from +// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/src +// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/src + #include "abb_hardware_interface/rws_service_provider_ros.hpp" #include diff --git a/abb_hardware_interface/src/rws_state_publisher_ros.cpp b/abb_hardware_interface/src/rws_state_publisher_ros.cpp index c73054e..a0fefdb 100644 --- a/abb_hardware_interface/src/rws_state_publisher_ros.cpp +++ b/abb_hardware_interface/src/rws_state_publisher_ros.cpp @@ -1,3 +1,43 @@ +/*********************************************************************************************************************** + * + * Copyright (c) 2020, ABB Schweiz AG + * 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 ABB 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 HOLDER 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. + * + *********************************************************************************************************************** + */ + +// This file is a modified copy from +// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/src +// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/src + #include "abb_hardware_interface/rws_state_publisher_ros.hpp" #include "abb_hardware_interface/mapping.hpp" diff --git a/abb_hardware_interface/src/utilities.cpp b/abb_hardware_interface/src/utilities.cpp index 90ab79e..2b3dc04 100644 --- a/abb_hardware_interface/src/utilities.cpp +++ b/abb_hardware_interface/src/utilities.cpp @@ -36,6 +36,7 @@ // This file is a modified copy from // https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/initialization.cpp +// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/verification.cpp #include From 70f7b1953d94ea7fac3bce3ebf26c9d05cd4fa4d Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Tue, 10 May 2022 13:45:29 +0200 Subject: [PATCH 10/27] Apply suggestions from code review Co-authored-by: Stephanie Eng --- abb.repos | 2 +- .../src/rws_state_publisher_ros.cpp | 12 ++++++++---- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/abb.repos b/abb.repos index 3c315a8..eb2b6cb 100644 --- a/abb.repos +++ b/abb.repos @@ -11,7 +11,7 @@ repositories: type: git url: https://github.com/ros-industrial/abb_egm_rws_managers.git version: master - abb_ros2_msgs + abb_ros2_msgs: type: git url: https://github.com/gbartyzel/abb_ros2_msgs.git version: rolling diff --git a/abb_hardware_interface/src/rws_state_publisher_ros.cpp b/abb_hardware_interface/src/rws_state_publisher_ros.cpp index a0fefdb..a1f9747 100644 --- a/abb_hardware_interface/src/rws_state_publisher_ros.cpp +++ b/abb_hardware_interface/src/rws_state_publisher_ros.cpp @@ -62,11 +62,11 @@ RWSStatePublisherROS::RWSStatePublisherROS(const rclcpp::Node::SharedPtr& node, rmw_qos_profile_sensor_data); joint_state_pub_ = node_->create_publisher("~/joint_states", sensor_qos); - system_state_pub_ = node_->create_publisher("~/system_state", 1); + system_state_pub_ = node_->create_publisher("~/system_states", 1); if (abb::robot::utilities::verify_state_machine_add_in_presence(robot_controller_description_.system_indicators())) { runtime_state_pub_ = - node_->create_publisher("~/sm_addin/runtime_state", 1); + node_->create_publisher("~/sm_addin/runtime_states", 1); } } @@ -132,7 +132,11 @@ void RWSStatePublisherROS::timer_callback() { system_state_msg.header.stamp = time; system_state_pub_->publish(system_state_msg); - sm_runtime_state_msg.header.stamp = time; - runtime_state_pub_->publish(sm_runtime_state_msg); + if (abb::robot::utilities::verify_state_machine_add_in_presence(robot_controller_description_.system_indicators())) + { + sm_runtime_state_msg.header.stamp = time; + runtime_state_pub_->publish(sm_runtime_state_msg); + } + } } // namespace abb_rws_client From 53027e94c068dc12c0c8237bf64f8b51cdcf1b6e Mon Sep 17 00:00:00 2001 From: Souphis Date: Mon, 23 May 2022 21:36:25 +0200 Subject: [PATCH 11/27] Move rws client to own package --- abb_hardware_interface/CMakeLists.txt | 25 ---- .../abb_system_position_only.hpp | 5 +- .../abb_hardware_interface/utilities.hpp | 27 +--- abb_hardware_interface/package.xml | 4 - .../src/abb_system_position_only.cpp | 2 +- abb_hardware_interface/src/utilities.cpp | 2 +- abb_rws_client/CMakeLists.txt | 79 ++++++++++++ .../include/abb_rws_client}/mapping.hpp | 5 +- .../include/abb_rws_client}/rws_client.hpp | 5 +- .../rws_service_provider_ros.hpp | 7 +- .../rws_state_publisher_ros.hpp | 7 +- .../include/abb_rws_client/utilities.hpp | 91 ++++++++++++++ abb_rws_client/package.xml | 27 ++++ .../src/mapping.cpp | 2 +- .../src/rws_client.cpp | 5 +- .../src/rws_client_node.cpp | 4 +- .../src/rws_service_provider_ros.cpp | 6 +- .../src/rws_state_publisher_ros.cpp | 6 +- abb_rws_client/src/utilities.cpp | 117 ++++++++++++++++++ 19 files changed, 337 insertions(+), 89 deletions(-) create mode 100644 abb_rws_client/CMakeLists.txt rename {abb_hardware_interface/include/abb_hardware_interface => abb_rws_client/include/abb_rws_client}/mapping.hpp (98%) rename {abb_hardware_interface/include/abb_hardware_interface => abb_rws_client/include/abb_rws_client}/rws_client.hpp (94%) rename {abb_hardware_interface/include/abb_hardware_interface => abb_rws_client/include/abb_rws_client}/rws_service_provider_ros.hpp (97%) rename {abb_hardware_interface/include/abb_hardware_interface => abb_rws_client/include/abb_rws_client}/rws_state_publisher_ros.hpp (92%) create mode 100644 abb_rws_client/include/abb_rws_client/utilities.hpp create mode 100644 abb_rws_client/package.xml rename {abb_hardware_interface => abb_rws_client}/src/mapping.cpp (99%) rename {abb_hardware_interface => abb_rws_client}/src/rws_client.cpp (96%) rename {abb_hardware_interface => abb_rws_client}/src/rws_client_node.cpp (85%) rename {abb_hardware_interface => abb_rws_client}/src/rws_service_provider_ros.cpp (99%) rename {abb_hardware_interface => abb_rws_client}/src/rws_state_publisher_ros.cpp (97%) create mode 100644 abb_rws_client/src/utilities.cpp diff --git a/abb_hardware_interface/CMakeLists.txt b/abb_hardware_interface/CMakeLists.txt index f5f2e80..c22ecd0 100644 --- a/abb_hardware_interface/CMakeLists.txt +++ b/abb_hardware_interface/CMakeLists.txt @@ -20,10 +20,6 @@ endif() set(THIS_PACKAGE_INCLUDE_DEPENDS abb_egm_rws_managers - abb_egm_msgs - abb_rapid_msgs - abb_rapid_sm_addin_msgs - abb_robot_msgs hardware_interface pluginlib rclcpp @@ -56,31 +52,10 @@ target_include_directories( pluginlib_export_plugin_description_file(hardware_interface abb_hardware_interface.xml) -add_executable(rws_client - src/rws_client_node.cpp - src/rws_client.cpp - src/rws_service_provider_ros.cpp - src/rws_state_publisher_ros.cpp - src/utilities.cpp - src/mapping.cpp -) -ament_target_dependencies(rws_client ${THIS_PACKAGE_INCLUDE_DEPENDS}) -# target_link_libraries(rws_client abb_egm_rws_managers::abb_egm_rws_managers) -target_include_directories( - rws_client - PRIVATE - include -) - ############# ## Install ## ############# -install( - TARGETS rws_client - DESTINATION lib/${PROJECT_NAME} -) - install( TARGETS ${PROJECT_NAME} DESTINATION lib diff --git a/abb_hardware_interface/include/abb_hardware_interface/abb_system_position_only.hpp b/abb_hardware_interface/include/abb_hardware_interface/abb_system_position_only.hpp index a5e2e2e..95c199c 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/abb_system_position_only.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/abb_system_position_only.hpp @@ -12,8 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ABB_HARDWARE_INTERFACE__ABB_SYSTEM_POSITION_ONLY_HPP__ -#define ABB_HARDWARE_INTERFACE__ABB_SYSTEM_POSITION_ONLY_HPP__ +#pragma once #include #include @@ -75,5 +74,3 @@ class ABBSystemPositionOnlyHardware : public hardware_interface::SystemInterface }; } // namespace abb_hardware_interface - -#endif // ABB_HARDWARE_INTERFACE__ABB_SYSTEM_POSITION_ONLY_HPP__ diff --git a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp b/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp index 18c7ea4..72ea178 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp @@ -38,8 +38,7 @@ // https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/initialization.h // https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/verification.h -#ifndef ABB_HARDWARE_INTERFACE__UTILITIES_HPP_ -#define ABB_HARDWARE_INTERFACE__UTILITIES_HPP_ +#pragma once #include @@ -64,31 +63,9 @@ namespace utilities * * \throw std::runtime_error if unable to establish a connection. */ -RobotControllerDescription establish_rws_connection( +RobotControllerDescription establishRWSConnection( RWSManager & rws_manager, const std::string & robot_controller_id, const bool no_connection_timeout); - -/** - * \brief Verifies that the RobotWare version is supported. - * - * Note: For now, only RobotWare versions in the range [6.07.01, 7.0) are supported (i.e. excluding 7.0). - * - * \param rw_version to verify. - * - * \throw std::runtime_error if the RobotWare version is not supported. - */ -void verify_robotware_version(const RobotWareVersion &rw_version); - -/** - * \brief Verifies that the RobotWare StateMachine Add-In is present in a system. - * - * \param system_indicators to verify. - * - * \return bool true if the StateMachine Add-In is present. - */ -bool verify_state_machine_add_in_presence(const SystemIndicators &system_indicators); } // namespace utilities } // namespace robot } // namespace abb - -#endif // ABB_HARDWARE_INTERFACE__UTILITIES_HPP_ diff --git a/abb_hardware_interface/package.xml b/abb_hardware_interface/package.xml index 7f97050..9ec41e5 100644 --- a/abb_hardware_interface/package.xml +++ b/abb_hardware_interface/package.xml @@ -15,10 +15,6 @@ ament_cmake abb_egm_rws_managers - abb_egm_msgs - abb_rapid_msgs - abb_robot_msgs - abb_rapid_sm_addin_msgs hardware_interface pluginlib rclcpp diff --git a/abb_hardware_interface/src/abb_system_position_only.cpp b/abb_hardware_interface/src/abb_system_position_only.cpp index 3f21826..2215677 100644 --- a/abb_hardware_interface/src/abb_system_position_only.cpp +++ b/abb_hardware_interface/src/abb_system_position_only.cpp @@ -40,7 +40,7 @@ CallbackReturn ABBSystemPositionOnlyHardware::on_init(const hardware_interface:: // Get robot controller description from RWS abb::robot::RWSManager rws_manager(rws_ip, rws_port, "Default User", "robotics"); const auto robot_controller_description_ = - abb::robot::utilities::establish_rws_connection(rws_manager, "IRB1200", true); + abb::robot::utilities::establishRWSConnection(rws_manager, "IRB1200", true); RCLCPP_INFO_STREAM( LOGGER, "Robot controller description:\n" << abb::robot::summaryText(robot_controller_description_)); diff --git a/abb_hardware_interface/src/utilities.cpp b/abb_hardware_interface/src/utilities.cpp index 2b3dc04..c196926 100644 --- a/abb_hardware_interface/src/utilities.cpp +++ b/abb_hardware_interface/src/utilities.cpp @@ -70,7 +70,7 @@ constexpr uint8_t RWS_RECONNECTION_WAIT_TIME{1}; auto LOGGER = rclcpp::get_logger("ABBHardwareInterfaceUtilities"); } // namespace -RobotControllerDescription establish_rws_connection( +RobotControllerDescription establishRWSConnection( RWSManager & rws_manager, const std::string & robot_controller_id, const bool no_connection_timeout) { diff --git a/abb_rws_client/CMakeLists.txt b/abb_rws_client/CMakeLists.txt new file mode 100644 index 0000000..362d260 --- /dev/null +++ b/abb_rws_client/CMakeLists.txt @@ -0,0 +1,79 @@ +cmake_minimum_required(VERSION 3.8) +project(abb_rws_client) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-W -Wall -Wextra + -Wwrite-strings -Wunreachable-code -Wpointer-arith + -Winit-self -Wredundant-decls + -Wno-unused-parameter -Wno-unused-function) +endif() + +set(THIS_PACKAGE_INCLUDE_DEPENDS + abb_egm_rws_managers + abb_egm_msgs + abb_robot_msgs + abb_rapid_msgs + abb_rapid_sm_addin_msgs + rclcpp + sensor_msgs +) + +# find dependencies +find_package(ament_cmake REQUIRED) + +foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) + find_package(${Dependency} REQUIRED) +endforeach() + +########### +## Build ## +########### + +add_executable(rws_client + src/rws_client_node.cpp + src/rws_client.cpp + src/rws_service_provider_ros.cpp + src/rws_state_publisher_ros.cpp + src/utilities.cpp + src/mapping.cpp +) +ament_target_dependencies(rws_client ${THIS_PACKAGE_INCLUDE_DEPENDS}) +# target_link_libraries(rws_client abb_egm_rws_managers::abb_egm_rws_managers) +target_include_directories( + rws_client + PRIVATE + include +) + +############# +## Install ## +############# + +install( + TARGETS rws_client + DESTINATION lib/${PROJECT_NAME} +) + +############# +## Testing ## +############# + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_export_include_directories(include) +ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) + +ament_package() diff --git a/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp b/abb_rws_client/include/abb_rws_client/mapping.hpp similarity index 98% rename from abb_hardware_interface/include/abb_hardware_interface/mapping.hpp rename to abb_rws_client/include/abb_rws_client/mapping.hpp index 992aecf..f207207 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/mapping.hpp +++ b/abb_rws_client/include/abb_rws_client/mapping.hpp @@ -37,8 +37,7 @@ // This file is a modified copy from // https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/mapping.h -#ifndef ABB_HARDWARE_INTERFACE__MAPPING_HPP_ -#define ABB_HARDWARE_INTERFACE__MAPPING_HPP_ +#pragma once #include #include @@ -262,5 +261,3 @@ std::string map_vector_to_string(const std::vector& vector); } // namespace utilities } // namespace robot } // namespace abb - -#endif // ABB_HARDWARE_INTERFACE__MAPPING_HPP_ diff --git a/abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp b/abb_rws_client/include/abb_rws_client/rws_client.hpp similarity index 94% rename from abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp rename to abb_rws_client/include/abb_rws_client/rws_client.hpp index 2b32838..ee9d153 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/rws_client.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_client.hpp @@ -38,8 +38,7 @@ // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/include/abb_rws_service_provider/ // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/include/abb_rws_state_publisher/ -#ifndef ABB_HARDWARE_INTERFACE__RWS_CLIENT_HPP_ -#define ABB_HARDWARE_INTERFACE__RWS_CLIENT_HPP_ +#pragma once // ROS #include @@ -65,5 +64,3 @@ class RWSClient { }; } // namespace abb_rws_client - -#endif // ABB_HARDWARE_INTERFACE__RWS_CLIENT_HPP_ diff --git a/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp similarity index 97% rename from abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp rename to abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp index e03e69d..5107b33 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/rws_service_provider_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp @@ -38,10 +38,9 @@ // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/include/abb_rws_service_provider/ // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/include/abb_rws_state_publisher/ -#ifndef ABB_HARDWARE_INTERFACE__RWS_SERCIVE_PROVIDER_ROS_HPP_ -#define ABB_HARDWARE_INTERFACE__RWS_SERCIVE_PROVIDER_ROS_HPP_ +#pragma once -#include "abb_hardware_interface/rws_client.hpp" +#include "abb_rws_client/rws_client.hpp" // SYSMTEM #include @@ -226,5 +225,3 @@ class RWSServiceProviderROS : RWSClient { }; } // namespace abb_rws_client - -#endif // ABB_HARDWARE_INTERFACE__RWS_SERCIVE_PROVIDER_ROS_HPP_ diff --git a/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp similarity index 92% rename from abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp rename to abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp index cfb3a1a..dd18c83 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/rws_state_publisher_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp @@ -38,10 +38,9 @@ // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/include/abb_rws_service_provider/ // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/include/abb_rws_state_publisher/ -#ifndef ABB_HARDWARE_INTERFACE__RWS_STATE_PUBLISHER_ROS_HPP_ -#define ABB_HARDWARE_INTERFACE__RWS_STATE_PUBLISHER_ROS_HPP_ +#pragma once -#include "abb_hardware_interface/rws_client.hpp" +#include "abb_rws_client/rws_client.hpp" // SYSTEM #include @@ -77,5 +76,3 @@ class RWSStatePublisherROS : RWSClient { }; } // namespace abb_rws_client - -#endif // ABB_HARDWARE_INTERFACE__RWS_STATE_PUBLISHER_ROS_HPP_ diff --git a/abb_rws_client/include/abb_rws_client/utilities.hpp b/abb_rws_client/include/abb_rws_client/utilities.hpp new file mode 100644 index 0000000..ac8f05d --- /dev/null +++ b/abb_rws_client/include/abb_rws_client/utilities.hpp @@ -0,0 +1,91 @@ +/*********************************************************************************************************************** + * + * Copyright (c) 2020, ABB Schweiz AG + * 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 ABB 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 HOLDER 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. + * + *********************************************************************************************************************** + */ + +// This file is a modified copy from +// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/initialization.h +// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/verification.h + +#pragma once + +#include + +#include + +namespace abb +{ +namespace robot +{ +namespace utilities +{ +/** + * \brief Attempts to establish a connection to a robot controller's RWS server. + * + * If a connection is established, then a structured description of the robot controller is returned. + * + * \param rws_manager for handling the RWS communication with the robot controller. + * \param robot_controller_id for an identifier/nickname for the targeted robot controller. + * \param no_connection_timeout indicator whether to wait indefinitely on the robot controller. + * + * \return RobotControllerDescription of the robot controller. + * + * \throw std::runtime_error if unable to establish a connection. + */ +RobotControllerDescription establish_rws_connection( + RWSManager & rws_manager, const std::string & robot_controller_id, + const bool no_connection_timeout); + +/** + * \brief Verifies that the RobotWare version is supported. + * + * Note: For now, only RobotWare versions in the range [6.07.01, 7.0) are supported (i.e. excluding 7.0). + * + * \param rw_version to verify. + * + * \throw std::runtime_error if the RobotWare version is not supported. + */ +void verify_robotware_version(const RobotWareVersion &rw_version); + +/** + * \brief Verifies that the RobotWare StateMachine Add-In is present in a system. + * + * \param system_indicators to verify. + * + * \return bool true if the StateMachine Add-In is present. + */ +bool verify_state_machine_add_in_presence(const SystemIndicators &system_indicators); +} // namespace utilities +} // namespace robot +} // namespace abb diff --git a/abb_rws_client/package.xml b/abb_rws_client/package.xml new file mode 100644 index 0000000..285fe7b --- /dev/null +++ b/abb_rws_client/package.xml @@ -0,0 +1,27 @@ + + + + abb_rws_client + 0.0.0 + TODO: Package description + Grzegorz Bartyzel + Apache2 + + rclcpp + abb_egm_rws_managers + sensor_msgs + abb_egm_msgs + abb_rapid_msgs + abb_robot_msgs + abb_rapid_sm_addin_msgs + + ament_cmake_gtest + + ament_lint_auto + ament_lint_common + + + ament_cmake + + + diff --git a/abb_hardware_interface/src/mapping.cpp b/abb_rws_client/src/mapping.cpp similarity index 99% rename from abb_hardware_interface/src/mapping.cpp rename to abb_rws_client/src/mapping.cpp index 79c4d04..e02c1d3 100644 --- a/abb_hardware_interface/src/mapping.cpp +++ b/abb_rws_client/src/mapping.cpp @@ -37,7 +37,7 @@ // This file is a modified copy from // https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/mapping.cpp -#include "abb_hardware_interface/mapping.hpp" +#include "abb_rws_client/mapping.hpp" // System #include diff --git a/abb_hardware_interface/src/rws_client.cpp b/abb_rws_client/src/rws_client.cpp similarity index 96% rename from abb_hardware_interface/src/rws_client.cpp rename to abb_rws_client/src/rws_client.cpp index d87950f..3c9c53a 100644 --- a/abb_hardware_interface/src/rws_client.cpp +++ b/abb_rws_client/src/rws_client.cpp @@ -38,9 +38,10 @@ // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/src // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/src -#include "abb_hardware_interface/rws_client.hpp" +#include "abb_rws_client/rws_client.hpp" + +#include "abb_rws_client/utilities.hpp" -#include "abb_hardware_interface/utilities.hpp" namespace abb_rws_client { RWSClient::RWSClient(const rclcpp::Node::SharedPtr &node, const std::string &robot_ip, unsigned short robot_port) diff --git a/abb_hardware_interface/src/rws_client_node.cpp b/abb_rws_client/src/rws_client_node.cpp similarity index 85% rename from abb_hardware_interface/src/rws_client_node.cpp rename to abb_rws_client/src/rws_client_node.cpp index 331a23a..af3c152 100644 --- a/abb_hardware_interface/src/rws_client_node.cpp +++ b/abb_rws_client/src/rws_client_node.cpp @@ -1,7 +1,7 @@ #include -#include "abb_hardware_interface/rws_service_provider_ros.hpp" -#include "abb_hardware_interface/rws_state_publisher_ros.hpp" +#include "abb_rws_client/rws_service_provider_ros.hpp" +#include "abb_rws_client/rws_state_publisher_ros.hpp" int main(int argc, char** argv) { rclcpp::init(argc, argv); diff --git a/abb_hardware_interface/src/rws_service_provider_ros.cpp b/abb_rws_client/src/rws_service_provider_ros.cpp similarity index 99% rename from abb_hardware_interface/src/rws_service_provider_ros.cpp rename to abb_rws_client/src/rws_service_provider_ros.cpp index 45144bc..c5f6ed9 100644 --- a/abb_hardware_interface/src/rws_service_provider_ros.cpp +++ b/abb_rws_client/src/rws_service_provider_ros.cpp @@ -38,12 +38,12 @@ // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/src // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/src -#include "abb_hardware_interface/rws_service_provider_ros.hpp" +#include "abb_rws_client/rws_service_provider_ros.hpp" #include -#include "abb_hardware_interface/mapping.hpp" -#include "abb_hardware_interface/utilities.hpp" +#include "abb_rws_client/mapping.hpp" +#include "abb_rws_client/utilities.hpp" using RAPIDSymbols = abb::rws::RWSStateMachineInterface::ResourceIdentifiers::RAPID::Symbols; diff --git a/abb_hardware_interface/src/rws_state_publisher_ros.cpp b/abb_rws_client/src/rws_state_publisher_ros.cpp similarity index 97% rename from abb_hardware_interface/src/rws_state_publisher_ros.cpp rename to abb_rws_client/src/rws_state_publisher_ros.cpp index a1f9747..15a1df8 100644 --- a/abb_hardware_interface/src/rws_state_publisher_ros.cpp +++ b/abb_rws_client/src/rws_state_publisher_ros.cpp @@ -38,10 +38,10 @@ // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/src // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/src -#include "abb_hardware_interface/rws_state_publisher_ros.hpp" +#include "abb_rws_client/rws_state_publisher_ros.hpp" -#include "abb_hardware_interface/mapping.hpp" -#include "abb_hardware_interface/utilities.hpp" +#include "abb_rws_client/mapping.hpp" +#include "abb_rws_client/utilities.hpp" namespace { /** diff --git a/abb_rws_client/src/utilities.cpp b/abb_rws_client/src/utilities.cpp new file mode 100644 index 0000000..fcfd7db --- /dev/null +++ b/abb_rws_client/src/utilities.cpp @@ -0,0 +1,117 @@ +/*********************************************************************************************************************** + * + * Copyright (c) 2020, ABB Schweiz AG + * 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 ABB 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 HOLDER 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. + * + *********************************************************************************************************************** + */ + +// This file is a modified copy from +// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/initialization.cpp +// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/verification.cpp + +#include + +#include + +#include "rclcpp/rclcpp.hpp" + +namespace abb +{ +namespace robot +{ +namespace utilities +{ +namespace +{ +/** + * \brief Max number of attempts when trying to connect to a robot controller via RWS. + */ +constexpr unsigned int RWS_MAX_CONNECTION_ATTEMPTS{5}; + +/** + * \brief Error message for failed connection attempts when trying to connect to a robot controller via RWS. + */ +constexpr char RWS_CONNECTION_ERROR_MESSAGE[]{ + "Failed to establish RWS connection to the robot controller"}; + +/** + * \brief Time [s] to wait before trying to reconnect to a robot controller via RWS. + */ +constexpr uint8_t RWS_RECONNECTION_WAIT_TIME{1}; +auto LOGGER = rclcpp::get_logger("ABBHardwareInterfaceUtilities"); +} // namespace + +RobotControllerDescription establish_rws_connection( + RWSManager & rws_manager, const std::string & robot_controller_id, + const bool no_connection_timeout) +{ + unsigned int attempt{0}; + + while (rclcpp::ok() && (no_connection_timeout || attempt++ < RWS_MAX_CONNECTION_ATTEMPTS)) { + try { + return rws_manager.collectAndParseSystemData(robot_controller_id); + } catch (const std::runtime_error & exception) { + if (!no_connection_timeout) { + RCLCPP_WARN_STREAM( + LOGGER, RWS_CONNECTION_ERROR_MESSAGE << " (attempt " << attempt << "/" + << RWS_MAX_CONNECTION_ATTEMPTS << "), reason: '" + << exception.what() << "'"); + } else { + RCLCPP_WARN_STREAM( + LOGGER, RWS_CONNECTION_ERROR_MESSAGE << " (waiting indefinitely), reason: '" + << exception.what() << "'"); + } + rclcpp::sleep_for(std::chrono::seconds(RWS_RECONNECTION_WAIT_TIME)); + } + } + + throw std::runtime_error{RWS_CONNECTION_ERROR_MESSAGE}; +} + +void verify_robotware_version(const RobotWareVersion& rw_version) { + if (rw_version.major_number() == 6 && rw_version.minor_number() < 7 && + rw_version.patch_number() < 1) { + auto error_message{"Unsupported RobotWare version (" + rw_version.name() + + ", need at least 6.07.01)"}; + + RCLCPP_FATAL_STREAM(LOGGER, error_message); + throw std::runtime_error{error_message}; + } +} + +bool verify_state_machine_add_in_presence(const SystemIndicators& system_indicators) { + return system_indicators.addins().state_machine_1_0() || + system_indicators.addins().state_machine_1_1(); +} +} // namespace utilities +} // namespace robot +} // namespace abb From 40163e921126400872f500168721cc8b3108b73c Mon Sep 17 00:00:00 2001 From: Souphis Date: Tue, 31 May 2022 11:26:46 +0200 Subject: [PATCH 12/27] Apply formatting --- abb_hardware_interface/src/utilities.cpp | 18 +- .../include/abb_rws_client/mapping.hpp | 10 +- .../include/abb_rws_client/rws_client.hpp | 15 +- .../rws_service_provider_ros.hpp | 11 +- .../rws_state_publisher_ros.hpp | 13 +- .../include/abb_rws_client/utilities.hpp | 9 +- abb_rws_client/package.xml | 1 - abb_rws_client/src/mapping.cpp | 109 ++- abb_rws_client/src/rws_client.cpp | 16 +- abb_rws_client/src/rws_client_node.cpp | 3 +- .../src/rws_service_provider_ros.cpp | 748 ++++++++++++------ .../src/rws_state_publisher_ros.cpp | 64 +- abb_rws_client/src/utilities.cpp | 63 +- 13 files changed, 705 insertions(+), 375 deletions(-) diff --git a/abb_hardware_interface/src/utilities.cpp b/abb_hardware_interface/src/utilities.cpp index 9432cfa..ecf5d16 100644 --- a/abb_hardware_interface/src/utilities.cpp +++ b/abb_hardware_interface/src/utilities.cpp @@ -100,20 +100,20 @@ RobotControllerDescription establishRWSConnection(RWSManager& rws_manager, const throw std::runtime_error{ RWS_CONNECTION_ERROR_MESSAGE }; } -void verify_robotware_version(const RobotWareVersion& rw_version) { - if (rw_version.major_number() == 6 && rw_version.minor_number() < 7 && - rw_version.patch_number() < 1) { - auto error_message{"Unsupported RobotWare version (" + rw_version.name() + - ", need at least 6.07.01)"}; +void verify_robotware_version(const RobotWareVersion& rw_version) +{ + if (rw_version.major_number() == 6 && rw_version.minor_number() < 7 && rw_version.patch_number() < 1) + { + auto error_message{ "Unsupported RobotWare version (" + rw_version.name() + ", need at least 6.07.01)" }; RCLCPP_FATAL_STREAM(LOGGER, error_message); - throw std::runtime_error{error_message}; + throw std::runtime_error{ error_message }; } } -bool verify_state_machine_add_in_presence(const SystemIndicators& system_indicators) { - return system_indicators.addins().state_machine_1_0() || - system_indicators.addins().state_machine_1_1(); +bool verify_state_machine_add_in_presence(const SystemIndicators& system_indicators) +{ + return system_indicators.addins().state_machine_1_0() || system_indicators.addins().state_machine_1_1(); } } // namespace utilities } // namespace robot diff --git a/abb_rws_client/include/abb_rws_client/mapping.hpp b/abb_rws_client/include/abb_rws_client/mapping.hpp index f207207..de54138 100644 --- a/abb_rws_client/include/abb_rws_client/mapping.hpp +++ b/abb_rws_client/include/abb_rws_client/mapping.hpp @@ -49,10 +49,12 @@ #include #include -namespace abb { -namespace robot { -namespace utilities { - +namespace abb +{ +namespace robot +{ +namespace utilities +{ /** * \brief Maps RAPID task execution state to ROS representation. * diff --git a/abb_rws_client/include/abb_rws_client/rws_client.hpp b/abb_rws_client/include/abb_rws_client/rws_client.hpp index ee9d153..6a435fb 100644 --- a/abb_rws_client/include/abb_rws_client/rws_client.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_client.hpp @@ -47,19 +47,20 @@ #include #include -namespace abb_rws_client { +namespace abb_rws_client +{ +class RWSClient +{ +public: + RWSClient(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port); -class RWSClient { - public: - RWSClient(const rclcpp::Node::SharedPtr &node, const std::string &robot_ip, unsigned short robot_port); - - protected: +protected: rclcpp::Node::SharedPtr node_; abb::robot::RWSManager rws_manager_; abb::robot::RobotControllerDescription robot_controller_description_; - private: +private: void connect(); }; diff --git a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp index 5107b33..85a9e6a 100644 --- a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp @@ -77,13 +77,14 @@ #include #include -namespace abb_rws_client { - -class RWSServiceProviderROS : RWSClient { - public: +namespace abb_rws_client +{ +class RWSServiceProviderROS : RWSClient +{ +public: RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port); - private: +private: void system_state_callback(const abb_robot_msgs::msg::SystemState& msg); void runtime_state_callback(const abb_rapid_sm_addin_msgs::msg::RuntimeState& msg); diff --git a/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp index dd18c83..0e700cd 100644 --- a/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp @@ -56,13 +56,14 @@ #include #include -namespace abb_rws_client { +namespace abb_rws_client +{ +class RWSStatePublisherROS : RWSClient +{ +public: + RWSStatePublisherROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port); -class RWSStatePublisherROS : RWSClient { - public: - RWSStatePublisherROS(const rclcpp::Node::SharedPtr &node, const std::string &robot_ip, unsigned short robot_port); - - private: +private: void timer_callback(); rclcpp::TimerBase::SharedPtr timer_; diff --git a/abb_rws_client/include/abb_rws_client/utilities.hpp b/abb_rws_client/include/abb_rws_client/utilities.hpp index ac8f05d..f29155d 100644 --- a/abb_rws_client/include/abb_rws_client/utilities.hpp +++ b/abb_rws_client/include/abb_rws_client/utilities.hpp @@ -63,9 +63,8 @@ namespace utilities * * \throw std::runtime_error if unable to establish a connection. */ -RobotControllerDescription establish_rws_connection( - RWSManager & rws_manager, const std::string & robot_controller_id, - const bool no_connection_timeout); +RobotControllerDescription establish_rws_connection(RWSManager& rws_manager, const std::string& robot_controller_id, + const bool no_connection_timeout); /** * \brief Verifies that the RobotWare version is supported. @@ -76,7 +75,7 @@ RobotControllerDescription establish_rws_connection( * * \throw std::runtime_error if the RobotWare version is not supported. */ -void verify_robotware_version(const RobotWareVersion &rw_version); +void verify_robotware_version(const RobotWareVersion& rw_version); /** * \brief Verifies that the RobotWare StateMachine Add-In is present in a system. @@ -85,7 +84,7 @@ void verify_robotware_version(const RobotWareVersion &rw_version); * * \return bool true if the StateMachine Add-In is present. */ -bool verify_state_machine_add_in_presence(const SystemIndicators &system_indicators); +bool verify_state_machine_add_in_presence(const SystemIndicators& system_indicators); } // namespace utilities } // namespace robot } // namespace abb diff --git a/abb_rws_client/package.xml b/abb_rws_client/package.xml index 285fe7b..de23dc2 100644 --- a/abb_rws_client/package.xml +++ b/abb_rws_client/package.xml @@ -24,4 +24,3 @@ ament_cmake - diff --git a/abb_rws_client/src/mapping.cpp b/abb_rws_client/src/mapping.cpp index e02c1d3..3c2d20e 100644 --- a/abb_rws_client/src/mapping.cpp +++ b/abb_rws_client/src/mapping.cpp @@ -51,12 +51,16 @@ #include #include -namespace abb { -namespace robot { -namespace utilities { - -uint8_t map(const rws::RWSInterface::RAPIDTaskExecutionState state) { - switch (state) { +namespace abb +{ +namespace robot +{ +namespace utilities +{ +uint8_t map(const rws::RWSInterface::RAPIDTaskExecutionState state) +{ + switch (state) + { case rws::RWSInterface::UNKNOWN: return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_UNKNOWN; break; @@ -83,8 +87,10 @@ uint8_t map(const rws::RWSInterface::RAPIDTaskExecutionState state) { } } -uint8_t map_state_machine_state(const rws::RAPIDNum& state) { - switch (static_cast(state.value)) { +uint8_t map_state_machine_state(const rws::RAPIDNum& state) +{ + switch (static_cast(state.value)) + { case 0: return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_IDLE; break; @@ -107,8 +113,10 @@ uint8_t map_state_machine_state(const rws::RAPIDNum& state) { } } -uint8_t map_state_machine_egm_action(const rws::RAPIDNum& action) { - switch (static_cast(action.value)) { +uint8_t map_state_machine_egm_action(const rws::RAPIDNum& action) +{ + switch (static_cast(action.value)) + { case 0: return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_NONE; break; @@ -139,7 +147,8 @@ uint8_t map_state_machine_egm_action(const rws::RAPIDNum& action) { } } -abb_rapid_msgs::msg::Pos map(const rws::Pos& rws_pos) { +abb_rapid_msgs::msg::Pos map(const rws::Pos& rws_pos) +{ abb_rapid_msgs::msg::Pos ros_pos{}; ros_pos.x = rws_pos.x.value; ros_pos.y = rws_pos.y.value; @@ -147,7 +156,8 @@ abb_rapid_msgs::msg::Pos map(const rws::Pos& rws_pos) { return ros_pos; } -abb_rapid_msgs::msg::Orient map(const rws::Orient& rws_orient) { +abb_rapid_msgs::msg::Orient map(const rws::Orient& rws_orient) +{ abb_rapid_msgs::msg::Orient ros_orient{}; ros_orient.q1 = rws_orient.q1.value; ros_orient.q2 = rws_orient.q2.value; @@ -156,14 +166,16 @@ abb_rapid_msgs::msg::Orient map(const rws::Orient& rws_orient) { return ros_orient; } -abb_rapid_msgs::msg::Pose map(const rws::Pose& rws_pose) { +abb_rapid_msgs::msg::Pose map(const rws::Pose& rws_pose) +{ abb_rapid_msgs::msg::Pose ros_pose{}; ros_pose.trans = map(rws_pose.pos); ros_pose.rot = map(rws_pose.rot); return ros_pose; } -abb_rapid_msgs::msg::LoadData map(const rws::LoadData& rws_loaddata) { +abb_rapid_msgs::msg::LoadData map(const rws::LoadData& rws_loaddata) +{ abb_rapid_msgs::msg::LoadData ros_loaddata{}; ros_loaddata.mass = rws_loaddata.mass.value; ros_loaddata.cog = map(rws_loaddata.cog); @@ -174,7 +186,8 @@ abb_rapid_msgs::msg::LoadData map(const rws::LoadData& rws_loaddata) { return ros_loaddata; } -abb_rapid_msgs::msg::ToolData map(const rws::ToolData& rws_tooldata) { +abb_rapid_msgs::msg::ToolData map(const rws::ToolData& rws_tooldata) +{ abb_rapid_msgs::msg::ToolData ros_tooldata{}; ros_tooldata.robhold = rws_tooldata.robhold.value; ros_tooldata.tframe = map(rws_tooldata.tframe); @@ -182,7 +195,8 @@ abb_rapid_msgs::msg::ToolData map(const rws::ToolData& rws_tooldata) { return ros_tooldata; } -abb_rapid_msgs::msg::WObjData map(const rws::WObjData& rws_wobjdata) { +abb_rapid_msgs::msg::WObjData map(const rws::WObjData& rws_wobjdata) +{ abb_rapid_msgs::msg::WObjData ros_wobjdata{}; ros_wobjdata.robhold = rws_wobjdata.robhold.value; ros_wobjdata.ufprog = rws_wobjdata.ufprog.value; @@ -192,7 +206,8 @@ abb_rapid_msgs::msg::WObjData map(const rws::WObjData& rws_wobjdata) { return ros_wobjdata; } -abb_rapid_sm_addin_msgs::msg::EGMSettings map(const rws::RWSStateMachineInterface::EGMSettings& rws_egm_settings) { +abb_rapid_sm_addin_msgs::msg::EGMSettings map(const rws::RWSStateMachineInterface::EGMSettings& rws_egm_settings) +{ abb_rapid_sm_addin_msgs::msg::EGMSettings ros_egm_settings{}; ros_egm_settings.allow_egm_motions = rws_egm_settings.allow_egm_motions.value; @@ -220,8 +235,10 @@ abb_rapid_sm_addin_msgs::msg::EGMSettings map(const rws::RWSStateMachineInterfac return ros_egm_settings; } -unsigned int map_state_machine_sg_command(const unsigned int command) { - switch (command) { +unsigned int map_state_machine_sg_command(const unsigned int command) +{ + switch (command) + { case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_NONE: return rws::RWSStateMachineInterface::SG_COMMAND_NONE; break; @@ -280,12 +297,13 @@ unsigned int map_state_machine_sg_command(const unsigned int command) { case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_UNKNOWN: default: - throw std::runtime_error{"Unknown SmartGripper command"}; + throw std::runtime_error{ "Unknown SmartGripper command" }; break; } } -rws::Pos map(const abb_rapid_msgs::msg::Pos& ros_pos) { +rws::Pos map(const abb_rapid_msgs::msg::Pos& ros_pos) +{ rws::Pos rws_pos{}; rws_pos.x.value = ros_pos.x; rws_pos.y.value = ros_pos.y; @@ -293,7 +311,8 @@ rws::Pos map(const abb_rapid_msgs::msg::Pos& ros_pos) { return rws_pos; } -rws::Orient map(const abb_rapid_msgs::msg::Orient& ros_orient) { +rws::Orient map(const abb_rapid_msgs::msg::Orient& ros_orient) +{ rws::Orient rws_orient{}; rws_orient.q1 = ros_orient.q1; rws_orient.q2 = ros_orient.q2; @@ -302,14 +321,16 @@ rws::Orient map(const abb_rapid_msgs::msg::Orient& ros_orient) { return rws_orient; } -rws::Pose map(const abb_rapid_msgs::msg::Pose& ros_pose) { +rws::Pose map(const abb_rapid_msgs::msg::Pose& ros_pose) +{ rws::Pose rws_pose{}; rws_pose.pos = map(ros_pose.trans); rws_pose.rot = map(ros_pose.rot); return rws_pose; } -rws::LoadData map(const abb_rapid_msgs::msg::LoadData& ros_loaddata) { +rws::LoadData map(const abb_rapid_msgs::msg::LoadData& ros_loaddata) +{ rws::LoadData rws_loaddata{}; rws_loaddata.mass.value = ros_loaddata.mass; rws_loaddata.cog = map(ros_loaddata.cog); @@ -320,7 +341,8 @@ rws::LoadData map(const abb_rapid_msgs::msg::LoadData& ros_loaddata) { return rws_loaddata; } -rws::ToolData map(const abb_rapid_msgs::msg::ToolData& ros_tooldata) { +rws::ToolData map(const abb_rapid_msgs::msg::ToolData& ros_tooldata) +{ rws::ToolData rws_tooldata{}; rws_tooldata.robhold = ros_tooldata.robhold; rws_tooldata.tframe = map(ros_tooldata.tframe); @@ -328,7 +350,8 @@ rws::ToolData map(const abb_rapid_msgs::msg::ToolData& ros_tooldata) { return rws_tooldata; } -rws::WObjData map(const abb_rapid_msgs::msg::WObjData& ros_wobjdata) { +rws::WObjData map(const abb_rapid_msgs::msg::WObjData& ros_wobjdata) +{ rws::WObjData rws_wobjdata{}; rws_wobjdata.robhold.value = ros_wobjdata.robhold; rws_wobjdata.ufprog.value = ros_wobjdata.ufprog; @@ -338,7 +361,8 @@ rws::WObjData map(const abb_rapid_msgs::msg::WObjData& ros_wobjdata) { return rws_wobjdata; } -rws::RWSStateMachineInterface::EGMSettings map(const abb_rapid_sm_addin_msgs::msg::EGMSettings& ros_egm_settings) { +rws::RWSStateMachineInterface::EGMSettings map(const abb_rapid_sm_addin_msgs::msg::EGMSettings& ros_egm_settings) +{ rws::RWSStateMachineInterface::EGMSettings rws_egm_settings{}; rws_egm_settings.allow_egm_motions.value = ros_egm_settings.allow_egm_motions; @@ -366,8 +390,10 @@ rws::RWSStateMachineInterface::EGMSettings map(const abb_rapid_sm_addin_msgs::ms return rws_egm_settings; } -uint8_t map(egm::wrapper::Status::EGMState state) { - switch (state) { +uint8_t map(egm::wrapper::Status::EGMState state) +{ + switch (state) + { case egm::wrapper::Status::EGM_ERROR: return abb_egm_msgs::msg::EGMChannelState::EGM_ERROR; break; @@ -387,8 +413,10 @@ uint8_t map(egm::wrapper::Status::EGMState state) { } } -uint8_t map(egm::wrapper::Status::MotorState state) { - switch (state) { +uint8_t map(egm::wrapper::Status::MotorState state) +{ + switch (state) + { case egm::wrapper::Status::MOTORS_ON: return abb_egm_msgs::msg::EGMChannelState::MOTORS_ON; break; @@ -404,8 +432,10 @@ uint8_t map(egm::wrapper::Status::MotorState state) { } } -uint8_t map(egm::wrapper::Status::RAPIDExecutionState state) { - switch (state) { +uint8_t map(egm::wrapper::Status::RAPIDExecutionState state) +{ + switch (state) + { case egm::wrapper::Status::RAPID_STOPPED: return abb_egm_msgs::msg::EGMChannelState::RAPID_STOPPED; break; @@ -422,16 +452,19 @@ uint8_t map(egm::wrapper::Status::RAPIDExecutionState state) { } template -std::string map_vector_to_string(const std::vector& vector) { +std::string map_vector_to_string(const std::vector& vector) +{ std::stringstream ss{}; ss << "["; - for (size_t i{0}; i < vector.size(); ++i) { + for (size_t i{ 0 }; i < vector.size(); ++i) + { ss << vector[i]; - if (ss.fail()) { - std::string error_message{"Failed to map vector to string"}; - throw std::runtime_error{error_message}; + if (ss.fail()) + { + std::string error_message{ "Failed to map vector to string" }; + throw std::runtime_error{ error_message }; } ss << (i < vector.size() - 1 ? ", " : ""); diff --git a/abb_rws_client/src/rws_client.cpp b/abb_rws_client/src/rws_client.cpp index 3c9c53a..239ac89 100644 --- a/abb_rws_client/src/rws_client.cpp +++ b/abb_rws_client/src/rws_client.cpp @@ -42,18 +42,20 @@ #include "abb_rws_client/utilities.hpp" - -namespace abb_rws_client { -RWSClient::RWSClient(const rclcpp::Node::SharedPtr &node, const std::string &robot_ip, unsigned short robot_port) - : node_(node), - rws_manager_{robot_ip, robot_port, abb::rws::SystemConstants::General::DEFAULT_USERNAME, - abb::rws::SystemConstants::General::DEFAULT_PASSWORD} { +namespace abb_rws_client +{ +RWSClient::RWSClient(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port) + : node_(node) + , rws_manager_{ robot_ip, robot_port, abb::rws::SystemConstants::General::DEFAULT_USERNAME, + abb::rws::SystemConstants::General::DEFAULT_PASSWORD } +{ node_->declare_parameter("robot_nickname", std::string{}); node_->declare_parameter("no_connection_timeout", false); connect(); } -void RWSClient::connect() { +void RWSClient::connect() +{ std::string robot_id; bool no_connection_timeout; diff --git a/abb_rws_client/src/rws_client_node.cpp b/abb_rws_client/src/rws_client_node.cpp index af3c152..97489ca 100644 --- a/abb_rws_client/src/rws_client_node.cpp +++ b/abb_rws_client/src/rws_client_node.cpp @@ -3,7 +3,8 @@ #include "abb_rws_client/rws_service_provider_ros.hpp" #include "abb_rws_client/rws_state_publisher_ros.hpp" -int main(int argc, char** argv) { +int main(int argc, char** argv) +{ rclcpp::init(argc, argv); rclcpp::Node::SharedPtr client_node = rclcpp::Node::make_shared("rws"); diff --git a/abb_rws_client/src/rws_service_provider_ros.cpp b/abb_rws_client/src/rws_service_provider_ros.cpp index c5f6ed9..b03f79c 100644 --- a/abb_rws_client/src/rws_service_provider_ros.cpp +++ b/abb_rws_client/src/rws_service_provider_ros.cpp @@ -47,10 +47,12 @@ using RAPIDSymbols = abb::rws::RWSStateMachineInterface::ResourceIdentifiers::RAPID::Symbols; -namespace abb_rws_client { +namespace abb_rws_client +{ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port) - : RWSClient(node, robot_ip, robot_port) { + : RWSClient(node, robot_ip, robot_port) +{ system_state_sub_ = node_->create_subscription( "system_states", 10, std::bind(&RWSServiceProviderROS::system_state_callback, this, std::placeholders::_1)); runtime_state_sub_ = node_->create_subscription( @@ -128,22 +130,29 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node auto has_sm_1_0 = system_indicators.addins().has_state_machine_1_0(); auto has_sm_1_1 = system_indicators.addins().has_state_machine_1_1(); - if (has_sm_1_0) { + if (has_sm_1_0) + { RCLCPP_DEBUG_STREAM(node_->get_logger(), "StateMachine Add-In 1.0 detected"); - } else if (has_sm_1_1) { + } + else if (has_sm_1_1) + { RCLCPP_DEBUG_STREAM(node_->get_logger(), "StateMachine Add-In 1.1 detected"); - } else { + } + else + { RCLCPP_DEBUG_STREAM(node_->get_logger(), "No StateMachine Add-In detected"); } - if (has_sm_1_0 || has_sm_1_1) { + if (has_sm_1_0 || has_sm_1_1) + { sm_services_.push_back(node_->create_service( "~/run_rapid_routine", std::bind(&RWSServiceProviderROS::run_rapid_routine, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( "~/set_rapid_routine", std::bind(&RWSServiceProviderROS::set_rapid_routine, this, std::placeholders::_1, std::placeholders::_2))); - if (system_indicators.options().egm()) { + if (system_indicators.options().egm()) + { sm_services_.push_back(node_->create_service( "get_egm_settings", std::bind(&RWSServiceProviderROS::get_egm_settings, this, std::placeholders::_1, std::placeholders::_2))); @@ -158,7 +167,8 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node std::bind(&RWSServiceProviderROS::start_egm_pose, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( "stop_egm", std::bind(&RWSServiceProviderROS::stop_egm, this, std::placeholders::_1, std::placeholders::_2))); - if (has_sm_1_1) { + if (has_sm_1_1) + { sm_services_.push_back(node_->create_service( "start_egm_stream", std::bind(&RWSServiceProviderROS::start_egm_stream, this, std::placeholders::_1, std::placeholders::_2))); @@ -168,7 +178,8 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node } } - if (system_indicators.addins().smart_gripper()) { + if (system_indicators.addins().smart_gripper()) + { sm_services_.push_back(node_->create_service( "run_sg_routine", std::bind(&RWSServiceProviderROS::run_sg_routine, this, std::placeholders::_1, std::placeholders::_2))); @@ -180,15 +191,20 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node RCLCPP_INFO(node_->get_logger(), "RWS client services initialized!"); } -void RWSServiceProviderROS::system_state_callback(const abb_robot_msgs::msg::SystemState& msg) { system_state_ = msg; } +void RWSServiceProviderROS::system_state_callback(const abb_robot_msgs::msg::SystemState& msg) +{ + system_state_ = msg; +} -void RWSServiceProviderROS::runtime_state_callback(const abb_rapid_sm_addin_msgs::msg::RuntimeState& msg) { +void RWSServiceProviderROS::runtime_state_callback(const abb_rapid_sm_addin_msgs::msg::RuntimeState& msg) +{ runtime_state_ = msg; } bool RWSServiceProviderROS::get_rc_description( const abb_robot_msgs::srv::GetRobotControllerDescription::Request::SharedPtr req, - abb_robot_msgs::srv::GetRobotControllerDescription::Response::SharedPtr res) { + abb_robot_msgs::srv::GetRobotControllerDescription::Response::SharedPtr res) +{ res->description = robot_controller_description_.DebugString(); res->message = abb_robot_msgs::msg::ServiceResponses::SUCCESS; @@ -198,18 +214,24 @@ bool RWSServiceProviderROS::get_rc_description( } bool RWSServiceProviderROS::get_file_contents(const abb_robot_msgs::srv::GetFileContents::Request::SharedPtr req, - abb_robot_msgs::srv::GetFileContents::Response::SharedPtr res) { - if (!verify_argument_filename(req->filename, res->result_code, res->message)) { + abb_robot_msgs::srv::GetFileContents::Response::SharedPtr res) +{ + if (!verify_argument_filename(req->filename, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.getFile(abb::rws::RWSClient::FileResource(req->filename), &res->contents)) { + if (interface.getFile(abb::rws::RWSClient::FileResource(req->filename), &res->contents)) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -220,20 +242,26 @@ bool RWSServiceProviderROS::get_file_contents(const abb_robot_msgs::srv::GetFile } bool RWSServiceProviderROS::get_io_signal(const abb_robot_msgs::srv::GetIOSignal::Request::SharedPtr req, - abb_robot_msgs::srv::GetIOSignal::Response::SharedPtr res) { - if (!verify_argument_signal(req->signal, res->result_code, res->message)) { + abb_robot_msgs::srv::GetIOSignal::Response::SharedPtr res) +{ + if (!verify_argument_signal(req->signal, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { res->value = interface.getIOSignal(req->signal); - if (!res->value.empty()) { + if (!res->value.empty()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -244,20 +272,26 @@ bool RWSServiceProviderROS::get_io_signal(const abb_robot_msgs::srv::GetIOSignal } bool RWSServiceProviderROS::get_rapid_bool(const abb_robot_msgs::srv::GetRAPIDBool::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDBool::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + abb_robot_msgs::srv::GetRAPIDBool::Response::SharedPtr res) +{ + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { abb::rws::RAPIDBool rapid_bool; - if (interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, &rapid_bool)) { + if (interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, &rapid_bool)) + { res->value = rapid_bool.value; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -268,20 +302,26 @@ bool RWSServiceProviderROS::get_rapid_bool(const abb_robot_msgs::srv::GetRAPIDBo } bool RWSServiceProviderROS::get_rapid_dnum(const abb_robot_msgs::srv::GetRAPIDDnum::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDDnum::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + abb_robot_msgs::srv::GetRAPIDDnum::Response::SharedPtr res) +{ + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { abb::rws::RAPIDDnum rapid_dnum; - if (interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, &rapid_dnum)) { + if (interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, &rapid_dnum)) + { res->value = rapid_dnum.value; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -292,20 +332,26 @@ bool RWSServiceProviderROS::get_rapid_dnum(const abb_robot_msgs::srv::GetRAPIDDn } bool RWSServiceProviderROS::get_rapid_num(const abb_robot_msgs::srv::GetRAPIDNum::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDNum::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + abb_robot_msgs::srv::GetRAPIDNum::Response::SharedPtr res) +{ + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { abb::rws::RAPIDNum rapid_num{}; - if (interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, &rapid_num)) { + if (interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, &rapid_num)) + { res->value = rapid_num.value; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -316,20 +362,26 @@ bool RWSServiceProviderROS::get_rapid_num(const abb_robot_msgs::srv::GetRAPIDNum } bool RWSServiceProviderROS::get_rapid_string(const abb_robot_msgs::srv::GetRAPIDString::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDString::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + abb_robot_msgs::srv::GetRAPIDString::Response::SharedPtr res) +{ + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { abb::rws::RAPIDString rapid_string{}; - if (interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, &rapid_string)) { + if (interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, &rapid_string)) + { res->value = rapid_string.value; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -340,20 +392,26 @@ bool RWSServiceProviderROS::get_rapid_string(const abb_robot_msgs::srv::GetRAPID } bool RWSServiceProviderROS::get_rapid_symbol(const abb_robot_msgs::srv::GetRAPIDSymbol::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDSymbol::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + abb_robot_msgs::srv::GetRAPIDSymbol::Response::SharedPtr res) +{ + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { res->value = interface.getRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol); - if (!res->value.empty()) { + if (!res->value.empty()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -364,16 +422,21 @@ bool RWSServiceProviderROS::get_rapid_symbol(const abb_robot_msgs::srv::GetRAPID } bool RWSServiceProviderROS::get_speed_ratio(const abb_robot_msgs::srv::GetSpeedRatio::Request::SharedPtr, - abb_robot_msgs::srv::GetSpeedRatio::Response::SharedPtr res) { - if (!verify_rws_manager_ready(res->result_code, res->message)) { + abb_robot_msgs::srv::GetSpeedRatio::Response::SharedPtr res) +{ + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - try { + try + { res->speed_ratio = interface.getSpeedRatio(); res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } catch (const std::runtime_error& exception) { + } + catch (const std::runtime_error& exception) + { res->message = exception.what(); res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -384,21 +447,28 @@ bool RWSServiceProviderROS::get_speed_ratio(const abb_robot_msgs::srv::GetSpeedR } bool RWSServiceProviderROS::pp_to_main(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) { + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rapid_stopped(res->result_code, res->message)) { + if (!verify_rapid_stopped(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.resetRAPIDProgramPointer()) { + if (interface.resetRAPIDProgramPointer()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } @@ -407,24 +477,32 @@ bool RWSServiceProviderROS::pp_to_main(const abb_robot_msgs::srv::TriggerWithRes return true; } bool RWSServiceProviderROS::run_rapid_routine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) { + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rapid_running(res->result_code, res->message)) { + if (!verify_rapid_running(res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.services().rapid().signalRunRAPIDRoutine()) { + if (interface.services().rapid().signalRunRAPIDRoutine()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -435,24 +513,32 @@ bool RWSServiceProviderROS::run_rapid_routine(const abb_robot_msgs::srv::Trigger } bool RWSServiceProviderROS::run_sg_routine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) { + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rapid_running(res->result_code, res->message)) { + if (!verify_rapid_running(res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.services().sg().signalRunSGRoutine()) { + if (interface.services().sg().signalRunSGRoutine()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -463,18 +549,24 @@ bool RWSServiceProviderROS::run_sg_routine(const abb_robot_msgs::srv::TriggerWit } bool RWSServiceProviderROS::set_file_contents(const abb_robot_msgs::srv::SetFileContents::Request::SharedPtr req, - abb_robot_msgs::srv::SetFileContents::Response::SharedPtr res) { - if (!verify_argument_filename(req->filename, res->result_code, res->message)) { + abb_robot_msgs::srv::SetFileContents::Response::SharedPtr res) +{ + if (!verify_argument_filename(req->filename, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.uploadFile(abb::rws::RWSClient::FileResource(req->filename), req->contents)) { + if (interface.uploadFile(abb::rws::RWSClient::FileResource(req->filename), req->contents)) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -485,18 +577,24 @@ bool RWSServiceProviderROS::set_file_contents(const abb_robot_msgs::srv::SetFile } bool RWSServiceProviderROS::set_io_signal(const abb_robot_msgs::srv::SetIOSignal::Request::SharedPtr req, - abb_robot_msgs::srv::SetIOSignal::Response::SharedPtr res) { - if (!verify_argument_signal(req->signal, res->result_code, res->message)) { + abb_robot_msgs::srv::SetIOSignal::Response::SharedPtr res) +{ + if (!verify_argument_signal(req->signal, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.setIOSignal(req->signal, req->value)) { + if (interface.setIOSignal(req->signal, req->value)) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -507,15 +605,20 @@ bool RWSServiceProviderROS::set_io_signal(const abb_robot_msgs::srv::SetIOSignal } bool RWSServiceProviderROS::set_motors_off(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_motors_on(res->result_code, res->message)) { + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verify_motors_on(res->result_code, res->message)) + { return true; } rws_manager_.runPriorityService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.setMotorsOff()) { + if (interface.setMotorsOff()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } @@ -525,21 +628,28 @@ bool RWSServiceProviderROS::set_motors_off(const abb_robot_msgs::srv::TriggerWit } bool RWSServiceProviderROS::set_motors_on(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) { + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_motors_off(res->result_code, res->message)) { + if (!verify_motors_off(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.setMotorsOn()) { + if (interface.setMotorsOn()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } @@ -549,22 +659,29 @@ bool RWSServiceProviderROS::set_motors_on(const abb_robot_msgs::srv::TriggerWith } bool RWSServiceProviderROS::set_rapid_bool(const abb_robot_msgs::srv::SetRAPIDBool::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDBool::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + abb_robot_msgs::srv::SetRAPIDBool::Response::SharedPtr res) +{ + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + { return true; } - if (!verify_auto_mode(res->result_code, res->message)) { + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { abb::rws::RAPIDBool rapid_bool = static_cast(req->value); - if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, rapid_bool)) { + if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, rapid_bool)) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -575,22 +692,29 @@ bool RWSServiceProviderROS::set_rapid_bool(const abb_robot_msgs::srv::SetRAPIDBo } bool RWSServiceProviderROS::set_rapid_dnum(const abb_robot_msgs::srv::SetRAPIDDnum::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDDnum::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + abb_robot_msgs::srv::SetRAPIDDnum::Response::SharedPtr res) +{ + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + { return true; } - if (!verify_auto_mode(res->result_code, res->message)) { + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { abb::rws::RAPIDDnum rapid_dnum = req->value; - if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, rapid_dnum)) { + if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, rapid_dnum)) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -601,25 +725,32 @@ bool RWSServiceProviderROS::set_rapid_dnum(const abb_robot_msgs::srv::SetRAPIDDn } bool RWSServiceProviderROS::set_rapid_num(const abb_robot_msgs::srv::SetRAPIDNum::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDNum::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + abb_robot_msgs::srv::SetRAPIDNum::Response::SharedPtr res) +{ + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + { return true; } - if (!verify_auto_mode(res->result_code, res->message)) { + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { abb::rws::RAPIDNum rapid_num = req->value; - if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, rapid_num)) { + if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, rapid_num)) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } }); @@ -627,22 +758,29 @@ bool RWSServiceProviderROS::set_rapid_num(const abb_robot_msgs::srv::SetRAPIDNum } bool RWSServiceProviderROS::set_rapid_string(const abb_robot_msgs::srv::SetRAPIDString::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDString::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + abb_robot_msgs::srv::SetRAPIDString::Response::SharedPtr res) +{ + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + { return true; } - if (!verify_auto_mode(res->result_code, res->message)) { + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { abb::rws::RAPIDString rapid_string = req->value; - if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, rapid_string)) { + if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, rapid_string)) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -653,21 +791,28 @@ bool RWSServiceProviderROS::set_rapid_string(const abb_robot_msgs::srv::SetRAPID } bool RWSServiceProviderROS::set_rapid_symbol(const abb_robot_msgs::srv::SetRAPIDSymbol::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDSymbol::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { + abb_robot_msgs::srv::SetRAPIDSymbol::Response::SharedPtr res) +{ + if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + { return true; } - if (!verify_auto_mode(res->result_code, res->message)) { + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, req->value)) { + if (interface.setRAPIDSymbolData(req->path.task, req->path.module, req->path.symbol, req->value)) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -678,23 +823,32 @@ bool RWSServiceProviderROS::set_rapid_symbol(const abb_robot_msgs::srv::SetRAPID } bool RWSServiceProviderROS::set_speed_ratio(const abb_robot_msgs::srv::SetSpeedRatio::Request::SharedPtr req, - abb_robot_msgs::srv::SetSpeedRatio::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) { + abb_robot_msgs::srv::SetSpeedRatio::Response::SharedPtr res) +{ + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - try { - if (interface.setSpeedRatio(req->speed_ratio)) { + try + { + if (interface.setSpeedRatio(req->speed_ratio)) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; } - } catch (const std::exception& exception) { + } + catch (const std::exception& exception) + { res->message = exception.what(); RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } @@ -704,21 +858,28 @@ bool RWSServiceProviderROS::set_speed_ratio(const abb_robot_msgs::srv::SetSpeedR } bool RWSServiceProviderROS::start_rapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) { + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_motors_on(res->result_code, res->message)) { + if (!verify_motors_on(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.startRAPIDExecution()) { + if (interface.startRAPIDExecution()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } @@ -728,15 +889,20 @@ bool RWSServiceProviderROS::start_rapid(const abb_robot_msgs::srv::TriggerWithRe } bool RWSServiceProviderROS::stop_rapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_rapid_running(res->result_code, res->message)) { + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verify_rapid_running(res->result_code, res->message)) + { return true; } rws_manager_.runPriorityService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.stopRAPIDExecution()) { + if (interface.stopRAPIDExecution()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); } @@ -746,27 +912,35 @@ bool RWSServiceProviderROS::stop_rapid(const abb_robot_msgs::srv::TriggerWithRes } bool RWSServiceProviderROS::get_egm_settings(const abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Request::SharedPtr req, - abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Response::SharedPtr res) { - if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) { + abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Response::SharedPtr res) +{ + if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) { + if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { abb::rws::RWSStateMachineInterface::EGMSettings settings; - if (interface.services().egm().getSettings(req->task, &settings)) { + if (interface.services().egm().getSettings(req->task, &settings)) + { res->settings = abb::robot::utilities::map(settings); res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -777,32 +951,42 @@ bool RWSServiceProviderROS::get_egm_settings(const abb_rapid_sm_addin_msgs::srv: } bool RWSServiceProviderROS::set_egm_settings(const abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Request::SharedPtr req, - abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Response::SharedPtr res) { - if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) { + abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Response::SharedPtr res) +{ + if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) + { return true; } - if (!verify_auto_mode(res->result_code, res->message)) { + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) { + if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_task_initialized(req->task, res->result_code, res->message)) { + if (!verify_sm_addin_task_initialized(req->task, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { abb::rws::RWSStateMachineInterface::EGMSettings settings = abb::robot::utilities::map(req->settings); - if (interface.services().egm().setSettings(req->task, settings)) { + if (interface.services().egm().setSettings(req->task, settings)) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -814,30 +998,40 @@ bool RWSServiceProviderROS::set_egm_settings(const abb_rapid_sm_addin_msgs::srv: bool RWSServiceProviderROS::set_rapid_routine( const abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Request::SharedPtr req, - abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Response::SharedPtr res) { - if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) { + abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Response::SharedPtr res) +{ + if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) + { return true; } - if (!verify_auto_mode(res->result_code, res->message)) { + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) { + if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_task_initialized(req->task, res->result_code, res->message)) { + if (!verify_sm_addin_task_initialized(req->task, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.services().rapid().setRoutineName(req->task, req->routine)) { + if (interface.services().rapid().setRoutineName(req->task, req->routine)) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -848,30 +1042,40 @@ bool RWSServiceProviderROS::set_rapid_routine( } bool RWSServiceProviderROS::set_sg_command(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, - abb_rapid_sm_addin_msgs::srv::SetSGCommand::Response::SharedPtr res) { - if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) { + abb_rapid_sm_addin_msgs::srv::SetSGCommand::Response::SharedPtr res) +{ + if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) + { return true; } - if (!verify_auto_mode(res->result_code, res->message)) { + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) { + if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_task_initialized(req->task, res->result_code, res->message)) { + if (!verify_sm_addin_task_initialized(req->task, res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } unsigned int req_command = 0; - try { + try + { req_command = abb::robot::utilities::map_state_machine_sg_command(req->command); - } catch (const std::runtime_error& exception) { + } + catch (const std::runtime_error& exception) + { res->message = exception.what(); res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; return true; @@ -882,9 +1086,12 @@ bool RWSServiceProviderROS::set_sg_command(const abb_rapid_sm_addin_msgs::srv::S abb::rws::RAPIDNum sg_target_position_input = req->target_position; if (interface.setRAPIDSymbolData(req->task, RAPIDSymbols::SG_COMMAND_INPUT, sg_command_input) && - interface.setRAPIDSymbolData(req->task, RAPIDSymbols::SG_TARGET_POSTION_INPUT, sg_target_position_input)) { + interface.setRAPIDSymbolData(req->task, RAPIDSymbols::SG_TARGET_POSTION_INPUT, sg_target_position_input)) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -895,24 +1102,32 @@ bool RWSServiceProviderROS::set_sg_command(const abb_rapid_sm_addin_msgs::srv::S } bool RWSServiceProviderROS::start_egm_joint(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) { + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rapid_running(res->result_code, res->message)) { + if (!verify_rapid_running(res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.services().egm().signalEGMStartJoint()) { + if (interface.services().egm().signalEGMStartJoint()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -923,24 +1138,32 @@ bool RWSServiceProviderROS::start_egm_joint(const abb_robot_msgs::srv::TriggerWi } bool RWSServiceProviderROS::start_egm_pose(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) { + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rapid_running(res->result_code, res->message)) { + if (!verify_rapid_running(res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.services().egm().signalEGMStartPose()) { + if (interface.services().egm().signalEGMStartPose()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -951,24 +1174,32 @@ bool RWSServiceProviderROS::start_egm_pose(const abb_robot_msgs::srv::TriggerWit } bool RWSServiceProviderROS::start_egm_stream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) { + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rapid_running(res->result_code, res->message)) { + if (!verify_rapid_running(res->result_code, res->message)) + { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) { + if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.services().egm().signalEGMStartStream()) { + if (interface.services().egm().signalEGMStartStream()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -979,21 +1210,28 @@ bool RWSServiceProviderROS::start_egm_stream(const abb_robot_msgs::srv::TriggerW } bool RWSServiceProviderROS::stop_egm(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) { + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rapid_running(res->result_code, res->message)) { + if (!verify_rapid_running(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runPriorityService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.services().egm().signalEGMStop()) { + if (interface.services().egm().signalEGMStop()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -1004,21 +1242,28 @@ bool RWSServiceProviderROS::stop_egm(const abb_robot_msgs::srv::TriggerWithResul } bool RWSServiceProviderROS::stop_egm_stream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) { + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verify_auto_mode(res->result_code, res->message)) + { return true; } - if (!verify_rapid_running(res->result_code, res->message)) { + if (!verify_rapid_running(res->result_code, res->message)) + { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) { + if (!verify_rws_manager_ready(res->result_code, res->message)) + { return true; } rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.services().egm().signalEGMStopStream()) { + if (interface.services().egm().signalEGMStopStream()) + { res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } else { + } + else + { res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); @@ -1028,8 +1273,10 @@ bool RWSServiceProviderROS::stop_egm_stream(const abb_robot_msgs::srv::TriggerWi return true; } -bool RWSServiceProviderROS::verify_auto_mode(uint16_t& result_code, std::string& message) { - if (!system_state_.auto_mode) { +bool RWSServiceProviderROS::verify_auto_mode(uint16_t& result_code, std::string& message) +{ + if (!system_state_.auto_mode) + { message = abb_robot_msgs::msg::ServiceResponses::NOT_IN_AUTO_MODE; result_code = abb_robot_msgs::msg::ServiceResponses::RC_NOT_IN_AUTO_MODE; return false; @@ -1039,8 +1286,10 @@ bool RWSServiceProviderROS::verify_auto_mode(uint16_t& result_code, std::string& } bool RWSServiceProviderROS::verify_argument_filename(const std::string& filename, uint16_t& result_code, - std::string& message) { - if (filename.empty()) { + std::string& message) +{ + if (filename.empty()) + { message = abb_robot_msgs::msg::ServiceResponses::EMPTY_FILENAME; result_code = abb_robot_msgs::msg::ServiceResponses::RC_EMPTY_FILENAME; return false; @@ -1050,20 +1299,24 @@ bool RWSServiceProviderROS::verify_argument_filename(const std::string& filename } bool RWSServiceProviderROS::verify_argument_rapid_symbol_path(const abb_robot_msgs::msg::RAPIDSymbolPath& path, - uint16_t& result_code, std::string& message) { - if (path.task.empty()) { + uint16_t& result_code, std::string& message) +{ + if (path.task.empty()) + { message = abb_robot_msgs::msg::ServiceResponses::EMPTY_RAPID_TASK_NAME; result_code = abb_robot_msgs::msg::ServiceResponses::RC_EMPTY_RAPID_TASK_NAME; return false; } - if (path.module.empty()) { + if (path.module.empty()) + { message = abb_robot_msgs::msg::ServiceResponses::EMPTY_RAPID_MODULE_NAME; result_code = abb_robot_msgs::msg::ServiceResponses::RC_EMPTY_RAPID_MODULE_NAME; return false; } - if (path.symbol.empty()) { + if (path.symbol.empty()) + { message = abb_robot_msgs::msg::ServiceResponses::EMPTY_RAPID_SYMBOL_NAME; result_code = abb_robot_msgs::msg::ServiceResponses::RC_EMPTY_RAPID_SYMBOL_NAME; return false; @@ -1073,8 +1326,10 @@ bool RWSServiceProviderROS::verify_argument_rapid_symbol_path(const abb_robot_ms } bool RWSServiceProviderROS::verify_argument_rapid_task(const std::string& task, uint16_t& result_code, - std::string& message) { - if (task.empty()) { + std::string& message) +{ + if (task.empty()) + { message = abb_robot_msgs::msg::ServiceResponses::EMPTY_RAPID_TASK_NAME; result_code = abb_robot_msgs::msg::ServiceResponses::RC_EMPTY_RAPID_TASK_NAME; return false; @@ -1084,8 +1339,10 @@ bool RWSServiceProviderROS::verify_argument_rapid_task(const std::string& task, } bool RWSServiceProviderROS::verify_argument_signal(const std::string& signal, uint16_t& result_code, - std::string& message) { - if (signal.empty()) { + std::string& message) +{ + if (signal.empty()) + { message = abb_robot_msgs::msg::ServiceResponses::EMPTY_SIGNAL_NAME; result_code = abb_robot_msgs::msg::ServiceResponses::RC_EMPTY_SIGNAL_NAME; return false; @@ -1094,8 +1351,10 @@ bool RWSServiceProviderROS::verify_argument_signal(const std::string& signal, ui return true; } -bool RWSServiceProviderROS::verify_motors_off(uint16_t& result_code, std::string& message) { - if (system_state_.motors_on) { +bool RWSServiceProviderROS::verify_motors_off(uint16_t& result_code, std::string& message) +{ + if (system_state_.motors_on) + { message = abb_robot_msgs::msg::ServiceResponses::MOTORS_ARE_ON; result_code = abb_robot_msgs::msg::ServiceResponses::RC_MOTORS_ARE_ON; return false; @@ -1104,8 +1363,10 @@ bool RWSServiceProviderROS::verify_motors_off(uint16_t& result_code, std::string return true; } -bool RWSServiceProviderROS::verify_motors_on(uint16_t& result_code, std::string& message) { - if (!system_state_.motors_on) { +bool RWSServiceProviderROS::verify_motors_on(uint16_t& result_code, std::string& message) +{ + if (!system_state_.motors_on) + { message = abb_robot_msgs::msg::ServiceResponses::MOTORS_ARE_OFF; result_code = abb_robot_msgs::msg::ServiceResponses::RC_MOTORS_ARE_OFF; return false; @@ -1114,8 +1375,10 @@ bool RWSServiceProviderROS::verify_motors_on(uint16_t& result_code, std::string& return true; } -bool RWSServiceProviderROS::verify_sm_addin_runtime_states(uint16_t& result_code, std::string& message) { - if (runtime_state_.state_machines.empty()) { +bool RWSServiceProviderROS::verify_sm_addin_runtime_states(uint16_t& result_code, std::string& message) +{ + if (runtime_state_.state_machines.empty()) + { message = abb_robot_msgs::msg::ServiceResponses::SM_RUNTIME_STATES_MISSING; result_code = abb_robot_msgs::msg::ServiceResponses::RC_SM_RUNTIME_STATES_MISSING; return false; @@ -1125,11 +1388,13 @@ bool RWSServiceProviderROS::verify_sm_addin_runtime_states(uint16_t& result_code } bool RWSServiceProviderROS::verify_sm_addin_task_exist(const std::string& task, uint16_t& result_code, - std::string& message) { + std::string& message) +{ auto it = std::find_if(runtime_state_.state_machines.begin(), runtime_state_.state_machines.end(), [&](const auto& sm) { return sm.rapid_task == task; }); - if (it == runtime_state_.state_machines.end()) { + if (it == runtime_state_.state_machines.end()) + { message = abb_robot_msgs::msg::ServiceResponses::SM_UNKNOWN_RAPID_TASK; result_code = abb_robot_msgs::msg::ServiceResponses::RC_SM_UNKNOWN_RAPID_TASK; return false; @@ -1139,14 +1404,17 @@ bool RWSServiceProviderROS::verify_sm_addin_task_exist(const std::string& task, } bool RWSServiceProviderROS::verify_sm_addin_task_initialized(const std::string& task, uint16_t& result_code, - std::string& message) { - if (!verify_sm_addin_task_exist(task, result_code, message)) return false; + std::string& message) +{ + if (!verify_sm_addin_task_exist(task, result_code, message)) + return false; auto it = std::find_if(runtime_state_.state_machines.begin(), runtime_state_.state_machines.end(), [&](const auto& sm) { return sm.rapid_task == task; }); if (it->sm_state == abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_UNKNOWN || - it->sm_state == abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_INITIALIZE) { + it->sm_state == abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_INITIALIZE) + { message = abb_robot_msgs::msg::ServiceResponses::SM_UNINITIALIZED; result_code = abb_robot_msgs::msg::ServiceResponses::RC_SM_UNINITIALIZED; return false; @@ -1155,8 +1423,10 @@ bool RWSServiceProviderROS::verify_sm_addin_task_initialized(const std::string& return true; } -bool RWSServiceProviderROS::verify_rapid_running(uint16_t& result_code, std::string& message) { - if (!system_state_.rapid_running) { +bool RWSServiceProviderROS::verify_rapid_running(uint16_t& result_code, std::string& message) +{ + if (!system_state_.rapid_running) + { message = abb_robot_msgs::msg::ServiceResponses::RAPID_NOT_RUNNING; result_code = abb_robot_msgs::msg::ServiceResponses::RC_RAPID_NOT_RUNNING; return false; @@ -1165,8 +1435,10 @@ bool RWSServiceProviderROS::verify_rapid_running(uint16_t& result_code, std::str return true; } -bool RWSServiceProviderROS::verify_rapid_stopped(uint16_t& result_code, std::string& message) { - if (system_state_.rapid_running) { +bool RWSServiceProviderROS::verify_rapid_stopped(uint16_t& result_code, std::string& message) +{ + if (system_state_.rapid_running) + { message = abb_robot_msgs::msg::ServiceResponses::RAPID_NOT_STOPPED; result_code = abb_robot_msgs::msg::ServiceResponses::RC_RAPID_NOT_STOPPED; return false; @@ -1175,8 +1447,10 @@ bool RWSServiceProviderROS::verify_rapid_stopped(uint16_t& result_code, std::str return true; } -bool RWSServiceProviderROS::verify_rws_manager_ready(uint16_t& result_code, std::string& message) { - if (!rws_manager_.isInterfaceReady()) { +bool RWSServiceProviderROS::verify_rws_manager_ready(uint16_t& result_code, std::string& message) +{ + if (!rws_manager_.isInterfaceReady()) + { message = abb_robot_msgs::msg::ServiceResponses::SERVER_IS_BUSY; result_code = abb_robot_msgs::msg::ServiceResponses::RC_SERVER_IS_BUSY; return false; diff --git a/abb_rws_client/src/rws_state_publisher_ros.cpp b/abb_rws_client/src/rws_state_publisher_ros.cpp index 15a1df8..b48f9f8 100644 --- a/abb_rws_client/src/rws_state_publisher_ros.cpp +++ b/abb_rws_client/src/rws_state_publisher_ros.cpp @@ -43,17 +43,20 @@ #include "abb_rws_client/mapping.hpp" #include "abb_rws_client/utilities.hpp" -namespace { +namespace +{ /** * \brief Time [s] for throttled ROS logging. */ -constexpr double THROTTLE_TIME{10.0}; +constexpr double THROTTLE_TIME{ 10.0 }; } // namespace -namespace abb_rws_client { +namespace abb_rws_client +{ RWSStatePublisherROS::RWSStatePublisherROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port) - : RWSClient(node, robot_ip, robot_port) { + : RWSClient(node, robot_ip, robot_port) +{ node_->declare_parameter("polling_rate", 5.0); abb::robot::initializeMotionData(motion_data_, robot_controller_description_); @@ -64,26 +67,34 @@ RWSStatePublisherROS::RWSStatePublisherROS(const rclcpp::Node::SharedPtr& node, system_state_pub_ = node_->create_publisher("~/system_states", 1); - if (abb::robot::utilities::verify_state_machine_add_in_presence(robot_controller_description_.system_indicators())) { + if (abb::robot::utilities::verify_state_machine_add_in_presence(robot_controller_description_.system_indicators())) + { runtime_state_pub_ = node_->create_publisher("~/sm_addin/runtime_states", 1); } } -void RWSStatePublisherROS::timer_callback() { - try { +void RWSStatePublisherROS::timer_callback() +{ + try + { rws_manager_.collectAndUpdateRuntimeData(system_state_data_, motion_data_); - } catch (const std::runtime_error& exception) { + } + catch (const std::runtime_error& exception) + { auto& clk = *node_->get_clock(); - RCLCPP_WARN_STREAM_THROTTLE( - node_->get_logger(), clk, THROTTLE_TIME, - "Periodic polling of runtime data via RWS failed with '" << exception.what() << "' (will try again later)"); + RCLCPP_WARN_STREAM_THROTTLE(node_->get_logger(), clk, THROTTLE_TIME, + "Periodic polling of runtime data via RWS failed with '" << exception.what() + << "' (will try again later)"); } sensor_msgs::msg::JointState joint_state_msg; - for (auto& group : motion_data_.groups) { - for (auto& unit : group.units) { - for (auto& joint : unit.joints) { + for (auto& group : motion_data_.groups) + { + for (auto& unit : group.units) + { + for (auto& joint : unit.joints) + { joint_state_msg.name.push_back(joint.name); joint_state_msg.position.push_back(joint.state.position); } @@ -95,7 +106,8 @@ void RWSStatePublisherROS::timer_callback() { system_state_msg.auto_mode = system_state_data_.auto_mode.isTrue(); system_state_msg.rapid_running = system_state_data_.rapid_running.isTrue(); - for (const auto& task : system_state_data_.rapid_tasks) { + for (const auto& task : system_state_data_.rapid_tasks) + { abb_robot_msgs::msg::RAPIDTaskState state{}; state.name = task.name; @@ -106,7 +118,8 @@ void RWSStatePublisherROS::timer_callback() { system_state_msg.rapid_tasks.push_back(state); } - for (const auto& unit : system_state_data_.mechanical_units) { + for (const auto& unit : system_state_data_.mechanical_units) + { abb_robot_msgs::msg::MechanicalUnitState state{}; state.name = unit.first; state.activated = unit.second.active; @@ -114,9 +127,11 @@ void RWSStatePublisherROS::timer_callback() { } abb_rapid_sm_addin_msgs::msg::RuntimeState sm_runtime_state_msg; - const auto& system_indicators{robot_controller_description_.system_indicators()}; - if (abb::robot::utilities::verify_state_machine_add_in_presence(system_indicators)) { - for (const auto& sm : system_state_data_.state_machines) { + const auto& system_indicators{ robot_controller_description_.system_indicators() }; + if (abb::robot::utilities::verify_state_machine_add_in_presence(system_indicators)) + { + for (const auto& sm : system_state_data_.state_machines) + { abb_rapid_sm_addin_msgs::msg::StateMachineState state; state.rapid_task = sm.rapid_task; state.sm_state = abb::robot::utilities::map_state_machine_state(sm.sm_state); @@ -132,11 +147,10 @@ void RWSStatePublisherROS::timer_callback() { system_state_msg.header.stamp = time; system_state_pub_->publish(system_state_msg); - if (abb::robot::utilities::verify_state_machine_add_in_presence(robot_controller_description_.system_indicators())) - { - sm_runtime_state_msg.header.stamp = time; - runtime_state_pub_->publish(sm_runtime_state_msg); - } - + if (abb::robot::utilities::verify_state_machine_add_in_presence(robot_controller_description_.system_indicators())) + { + sm_runtime_state_msg.header.stamp = time; + runtime_state_pub_->publish(sm_runtime_state_msg); + } } } // namespace abb_rws_client diff --git a/abb_rws_client/src/utilities.cpp b/abb_rws_client/src/utilities.cpp index fcfd7db..7a4e9e8 100644 --- a/abb_rws_client/src/utilities.cpp +++ b/abb_rws_client/src/utilities.cpp @@ -55,62 +55,65 @@ namespace /** * \brief Max number of attempts when trying to connect to a robot controller via RWS. */ -constexpr unsigned int RWS_MAX_CONNECTION_ATTEMPTS{5}; +constexpr unsigned int RWS_MAX_CONNECTION_ATTEMPTS{ 5 }; /** * \brief Error message for failed connection attempts when trying to connect to a robot controller via RWS. */ -constexpr char RWS_CONNECTION_ERROR_MESSAGE[]{ - "Failed to establish RWS connection to the robot controller"}; +constexpr char RWS_CONNECTION_ERROR_MESSAGE[]{ "Failed to establish RWS connection to the robot controller" }; /** * \brief Time [s] to wait before trying to reconnect to a robot controller via RWS. */ -constexpr uint8_t RWS_RECONNECTION_WAIT_TIME{1}; +constexpr uint8_t RWS_RECONNECTION_WAIT_TIME{ 1 }; auto LOGGER = rclcpp::get_logger("ABBHardwareInterfaceUtilities"); } // namespace -RobotControllerDescription establish_rws_connection( - RWSManager & rws_manager, const std::string & robot_controller_id, - const bool no_connection_timeout) +RobotControllerDescription establish_rws_connection(RWSManager& rws_manager, const std::string& robot_controller_id, + const bool no_connection_timeout) { - unsigned int attempt{0}; + unsigned int attempt{ 0 }; - while (rclcpp::ok() && (no_connection_timeout || attempt++ < RWS_MAX_CONNECTION_ATTEMPTS)) { - try { + while (rclcpp::ok() && (no_connection_timeout || attempt++ < RWS_MAX_CONNECTION_ATTEMPTS)) + { + try + { return rws_manager.collectAndParseSystemData(robot_controller_id); - } catch (const std::runtime_error & exception) { - if (!no_connection_timeout) { - RCLCPP_WARN_STREAM( - LOGGER, RWS_CONNECTION_ERROR_MESSAGE << " (attempt " << attempt << "/" - << RWS_MAX_CONNECTION_ATTEMPTS << "), reason: '" - << exception.what() << "'"); - } else { - RCLCPP_WARN_STREAM( - LOGGER, RWS_CONNECTION_ERROR_MESSAGE << " (waiting indefinitely), reason: '" - << exception.what() << "'"); + } + catch (const std::runtime_error& exception) + { + if (!no_connection_timeout) + { + RCLCPP_WARN_STREAM(LOGGER, RWS_CONNECTION_ERROR_MESSAGE << " (attempt " << attempt << "/" + << RWS_MAX_CONNECTION_ATTEMPTS << "), reason: '" + << exception.what() << "'"); + } + else + { + RCLCPP_WARN_STREAM(LOGGER, RWS_CONNECTION_ERROR_MESSAGE << " (waiting indefinitely), reason: '" + << exception.what() << "'"); } rclcpp::sleep_for(std::chrono::seconds(RWS_RECONNECTION_WAIT_TIME)); } } - throw std::runtime_error{RWS_CONNECTION_ERROR_MESSAGE}; + throw std::runtime_error{ RWS_CONNECTION_ERROR_MESSAGE }; } -void verify_robotware_version(const RobotWareVersion& rw_version) { - if (rw_version.major_number() == 6 && rw_version.minor_number() < 7 && - rw_version.patch_number() < 1) { - auto error_message{"Unsupported RobotWare version (" + rw_version.name() + - ", need at least 6.07.01)"}; +void verify_robotware_version(const RobotWareVersion& rw_version) +{ + if (rw_version.major_number() == 6 && rw_version.minor_number() < 7 && rw_version.patch_number() < 1) + { + auto error_message{ "Unsupported RobotWare version (" + rw_version.name() + ", need at least 6.07.01)" }; RCLCPP_FATAL_STREAM(LOGGER, error_message); - throw std::runtime_error{error_message}; + throw std::runtime_error{ error_message }; } } -bool verify_state_machine_add_in_presence(const SystemIndicators& system_indicators) { - return system_indicators.addins().state_machine_1_0() || - system_indicators.addins().state_machine_1_1(); +bool verify_state_machine_add_in_presence(const SystemIndicators& system_indicators) +{ + return system_indicators.addins().state_machine_1_0() || system_indicators.addins().state_machine_1_1(); } } // namespace utilities } // namespace robot From 381e3945a4e239af21ae668afe071b810c3c78b1 Mon Sep 17 00:00:00 2001 From: Souphis Date: Tue, 31 May 2022 12:28:06 +0200 Subject: [PATCH 13/27] Rename methods --- .../include/abb_rws_client/mapping.hpp | 8 +- .../rws_service_provider_ros.hpp | 164 ++++++------ abb_rws_client/src/mapping.cpp | 8 +- .../src/rws_service_provider_ros.cpp | 248 +++++++++--------- .../src/rws_state_publisher_ros.cpp | 4 +- 5 files changed, 214 insertions(+), 218 deletions(-) diff --git a/abb_rws_client/include/abb_rws_client/mapping.hpp b/abb_rws_client/include/abb_rws_client/mapping.hpp index de54138..d6e7c73 100644 --- a/abb_rws_client/include/abb_rws_client/mapping.hpp +++ b/abb_rws_client/include/abb_rws_client/mapping.hpp @@ -71,7 +71,7 @@ uint8_t map(const rws::RWSInterface::RAPIDTaskExecutionState state); * * \return uint8_t containing the mapped state. */ -uint8_t map_state_machine_state(const rws::RAPIDNum& state); +uint8_t mapStateMachineState(const rws::RAPIDNum& state); /** * \brief Maps RobotWare StateMachine Add-In EGM action to ROS representation. @@ -80,7 +80,7 @@ uint8_t map_state_machine_state(const rws::RAPIDNum& state); * * \return uint8_t containing the mapped state. */ -uint8_t map_state_machine_egm_action(const rws::RAPIDNum& action); +uint8_t mapStateMachineEGMAction(const rws::RAPIDNum& action); /** * \brief Maps RobotWare StateMachine Add-In SmartGripper command to RWS representation. @@ -91,7 +91,7 @@ uint8_t map_state_machine_egm_action(const rws::RAPIDNum& action); * * \throw std::runtime_error if the command is unknown. */ -unsigned int map_state_machine_sg_command(const unsigned int command); +unsigned int mapStateMachineSGCommand(const unsigned int command); /** * \brief Maps a RAPID 'pos' data type from RWS to ROS representation. @@ -258,7 +258,7 @@ uint8_t map(const egm::wrapper::Status::RAPIDExecutionState rapid_execution_stat * \throw std::runtime if the mapping failed. */ template -std::string map_vector_to_string(const std::vector& vector); +std::string mapVectorToString(const std::vector& vector); } // namespace utilities } // namespace robot diff --git a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp index 85a9e6a..145a41e 100644 --- a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp @@ -85,135 +85,135 @@ class RWSServiceProviderROS : RWSClient RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port); private: - void system_state_callback(const abb_robot_msgs::msg::SystemState& msg); + void systemStateCallback(const abb_robot_msgs::msg::SystemState& msg); - void runtime_state_callback(const abb_rapid_sm_addin_msgs::msg::RuntimeState& msg); + void runtimeStateCallback(const abb_rapid_sm_addin_msgs::msg::RuntimeState& msg); - bool get_file_contents(const abb_robot_msgs::srv::GetFileContents::Request::SharedPtr req, - abb_robot_msgs::srv::GetFileContents::Response::SharedPtr res); + bool getFileContents(const abb_robot_msgs::srv::GetFileContents::Request::SharedPtr req, + abb_robot_msgs::srv::GetFileContents::Response::SharedPtr res); - bool get_io_signal(const abb_robot_msgs::srv::GetIOSignal::Request::SharedPtr req, - abb_robot_msgs::srv::GetIOSignal::Response::SharedPtr res); + bool getIOSignal(const abb_robot_msgs::srv::GetIOSignal::Request::SharedPtr req, + abb_robot_msgs::srv::GetIOSignal::Response::SharedPtr res); - bool get_rapid_bool(const abb_robot_msgs::srv::GetRAPIDBool::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDBool::Response::SharedPtr res); + bool getRapidBool(const abb_robot_msgs::srv::GetRAPIDBool::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDBool::Response::SharedPtr res); - bool get_rapid_dnum(const abb_robot_msgs::srv::GetRAPIDDnum::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDDnum::Response::SharedPtr res); + bool getRapidDNum(const abb_robot_msgs::srv::GetRAPIDDnum::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDDnum::Response::SharedPtr res); - bool get_rapid_num(const abb_robot_msgs::srv::GetRAPIDNum::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDNum::Response::SharedPtr res); + bool getRapidNum(const abb_robot_msgs::srv::GetRAPIDNum::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDNum::Response::SharedPtr res); - bool get_rapid_string(const abb_robot_msgs::srv::GetRAPIDString::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDString::Response::SharedPtr res); + bool getRapidString(const abb_robot_msgs::srv::GetRAPIDString::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDString::Response::SharedPtr res); - bool get_rapid_symbol(const abb_robot_msgs::srv::GetRAPIDSymbol::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDSymbol::Response::SharedPtr res); + bool getRapidSymbol(const abb_robot_msgs::srv::GetRAPIDSymbol::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDSymbol::Response::SharedPtr res); - bool get_rc_description(const abb_robot_msgs::srv::GetRobotControllerDescription::Request::SharedPtr req, - abb_robot_msgs::srv::GetRobotControllerDescription::Response::SharedPtr res); + bool getRCDescription(const abb_robot_msgs::srv::GetRobotControllerDescription::Request::SharedPtr req, + abb_robot_msgs::srv::GetRobotControllerDescription::Response::SharedPtr res); - bool get_speed_ratio(const abb_robot_msgs::srv::GetSpeedRatio::Request::SharedPtr req, - abb_robot_msgs::srv::GetSpeedRatio::Response::SharedPtr res); + bool getSpeedRatio(const abb_robot_msgs::srv::GetSpeedRatio::Request::SharedPtr req, + abb_robot_msgs::srv::GetSpeedRatio::Response::SharedPtr res); - bool pp_to_main(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + bool ppToMain(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); - bool run_rapid_routine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + bool runRapidRoutine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); - bool run_sg_routine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + bool runSGRoutine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); - bool set_file_contents(const abb_robot_msgs::srv::SetFileContents::Request::SharedPtr req, - abb_robot_msgs::srv::SetFileContents::Response::SharedPtr res); + bool setFileContents(const abb_robot_msgs::srv::SetFileContents::Request::SharedPtr req, + abb_robot_msgs::srv::SetFileContents::Response::SharedPtr res); - bool set_io_signal(const abb_robot_msgs::srv::SetIOSignal::Request::SharedPtr req, - abb_robot_msgs::srv::SetIOSignal::Response::SharedPtr res); + bool setIOSignal(const abb_robot_msgs::srv::SetIOSignal::Request::SharedPtr req, + abb_robot_msgs::srv::SetIOSignal::Response::SharedPtr res); - bool set_motors_off(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + bool setMotorsOff(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); - bool set_motors_on(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); - - bool set_rapid_bool(const abb_robot_msgs::srv::SetRAPIDBool::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDBool::Response::SharedPtr res); + bool setMotorsOn(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); - bool set_rapid_dnum(const abb_robot_msgs::srv::SetRAPIDDnum::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDDnum::Response::SharedPtr res); + bool setRapidBool(const abb_robot_msgs::srv::SetRAPIDBool::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDBool::Response::SharedPtr res); - bool set_rapid_num(const abb_robot_msgs::srv::SetRAPIDNum::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDNum::Response::SharedPtr res); + bool setRapidDNum(const abb_robot_msgs::srv::SetRAPIDDnum::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDDnum::Response::SharedPtr res); - bool set_rapid_string(const abb_robot_msgs::srv::SetRAPIDString::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDString::Response::SharedPtr res); + bool setRapidNum(const abb_robot_msgs::srv::SetRAPIDNum::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDNum::Response::SharedPtr res); - bool set_rapid_symbol(const abb_robot_msgs::srv::SetRAPIDSymbol::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDSymbol::Response::SharedPtr res); + bool setRapidString(const abb_robot_msgs::srv::SetRAPIDString::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDString::Response::SharedPtr res); - bool set_speed_ratio(const abb_robot_msgs::srv::SetSpeedRatio::Request::SharedPtr req, - abb_robot_msgs::srv::SetSpeedRatio::Response::SharedPtr res); + bool setRapidSymbol(const abb_robot_msgs::srv::SetRAPIDSymbol::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDSymbol::Response::SharedPtr res); - bool start_rapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + bool setSpeedRatio(const abb_robot_msgs::srv::SetSpeedRatio::Request::SharedPtr req, + abb_robot_msgs::srv::SetSpeedRatio::Response::SharedPtr res); - bool stop_rapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + bool startRapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); - bool get_egm_settings(const abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Request::SharedPtr req, - abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Response::SharedPtr res); + bool stopRapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); - bool set_egm_settings(const abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Request::SharedPtr req, - abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Response::SharedPtr res); + bool getEGMSettings(const abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Response::SharedPtr res); - bool set_rapid_routine(const abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Request::SharedPtr req, - abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Response::SharedPtr res); + bool setEGMSettings(const abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Response::SharedPtr res); - bool set_sg_command(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, - abb_rapid_sm_addin_msgs::srv::SetSGCommand::Response::SharedPtr res); + bool setRapidRoutine(const abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Response::SharedPtr res); - bool start_egm_joint(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + bool setSGCOmmand(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::SetSGCommand::Response::SharedPtr res); - bool start_egm_pose(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + bool startEGMJoint(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); - bool start_egm_stream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + bool startEGMPose(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); - bool stop_egm(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + bool startEGMStream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); - bool stop_egm_stream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + bool stopEGM(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + + bool stopEGMStream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); - bool verify_auto_mode(uint16_t& result_code, std::string& message); + bool verifyAutoMode(uint16_t& result_code, std::string& message); - bool verify_argument_filename(const std::string& filename, uint16_t& result_code, std::string& message); + bool verifyArgumentFilename(const std::string& filename, uint16_t& result_code, std::string& message); - bool verify_argument_rapid_symbol_path(const abb_robot_msgs::msg::RAPIDSymbolPath& path, uint16_t& result_code, - std::string& message); + bool verifyArgumentRapidSymbolPath(const abb_robot_msgs::msg::RAPIDSymbolPath& path, uint16_t& result_code, + std::string& message); - bool verify_argument_rapid_task(const std::string& task, uint16_t& result_code, std::string& message); + bool verifyArgumentRapidTask(const std::string& task, uint16_t& result_code, std::string& message); - bool verify_argument_signal(const std::string& signal, uint16_t& result_code, std::string& message); + bool verifyArgumentSignal(const std::string& signal, uint16_t& result_code, std::string& message); - bool verify_motors_off(uint16_t& result_code, std::string& message); + bool verifyMotorsOff(uint16_t& result_code, std::string& message); - bool verify_motors_on(uint16_t& result_code, std::string& message); + bool verifyMotorsOn(uint16_t& result_code, std::string& message); - bool verify_sm_addin_runtime_states(uint16_t& result_code, std::string& message); + bool verifySMAddingRuntimeStates(uint16_t& result_code, std::string& message); - bool verify_sm_addin_task_exist(const std::string& task, uint16_t& result_code, std::string& message); + bool verifySMAddingTaskExist(const std::string& task, uint16_t& result_code, std::string& message); - bool verify_sm_addin_task_initialized(const std::string& task, uint16_t& result_code, std::string& message); + bool verifySMAddingTaskInitialized(const std::string& task, uint16_t& result_code, std::string& message); - bool verify_rapid_running(uint16_t& result_code, std::string& message); + bool verifyRapidRunning(uint16_t& result_code, std::string& message); - bool verify_rapid_stopped(uint16_t& result_code, std::string& message); + bool verifyRapidStopped(uint16_t& result_code, std::string& message); - bool verify_rws_manager_ready(uint16_t& result_code, std::string& message); + bool verifyRWSManagerReady(uint16_t& result_code, std::string& message); rclcpp::Subscription::SharedPtr system_state_sub_; rclcpp::Subscription::SharedPtr runtime_state_sub_; diff --git a/abb_rws_client/src/mapping.cpp b/abb_rws_client/src/mapping.cpp index 3c2d20e..93cd324 100644 --- a/abb_rws_client/src/mapping.cpp +++ b/abb_rws_client/src/mapping.cpp @@ -87,7 +87,7 @@ uint8_t map(const rws::RWSInterface::RAPIDTaskExecutionState state) } } -uint8_t map_state_machine_state(const rws::RAPIDNum& state) +uint8_t mapStateMachineState(const rws::RAPIDNum& state) { switch (static_cast(state.value)) { @@ -113,7 +113,7 @@ uint8_t map_state_machine_state(const rws::RAPIDNum& state) } } -uint8_t map_state_machine_egm_action(const rws::RAPIDNum& action) +uint8_t mapStateMachineEGMAction(const rws::RAPIDNum& action) { switch (static_cast(action.value)) { @@ -235,7 +235,7 @@ abb_rapid_sm_addin_msgs::msg::EGMSettings map(const rws::RWSStateMachineInterfac return ros_egm_settings; } -unsigned int map_state_machine_sg_command(const unsigned int command) +unsigned int mapStateMachineSGCommand(const unsigned int command) { switch (command) { @@ -452,7 +452,7 @@ uint8_t map(egm::wrapper::Status::RAPIDExecutionState state) } template -std::string map_vector_to_string(const std::vector& vector) +std::string mapVectorToString(const std::vector& vector) { std::stringstream ss{}; diff --git a/abb_rws_client/src/rws_service_provider_ros.cpp b/abb_rws_client/src/rws_service_provider_ros.cpp index b03f79c..413f311 100644 --- a/abb_rws_client/src/rws_service_provider_ros.cpp +++ b/abb_rws_client/src/rws_service_provider_ros.cpp @@ -54,77 +54,75 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node : RWSClient(node, robot_ip, robot_port) { system_state_sub_ = node_->create_subscription( - "system_states", 10, std::bind(&RWSServiceProviderROS::system_state_callback, this, std::placeholders::_1)); + "system_states", 10, std::bind(&RWSServiceProviderROS::systemStateCallback, this, std::placeholders::_1)); runtime_state_sub_ = node_->create_subscription( "sm_addin/runtime_states", 10, - std::bind(&RWSServiceProviderROS::runtime_state_callback, this, std::placeholders::_1)); + std::bind(&RWSServiceProviderROS::runtimeStateCallback, this, std::placeholders::_1)); core_services_.push_back(node_->create_service( "~/get_robot_controller_description", - std::bind(&RWSServiceProviderROS::get_rc_description, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::getRCDescription, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/get_file_contents", - std::bind(&RWSServiceProviderROS::get_file_contents, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::getFileContents, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/get_io_signal", - std::bind(&RWSServiceProviderROS::get_io_signal, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::getIOSignal, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/get_rapid_bool", - std::bind(&RWSServiceProviderROS::get_rapid_bool, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::getRapidBool, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/get_rapid_dnum", - std::bind(&RWSServiceProviderROS::get_rapid_dnum, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::getRapidDNum, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/get_rapid_num", - std::bind(&RWSServiceProviderROS::get_rapid_num, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::getRapidNum, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/get_rapid_string", - std::bind(&RWSServiceProviderROS::get_rapid_string, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::getRapidString, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/get_rapid_symbol", - std::bind(&RWSServiceProviderROS::get_rapid_symbol, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::getRapidSymbol, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/get_speed_ratio", - std::bind(&RWSServiceProviderROS::get_speed_ratio, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::getSpeedRatio, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( - "~/pp_to_main", - std::bind(&RWSServiceProviderROS::pp_to_main, this, std::placeholders::_1, std::placeholders::_2))); + "~/pp_to_main", std::bind(&RWSServiceProviderROS::ppToMain, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/set_file_contents", - std::bind(&RWSServiceProviderROS::set_file_contents, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setFileContents, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/set_io_signal", - std::bind(&RWSServiceProviderROS::set_io_signal, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setIOSignal, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/set_motors_off", - std::bind(&RWSServiceProviderROS::set_motors_off, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setMotorsOff, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/set_motors_on", - std::bind(&RWSServiceProviderROS::set_motors_on, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setMotorsOn, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/set_rapid_bool", - std::bind(&RWSServiceProviderROS::set_rapid_bool, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setRapidBool, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/set_rapid_dnum", - std::bind(&RWSServiceProviderROS::set_rapid_dnum, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setRapidDNum, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/set_rapid_num", - std::bind(&RWSServiceProviderROS::set_rapid_num, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setRapidNum, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/set_rapid_string", - std::bind(&RWSServiceProviderROS::set_rapid_string, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setRapidString, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/set_rapid_symbol", - std::bind(&RWSServiceProviderROS::set_rapid_symbol, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setRapidSymbol, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/set_speed_ratio", - std::bind(&RWSServiceProviderROS::set_speed_ratio, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setSpeedRatio, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( "~/start_rapid", - std::bind(&RWSServiceProviderROS::start_rapid, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::startRapid, this, std::placeholders::_1, std::placeholders::_2))); core_services_.push_back(node_->create_service( - "~/stop_rapid", - std::bind(&RWSServiceProviderROS::stop_rapid, this, std::placeholders::_1, std::placeholders::_2))); + "~/stop_rapid", std::bind(&RWSServiceProviderROS::stopRapid, this, std::placeholders::_1, std::placeholders::_2))); const auto& system_indicators = robot_controller_description_.system_indicators(); @@ -147,34 +145,34 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node { sm_services_.push_back(node_->create_service( "~/run_rapid_routine", - std::bind(&RWSServiceProviderROS::run_rapid_routine, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::runRapidRoutine, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( "~/set_rapid_routine", - std::bind(&RWSServiceProviderROS::set_rapid_routine, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setRapidRoutine, this, std::placeholders::_1, std::placeholders::_2))); if (system_indicators.options().egm()) { sm_services_.push_back(node_->create_service( "get_egm_settings", - std::bind(&RWSServiceProviderROS::get_egm_settings, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::getEGMSettings, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( "set_egm_settings", - std::bind(&RWSServiceProviderROS::set_egm_settings, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setEGMSettings, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( "start_egm_joint", - std::bind(&RWSServiceProviderROS::start_egm_joint, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::startEGMJoint, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( "start_egm_pose", - std::bind(&RWSServiceProviderROS::start_egm_pose, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::startEGMPose, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( - "stop_egm", std::bind(&RWSServiceProviderROS::stop_egm, this, std::placeholders::_1, std::placeholders::_2))); + "stop_egm", std::bind(&RWSServiceProviderROS::stopEGM, this, std::placeholders::_1, std::placeholders::_2))); if (has_sm_1_1) { sm_services_.push_back(node_->create_service( "start_egm_stream", - std::bind(&RWSServiceProviderROS::start_egm_stream, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::startEGMStream, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( "stop_egm_stream", - std::bind(&RWSServiceProviderROS::stop_egm_stream, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::stopEGMStream, this, std::placeholders::_1, std::placeholders::_2))); } } @@ -182,26 +180,26 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node { sm_services_.push_back(node_->create_service( "run_sg_routine", - std::bind(&RWSServiceProviderROS::run_sg_routine, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::runSGRoutine, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( "set_sg_command", - std::bind(&RWSServiceProviderROS::set_sg_command, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setSGCOmmand, this, std::placeholders::_1, std::placeholders::_2))); } } RCLCPP_INFO(node_->get_logger(), "RWS client services initialized!"); } -void RWSServiceProviderROS::system_state_callback(const abb_robot_msgs::msg::SystemState& msg) +void RWSServiceProviderROS::systemStateCallback(const abb_robot_msgs::msg::SystemState& msg) { system_state_ = msg; } -void RWSServiceProviderROS::runtime_state_callback(const abb_rapid_sm_addin_msgs::msg::RuntimeState& msg) +void RWSServiceProviderROS::runtimeStateCallback(const abb_rapid_sm_addin_msgs::msg::RuntimeState& msg) { runtime_state_ = msg; } -bool RWSServiceProviderROS::get_rc_description( +bool RWSServiceProviderROS::getRCDescription( const abb_robot_msgs::srv::GetRobotControllerDescription::Request::SharedPtr req, abb_robot_msgs::srv::GetRobotControllerDescription::Response::SharedPtr res) { @@ -213,8 +211,8 @@ bool RWSServiceProviderROS::get_rc_description( return true; } -bool RWSServiceProviderROS::get_file_contents(const abb_robot_msgs::srv::GetFileContents::Request::SharedPtr req, - abb_robot_msgs::srv::GetFileContents::Response::SharedPtr res) +bool RWSServiceProviderROS::getFileContents(const abb_robot_msgs::srv::GetFileContents::Request::SharedPtr req, + abb_robot_msgs::srv::GetFileContents::Response::SharedPtr res) { if (!verify_argument_filename(req->filename, res->result_code, res->message)) { @@ -241,8 +239,8 @@ bool RWSServiceProviderROS::get_file_contents(const abb_robot_msgs::srv::GetFile return true; } -bool RWSServiceProviderROS::get_io_signal(const abb_robot_msgs::srv::GetIOSignal::Request::SharedPtr req, - abb_robot_msgs::srv::GetIOSignal::Response::SharedPtr res) +bool RWSServiceProviderROS::getIOSignal(const abb_robot_msgs::srv::GetIOSignal::Request::SharedPtr req, + abb_robot_msgs::srv::GetIOSignal::Response::SharedPtr res) { if (!verify_argument_signal(req->signal, res->result_code, res->message)) { @@ -271,8 +269,8 @@ bool RWSServiceProviderROS::get_io_signal(const abb_robot_msgs::srv::GetIOSignal return true; } -bool RWSServiceProviderROS::get_rapid_bool(const abb_robot_msgs::srv::GetRAPIDBool::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDBool::Response::SharedPtr res) +bool RWSServiceProviderROS::getRapidBool(const abb_robot_msgs::srv::GetRAPIDBool::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDBool::Response::SharedPtr res) { if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { @@ -301,8 +299,8 @@ bool RWSServiceProviderROS::get_rapid_bool(const abb_robot_msgs::srv::GetRAPIDBo return true; } -bool RWSServiceProviderROS::get_rapid_dnum(const abb_robot_msgs::srv::GetRAPIDDnum::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDDnum::Response::SharedPtr res) +bool RWSServiceProviderROS::getRapidDNum(const abb_robot_msgs::srv::GetRAPIDDnum::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDDnum::Response::SharedPtr res) { if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { @@ -331,8 +329,8 @@ bool RWSServiceProviderROS::get_rapid_dnum(const abb_robot_msgs::srv::GetRAPIDDn return true; } -bool RWSServiceProviderROS::get_rapid_num(const abb_robot_msgs::srv::GetRAPIDNum::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDNum::Response::SharedPtr res) +bool RWSServiceProviderROS::getRapidNum(const abb_robot_msgs::srv::GetRAPIDNum::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDNum::Response::SharedPtr res) { if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { @@ -361,8 +359,8 @@ bool RWSServiceProviderROS::get_rapid_num(const abb_robot_msgs::srv::GetRAPIDNum return true; } -bool RWSServiceProviderROS::get_rapid_string(const abb_robot_msgs::srv::GetRAPIDString::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDString::Response::SharedPtr res) +bool RWSServiceProviderROS::getRapidString(const abb_robot_msgs::srv::GetRAPIDString::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDString::Response::SharedPtr res) { if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { @@ -391,8 +389,8 @@ bool RWSServiceProviderROS::get_rapid_string(const abb_robot_msgs::srv::GetRAPID return true; } -bool RWSServiceProviderROS::get_rapid_symbol(const abb_robot_msgs::srv::GetRAPIDSymbol::Request::SharedPtr req, - abb_robot_msgs::srv::GetRAPIDSymbol::Response::SharedPtr res) +bool RWSServiceProviderROS::getRapidSymbol(const abb_robot_msgs::srv::GetRAPIDSymbol::Request::SharedPtr req, + abb_robot_msgs::srv::GetRAPIDSymbol::Response::SharedPtr res) { if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { @@ -421,8 +419,8 @@ bool RWSServiceProviderROS::get_rapid_symbol(const abb_robot_msgs::srv::GetRAPID return true; } -bool RWSServiceProviderROS::get_speed_ratio(const abb_robot_msgs::srv::GetSpeedRatio::Request::SharedPtr, - abb_robot_msgs::srv::GetSpeedRatio::Response::SharedPtr res) +bool RWSServiceProviderROS::getSpeedRatio(const abb_robot_msgs::srv::GetSpeedRatio::Request::SharedPtr, + abb_robot_msgs::srv::GetSpeedRatio::Response::SharedPtr res) { if (!verify_rws_manager_ready(res->result_code, res->message)) { @@ -446,8 +444,8 @@ bool RWSServiceProviderROS::get_speed_ratio(const abb_robot_msgs::srv::GetSpeedR return true; } -bool RWSServiceProviderROS::pp_to_main(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +bool RWSServiceProviderROS::ppToMain(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { if (!verify_auto_mode(res->result_code, res->message)) { @@ -476,8 +474,8 @@ bool RWSServiceProviderROS::pp_to_main(const abb_robot_msgs::srv::TriggerWithRes return true; } -bool RWSServiceProviderROS::run_rapid_routine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +bool RWSServiceProviderROS::runRapidRoutine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { if (!verify_auto_mode(res->result_code, res->message)) { @@ -512,8 +510,8 @@ bool RWSServiceProviderROS::run_rapid_routine(const abb_robot_msgs::srv::Trigger return true; } -bool RWSServiceProviderROS::run_sg_routine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +bool RWSServiceProviderROS::runSGRoutine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { if (!verify_auto_mode(res->result_code, res->message)) { @@ -548,8 +546,8 @@ bool RWSServiceProviderROS::run_sg_routine(const abb_robot_msgs::srv::TriggerWit return true; } -bool RWSServiceProviderROS::set_file_contents(const abb_robot_msgs::srv::SetFileContents::Request::SharedPtr req, - abb_robot_msgs::srv::SetFileContents::Response::SharedPtr res) +bool RWSServiceProviderROS::setFileContents(const abb_robot_msgs::srv::SetFileContents::Request::SharedPtr req, + abb_robot_msgs::srv::SetFileContents::Response::SharedPtr res) { if (!verify_argument_filename(req->filename, res->result_code, res->message)) { @@ -576,8 +574,8 @@ bool RWSServiceProviderROS::set_file_contents(const abb_robot_msgs::srv::SetFile return true; } -bool RWSServiceProviderROS::set_io_signal(const abb_robot_msgs::srv::SetIOSignal::Request::SharedPtr req, - abb_robot_msgs::srv::SetIOSignal::Response::SharedPtr res) +bool RWSServiceProviderROS::setIOSignal(const abb_robot_msgs::srv::SetIOSignal::Request::SharedPtr req, + abb_robot_msgs::srv::SetIOSignal::Response::SharedPtr res) { if (!verify_argument_signal(req->signal, res->result_code, res->message)) { @@ -604,8 +602,8 @@ bool RWSServiceProviderROS::set_io_signal(const abb_robot_msgs::srv::SetIOSignal return true; } -bool RWSServiceProviderROS::set_motors_off(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +bool RWSServiceProviderROS::setMotorsOff(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { if (!verify_motors_on(res->result_code, res->message)) { @@ -627,8 +625,8 @@ bool RWSServiceProviderROS::set_motors_off(const abb_robot_msgs::srv::TriggerWit return true; } -bool RWSServiceProviderROS::set_motors_on(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +bool RWSServiceProviderROS::setMotorsOn(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { if (!verify_auto_mode(res->result_code, res->message)) { @@ -658,8 +656,8 @@ bool RWSServiceProviderROS::set_motors_on(const abb_robot_msgs::srv::TriggerWith return true; } -bool RWSServiceProviderROS::set_rapid_bool(const abb_robot_msgs::srv::SetRAPIDBool::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDBool::Response::SharedPtr res) +bool RWSServiceProviderROS::setRapidBool(const abb_robot_msgs::srv::SetRAPIDBool::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDBool::Response::SharedPtr res) { if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { @@ -691,8 +689,8 @@ bool RWSServiceProviderROS::set_rapid_bool(const abb_robot_msgs::srv::SetRAPIDBo return true; } -bool RWSServiceProviderROS::set_rapid_dnum(const abb_robot_msgs::srv::SetRAPIDDnum::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDDnum::Response::SharedPtr res) +bool RWSServiceProviderROS::setRapidDNum(const abb_robot_msgs::srv::SetRAPIDDnum::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDDnum::Response::SharedPtr res) { if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { @@ -724,8 +722,8 @@ bool RWSServiceProviderROS::set_rapid_dnum(const abb_robot_msgs::srv::SetRAPIDDn return true; } -bool RWSServiceProviderROS::set_rapid_num(const abb_robot_msgs::srv::SetRAPIDNum::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDNum::Response::SharedPtr res) +bool RWSServiceProviderROS::setRapidNum(const abb_robot_msgs::srv::SetRAPIDNum::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDNum::Response::SharedPtr res) { if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { @@ -757,8 +755,8 @@ bool RWSServiceProviderROS::set_rapid_num(const abb_robot_msgs::srv::SetRAPIDNum return true; } -bool RWSServiceProviderROS::set_rapid_string(const abb_robot_msgs::srv::SetRAPIDString::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDString::Response::SharedPtr res) +bool RWSServiceProviderROS::setRapidString(const abb_robot_msgs::srv::SetRAPIDString::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDString::Response::SharedPtr res) { if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { @@ -790,8 +788,8 @@ bool RWSServiceProviderROS::set_rapid_string(const abb_robot_msgs::srv::SetRAPID return true; } -bool RWSServiceProviderROS::set_rapid_symbol(const abb_robot_msgs::srv::SetRAPIDSymbol::Request::SharedPtr req, - abb_robot_msgs::srv::SetRAPIDSymbol::Response::SharedPtr res) +bool RWSServiceProviderROS::setRapidSymbol(const abb_robot_msgs::srv::SetRAPIDSymbol::Request::SharedPtr req, + abb_robot_msgs::srv::SetRAPIDSymbol::Response::SharedPtr res) { if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) { @@ -822,8 +820,8 @@ bool RWSServiceProviderROS::set_rapid_symbol(const abb_robot_msgs::srv::SetRAPID return true; } -bool RWSServiceProviderROS::set_speed_ratio(const abb_robot_msgs::srv::SetSpeedRatio::Request::SharedPtr req, - abb_robot_msgs::srv::SetSpeedRatio::Response::SharedPtr res) +bool RWSServiceProviderROS::setSpeedRatio(const abb_robot_msgs::srv::SetSpeedRatio::Request::SharedPtr req, + abb_robot_msgs::srv::SetSpeedRatio::Response::SharedPtr res) { if (!verify_auto_mode(res->result_code, res->message)) { @@ -857,8 +855,8 @@ bool RWSServiceProviderROS::set_speed_ratio(const abb_robot_msgs::srv::SetSpeedR return true; } -bool RWSServiceProviderROS::start_rapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +bool RWSServiceProviderROS::startRapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { if (!verify_auto_mode(res->result_code, res->message)) { @@ -888,8 +886,8 @@ bool RWSServiceProviderROS::start_rapid(const abb_robot_msgs::srv::TriggerWithRe return true; } -bool RWSServiceProviderROS::stop_rapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +bool RWSServiceProviderROS::stopRapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { if (!verify_rapid_running(res->result_code, res->message)) { @@ -911,8 +909,8 @@ bool RWSServiceProviderROS::stop_rapid(const abb_robot_msgs::srv::TriggerWithRes return true; } -bool RWSServiceProviderROS::get_egm_settings(const abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Request::SharedPtr req, - abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Response::SharedPtr res) +bool RWSServiceProviderROS::getEGMSettings(const abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Response::SharedPtr res) { if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) { @@ -950,8 +948,8 @@ bool RWSServiceProviderROS::get_egm_settings(const abb_rapid_sm_addin_msgs::srv: return true; } -bool RWSServiceProviderROS::set_egm_settings(const abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Request::SharedPtr req, - abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Response::SharedPtr res) +bool RWSServiceProviderROS::setEGMSettings(const abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Response::SharedPtr res) { if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) { @@ -996,9 +994,8 @@ bool RWSServiceProviderROS::set_egm_settings(const abb_rapid_sm_addin_msgs::srv: return true; } -bool RWSServiceProviderROS::set_rapid_routine( - const abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Request::SharedPtr req, - abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Response::SharedPtr res) +bool RWSServiceProviderROS::setRapidRoutine(const abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Response::SharedPtr res) { if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) { @@ -1041,8 +1038,8 @@ bool RWSServiceProviderROS::set_rapid_routine( return true; } -bool RWSServiceProviderROS::set_sg_command(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, - abb_rapid_sm_addin_msgs::srv::SetSGCommand::Response::SharedPtr res) +bool RWSServiceProviderROS::setSGCOmmand(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, + abb_rapid_sm_addin_msgs::srv::SetSGCommand::Response::SharedPtr res) { if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) { @@ -1072,7 +1069,7 @@ bool RWSServiceProviderROS::set_sg_command(const abb_rapid_sm_addin_msgs::srv::S unsigned int req_command = 0; try { - req_command = abb::robot::utilities::map_state_machine_sg_command(req->command); + req_command = abb::robot::utilities::mapStateMachineSGCommand(req->command); } catch (const std::runtime_error& exception) { @@ -1101,8 +1098,8 @@ bool RWSServiceProviderROS::set_sg_command(const abb_rapid_sm_addin_msgs::srv::S return true; } -bool RWSServiceProviderROS::start_egm_joint(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +bool RWSServiceProviderROS::startEGMJoint(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { if (!verify_auto_mode(res->result_code, res->message)) { @@ -1137,8 +1134,8 @@ bool RWSServiceProviderROS::start_egm_joint(const abb_robot_msgs::srv::TriggerWi return true; } -bool RWSServiceProviderROS::start_egm_pose(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +bool RWSServiceProviderROS::startEGMPose(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { if (!verify_auto_mode(res->result_code, res->message)) { @@ -1173,8 +1170,8 @@ bool RWSServiceProviderROS::start_egm_pose(const abb_robot_msgs::srv::TriggerWit return true; } -bool RWSServiceProviderROS::start_egm_stream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +bool RWSServiceProviderROS::startEGMStream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { if (!verify_auto_mode(res->result_code, res->message)) { @@ -1209,8 +1206,8 @@ bool RWSServiceProviderROS::start_egm_stream(const abb_robot_msgs::srv::TriggerW return true; } -bool RWSServiceProviderROS::stop_egm(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +bool RWSServiceProviderROS::stopEGM(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { if (!verify_auto_mode(res->result_code, res->message)) { @@ -1241,8 +1238,8 @@ bool RWSServiceProviderROS::stop_egm(const abb_robot_msgs::srv::TriggerWithResul return true; } -bool RWSServiceProviderROS::stop_egm_stream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +bool RWSServiceProviderROS::stopEGMStream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { if (!verify_auto_mode(res->result_code, res->message)) { @@ -1273,7 +1270,7 @@ bool RWSServiceProviderROS::stop_egm_stream(const abb_robot_msgs::srv::TriggerWi return true; } -bool RWSServiceProviderROS::verify_auto_mode(uint16_t& result_code, std::string& message) +bool RWSServiceProviderROS::verifyAutoMode(uint16_t& result_code, std::string& message) { if (!system_state_.auto_mode) { @@ -1285,8 +1282,8 @@ bool RWSServiceProviderROS::verify_auto_mode(uint16_t& result_code, std::string& return true; } -bool RWSServiceProviderROS::verify_argument_filename(const std::string& filename, uint16_t& result_code, - std::string& message) +bool RWSServiceProviderROS::verifyArgumentFilename(const std::string& filename, uint16_t& result_code, + std::string& message) { if (filename.empty()) { @@ -1298,8 +1295,8 @@ bool RWSServiceProviderROS::verify_argument_filename(const std::string& filename return true; } -bool RWSServiceProviderROS::verify_argument_rapid_symbol_path(const abb_robot_msgs::msg::RAPIDSymbolPath& path, - uint16_t& result_code, std::string& message) +bool RWSServiceProviderROS::verifyArgumentRapidSymbolPath(const abb_robot_msgs::msg::RAPIDSymbolPath& path, + uint16_t& result_code, std::string& message) { if (path.task.empty()) { @@ -1325,8 +1322,8 @@ bool RWSServiceProviderROS::verify_argument_rapid_symbol_path(const abb_robot_ms return true; } -bool RWSServiceProviderROS::verify_argument_rapid_task(const std::string& task, uint16_t& result_code, - std::string& message) +bool RWSServiceProviderROS::verifyArgumentRapidTask(const std::string& task, uint16_t& result_code, + std::string& message) { if (task.empty()) { @@ -1338,8 +1335,7 @@ bool RWSServiceProviderROS::verify_argument_rapid_task(const std::string& task, return true; } -bool RWSServiceProviderROS::verify_argument_signal(const std::string& signal, uint16_t& result_code, - std::string& message) +bool RWSServiceProviderROS::verifyArgumentSignal(const std::string& signal, uint16_t& result_code, std::string& message) { if (signal.empty()) { @@ -1351,7 +1347,7 @@ bool RWSServiceProviderROS::verify_argument_signal(const std::string& signal, ui return true; } -bool RWSServiceProviderROS::verify_motors_off(uint16_t& result_code, std::string& message) +bool RWSServiceProviderROS::verifyMotorsOff(uint16_t& result_code, std::string& message) { if (system_state_.motors_on) { @@ -1363,7 +1359,7 @@ bool RWSServiceProviderROS::verify_motors_off(uint16_t& result_code, std::string return true; } -bool RWSServiceProviderROS::verify_motors_on(uint16_t& result_code, std::string& message) +bool RWSServiceProviderROS::verifyMotorsOn(uint16_t& result_code, std::string& message) { if (!system_state_.motors_on) { @@ -1375,7 +1371,7 @@ bool RWSServiceProviderROS::verify_motors_on(uint16_t& result_code, std::string& return true; } -bool RWSServiceProviderROS::verify_sm_addin_runtime_states(uint16_t& result_code, std::string& message) +bool RWSServiceProviderROS::verifySMAddingRuntimeStates(uint16_t& result_code, std::string& message) { if (runtime_state_.state_machines.empty()) { @@ -1387,8 +1383,8 @@ bool RWSServiceProviderROS::verify_sm_addin_runtime_states(uint16_t& result_code return true; } -bool RWSServiceProviderROS::verify_sm_addin_task_exist(const std::string& task, uint16_t& result_code, - std::string& message) +bool RWSServiceProviderROS::verifySMAddingTaskExist(const std::string& task, uint16_t& result_code, + std::string& message) { auto it = std::find_if(runtime_state_.state_machines.begin(), runtime_state_.state_machines.end(), [&](const auto& sm) { return sm.rapid_task == task; }); @@ -1403,10 +1399,10 @@ bool RWSServiceProviderROS::verify_sm_addin_task_exist(const std::string& task, return true; } -bool RWSServiceProviderROS::verify_sm_addin_task_initialized(const std::string& task, uint16_t& result_code, - std::string& message) +bool RWSServiceProviderROS::verifySMAddingTaskInitialized(const std::string& task, uint16_t& result_code, + std::string& message) { - if (!verify_sm_addin_task_exist(task, result_code, message)) + if (!verifySMAddingTaskExist(task, result_code, message)) return false; auto it = std::find_if(runtime_state_.state_machines.begin(), runtime_state_.state_machines.end(), @@ -1423,7 +1419,7 @@ bool RWSServiceProviderROS::verify_sm_addin_task_initialized(const std::string& return true; } -bool RWSServiceProviderROS::verify_rapid_running(uint16_t& result_code, std::string& message) +bool RWSServiceProviderROS::verifyRapidRunning(uint16_t& result_code, std::string& message) { if (!system_state_.rapid_running) { @@ -1435,7 +1431,7 @@ bool RWSServiceProviderROS::verify_rapid_running(uint16_t& result_code, std::str return true; } -bool RWSServiceProviderROS::verify_rapid_stopped(uint16_t& result_code, std::string& message) +bool RWSServiceProviderROS::verifyRapidStopped(uint16_t& result_code, std::string& message) { if (system_state_.rapid_running) { @@ -1447,7 +1443,7 @@ bool RWSServiceProviderROS::verify_rapid_stopped(uint16_t& result_code, std::str return true; } -bool RWSServiceProviderROS::verify_rws_manager_ready(uint16_t& result_code, std::string& message) +bool RWSServiceProviderROS::verifyRWSManagerReady(uint16_t& result_code, std::string& message) { if (!rws_manager_.isInterfaceReady()) { diff --git a/abb_rws_client/src/rws_state_publisher_ros.cpp b/abb_rws_client/src/rws_state_publisher_ros.cpp index b48f9f8..1ccabeb 100644 --- a/abb_rws_client/src/rws_state_publisher_ros.cpp +++ b/abb_rws_client/src/rws_state_publisher_ros.cpp @@ -134,8 +134,8 @@ void RWSStatePublisherROS::timer_callback() { abb_rapid_sm_addin_msgs::msg::StateMachineState state; state.rapid_task = sm.rapid_task; - state.sm_state = abb::robot::utilities::map_state_machine_state(sm.sm_state); - state.egm_action = abb::robot::utilities::map_state_machine_egm_action(sm.egm_action); + state.sm_state = abb::robot::utilities::mapStateMachineState(sm.sm_state); + state.egm_action = abb::robot::utilities::mapStateMachineEGMAction(sm.egm_action); sm_runtime_state_msg.state_machines.push_back(state); } } From c503da4e82cf1b1b9f4c6e1ac78b7790ea50a7f8 Mon Sep 17 00:00:00 2001 From: Souphis Date: Tue, 31 May 2022 13:30:49 +0200 Subject: [PATCH 14/27] Apply fixes --- .../rws_service_provider_ros.hpp | 6 +- abb_rws_client/src/mapping.cpp | 8 +- .../src/rws_service_provider_ros.cpp | 201 +++++++++--------- 3 files changed, 107 insertions(+), 108 deletions(-) diff --git a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp index 145a41e..ce67dc1 100644 --- a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp @@ -203,11 +203,11 @@ class RWSServiceProviderROS : RWSClient bool verifyMotorsOn(uint16_t& result_code, std::string& message); - bool verifySMAddingRuntimeStates(uint16_t& result_code, std::string& message); + bool verifySMAddinRuntimeStates(uint16_t& result_code, std::string& message); - bool verifySMAddingTaskExist(const std::string& task, uint16_t& result_code, std::string& message); + bool verifySMAddinTaskExist(const std::string& task, uint16_t& result_code, std::string& message); - bool verifySMAddingTaskInitialized(const std::string& task, uint16_t& result_code, std::string& message); + bool verifySMAddinTaskInitialized(const std::string& task, uint16_t& result_code, std::string& message); bool verifyRapidRunning(uint16_t& result_code, std::string& message); diff --git a/abb_rws_client/src/mapping.cpp b/abb_rws_client/src/mapping.cpp index 93cd324..50552eb 100644 --- a/abb_rws_client/src/mapping.cpp +++ b/abb_rws_client/src/mapping.cpp @@ -474,10 +474,10 @@ std::string mapVectorToString(const std::vector& vector) return ss.str(); } -template std::string map_vector_to_string(const std::vector& vector); -template std::string map_vector_to_string(const std::vector& vector); -template std::string map_vector_to_string(const std::vector& vector); -template std::string map_vector_to_string(const std::vector& vector); +template std::string mapVectorToString(const std::vector& vector); +template std::string mapVectorToString(const std::vector& vector); +template std::string mapVectorToString(const std::vector& vector); +template std::string mapVectorToString(const std::vector& vector); } // namespace utilities } // namespace robot diff --git a/abb_rws_client/src/rws_service_provider_ros.cpp b/abb_rws_client/src/rws_service_provider_ros.cpp index 413f311..ccb9748 100644 --- a/abb_rws_client/src/rws_service_provider_ros.cpp +++ b/abb_rws_client/src/rws_service_provider_ros.cpp @@ -214,11 +214,11 @@ bool RWSServiceProviderROS::getRCDescription( bool RWSServiceProviderROS::getFileContents(const abb_robot_msgs::srv::GetFileContents::Request::SharedPtr req, abb_robot_msgs::srv::GetFileContents::Response::SharedPtr res) { - if (!verify_argument_filename(req->filename, res->result_code, res->message)) + if (!verifyArgumentFilename(req->filename, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -242,11 +242,11 @@ bool RWSServiceProviderROS::getFileContents(const abb_robot_msgs::srv::GetFileCo bool RWSServiceProviderROS::getIOSignal(const abb_robot_msgs::srv::GetIOSignal::Request::SharedPtr req, abb_robot_msgs::srv::GetIOSignal::Response::SharedPtr res) { - if (!verify_argument_signal(req->signal, res->result_code, res->message)) + if (!verifyArgumentSignal(req->signal, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -272,11 +272,11 @@ bool RWSServiceProviderROS::getIOSignal(const abb_robot_msgs::srv::GetIOSignal:: bool RWSServiceProviderROS::getRapidBool(const abb_robot_msgs::srv::GetRAPIDBool::Request::SharedPtr req, abb_robot_msgs::srv::GetRAPIDBool::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + if (!verifyArgumentRapidSymbolPath(req->path, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -302,11 +302,11 @@ bool RWSServiceProviderROS::getRapidBool(const abb_robot_msgs::srv::GetRAPIDBool bool RWSServiceProviderROS::getRapidDNum(const abb_robot_msgs::srv::GetRAPIDDnum::Request::SharedPtr req, abb_robot_msgs::srv::GetRAPIDDnum::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + if (!verifyArgumentRapidSymbolPath(req->path, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -332,11 +332,11 @@ bool RWSServiceProviderROS::getRapidDNum(const abb_robot_msgs::srv::GetRAPIDDnum bool RWSServiceProviderROS::getRapidNum(const abb_robot_msgs::srv::GetRAPIDNum::Request::SharedPtr req, abb_robot_msgs::srv::GetRAPIDNum::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + if (!verifyArgumentRapidSymbolPath(req->path, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -362,11 +362,11 @@ bool RWSServiceProviderROS::getRapidNum(const abb_robot_msgs::srv::GetRAPIDNum:: bool RWSServiceProviderROS::getRapidString(const abb_robot_msgs::srv::GetRAPIDString::Request::SharedPtr req, abb_robot_msgs::srv::GetRAPIDString::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + if (!verifyArgumentRapidSymbolPath(req->path, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -392,11 +392,11 @@ bool RWSServiceProviderROS::getRapidString(const abb_robot_msgs::srv::GetRAPIDSt bool RWSServiceProviderROS::getRapidSymbol(const abb_robot_msgs::srv::GetRAPIDSymbol::Request::SharedPtr req, abb_robot_msgs::srv::GetRAPIDSymbol::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + if (!verifyArgumentRapidSymbolPath(req->path, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -422,7 +422,7 @@ bool RWSServiceProviderROS::getRapidSymbol(const abb_robot_msgs::srv::GetRAPIDSy bool RWSServiceProviderROS::getSpeedRatio(const abb_robot_msgs::srv::GetSpeedRatio::Request::SharedPtr, abb_robot_msgs::srv::GetSpeedRatio::Response::SharedPtr res) { - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -447,15 +447,15 @@ bool RWSServiceProviderROS::getSpeedRatio(const abb_robot_msgs::srv::GetSpeedRat bool RWSServiceProviderROS::ppToMain(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rapid_stopped(res->result_code, res->message)) + if (!verifyRapidStopped(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -477,19 +477,19 @@ bool RWSServiceProviderROS::ppToMain(const abb_robot_msgs::srv::TriggerWithResul bool RWSServiceProviderROS::runRapidRoutine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rapid_running(res->result_code, res->message)) + if (!verifyRapidRunning(res->result_code, res->message)) { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + if (!verifySMAddinRuntimeStates(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -513,19 +513,19 @@ bool RWSServiceProviderROS::runRapidRoutine(const abb_robot_msgs::srv::TriggerWi bool RWSServiceProviderROS::runSGRoutine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rapid_running(res->result_code, res->message)) + if (!verifyRapidRunning(res->result_code, res->message)) { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + if (!verifySMAddinRuntimeStates(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -549,11 +549,11 @@ bool RWSServiceProviderROS::runSGRoutine(const abb_robot_msgs::srv::TriggerWithR bool RWSServiceProviderROS::setFileContents(const abb_robot_msgs::srv::SetFileContents::Request::SharedPtr req, abb_robot_msgs::srv::SetFileContents::Response::SharedPtr res) { - if (!verify_argument_filename(req->filename, res->result_code, res->message)) + if (!verifyArgumentFilename(req->filename, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -577,11 +577,11 @@ bool RWSServiceProviderROS::setFileContents(const abb_robot_msgs::srv::SetFileCo bool RWSServiceProviderROS::setIOSignal(const abb_robot_msgs::srv::SetIOSignal::Request::SharedPtr req, abb_robot_msgs::srv::SetIOSignal::Response::SharedPtr res) { - if (!verify_argument_signal(req->signal, res->result_code, res->message)) + if (!verifyArgumentSignal(req->signal, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -605,7 +605,7 @@ bool RWSServiceProviderROS::setIOSignal(const abb_robot_msgs::srv::SetIOSignal:: bool RWSServiceProviderROS::setMotorsOff(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_motors_on(res->result_code, res->message)) + if (!verifyMotorsOn(res->result_code, res->message)) { return true; } @@ -628,15 +628,15 @@ bool RWSServiceProviderROS::setMotorsOff(const abb_robot_msgs::srv::TriggerWithR bool RWSServiceProviderROS::setMotorsOn(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_motors_off(res->result_code, res->message)) + if (!verifyMotorsOff(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -659,15 +659,15 @@ bool RWSServiceProviderROS::setMotorsOn(const abb_robot_msgs::srv::TriggerWithRe bool RWSServiceProviderROS::setRapidBool(const abb_robot_msgs::srv::SetRAPIDBool::Request::SharedPtr req, abb_robot_msgs::srv::SetRAPIDBool::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + if (!verifyArgumentRapidSymbolPath(req->path, res->result_code, res->message)) { return true; } - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -692,15 +692,15 @@ bool RWSServiceProviderROS::setRapidBool(const abb_robot_msgs::srv::SetRAPIDBool bool RWSServiceProviderROS::setRapidDNum(const abb_robot_msgs::srv::SetRAPIDDnum::Request::SharedPtr req, abb_robot_msgs::srv::SetRAPIDDnum::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + if (!verifyArgumentRapidSymbolPath(req->path, res->result_code, res->message)) { return true; } - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -725,15 +725,15 @@ bool RWSServiceProviderROS::setRapidDNum(const abb_robot_msgs::srv::SetRAPIDDnum bool RWSServiceProviderROS::setRapidNum(const abb_robot_msgs::srv::SetRAPIDNum::Request::SharedPtr req, abb_robot_msgs::srv::SetRAPIDNum::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + if (!verifyArgumentRapidSymbolPath(req->path, res->result_code, res->message)) { return true; } - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -758,15 +758,15 @@ bool RWSServiceProviderROS::setRapidNum(const abb_robot_msgs::srv::SetRAPIDNum:: bool RWSServiceProviderROS::setRapidString(const abb_robot_msgs::srv::SetRAPIDString::Request::SharedPtr req, abb_robot_msgs::srv::SetRAPIDString::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + if (!verifyArgumentRapidSymbolPath(req->path, res->result_code, res->message)) { return true; } - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -791,15 +791,15 @@ bool RWSServiceProviderROS::setRapidString(const abb_robot_msgs::srv::SetRAPIDSt bool RWSServiceProviderROS::setRapidSymbol(const abb_robot_msgs::srv::SetRAPIDSymbol::Request::SharedPtr req, abb_robot_msgs::srv::SetRAPIDSymbol::Response::SharedPtr res) { - if (!verify_argument_rapid_symbol_path(req->path, res->result_code, res->message)) + if (!verifyArgumentRapidSymbolPath(req->path, res->result_code, res->message)) { return true; } - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -823,11 +823,11 @@ bool RWSServiceProviderROS::setRapidSymbol(const abb_robot_msgs::srv::SetRAPIDSy bool RWSServiceProviderROS::setSpeedRatio(const abb_robot_msgs::srv::SetSpeedRatio::Request::SharedPtr req, abb_robot_msgs::srv::SetSpeedRatio::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -858,15 +858,15 @@ bool RWSServiceProviderROS::setSpeedRatio(const abb_robot_msgs::srv::SetSpeedRat bool RWSServiceProviderROS::startRapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_motors_on(res->result_code, res->message)) + if (!verifyMotorsOn(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -889,7 +889,7 @@ bool RWSServiceProviderROS::startRapid(const abb_robot_msgs::srv::TriggerWithRes bool RWSServiceProviderROS::stopRapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_rapid_running(res->result_code, res->message)) + if (!verifyRapidRunning(res->result_code, res->message)) { return true; } @@ -912,19 +912,19 @@ bool RWSServiceProviderROS::stopRapid(const abb_robot_msgs::srv::TriggerWithResu bool RWSServiceProviderROS::getEGMSettings(const abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Request::SharedPtr req, abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Response::SharedPtr res) { - if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) + if (!verifyArgumentRapidTask(req->task, res->result_code, res->message)) { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + if (!verifySMAddinRuntimeStates(res->result_code, res->message)) { return true; } - if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) + if (!verifySMAddinTaskExist(req->task, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -951,27 +951,27 @@ bool RWSServiceProviderROS::getEGMSettings(const abb_rapid_sm_addin_msgs::srv::G bool RWSServiceProviderROS::setEGMSettings(const abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Request::SharedPtr req, abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Response::SharedPtr res) { - if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) + if (!verifyArgumentRapidTask(req->task, res->result_code, res->message)) { return true; } - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + if (!verifySMAddinRuntimeStates(res->result_code, res->message)) { return true; } - if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) + if (!verifySMAddinTaskExist(req->task, res->result_code, res->message)) { return true; } - if (!verify_sm_addin_task_initialized(req->task, res->result_code, res->message)) + if (!verifySMAddinTaskInitialized(req->task, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -997,27 +997,27 @@ bool RWSServiceProviderROS::setEGMSettings(const abb_rapid_sm_addin_msgs::srv::S bool RWSServiceProviderROS::setRapidRoutine(const abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Request::SharedPtr req, abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Response::SharedPtr res) { - if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) + if (!verifyArgumentRapidTask(req->task, res->result_code, res->message)) { return true; } - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + if (!verifySMAddinRuntimeStates(res->result_code, res->message)) { return true; } - if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) + if (!verifySMAddinTaskExist(req->task, res->result_code, res->message)) { return true; } - if (!verify_sm_addin_task_initialized(req->task, res->result_code, res->message)) + if (!verifySMAddinTaskInitialized(req->task, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -1041,27 +1041,27 @@ bool RWSServiceProviderROS::setRapidRoutine(const abb_rapid_sm_addin_msgs::srv:: bool RWSServiceProviderROS::setSGCOmmand(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, abb_rapid_sm_addin_msgs::srv::SetSGCommand::Response::SharedPtr res) { - if (!verify_argument_rapid_task(req->task, res->result_code, res->message)) + if (!verifyArgumentRapidTask(req->task, res->result_code, res->message)) { return true; } - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + if (!verifySMAddinRuntimeStates(res->result_code, res->message)) { return true; } - if (!verify_sm_addin_task_exist(req->task, res->result_code, res->message)) + if (!verifySMAddinTaskExist(req->task, res->result_code, res->message)) { return true; } - if (!verify_sm_addin_task_initialized(req->task, res->result_code, res->message)) + if (!verifySMAddinTaskInitialized(req->task, res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -1101,19 +1101,19 @@ bool RWSServiceProviderROS::setSGCOmmand(const abb_rapid_sm_addin_msgs::srv::Set bool RWSServiceProviderROS::startEGMJoint(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rapid_running(res->result_code, res->message)) + if (!verifyRapidRunning(res->result_code, res->message)) { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + if (!verifySMAddinRuntimeStates(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -1137,19 +1137,19 @@ bool RWSServiceProviderROS::startEGMJoint(const abb_robot_msgs::srv::TriggerWith bool RWSServiceProviderROS::startEGMPose(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rapid_running(res->result_code, res->message)) + if (!verifyRapidRunning(res->result_code, res->message)) { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + if (!verifySMAddinRuntimeStates(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -1173,19 +1173,19 @@ bool RWSServiceProviderROS::startEGMPose(const abb_robot_msgs::srv::TriggerWithR bool RWSServiceProviderROS::startEGMStream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rapid_running(res->result_code, res->message)) + if (!verifyRapidRunning(res->result_code, res->message)) { return true; } - if (!verify_sm_addin_runtime_states(res->result_code, res->message)) + if (!verifySMAddinRuntimeStates(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -1209,15 +1209,15 @@ bool RWSServiceProviderROS::startEGMStream(const abb_robot_msgs::srv::TriggerWit bool RWSServiceProviderROS::stopEGM(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rapid_running(res->result_code, res->message)) + if (!verifyRapidRunning(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -1241,15 +1241,15 @@ bool RWSServiceProviderROS::stopEGM(const abb_robot_msgs::srv::TriggerWithResult bool RWSServiceProviderROS::stopEGMStream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) { - if (!verify_auto_mode(res->result_code, res->message)) + if (!verifyAutoMode(res->result_code, res->message)) { return true; } - if (!verify_rapid_running(res->result_code, res->message)) + if (!verifyRapidRunning(res->result_code, res->message)) { return true; } - if (!verify_rws_manager_ready(res->result_code, res->message)) + if (!verifyRWSManagerReady(res->result_code, res->message)) { return true; } @@ -1371,7 +1371,7 @@ bool RWSServiceProviderROS::verifyMotorsOn(uint16_t& result_code, std::string& m return true; } -bool RWSServiceProviderROS::verifySMAddingRuntimeStates(uint16_t& result_code, std::string& message) +bool RWSServiceProviderROS::verifySMAddinRuntimeStates(uint16_t& result_code, std::string& message) { if (runtime_state_.state_machines.empty()) { @@ -1383,8 +1383,7 @@ bool RWSServiceProviderROS::verifySMAddingRuntimeStates(uint16_t& result_code, s return true; } -bool RWSServiceProviderROS::verifySMAddingTaskExist(const std::string& task, uint16_t& result_code, - std::string& message) +bool RWSServiceProviderROS::verifySMAddinTaskExist(const std::string& task, uint16_t& result_code, std::string& message) { auto it = std::find_if(runtime_state_.state_machines.begin(), runtime_state_.state_machines.end(), [&](const auto& sm) { return sm.rapid_task == task; }); @@ -1399,10 +1398,10 @@ bool RWSServiceProviderROS::verifySMAddingTaskExist(const std::string& task, uin return true; } -bool RWSServiceProviderROS::verifySMAddingTaskInitialized(const std::string& task, uint16_t& result_code, - std::string& message) +bool RWSServiceProviderROS::verifySMAddinTaskInitialized(const std::string& task, uint16_t& result_code, + std::string& message) { - if (!verifySMAddingTaskExist(task, result_code, message)) + if (!verifySMAddinTaskExist(task, result_code, message)) return false; auto it = std::find_if(runtime_state_.state_machines.begin(), runtime_state_.state_machines.end(), From c464ad944b7cae49ff76940de338fbe3c18e496f Mon Sep 17 00:00:00 2001 From: Souphis Date: Wed, 15 Jun 2022 00:51:09 +0200 Subject: [PATCH 15/27] Resolving review comments --- .../abb_hardware_interface/utilities.hpp | 19 +++ abb_hardware_interface/src/utilities.cpp | 6 +- abb_rws_client/CMakeLists.txt | 3 +- .../include/abb_rws_client/rws_client.hpp | 2 - .../rws_service_provider_ros.hpp | 7 +- .../rws_state_publisher_ros.hpp | 7 +- .../include/abb_rws_client/utilities.hpp | 90 ------------- abb_rws_client/package.xml | 1 + abb_rws_client/src/mapping.cpp | 79 +++--------- abb_rws_client/src/rws_client.cpp | 8 +- abb_rws_client/src/rws_client_node.cpp | 4 +- .../src/rws_service_provider_ros.cpp | 6 +- .../src/rws_state_publisher_ros.cpp | 12 +- abb_rws_client/src/utilities.cpp | 120 ------------------ 14 files changed, 59 insertions(+), 305 deletions(-) delete mode 100644 abb_rws_client/include/abb_rws_client/utilities.hpp delete mode 100644 abb_rws_client/src/utilities.cpp diff --git a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp b/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp index fd80fe4..f908881 100644 --- a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp +++ b/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp @@ -68,6 +68,25 @@ namespace utilities RobotControllerDescription establishRWSConnection(RWSManager& rws_manager, const std::string& robot_controller_id, const bool no_connection_timeout); +/** + * \brief Verifies that the RobotWare version is supported. + * + * Note: For now, only RobotWare versions in the range [6.07.01, 7.0) are supported (i.e. excluding 7.0). + * + * \param rw_version to verify. + * + * \throw std::runtime_error if the RobotWare version is not supported. + */ +void verifyRobotWareVersion(const RobotWareVersion& rw_version); + +/** + * \brief Verifies that the RobotWare StateMachine Add-In is present in a system. + * + * \param system_indicators to verify. + * + * \return bool true if the StateMachine Add-In is present. + */ +bool verifyStateMachineAddInPresence(const SystemIndicators& system_indicators); } // namespace utilities } // namespace robot } // namespace abb diff --git a/abb_hardware_interface/src/utilities.cpp b/abb_hardware_interface/src/utilities.cpp index ecf5d16..5a94675 100644 --- a/abb_hardware_interface/src/utilities.cpp +++ b/abb_hardware_interface/src/utilities.cpp @@ -42,7 +42,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include namespace abb { @@ -100,7 +100,7 @@ RobotControllerDescription establishRWSConnection(RWSManager& rws_manager, const throw std::runtime_error{ RWS_CONNECTION_ERROR_MESSAGE }; } -void verify_robotware_version(const RobotWareVersion& rw_version) +void verifyRobotWareVersion(const RobotWareVersion& rw_version) { if (rw_version.major_number() == 6 && rw_version.minor_number() < 7 && rw_version.patch_number() < 1) { @@ -111,7 +111,7 @@ void verify_robotware_version(const RobotWareVersion& rw_version) } } -bool verify_state_machine_add_in_presence(const SystemIndicators& system_indicators) +bool verifyStateMachineAddInPresence(const SystemIndicators& system_indicators) { return system_indicators.addins().state_machine_1_0() || system_indicators.addins().state_machine_1_1(); } diff --git a/abb_rws_client/CMakeLists.txt b/abb_rws_client/CMakeLists.txt index 362d260..9782a03 100644 --- a/abb_rws_client/CMakeLists.txt +++ b/abb_rws_client/CMakeLists.txt @@ -24,6 +24,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS abb_robot_msgs abb_rapid_msgs abb_rapid_sm_addin_msgs + abb_hardware_interface rclcpp sensor_msgs ) @@ -44,11 +45,9 @@ add_executable(rws_client src/rws_client.cpp src/rws_service_provider_ros.cpp src/rws_state_publisher_ros.cpp - src/utilities.cpp src/mapping.cpp ) ament_target_dependencies(rws_client ${THIS_PACKAGE_INCLUDE_DEPENDS}) -# target_link_libraries(rws_client abb_egm_rws_managers::abb_egm_rws_managers) target_include_directories( rws_client PRIVATE diff --git a/abb_rws_client/include/abb_rws_client/rws_client.hpp b/abb_rws_client/include/abb_rws_client/rws_client.hpp index 6a435fb..5c43b87 100644 --- a/abb_rws_client/include/abb_rws_client/rws_client.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_client.hpp @@ -40,10 +40,8 @@ #pragma once -// ROS #include -// ABB #include #include diff --git a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp index ce67dc1..e4d8299 100644 --- a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp @@ -40,24 +40,21 @@ #pragma once -#include "abb_rws_client/rws_client.hpp" +#include -// SYSMTEM #include #include -// ROS #include -// ABB MSG #include #include -// ABB SRV #include #include #include #include + #include #include #include diff --git a/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp index 0e700cd..665c839 100644 --- a/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp @@ -40,18 +40,13 @@ #pragma once -#include "abb_rws_client/rws_client.hpp" +#include -// SYSTEM #include -// ROS #include - -// ROS INTERFACES #include -// ABB INTERFACES #include #include #include diff --git a/abb_rws_client/include/abb_rws_client/utilities.hpp b/abb_rws_client/include/abb_rws_client/utilities.hpp deleted file mode 100644 index f29155d..0000000 --- a/abb_rws_client/include/abb_rws_client/utilities.hpp +++ /dev/null @@ -1,90 +0,0 @@ -/*********************************************************************************************************************** - * - * Copyright (c) 2020, ABB Schweiz AG - * 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 ABB 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 HOLDER 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. - * - *********************************************************************************************************************** - */ - -// This file is a modified copy from -// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/initialization.h -// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/include/abb_robot_cpp_utilities/verification.h - -#pragma once - -#include - -#include - -namespace abb -{ -namespace robot -{ -namespace utilities -{ -/** - * \brief Attempts to establish a connection to a robot controller's RWS server. - * - * If a connection is established, then a structured description of the robot controller is returned. - * - * \param rws_manager for handling the RWS communication with the robot controller. - * \param robot_controller_id for an identifier/nickname for the targeted robot controller. - * \param no_connection_timeout indicator whether to wait indefinitely on the robot controller. - * - * \return RobotControllerDescription of the robot controller. - * - * \throw std::runtime_error if unable to establish a connection. - */ -RobotControllerDescription establish_rws_connection(RWSManager& rws_manager, const std::string& robot_controller_id, - const bool no_connection_timeout); - -/** - * \brief Verifies that the RobotWare version is supported. - * - * Note: For now, only RobotWare versions in the range [6.07.01, 7.0) are supported (i.e. excluding 7.0). - * - * \param rw_version to verify. - * - * \throw std::runtime_error if the RobotWare version is not supported. - */ -void verify_robotware_version(const RobotWareVersion& rw_version); - -/** - * \brief Verifies that the RobotWare StateMachine Add-In is present in a system. - * - * \param system_indicators to verify. - * - * \return bool true if the StateMachine Add-In is present. - */ -bool verify_state_machine_add_in_presence(const SystemIndicators& system_indicators); -} // namespace utilities -} // namespace robot -} // namespace abb diff --git a/abb_rws_client/package.xml b/abb_rws_client/package.xml index de23dc2..a167d0c 100644 --- a/abb_rws_client/package.xml +++ b/abb_rws_client/package.xml @@ -14,6 +14,7 @@ abb_rapid_msgs abb_robot_msgs abb_rapid_sm_addin_msgs + abb_hardware_interface ament_cmake_gtest diff --git a/abb_rws_client/src/mapping.cpp b/abb_rws_client/src/mapping.cpp index 50552eb..f368da4 100644 --- a/abb_rws_client/src/mapping.cpp +++ b/abb_rws_client/src/mapping.cpp @@ -37,14 +37,12 @@ // This file is a modified copy from // https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/mapping.cpp -#include "abb_rws_client/mapping.hpp" +#include -// System #include #include #include -// ABB INTERFACES #include #include #include @@ -63,27 +61,21 @@ uint8_t map(const rws::RWSInterface::RAPIDTaskExecutionState state) { case rws::RWSInterface::UNKNOWN: return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_UNKNOWN; - break; case rws::RWSInterface::READY: return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_READY; - break; case rws::RWSInterface::STOPPED: return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_STOPPED; - break; case rws::RWSInterface::STARTED: return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_STARTED; - break; case rws::RWSInterface::UNINITIALIZED: return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_UNINITIALIZED; - break; default: return abb_robot_msgs::msg::RAPIDTaskState::EXECUTION_STATE_UNKNOWN; - break; } } @@ -93,23 +85,18 @@ uint8_t mapStateMachineState(const rws::RAPIDNum& state) { case 0: return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_IDLE; - break; case 1: return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_INITIALIZE; - break; case 2: return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_RUN_RAPID_ROUTINE; - break; case 3: return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_RUN_EGM_ROUTINE; - break; default: return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_UNKNOWN; - break; } } @@ -119,37 +106,30 @@ uint8_t mapStateMachineEGMAction(const rws::RAPIDNum& action) { case 0: return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_NONE; - break; case 1: return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_RUN_JOINT; - break; case 2: return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_RUN_POSE; - break; case 3: return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_STOP; - break; case 4: return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_START_STREAM; - break; case 5: return abb_rapid_sm_addin_msgs::msg::StateMachineState::EGM_ACTION_STOP_STREAM; - break; default: return abb_rapid_sm_addin_msgs::msg::StateMachineState::SM_STATE_UNKNOWN; - break; } } abb_rapid_msgs::msg::Pos map(const rws::Pos& rws_pos) { - abb_rapid_msgs::msg::Pos ros_pos{}; + abb_rapid_msgs::msg::Pos ros_pos; ros_pos.x = rws_pos.x.value; ros_pos.y = rws_pos.y.value; ros_pos.z = rws_pos.z.value; @@ -158,7 +138,7 @@ abb_rapid_msgs::msg::Pos map(const rws::Pos& rws_pos) abb_rapid_msgs::msg::Orient map(const rws::Orient& rws_orient) { - abb_rapid_msgs::msg::Orient ros_orient{}; + abb_rapid_msgs::msg::Orient ros_orient; ros_orient.q1 = rws_orient.q1.value; ros_orient.q2 = rws_orient.q2.value; ros_orient.q3 = rws_orient.q3.value; @@ -168,7 +148,7 @@ abb_rapid_msgs::msg::Orient map(const rws::Orient& rws_orient) abb_rapid_msgs::msg::Pose map(const rws::Pose& rws_pose) { - abb_rapid_msgs::msg::Pose ros_pose{}; + abb_rapid_msgs::msg::Pose ros_pose; ros_pose.trans = map(rws_pose.pos); ros_pose.rot = map(rws_pose.rot); return ros_pose; @@ -176,7 +156,7 @@ abb_rapid_msgs::msg::Pose map(const rws::Pose& rws_pose) abb_rapid_msgs::msg::LoadData map(const rws::LoadData& rws_loaddata) { - abb_rapid_msgs::msg::LoadData ros_loaddata{}; + abb_rapid_msgs::msg::LoadData ros_loaddata; ros_loaddata.mass = rws_loaddata.mass.value; ros_loaddata.cog = map(rws_loaddata.cog); ros_loaddata.aom = map(rws_loaddata.aom); @@ -188,7 +168,7 @@ abb_rapid_msgs::msg::LoadData map(const rws::LoadData& rws_loaddata) abb_rapid_msgs::msg::ToolData map(const rws::ToolData& rws_tooldata) { - abb_rapid_msgs::msg::ToolData ros_tooldata{}; + abb_rapid_msgs::msg::ToolData ros_tooldata; ros_tooldata.robhold = rws_tooldata.robhold.value; ros_tooldata.tframe = map(rws_tooldata.tframe); ros_tooldata.tload = map(rws_tooldata.tload); @@ -197,7 +177,7 @@ abb_rapid_msgs::msg::ToolData map(const rws::ToolData& rws_tooldata) abb_rapid_msgs::msg::WObjData map(const rws::WObjData& rws_wobjdata) { - abb_rapid_msgs::msg::WObjData ros_wobjdata{}; + abb_rapid_msgs::msg::WObjData ros_wobjdata; ros_wobjdata.robhold = rws_wobjdata.robhold.value; ros_wobjdata.ufprog = rws_wobjdata.ufprog.value; ros_wobjdata.ufmec = rws_wobjdata.ufmec.value; @@ -208,7 +188,7 @@ abb_rapid_msgs::msg::WObjData map(const rws::WObjData& rws_wobjdata) abb_rapid_sm_addin_msgs::msg::EGMSettings map(const rws::RWSStateMachineInterface::EGMSettings& rws_egm_settings) { - abb_rapid_sm_addin_msgs::msg::EGMSettings ros_egm_settings{}; + abb_rapid_sm_addin_msgs::msg::EGMSettings ros_egm_settings; ros_egm_settings.allow_egm_motions = rws_egm_settings.allow_egm_motions.value; ros_egm_settings.use_presync = rws_egm_settings.use_presync.value; @@ -241,70 +221,55 @@ unsigned int mapStateMachineSGCommand(const unsigned int command) { case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_NONE: return rws::RWSStateMachineInterface::SG_COMMAND_NONE; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_INITIALIZE: return rws::RWSStateMachineInterface::SG_COMMAND_INITIALIZE; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_CALIBRATE: return rws::RWSStateMachineInterface::SG_COMMAND_CALIBRATE; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_MOVE_TO: return rws::RWSStateMachineInterface::SG_COMMAND_MOVE_TO; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_GRIP_IN: return rws::RWSStateMachineInterface::SG_COMMAND_GRIP_IN; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_GRIP_OUT: return rws::RWSStateMachineInterface::SG_COMMAND_GRIP_OUT; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_BLOW_ON_1: return rws::RWSStateMachineInterface::SG_COMMAND_BLOW_ON_1; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_BLOW_ON_2: return rws::RWSStateMachineInterface::SG_COMMAND_BLOW_ON_2; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_BLOW_OFF_1: return rws::RWSStateMachineInterface::SG_COMMAND_BLOW_OFF_1; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_BLOW_OFF_2: return rws::RWSStateMachineInterface::SG_COMMAND_BLOW_OFF_2; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_VACUUM_ON_1: return rws::RWSStateMachineInterface::SG_COMMAND_VACUUM_ON_1; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_VACUUM_ON_2: return rws::RWSStateMachineInterface::SG_COMMAND_VACUUM_ON_2; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_VACUUM_OFF_1: return rws::RWSStateMachineInterface::SG_COMMAND_VACUUM_OFF_1; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_VACUUM_OFF_2: return rws::RWSStateMachineInterface::SG_COMMAND_VACUUM_OFF_2; - break; case abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SG_COMMAND_UNKNOWN: default: throw std::runtime_error{ "Unknown SmartGripper command" }; - break; } } rws::Pos map(const abb_rapid_msgs::msg::Pos& ros_pos) { - rws::Pos rws_pos{}; + rws::Pos rws_pos; rws_pos.x.value = ros_pos.x; rws_pos.y.value = ros_pos.y; rws_pos.z.value = ros_pos.z; @@ -313,7 +278,7 @@ rws::Pos map(const abb_rapid_msgs::msg::Pos& ros_pos) rws::Orient map(const abb_rapid_msgs::msg::Orient& ros_orient) { - rws::Orient rws_orient{}; + rws::Orient rws_orient; rws_orient.q1 = ros_orient.q1; rws_orient.q2 = ros_orient.q2; rws_orient.q3 = ros_orient.q3; @@ -323,7 +288,7 @@ rws::Orient map(const abb_rapid_msgs::msg::Orient& ros_orient) rws::Pose map(const abb_rapid_msgs::msg::Pose& ros_pose) { - rws::Pose rws_pose{}; + rws::Pose rws_pose; rws_pose.pos = map(ros_pose.trans); rws_pose.rot = map(ros_pose.rot); return rws_pose; @@ -331,7 +296,7 @@ rws::Pose map(const abb_rapid_msgs::msg::Pose& ros_pose) rws::LoadData map(const abb_rapid_msgs::msg::LoadData& ros_loaddata) { - rws::LoadData rws_loaddata{}; + rws::LoadData rws_loaddata; rws_loaddata.mass.value = ros_loaddata.mass; rws_loaddata.cog = map(ros_loaddata.cog); rws_loaddata.aom = map(ros_loaddata.aom); @@ -343,7 +308,7 @@ rws::LoadData map(const abb_rapid_msgs::msg::LoadData& ros_loaddata) rws::ToolData map(const abb_rapid_msgs::msg::ToolData& ros_tooldata) { - rws::ToolData rws_tooldata{}; + rws::ToolData rws_tooldata; rws_tooldata.robhold = ros_tooldata.robhold; rws_tooldata.tframe = map(ros_tooldata.tframe); rws_tooldata.tload = map(ros_tooldata.tload); @@ -352,7 +317,7 @@ rws::ToolData map(const abb_rapid_msgs::msg::ToolData& ros_tooldata) rws::WObjData map(const abb_rapid_msgs::msg::WObjData& ros_wobjdata) { - rws::WObjData rws_wobjdata{}; + rws::WObjData rws_wobjdata; rws_wobjdata.robhold.value = ros_wobjdata.robhold; rws_wobjdata.ufprog.value = ros_wobjdata.ufprog; rws_wobjdata.ufmec.value = ros_wobjdata.ufmec; @@ -363,7 +328,7 @@ rws::WObjData map(const abb_rapid_msgs::msg::WObjData& ros_wobjdata) rws::RWSStateMachineInterface::EGMSettings map(const abb_rapid_sm_addin_msgs::msg::EGMSettings& ros_egm_settings) { - rws::RWSStateMachineInterface::EGMSettings rws_egm_settings{}; + rws::RWSStateMachineInterface::EGMSettings rws_egm_settings; rws_egm_settings.allow_egm_motions.value = ros_egm_settings.allow_egm_motions; rws_egm_settings.use_presync.value = ros_egm_settings.use_presync; @@ -396,20 +361,16 @@ uint8_t map(egm::wrapper::Status::EGMState state) { case egm::wrapper::Status::EGM_ERROR: return abb_egm_msgs::msg::EGMChannelState::EGM_ERROR; - break; case egm::wrapper::Status::EGM_STOPPED: return abb_egm_msgs::msg::EGMChannelState::EGM_STOPPED; - break; case egm::wrapper::Status::EGM_RUNNING: return abb_egm_msgs::msg::EGMChannelState::EGM_RUNNING; - break; case egm::wrapper::Status::EGM_UNDEFINED: default: return abb_egm_msgs::msg::EGMChannelState::EGM_UNDEFINED; - break; } } @@ -419,16 +380,13 @@ uint8_t map(egm::wrapper::Status::MotorState state) { case egm::wrapper::Status::MOTORS_ON: return abb_egm_msgs::msg::EGMChannelState::MOTORS_ON; - break; case egm::wrapper::Status::MOTORS_OFF: return abb_egm_msgs::msg::EGMChannelState::MOTORS_OFF; - break; case egm::wrapper::Status::MOTORS_UNDEFINED: default: return abb_egm_msgs::msg::EGMChannelState::MOTORS_UNDEFINED; - break; } } @@ -438,26 +396,23 @@ uint8_t map(egm::wrapper::Status::RAPIDExecutionState state) { case egm::wrapper::Status::RAPID_STOPPED: return abb_egm_msgs::msg::EGMChannelState::RAPID_STOPPED; - break; case egm::wrapper::Status::RAPID_RUNNING: return abb_egm_msgs::msg::EGMChannelState::RAPID_RUNNING; - break; case egm::wrapper::Status::RAPID_UNDEFINED: default: return abb_egm_msgs::msg::EGMChannelState::RAPID_UNDEFINED; - break; } } template std::string mapVectorToString(const std::vector& vector) { - std::stringstream ss{}; + std::stringstream ss; ss << "["; - for (size_t i{ 0 }; i < vector.size(); ++i) + for (size_t i = 0; i < vector.size(); ++i) { ss << vector[i]; diff --git a/abb_rws_client/src/rws_client.cpp b/abb_rws_client/src/rws_client.cpp index 239ac89..44ae3a7 100644 --- a/abb_rws_client/src/rws_client.cpp +++ b/abb_rws_client/src/rws_client.cpp @@ -38,9 +38,9 @@ // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/src // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/src -#include "abb_rws_client/rws_client.hpp" +#include -#include "abb_rws_client/utilities.hpp" +#include namespace abb_rws_client { @@ -62,7 +62,7 @@ void RWSClient::connect() node_->get_parameter("robot_nickname", robot_id); node_->get_parameter("no_connection_timeout", no_connection_timeout); robot_controller_description_ = - abb::robot::utilities::establish_rws_connection(rws_manager_, robot_id, no_connection_timeout); - abb::robot::utilities::verify_robotware_version(robot_controller_description_.header().robot_ware_version()); + abb::robot::utilities::establishRWSConnection(rws_manager_, robot_id, no_connection_timeout); + abb::robot::utilities::verifyRobotWareVersion(robot_controller_description_.header().robot_ware_version()); } } // namespace abb_rws_client diff --git a/abb_rws_client/src/rws_client_node.cpp b/abb_rws_client/src/rws_client_node.cpp index 97489ca..5c2bbd7 100644 --- a/abb_rws_client/src/rws_client_node.cpp +++ b/abb_rws_client/src/rws_client_node.cpp @@ -1,7 +1,7 @@ #include -#include "abb_rws_client/rws_service_provider_ros.hpp" -#include "abb_rws_client/rws_state_publisher_ros.hpp" +#include +#include int main(int argc, char** argv) { diff --git a/abb_rws_client/src/rws_service_provider_ros.cpp b/abb_rws_client/src/rws_service_provider_ros.cpp index ccb9748..c718725 100644 --- a/abb_rws_client/src/rws_service_provider_ros.cpp +++ b/abb_rws_client/src/rws_service_provider_ros.cpp @@ -38,12 +38,12 @@ // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/src // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/src -#include "abb_rws_client/rws_service_provider_ros.hpp" +#include #include -#include "abb_rws_client/mapping.hpp" -#include "abb_rws_client/utilities.hpp" +#include +#include using RAPIDSymbols = abb::rws::RWSStateMachineInterface::ResourceIdentifiers::RAPID::Symbols; diff --git a/abb_rws_client/src/rws_state_publisher_ros.cpp b/abb_rws_client/src/rws_state_publisher_ros.cpp index 1ccabeb..66ef00c 100644 --- a/abb_rws_client/src/rws_state_publisher_ros.cpp +++ b/abb_rws_client/src/rws_state_publisher_ros.cpp @@ -38,10 +38,10 @@ // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/src // https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/src -#include "abb_rws_client/rws_state_publisher_ros.hpp" +#include -#include "abb_rws_client/mapping.hpp" -#include "abb_rws_client/utilities.hpp" +#include +#include namespace { @@ -67,7 +67,7 @@ RWSStatePublisherROS::RWSStatePublisherROS(const rclcpp::Node::SharedPtr& node, system_state_pub_ = node_->create_publisher("~/system_states", 1); - if (abb::robot::utilities::verify_state_machine_add_in_presence(robot_controller_description_.system_indicators())) + if (abb::robot::utilities::verifyStateMachineAddInPresence(robot_controller_description_.system_indicators())) { runtime_state_pub_ = node_->create_publisher("~/sm_addin/runtime_states", 1); @@ -128,7 +128,7 @@ void RWSStatePublisherROS::timer_callback() abb_rapid_sm_addin_msgs::msg::RuntimeState sm_runtime_state_msg; const auto& system_indicators{ robot_controller_description_.system_indicators() }; - if (abb::robot::utilities::verify_state_machine_add_in_presence(system_indicators)) + if (abb::robot::utilities::verifyStateMachineAddInPresence(system_indicators)) { for (const auto& sm : system_state_data_.state_machines) { @@ -147,7 +147,7 @@ void RWSStatePublisherROS::timer_callback() system_state_msg.header.stamp = time; system_state_pub_->publish(system_state_msg); - if (abb::robot::utilities::verify_state_machine_add_in_presence(robot_controller_description_.system_indicators())) + if (abb::robot::utilities::verifyStateMachineAddInPresence(robot_controller_description_.system_indicators())) { sm_runtime_state_msg.header.stamp = time; runtime_state_pub_->publish(sm_runtime_state_msg); diff --git a/abb_rws_client/src/utilities.cpp b/abb_rws_client/src/utilities.cpp deleted file mode 100644 index 7a4e9e8..0000000 --- a/abb_rws_client/src/utilities.cpp +++ /dev/null @@ -1,120 +0,0 @@ -/*********************************************************************************************************************** - * - * Copyright (c) 2020, ABB Schweiz AG - * 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 ABB 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 HOLDER 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. - * - *********************************************************************************************************************** - */ - -// This file is a modified copy from -// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/initialization.cpp -// https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/verification.cpp - -#include - -#include - -#include "rclcpp/rclcpp.hpp" - -namespace abb -{ -namespace robot -{ -namespace utilities -{ -namespace -{ -/** - * \brief Max number of attempts when trying to connect to a robot controller via RWS. - */ -constexpr unsigned int RWS_MAX_CONNECTION_ATTEMPTS{ 5 }; - -/** - * \brief Error message for failed connection attempts when trying to connect to a robot controller via RWS. - */ -constexpr char RWS_CONNECTION_ERROR_MESSAGE[]{ "Failed to establish RWS connection to the robot controller" }; - -/** - * \brief Time [s] to wait before trying to reconnect to a robot controller via RWS. - */ -constexpr uint8_t RWS_RECONNECTION_WAIT_TIME{ 1 }; -auto LOGGER = rclcpp::get_logger("ABBHardwareInterfaceUtilities"); -} // namespace - -RobotControllerDescription establish_rws_connection(RWSManager& rws_manager, const std::string& robot_controller_id, - const bool no_connection_timeout) -{ - unsigned int attempt{ 0 }; - - while (rclcpp::ok() && (no_connection_timeout || attempt++ < RWS_MAX_CONNECTION_ATTEMPTS)) - { - try - { - return rws_manager.collectAndParseSystemData(robot_controller_id); - } - catch (const std::runtime_error& exception) - { - if (!no_connection_timeout) - { - RCLCPP_WARN_STREAM(LOGGER, RWS_CONNECTION_ERROR_MESSAGE << " (attempt " << attempt << "/" - << RWS_MAX_CONNECTION_ATTEMPTS << "), reason: '" - << exception.what() << "'"); - } - else - { - RCLCPP_WARN_STREAM(LOGGER, RWS_CONNECTION_ERROR_MESSAGE << " (waiting indefinitely), reason: '" - << exception.what() << "'"); - } - rclcpp::sleep_for(std::chrono::seconds(RWS_RECONNECTION_WAIT_TIME)); - } - } - - throw std::runtime_error{ RWS_CONNECTION_ERROR_MESSAGE }; -} - -void verify_robotware_version(const RobotWareVersion& rw_version) -{ - if (rw_version.major_number() == 6 && rw_version.minor_number() < 7 && rw_version.patch_number() < 1) - { - auto error_message{ "Unsupported RobotWare version (" + rw_version.name() + ", need at least 6.07.01)" }; - - RCLCPP_FATAL_STREAM(LOGGER, error_message); - throw std::runtime_error{ error_message }; - } -} - -bool verify_state_machine_add_in_presence(const SystemIndicators& system_indicators) -{ - return system_indicators.addins().state_machine_1_0() || system_indicators.addins().state_machine_1_1(); -} -} // namespace utilities -} // namespace robot -} // namespace abb From d543aea7772af05e9c8e48859e3b0807e8ce7f18 Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Wed, 15 Jun 2022 15:39:57 +0200 Subject: [PATCH 16/27] Changed cmake and launch file --- abb_bringup/launch/abb_rws_client.launch.py | 85 ++++++++++++------- abb_rws_client/CMakeLists.txt | 21 ++++- .../rws_service_provider_ros.hpp | 4 +- .../src/rws_state_publisher_ros.cpp | 3 + 4 files changed, 79 insertions(+), 34 deletions(-) diff --git a/abb_bringup/launch/abb_rws_client.launch.py b/abb_bringup/launch/abb_rws_client.launch.py index e2f9f99..9d9c9f1 100644 --- a/abb_bringup/launch/abb_rws_client.launch.py +++ b/abb_bringup/launch/abb_rws_client.launch.py @@ -1,45 +1,70 @@ from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node -def launch_setup(context, *args, **kwargs): +def generate_launch_description(): robot_ip = LaunchConfiguration("robot_ip") robot_port = LaunchConfiguration("robot_port") robot_nickname = LaunchConfiguration("robot_nickname") polling_rate = LaunchConfiguration("polling_rate") no_connection_timeout = LaunchConfiguration("no_connection_timeout") - return [ - Node( - package="abb_hardware_interface", - executable="rws_client", - name="rws_client", - output="screen", - parameters=[ - { - "robot_ip": robot_ip, - "robot_port": int(robot_port.perform(context)), - "robot_nickname": robot_nickname, - "polling_rate": float(polling_rate.perform(context)), - "no_connection_timeout": bool( - no_connection_timeout.perform(context) - ), - } - ], + declared_arguments = [] + + declared_arguments.append( + DeclareLaunchArgument( + "robot_ip", + default_value="None", + description="IP address to the robot controller's RWS server", ) - ] + ) + declared_arguments.append( + DeclareLaunchArgument( + "robot_port", + default_value="80", + description="Port number of the robot controller's RWS server", + ) + ) -def generate_launch_description(): - return LaunchDescription( - [ - DeclareLaunchArgument("robot_ip"), - DeclareLaunchArgument("robot_port"), - DeclareLaunchArgument("robot_nickname"), - DeclareLaunchArgument("polling_rate"), - DeclareLaunchArgument("no_connection_timeout"), - OpaqueFunction(function=launch_setup), - ] + declared_arguments.append( + DeclareLaunchArgument( + "robot_nickname", + default_value="", + description="Arbitrary user nickname/identifier for the robot controller", + ) + ) + + declared_arguments.append( + DeclareLaunchArgument( + "no_connection_timeout", + default_value="false", + description="Specifies whether the node is allowed to wait indefinitely \ + for the robot controller during initialization.", + ) + ) + + declared_arguments.append( + DeclareLaunchArgument( + "polling_rate", + default_value="5.0", + description="The frequency [Hz] at which the controller state is collected.", + ) + ) + + node = Node( + package="abb_rws_client", + executable="rws_client", + name="rws_client", + output="screen", + parameters=[ + {"robot_ip": robot_ip}, + {"robot_port": robot_port}, + {"robot_nickname": robot_nickname}, + {"polling_rate": polling_rate}, + {"no_connection_timeout": no_connection_timeout}, + ], ) + return LaunchDescription(declared_arguments + [node]) diff --git a/abb_rws_client/CMakeLists.txt b/abb_rws_client/CMakeLists.txt index 9782a03..b35ef3f 100644 --- a/abb_rws_client/CMakeLists.txt +++ b/abb_rws_client/CMakeLists.txt @@ -40,14 +40,23 @@ endforeach() ## Build ## ########### -add_executable(rws_client +add_library(rws_client_lib src/rws_client_node.cpp src/rws_client.cpp src/rws_service_provider_ros.cpp src/rws_state_publisher_ros.cpp src/mapping.cpp ) -ament_target_dependencies(rws_client ${THIS_PACKAGE_INCLUDE_DEPENDS}) +ament_target_dependencies(rws_client_lib ${THIS_PACKAGE_INCLUDE_DEPENDS}) +target_include_directories( + rws_client_lib + PRIVATE + include +) + +add_executable(rws_client src/rws_client.cpp) +target_link_libraries(rws_client rws_client_lib) +ament_target_dependencies(rws_client "rclcpp") target_include_directories( rws_client PRIVATE @@ -63,6 +72,14 @@ install( DESTINATION lib/${PROJECT_NAME} ) +install( + TARGETS + rws_client_lib + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + ############# ## Testing ## ############# diff --git a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp index e4d8299..18c295c 100644 --- a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp @@ -215,8 +215,8 @@ class RWSServiceProviderROS : RWSClient rclcpp::Subscription::SharedPtr system_state_sub_; rclcpp::Subscription::SharedPtr runtime_state_sub_; - std::vector core_services_; - std::vector sm_services_; + std::vector core_services_; + std::vector sm_services_; abb_robot_msgs::msg::SystemState system_state_; abb_rapid_sm_addin_msgs::msg::RuntimeState runtime_state_; diff --git a/abb_rws_client/src/rws_state_publisher_ros.cpp b/abb_rws_client/src/rws_state_publisher_ros.cpp index 66ef00c..67eebbb 100644 --- a/abb_rws_client/src/rws_state_publisher_ros.cpp +++ b/abb_rws_client/src/rws_state_publisher_ros.cpp @@ -72,6 +72,9 @@ RWSStatePublisherROS::RWSStatePublisherROS(const rclcpp::Node::SharedPtr& node, runtime_state_pub_ = node_->create_publisher("~/sm_addin/runtime_states", 1); } + auto polling_rate = node_->get_parameter("polling_rate").as_double(); + node_->create_wall_timer(std::chrono::milliseconds(static_cast(1000.0 / polling_rate)), + std::bind(&RWSStatePublisherROS::timer_callback, this)); } void RWSStatePublisherROS::timer_callback() From 6246534a5b134e8d3b0c50be45c5ffff34eb8709 Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Wed, 15 Jun 2022 16:06:26 +0200 Subject: [PATCH 17/27] Fixed connection problems --- abb_rws_client/src/rws_client.cpp | 3 --- abb_rws_client/src/rws_client_node.cpp | 2 ++ abb_rws_client/src/rws_state_publisher_ros.cpp | 4 ++-- 3 files changed, 4 insertions(+), 5 deletions(-) diff --git a/abb_rws_client/src/rws_client.cpp b/abb_rws_client/src/rws_client.cpp index 44ae3a7..e2d2ab5 100644 --- a/abb_rws_client/src/rws_client.cpp +++ b/abb_rws_client/src/rws_client.cpp @@ -49,9 +49,6 @@ RWSClient::RWSClient(const rclcpp::Node::SharedPtr& node, const std::string& rob , rws_manager_{ robot_ip, robot_port, abb::rws::SystemConstants::General::DEFAULT_USERNAME, abb::rws::SystemConstants::General::DEFAULT_PASSWORD } { - node_->declare_parameter("robot_nickname", std::string{}); - node_->declare_parameter("no_connection_timeout", false); - connect(); } void RWSClient::connect() diff --git a/abb_rws_client/src/rws_client_node.cpp b/abb_rws_client/src/rws_client_node.cpp index 5c2bbd7..2ad0068 100644 --- a/abb_rws_client/src/rws_client_node.cpp +++ b/abb_rws_client/src/rws_client_node.cpp @@ -9,6 +9,8 @@ int main(int argc, char** argv) rclcpp::Node::SharedPtr client_node = rclcpp::Node::make_shared("rws"); + client_node->declare_parameter("robot_nickname", std::string{}); + client_node->declare_parameter("no_connection_timeout", false); std::string robot_ip = client_node->declare_parameter("robot_ip", "127.0.0.1"); int robot_port = client_node->declare_parameter("robot_port", 65535); diff --git a/abb_rws_client/src/rws_state_publisher_ros.cpp b/abb_rws_client/src/rws_state_publisher_ros.cpp index 67eebbb..fe1f235 100644 --- a/abb_rws_client/src/rws_state_publisher_ros.cpp +++ b/abb_rws_client/src/rws_state_publisher_ros.cpp @@ -73,8 +73,8 @@ RWSStatePublisherROS::RWSStatePublisherROS(const rclcpp::Node::SharedPtr& node, node_->create_publisher("~/sm_addin/runtime_states", 1); } auto polling_rate = node_->get_parameter("polling_rate").as_double(); - node_->create_wall_timer(std::chrono::milliseconds(static_cast(1000.0 / polling_rate)), - std::bind(&RWSStatePublisherROS::timer_callback, this)); + timer_ = node_->create_wall_timer(std::chrono::milliseconds(static_cast(1000.0 / polling_rate)), + std::bind(&RWSStatePublisherROS::timer_callback, this)); } void RWSStatePublisherROS::timer_callback() From 62d7e6acccd8aa1980b91a4f29e3e6de2667c1c9 Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Mon, 20 Jun 2022 11:35:54 +0200 Subject: [PATCH 18/27] Add docstrings and perform minor clean up --- abb_rws_client/CMakeLists.txt | 4 +- .../include/abb_rws_client/rws_client.hpp | 65 --- .../rws_service_provider_ros.hpp | 464 +++++++++++++++++- .../rws_state_publisher_ros.hpp | 48 +- abb_rws_client/src/rws_client.cpp | 65 --- .../src/rws_service_provider_ros.cpp | 28 +- .../src/rws_state_publisher_ros.cpp | 12 +- 7 files changed, 535 insertions(+), 151 deletions(-) delete mode 100644 abb_rws_client/include/abb_rws_client/rws_client.hpp delete mode 100644 abb_rws_client/src/rws_client.cpp diff --git a/abb_rws_client/CMakeLists.txt b/abb_rws_client/CMakeLists.txt index b35ef3f..1299ea3 100644 --- a/abb_rws_client/CMakeLists.txt +++ b/abb_rws_client/CMakeLists.txt @@ -41,8 +41,6 @@ endforeach() ########### add_library(rws_client_lib - src/rws_client_node.cpp - src/rws_client.cpp src/rws_service_provider_ros.cpp src/rws_state_publisher_ros.cpp src/mapping.cpp @@ -54,7 +52,7 @@ target_include_directories( include ) -add_executable(rws_client src/rws_client.cpp) +add_executable(rws_client src/rws_client_node.cpp) target_link_libraries(rws_client rws_client_lib) ament_target_dependencies(rws_client "rclcpp") target_include_directories( diff --git a/abb_rws_client/include/abb_rws_client/rws_client.hpp b/abb_rws_client/include/abb_rws_client/rws_client.hpp deleted file mode 100644 index 5c43b87..0000000 --- a/abb_rws_client/include/abb_rws_client/rws_client.hpp +++ /dev/null @@ -1,65 +0,0 @@ -/*********************************************************************************************************************** - * - * Copyright (c) 2020, ABB Schweiz AG - * 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 ABB 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 HOLDER 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. - * - *********************************************************************************************************************** - */ - -// This file is a modified copy from -// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/include/abb_rws_service_provider/ -// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/include/abb_rws_state_publisher/ - -#pragma once - -#include - -#include -#include - -namespace abb_rws_client -{ -class RWSClient -{ -public: - RWSClient(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port); - -protected: - rclcpp::Node::SharedPtr node_; - abb::robot::RWSManager rws_manager_; - - abb::robot::RobotControllerDescription robot_controller_description_; - -private: - void connect(); -}; - -} // namespace abb_rws_client diff --git a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp index 18c295c..c851592 100644 --- a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp @@ -40,13 +40,14 @@ #pragma once -#include - #include #include #include +#include +#include + #include #include @@ -76,149 +77,604 @@ namespace abb_rws_client { -class RWSServiceProviderROS : RWSClient +class RWSServiceProviderROS { public: + /** + * \brief Creates a services server. + * + * \param node ROS2 node. + * \param robot_ip IP address for the robot controller's RWS server. + * \param robot_poty Port number for the robot controller's RWS server. + */ RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port); private: + /** + * \brief Callback for robot controller system state messages. + * + * \param message to process. + */ void systemStateCallback(const abb_robot_msgs::msg::SystemState& msg); + /** + * \brief Callback for RobotWare StateMachine Add-In runtime state messages. + * + * Note: Only used if the Add-In is present in the robot controller's system. + * + * \param message to process. + */ void runtimeStateCallback(const abb_rapid_sm_addin_msgs::msg::RuntimeState& msg); + /** + * \brief Gets the contents of a file. + * + * The file must be located in the robot controller's home directory. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool getFileContents(const abb_robot_msgs::srv::GetFileContents::Request::SharedPtr req, abb_robot_msgs::srv::GetFileContents::Response::SharedPtr res); - + /** + * \brief Gets an IO-signal. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool getIOSignal(const abb_robot_msgs::srv::GetIOSignal::Request::SharedPtr req, abb_robot_msgs::srv::GetIOSignal::Response::SharedPtr res); + /** + * \brief Gets a RAPID 'bool' symbol. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool getRapidBool(const abb_robot_msgs::srv::GetRAPIDBool::Request::SharedPtr req, abb_robot_msgs::srv::GetRAPIDBool::Response::SharedPtr res); + /** + * \brief Gets a RAPID 'dnum' symbol. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool getRapidDNum(const abb_robot_msgs::srv::GetRAPIDDnum::Request::SharedPtr req, abb_robot_msgs::srv::GetRAPIDDnum::Response::SharedPtr res); + /** + * \brief Gets a RAPID 'num' symbol. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool getRapidNum(const abb_robot_msgs::srv::GetRAPIDNum::Request::SharedPtr req, abb_robot_msgs::srv::GetRAPIDNum::Response::SharedPtr res); + /** + * \brief Gets a RAPID 'string' symbol. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool getRapidString(const abb_robot_msgs::srv::GetRAPIDString::Request::SharedPtr req, abb_robot_msgs::srv::GetRAPIDString::Response::SharedPtr res); + /** + * \brief Gets a RAPID symbol (in raw text format). + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool getRapidSymbol(const abb_robot_msgs::srv::GetRAPIDSymbol::Request::SharedPtr req, abb_robot_msgs::srv::GetRAPIDSymbol::Response::SharedPtr res); + /** + * \brief Gets a description of the connected robot controller. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool getRCDescription(const abb_robot_msgs::srv::GetRobotControllerDescription::Request::SharedPtr req, abb_robot_msgs::srv::GetRobotControllerDescription::Response::SharedPtr res); + /** + * \brief Gets the controller speed ratio (in the range [0, 100]) for RAPID motions. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool getSpeedRatio(const abb_robot_msgs::srv::GetSpeedRatio::Request::SharedPtr req, abb_robot_msgs::srv::GetSpeedRatio::Response::SharedPtr res); + /** + * \brief Sets all RAPID program pointers to respective main procedure. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool ppToMain(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + /** + * \brief Signals that SmartGripper command(s) should be run for all RAPID programs. + * + * Notes: + * - Requires the StateMachine Add-In. + * - The desired SmartGripper command(s) needs to be specified beforehand (one per RAPID task). + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool runRapidRoutine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + /** + * \brief Signals that SmartGripper command(s) should be run for all RAPID programs. + * + * Notes: + * - Requires the StateMachine Add-In. + * - The desired SmartGripper command(s) needs to be specified beforehand (one per RAPID task). + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool runSGRoutine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + /** + * \brief Sets the contents of a file. + * + * The file will be uploaded to the robot controller's home directory. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setFileContents(const abb_robot_msgs::srv::SetFileContents::Request::SharedPtr req, abb_robot_msgs::srv::SetFileContents::Response::SharedPtr res); + /** + * \brief Sets an IO-signal. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setIOSignal(const abb_robot_msgs::srv::SetIOSignal::Request::SharedPtr req, abb_robot_msgs::srv::SetIOSignal::Response::SharedPtr res); + /** + * \brief Sets the motors off. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setMotorsOff(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + /** + * \brief Sets the motors on. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setMotorsOn(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + /** + * \brief Sets a RAPID 'bool' symbol. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setRapidBool(const abb_robot_msgs::srv::SetRAPIDBool::Request::SharedPtr req, abb_robot_msgs::srv::SetRAPIDBool::Response::SharedPtr res); + /** + * \brief Sets a RAPID 'dnum' symbol. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setRapidDNum(const abb_robot_msgs::srv::SetRAPIDDnum::Request::SharedPtr req, abb_robot_msgs::srv::SetRAPIDDnum::Response::SharedPtr res); + /** + * \brief Sets a RAPID 'num' symbol. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setRapidNum(const abb_robot_msgs::srv::SetRAPIDNum::Request::SharedPtr req, abb_robot_msgs::srv::SetRAPIDNum::Response::SharedPtr res); + /** + * \brief Sets a RAPID 'string' symbol. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setRapidString(const abb_robot_msgs::srv::SetRAPIDString::Request::SharedPtr req, abb_robot_msgs::srv::SetRAPIDString::Response::SharedPtr res); + /** + * \brief Sets a RAPID symbol. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setRapidSymbol(const abb_robot_msgs::srv::SetRAPIDSymbol::Request::SharedPtr req, abb_robot_msgs::srv::SetRAPIDSymbol::Response::SharedPtr res); + /** + * \brief Sets the controller speed ratio (in the range [0, 100]) for RAPID motions. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setSpeedRatio(const abb_robot_msgs::srv::SetSpeedRatio::Request::SharedPtr req, abb_robot_msgs::srv::SetSpeedRatio::Response::SharedPtr res); + /** + * \brief Starts all RAPID programs. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool startRapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + /** + * \brief Stop all RAPID programs. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool stopRapid(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + /** + * \brief Gets EGM settings used by a specific RAPID task. + * + * Note: Requires the StateMachine Add-In. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool getEGMSettings(const abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Request::SharedPtr req, abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Response::SharedPtr res); + /** + * \brief Sets EGM settings used by a specific RAPID task. + * + * Note: Requires the StateMachine Add-In. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setEGMSettings(const abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Request::SharedPtr req, abb_rapid_sm_addin_msgs::srv::SetEGMSettings::Response::SharedPtr res); + /** + * \brief Sets desired custom RAPID routine for a specific RAPID task. + * + * Note: Requires the StateMachine Add-In. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setRapidRoutine(const abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Request::SharedPtr req, abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Response::SharedPtr res); + /** + * \brief Sets desired SmartGripper command for a specific RAPID task. + * + * Note: Requires the StateMachine Add-In. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool setSGCOmmand(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, abb_rapid_sm_addin_msgs::srv::SetSGCommand::Response::SharedPtr res); + /** + * \brief Starts EGM joint motions for all RAPID programs. + * + * Note: Requires the StateMachine Add-In. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool startEGMJoint(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + /** + * \brief Starts EGM pose motions for all RAPID programs. + * + * Note: Requires the StateMachine Add-In. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool startEGMPose(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + /** + * \brief Starts EGM position streaming for all RAPID programs. + * + * Note: Requires the StateMachine Add-In. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool startEGMStream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + /** + * \brief Stops EGM motions for all RAPID programs. + * + * Note: Requires the StateMachine Add-In. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool stopEGM(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + /** + * \brief Stops EGM position streaming for all RAPID programs. + * + * Note: Requires the StateMachine Add-In. + * + * \param request to process. + * \param response for containing the result. + * + * \return bool true if the request was processed. + */ bool stopEGMStream(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr req, abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); + /** + * \brief Verify that auto mode is active. + * + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if auto mode is active. + */ bool verifyAutoMode(uint16_t& result_code, std::string& message); + /** + * \brief Verify that a filename is not empty. + * + * \param filename to verify. + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if the filename is not empty. + */ bool verifyArgumentFilename(const std::string& filename, uint16_t& result_code, std::string& message); + /** + * \brief Verify that a RAPID symbol path does not contain any empty subcomponents. + * + * \param path to verify. + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if the RAPID symbol path does not contain any empty subcomponents.. + */ bool verifyArgumentRapidSymbolPath(const abb_robot_msgs::msg::RAPIDSymbolPath& path, uint16_t& result_code, std::string& message); + /** + * \brief Verify that a RAPID task name is not empty. + * + * \param task to verify. + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if the RAPID task name is not empty. + */ bool verifyArgumentRapidTask(const std::string& task, uint16_t& result_code, std::string& message); + /** + * \brief Verify that an IO-signal name is not empty. + * + * \param signal to verify. + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if the IO-signal name is not empty. + */ bool verifyArgumentSignal(const std::string& signal, uint16_t& result_code, std::string& message); + /** + * \brief Verify that motors are off. + * + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if the motors are off. + */ bool verifyMotorsOff(uint16_t& result_code, std::string& message); + /** + * \brief Verify that motors are on. + * + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if the motors are on. + */ bool verifyMotorsOn(uint16_t& result_code, std::string& message); + /** + * \brief Verify that runtime states has been received for StateMachine Add-In instances. + * + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if runtime states has been received. + */ bool verifySMAddinRuntimeStates(uint16_t& result_code, std::string& message); + /** + * \brief Verify that a StateMachine Add-In instance is used by a RAPID task. + * + * \param task to check. + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if the RAPID task is used by a StateMachine Add-In instance. + */ bool verifySMAddinTaskExist(const std::string& task, uint16_t& result_code, std::string& message); + /** + * \brief Verify that a StateMachine Add-In instance is used by a RAPID task and that it has been initialized. + * + * \param task to check. + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if the RAPID task is used by a StateMachine Add-In instance and has been initialized. + */ bool verifySMAddinTaskInitialized(const std::string& task, uint16_t& result_code, std::string& message); + /** + * \brief Verify that RAPID is running. + * + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if RAPID is running. + */ bool verifyRapidRunning(uint16_t& result_code, std::string& message); + /** + * \brief Verify that RAPID is stopped. + * + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if RAPID is stopped. + */ bool verifyRapidStopped(uint16_t& result_code, std::string& message); + /** + * \brief Verify that the RWS communication manager is ready. + * + * \param[out] result_code numerical error code. + * \param[out] message container for possible error message. + * + * \return bool true if the RWS communication manager is ready. + */ bool verifyRWSManagerReady(uint16_t& result_code, std::string& message); + rclcpp::Node::SharedPtr node_; + + /** + * \brief Manager for handling RWS communication with the robot controller. + */ + abb::robot::RWSManager rws_manager_; + + /** + * \brief Description of the connected robot controller. + */ + abb::robot::RobotControllerDescription robot_controller_description_; + + /** + * \brief Subscriber for robot controller system states. + */ rclcpp::Subscription::SharedPtr system_state_sub_; + + /** + * \brief Subscriber for RobotWare StateMachine Add-In runtime states. + */ rclcpp::Subscription::SharedPtr runtime_state_sub_; + /** + * \brief List of provided ROS core services. + */ std::vector core_services_; + + /** + * \brief List of provided ROS state machine services. + */ std::vector sm_services_; + /** + * \brief The latest known robot controller system state. + */ abb_robot_msgs::msg::SystemState system_state_; + + /** + * \brief The latest known RobotWare StateMachine Add-In runtime state. + */ abb_rapid_sm_addin_msgs::msg::RuntimeState runtime_state_; }; diff --git a/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp index 665c839..7a8a311 100644 --- a/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_state_publisher_ros.hpp @@ -40,34 +40,76 @@ #pragma once -#include - #include #include #include +#include +#include + #include #include #include namespace abb_rws_client { -class RWSStatePublisherROS : RWSClient +class RWSStatePublisherROS { public: + /** + * \brief Creates a state publisher. + * + * \param node ROS2 node. + * \param robot_ip IP address for the robot controller's RWS server. + * \param robot_poty Port number for the robot controller's RWS server. + */ RWSStatePublisherROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port); private: + /** + * \brief Time callback for receving and publishing of system states from robot. + */ void timer_callback(); + rclcpp::Node::SharedPtr node_; rclcpp::TimerBase::SharedPtr timer_; + /** + * \brief Manager for handling RWS communication with the robot controller. + */ + abb::robot::RWSManager rws_manager_; + + /** + * \brief Description of the connected robot controller. + */ + abb::robot::RobotControllerDescription robot_controller_description_; + + /** + * \brief Publisher for joint states. + */ rclcpp::Publisher::SharedPtr joint_state_pub_; + + /** + * \brief Publisher for general system states. + */ rclcpp::Publisher::SharedPtr system_state_pub_; + + /** + * \brief Publisher for RobotWare StateMachine Add-In runtime states. + * + * Note: Only used if the Add-In is present in the system. + */ rclcpp::Publisher::SharedPtr runtime_state_pub_; + /** + * \brief Motion data for each mechanical unit defined in the robot controller. + */ abb::robot::MotionData motion_data_; + + /** + * \brief Data about the robot controller's system state. + */ abb::robot::SystemStateData system_state_data_; }; diff --git a/abb_rws_client/src/rws_client.cpp b/abb_rws_client/src/rws_client.cpp deleted file mode 100644 index e2d2ab5..0000000 --- a/abb_rws_client/src/rws_client.cpp +++ /dev/null @@ -1,65 +0,0 @@ -/*********************************************************************************************************************** - * - * Copyright (c) 2020, ABB Schweiz AG - * 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 ABB 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 HOLDER 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. - * - *********************************************************************************************************************** - */ - -// This file is a modified copy from -// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_service_provider/src -// https://github.com/ros-industrial/abb_robot_driver/tree/master/abb_rws_state_publisher/src - -#include - -#include - -namespace abb_rws_client -{ -RWSClient::RWSClient(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port) - : node_(node) - , rws_manager_{ robot_ip, robot_port, abb::rws::SystemConstants::General::DEFAULT_USERNAME, - abb::rws::SystemConstants::General::DEFAULT_PASSWORD } -{ - connect(); -} -void RWSClient::connect() -{ - std::string robot_id; - bool no_connection_timeout; - - node_->get_parameter("robot_nickname", robot_id); - node_->get_parameter("no_connection_timeout", no_connection_timeout); - robot_controller_description_ = - abb::robot::utilities::establishRWSConnection(rws_manager_, robot_id, no_connection_timeout); - abb::robot::utilities::verifyRobotWareVersion(robot_controller_description_.header().robot_ware_version()); -} -} // namespace abb_rws_client diff --git a/abb_rws_client/src/rws_service_provider_ros.cpp b/abb_rws_client/src/rws_service_provider_ros.cpp index c718725..8f753c0 100644 --- a/abb_rws_client/src/rws_service_provider_ros.cpp +++ b/abb_rws_client/src/rws_service_provider_ros.cpp @@ -51,8 +51,16 @@ namespace abb_rws_client { RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port) - : RWSClient(node, robot_ip, robot_port) + : node_(node) + , rws_manager_{ robot_ip, robot_port, abb::rws::SystemConstants::General::DEFAULT_USERNAME, + abb::rws::SystemConstants::General::DEFAULT_PASSWORD } { + std::string robot_id = node_->get_parameter("robot_nickname").as_string(); + bool no_connection_timeout = node_->get_parameter("no_connection_timeout").as_bool(); + robot_controller_description_ = + abb::robot::utilities::establishRWSConnection(rws_manager_, robot_id, no_connection_timeout); + abb::robot::utilities::verifyRobotWareVersion(robot_controller_description_.header().robot_ware_version()); + system_state_sub_ = node_->create_subscription( "system_states", 10, std::bind(&RWSServiceProviderROS::systemStateCallback, this, std::placeholders::_1)); runtime_state_sub_ = node_->create_subscription( @@ -152,26 +160,26 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node if (system_indicators.options().egm()) { sm_services_.push_back(node_->create_service( - "get_egm_settings", + "~/get_egm_settings", std::bind(&RWSServiceProviderROS::getEGMSettings, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( - "set_egm_settings", + "~/set_egm_settings", std::bind(&RWSServiceProviderROS::setEGMSettings, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( - "start_egm_joint", + "~/start_egm_joint", std::bind(&RWSServiceProviderROS::startEGMJoint, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( - "start_egm_pose", + "~/start_egm_pose", std::bind(&RWSServiceProviderROS::startEGMPose, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( - "stop_egm", std::bind(&RWSServiceProviderROS::stopEGM, this, std::placeholders::_1, std::placeholders::_2))); + "~/stop_egm", std::bind(&RWSServiceProviderROS::stopEGM, this, std::placeholders::_1, std::placeholders::_2))); if (has_sm_1_1) { sm_services_.push_back(node_->create_service( - "start_egm_stream", + "~/start_egm_stream", std::bind(&RWSServiceProviderROS::startEGMStream, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( - "stop_egm_stream", + "~/stop_egm_stream", std::bind(&RWSServiceProviderROS::stopEGMStream, this, std::placeholders::_1, std::placeholders::_2))); } } @@ -179,10 +187,10 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node if (system_indicators.addins().smart_gripper()) { sm_services_.push_back(node_->create_service( - "run_sg_routine", + "~/run_sg_routine", std::bind(&RWSServiceProviderROS::runSGRoutine, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( - "set_sg_command", + "~/set_sg_command", std::bind(&RWSServiceProviderROS::setSGCOmmand, this, std::placeholders::_1, std::placeholders::_2))); } } diff --git a/abb_rws_client/src/rws_state_publisher_ros.cpp b/abb_rws_client/src/rws_state_publisher_ros.cpp index fe1f235..884495a 100644 --- a/abb_rws_client/src/rws_state_publisher_ros.cpp +++ b/abb_rws_client/src/rws_state_publisher_ros.cpp @@ -55,9 +55,18 @@ namespace abb_rws_client { RWSStatePublisherROS::RWSStatePublisherROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port) - : RWSClient(node, robot_ip, robot_port) + : node_(node) + , rws_manager_{ robot_ip, robot_port, abb::rws::SystemConstants::General::DEFAULT_USERNAME, + abb::rws::SystemConstants::General::DEFAULT_PASSWORD } { node_->declare_parameter("polling_rate", 5.0); + + std::string robot_id = node_->get_parameter("robot_nickname").as_string(); + bool no_connection_timeout = node_->get_parameter("no_connection_timeout").as_bool(); + robot_controller_description_ = + abb::robot::utilities::establishRWSConnection(rws_manager_, robot_id, no_connection_timeout); + abb::robot::utilities::verifyRobotWareVersion(robot_controller_description_.header().robot_ware_version()); + abb::robot::initializeMotionData(motion_data_, robot_controller_description_); auto sensor_qos = @@ -75,6 +84,7 @@ RWSStatePublisherROS::RWSStatePublisherROS(const rclcpp::Node::SharedPtr& node, auto polling_rate = node_->get_parameter("polling_rate").as_double(); timer_ = node_->create_wall_timer(std::chrono::milliseconds(static_cast(1000.0 / polling_rate)), std::bind(&RWSStatePublisherROS::timer_callback, this)); + RCLCPP_INFO(node_->get_logger(), "RWS state publisher initialized!"); } void RWSStatePublisherROS::timer_callback() From a3181e53b624d8674c0f62d4d3e74ce0b50b433f Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Mon, 20 Jun 2022 11:46:12 +0200 Subject: [PATCH 19/27] Fix bug with topic name in service provider class --- abb_rws_client/src/rws_service_provider_ros.cpp | 4 ++-- abb_rws_client/src/rws_state_publisher_ros.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/abb_rws_client/src/rws_service_provider_ros.cpp b/abb_rws_client/src/rws_service_provider_ros.cpp index 8f753c0..38bb540 100644 --- a/abb_rws_client/src/rws_service_provider_ros.cpp +++ b/abb_rws_client/src/rws_service_provider_ros.cpp @@ -62,9 +62,9 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node abb::robot::utilities::verifyRobotWareVersion(robot_controller_description_.header().robot_ware_version()); system_state_sub_ = node_->create_subscription( - "system_states", 10, std::bind(&RWSServiceProviderROS::systemStateCallback, this, std::placeholders::_1)); + "~/system_states", 10, std::bind(&RWSServiceProviderROS::systemStateCallback, this, std::placeholders::_1)); runtime_state_sub_ = node_->create_subscription( - "sm_addin/runtime_states", 10, + "~/sm_addin/runtime_states", 10, std::bind(&RWSServiceProviderROS::runtimeStateCallback, this, std::placeholders::_1)); core_services_.push_back(node_->create_service( diff --git a/abb_rws_client/src/rws_state_publisher_ros.cpp b/abb_rws_client/src/rws_state_publisher_ros.cpp index 884495a..73e9572 100644 --- a/abb_rws_client/src/rws_state_publisher_ros.cpp +++ b/abb_rws_client/src/rws_state_publisher_ros.cpp @@ -74,12 +74,12 @@ RWSStatePublisherROS::RWSStatePublisherROS(const rclcpp::Node::SharedPtr& node, rmw_qos_profile_sensor_data); joint_state_pub_ = node_->create_publisher("~/joint_states", sensor_qos); - system_state_pub_ = node_->create_publisher("~/system_states", 1); + system_state_pub_ = node_->create_publisher("~/system_states", 10); if (abb::robot::utilities::verifyStateMachineAddInPresence(robot_controller_description_.system_indicators())) { runtime_state_pub_ = - node_->create_publisher("~/sm_addin/runtime_states", 1); + node_->create_publisher("~/sm_addin/runtime_states", 10); } auto polling_rate = node_->get_parameter("polling_rate").as_double(); timer_ = node_->create_wall_timer(std::chrono::milliseconds(static_cast(1000.0 / polling_rate)), From 0706407b13e991ce5bc39e6bf0e95e6abf5868d7 Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Mon, 20 Jun 2022 14:04:22 +0200 Subject: [PATCH 20/27] Add simple quick start documentation --- .../rws_service_provider_ros.hpp | 10 +++-- docs/README.md | 6 +++ docs/RWSQuickStart.md | 41 +++++++++++++++++++ 3 files changed, 54 insertions(+), 3 deletions(-) create mode 100644 docs/RWSQuickStart.md diff --git a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp index c851592..ace5620 100644 --- a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp @@ -89,6 +89,10 @@ class RWSServiceProviderROS */ RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node, const std::string& robot_ip, unsigned short robot_port); + RWSServiceProviderROS() = delete; + + virtual ~RWSServiceProviderROS() = default; + private: /** * \brief Callback for robot controller system state messages. @@ -208,7 +212,7 @@ class RWSServiceProviderROS /** * \brief Sets all RAPID program pointers to respective main procedure. - * + * Starts all RAPID programs. * \param request to process. * \param response for containing the result. * @@ -218,11 +222,11 @@ class RWSServiceProviderROS abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res); /** - * \brief Signals that SmartGripper command(s) should be run for all RAPID programs. + * \brief Signals that custom RAPID routine(s) should be run for all RAPID programs. * * Notes: * - Requires the StateMachine Add-In. - * - The desired SmartGripper command(s) needs to be specified beforehand (one per RAPID task). + * - The desired RAPID routine(s) needs to be specified beforehand (one per RAPID task). * * \param request to process. * \param response for containing the result. diff --git a/docs/README.md b/docs/README.md index 8a67957..d104bd6 100644 --- a/docs/README.md +++ b/docs/README.md @@ -100,11 +100,17 @@ After launching the controllers, launch MoveIt: ros2 launch abb_bringup abb_moveit.launch.py robot_xacro_file:=irb1200_5_90.xacro support_package:=abb_irb1200_support moveit_config_package:=abb_irb1200_5_90_moveit_config moveit_config_file:=abb_irb1200_5_90.srdf.xacro + ## Connecting to RWS RWS is a platform that allows interaction with the robot controller over HTTP, which is used by the driver to get information about the robot. Note that only RWS 1.0 is supported - RobotWare 7.0 and higher use RWS 2.0 and are not currently supported. +To launch only RWS communication: + + ros2 launch abb_bringup abb_rws_client.launch.py robot_ip:= + # More Info - [Robot Studio Setup Guide](./RobotStudioSetup.md) - [Network Configuration](./NetworkingConfiguration.md) - [Troubleshooting](./Troubleshooting.md) +- [RWSQuickStart](./RWSQuickStart.md) diff --git a/docs/RWSQuickStart.md b/docs/RWSQuickStart.md new file mode 100644 index 0000000..5d27a3d --- /dev/null +++ b/docs/RWSQuickStart.md @@ -0,0 +1,41 @@ +# Robot Web Services client + +This documentation specified ROS services provided by `abb_rws_client` package for commanding ABB robots via the RWS interface. + +## List of core services + +Below is a list of core services for commanding the ABB robot via the RWS interface. + +| Service name | Description | +|------------------------------------|-------------------------------------------------------------------------------------------------| +| `get_robot_controller_description` | Gets a description of the connected robot controller. | +| `pp_to_main` | Sets all RAPID program pointers to respective main procedure. Starts all RAPID programs. | +| `start_rapid` | Starts all RAPID programs. | +| `stop_rapid` | Stop all RAPID programs. | +| `set_motors_on/off` | Sets the motors on/off. | +| `get/set_file_contents` | Gets/Sets the contents of a file. | +| `get/set_io_signal` | Gets/Sets an IO-signal. | +| `get/set_rapid_bool` | Gets/Sets a RAPID `bool` symbol. | +| `get/set_rapid_dnum` | Gets/Sets a RAPID `dnum` symbol. | +| `get/set_rapid_num` | Gets/Sets a RAPID `num` symbol. | +| `get/set_rapid_string` | Gets/Sets a RAPID `string` symbol. | +| `get/set_rapid_symbol ` | Gets/Sets a RAPID symbol (in raw text format). | +| `get/set_speed_ratio` | Gets/Sets the controller speed ratio (in the range [0, 100]) for RAPID motions. | + + +## List of RobotWare StateMachine Add-in services + +Below is a list of services for operating a robot via the RWS interface with the RobotWare StateMachine Add-in installed. + +| Service name | Description | +|------------------------|----------------------------------------------------------------------------| +| `run_rapid_routine` | Signals that custom RAPID routine(s) should be run for all RAPID programs. | +| `set_rapid_routune` | Sets desired custom RAPID routine for a specific RAPID task. | +| `get/set_egm_settings` | Gets/Sets EGM settings used by a specific RAPID task. | +| `start_egm_joint` | Starts EGM joint motions for all RAPID programs. | +| `start_egm_pose` | Starts EGM pose motions for all RAPID programs. | +| `start_egm_stream` | Starts EGM position streaming for all RAPID programs. | +| `stop_egm` | Stops EGM motions for all RAPID programs. | +| `stop_egm_stream` | Stops EGM position streaming for all RAPID programs. | +| `run_sg_routine` | Signals that SmartGripper command(s) should be run for all RAPID programs. | +| `set_sg_command` | Sets desired SmartGripper command for a specific RAPID task. | From d9c1d6139073a2d0fb605f8a62b336173169ef12 Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Mon, 20 Jun 2022 14:27:12 +0200 Subject: [PATCH 21/27] Add comments to rws_service_provider source files --- README.md | 1 + .../rws_service_provider_ros.hpp | 2 +- .../src/rws_service_provider_ros.cpp | 160 ++++++++++-------- 3 files changed, 88 insertions(+), 75 deletions(-) diff --git a/README.md b/README.md index d3ea067..1f9ee58 100644 --- a/README.md +++ b/README.md @@ -2,6 +2,7 @@ This is a meta-package containing everything to run an ABB robot or simulation w - `abb_bringup`: Launch files and ros2_control config files that are generic to many types of ABB robots. - `abb_hardware_interface`: A ros2_control hardware interface using abb_libegm. +- `abb_rws_client`: A package containg nodes for RWS only communication. - `robot_specific_config`: Packages containing robot description and config files that are unique to each type of ABB robot. - `abb_resources`: A small package containing ABB-related xacro resources. - `docs`: More detailed documentation. diff --git a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp index ace5620..cf9ff8a 100644 --- a/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp +++ b/abb_rws_client/include/abb_rws_client/rws_service_provider_ros.hpp @@ -434,7 +434,7 @@ class RWSServiceProviderROS * * \return bool true if the request was processed. */ - bool setSGCOmmand(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, + bool setSGCommand(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, abb_rapid_sm_addin_msgs::srv::SetSGCommand::Response::SharedPtr res); /** diff --git a/abb_rws_client/src/rws_service_provider_ros.cpp b/abb_rws_client/src/rws_service_provider_ros.cpp index 38bb540..1b5008e 100644 --- a/abb_rws_client/src/rws_service_provider_ros.cpp +++ b/abb_rws_client/src/rws_service_provider_ros.cpp @@ -191,7 +191,7 @@ RWSServiceProviderROS::RWSServiceProviderROS(const rclcpp::Node::SharedPtr& node std::bind(&RWSServiceProviderROS::runSGRoutine, this, std::placeholders::_1, std::placeholders::_2))); sm_services_.push_back(node_->create_service( "~/set_sg_command", - std::bind(&RWSServiceProviderROS::setSGCOmmand, this, std::placeholders::_1, std::placeholders::_2))); + std::bind(&RWSServiceProviderROS::setSGCommand, this, std::placeholders::_1, std::placeholders::_2))); } } RCLCPP_INFO(node_->get_logger(), "RWS client services initialized!"); @@ -207,6 +207,10 @@ void RWSServiceProviderROS::runtimeStateCallback(const abb_rapid_sm_addin_msgs:: runtime_state_ = msg; } +/************************************************************************************************************* + **************************************** RWS core services methods ****************************************** + ************************************************************************************************************/ + bool RWSServiceProviderROS::getRCDescription( const abb_robot_msgs::srv::GetRobotControllerDescription::Request::SharedPtr req, abb_robot_msgs::srv::GetRobotControllerDescription::Response::SharedPtr res) @@ -482,77 +486,6 @@ bool RWSServiceProviderROS::ppToMain(const abb_robot_msgs::srv::TriggerWithResul return true; } -bool RWSServiceProviderROS::runRapidRoutine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) -{ - if (!verifyAutoMode(res->result_code, res->message)) - { - return true; - } - if (!verifyRapidRunning(res->result_code, res->message)) - { - return true; - } - if (!verifySMAddinRuntimeStates(res->result_code, res->message)) - { - return true; - } - if (!verifyRWSManagerReady(res->result_code, res->message)) - { - return true; - } - - rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.services().rapid().signalRunRAPIDRoutine()) - { - res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } - else - { - res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; - res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); - } - }); - - return true; -} - -bool RWSServiceProviderROS::runSGRoutine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, - abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) -{ - if (!verifyAutoMode(res->result_code, res->message)) - { - return true; - } - if (!verifyRapidRunning(res->result_code, res->message)) - { - return true; - } - if (!verifySMAddinRuntimeStates(res->result_code, res->message)) - { - return true; - } - if (!verifyRWSManagerReady(res->result_code, res->message)) - { - return true; - } - - rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { - if (interface.services().sg().signalRunSGRoutine()) - { - res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; - } - else - { - res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; - res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; - RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); - } - }); - - return true; -} bool RWSServiceProviderROS::setFileContents(const abb_robot_msgs::srv::SetFileContents::Request::SharedPtr req, abb_robot_msgs::srv::SetFileContents::Response::SharedPtr res) @@ -917,6 +850,10 @@ bool RWSServiceProviderROS::stopRapid(const abb_robot_msgs::srv::TriggerWithResu return true; } +/************************************************************************************************************* + ******************************** RWS State Machine Add-in services methods ********************************** + ************************************************************************************************************/ + bool RWSServiceProviderROS::getEGMSettings(const abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Request::SharedPtr req, abb_rapid_sm_addin_msgs::srv::GetEGMSettings::Response::SharedPtr res) { @@ -1002,6 +939,78 @@ bool RWSServiceProviderROS::setEGMSettings(const abb_rapid_sm_addin_msgs::srv::S return true; } +bool RWSServiceProviderROS::runRapidRoutine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verifyAutoMode(res->result_code, res->message)) + { + return true; + } + if (!verifyRapidRunning(res->result_code, res->message)) + { + return true; + } + if (!verifySMAddinRuntimeStates(res->result_code, res->message)) + { + return true; + } + if (!verifyRWSManagerReady(res->result_code, res->message)) + { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.services().rapid().signalRunRAPIDRoutine()) + { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } + else + { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); + } + }); + + return true; +} + +bool RWSServiceProviderROS::runSGRoutine(const abb_robot_msgs::srv::TriggerWithResultCode::Request::SharedPtr, + abb_robot_msgs::srv::TriggerWithResultCode::Response::SharedPtr res) +{ + if (!verifyAutoMode(res->result_code, res->message)) + { + return true; + } + if (!verifyRapidRunning(res->result_code, res->message)) + { + return true; + } + if (!verifySMAddinRuntimeStates(res->result_code, res->message)) + { + return true; + } + if (!verifyRWSManagerReady(res->result_code, res->message)) + { + return true; + } + + rws_manager_.runService([&](abb::rws::RWSStateMachineInterface& interface) { + if (interface.services().sg().signalRunSGRoutine()) + { + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_SUCCESS; + } + else + { + res->message = abb_robot_msgs::msg::ServiceResponses::FAILED; + res->result_code = abb_robot_msgs::msg::ServiceResponses::RC_FAILED; + RCLCPP_DEBUG_STREAM(node_->get_logger(), interface.getLogTextLatestEvent()); + } + }); + + return true; +} + bool RWSServiceProviderROS::setRapidRoutine(const abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Request::SharedPtr req, abb_rapid_sm_addin_msgs::srv::SetRAPIDRoutine::Response::SharedPtr res) { @@ -1046,7 +1055,7 @@ bool RWSServiceProviderROS::setRapidRoutine(const abb_rapid_sm_addin_msgs::srv:: return true; } -bool RWSServiceProviderROS::setSGCOmmand(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, +bool RWSServiceProviderROS::setSGCommand(const abb_rapid_sm_addin_msgs::srv::SetSGCommand::Request::SharedPtr req, abb_rapid_sm_addin_msgs::srv::SetSGCommand::Response::SharedPtr res) { if (!verifyArgumentRapidTask(req->task, res->result_code, res->message)) @@ -1278,6 +1287,10 @@ bool RWSServiceProviderROS::stopEGMStream(const abb_robot_msgs::srv::TriggerWith return true; } +/************************************************************************************************************* + **************************************** Verification helper methods **************************************** + ************************************************************************************************************/ + bool RWSServiceProviderROS::verifyAutoMode(uint16_t& result_code, std::string& message) { if (!system_state_.auto_mode) @@ -1461,5 +1474,4 @@ bool RWSServiceProviderROS::verifyRWSManagerReady(uint16_t& result_code, std::st return true; } - } // namespace abb_rws_client From 6d01a3eed07ff823abea08a25f8eeac96ac60851 Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Mon, 20 Jun 2022 14:46:27 +0200 Subject: [PATCH 22/27] Modify RWS docs --- docs/README.md | 4 ---- docs/RWSQuickStart.md | 13 ++++++++++++- 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/docs/README.md b/docs/README.md index d104bd6..30cba0a 100644 --- a/docs/README.md +++ b/docs/README.md @@ -105,10 +105,6 @@ After launching the controllers, launch MoveIt: RWS is a platform that allows interaction with the robot controller over HTTP, which is used by the driver to get information about the robot. Note that only RWS 1.0 is supported - RobotWare 7.0 and higher use RWS 2.0 and are not currently supported. -To launch only RWS communication: - - ros2 launch abb_bringup abb_rws_client.launch.py robot_ip:= - # More Info - [Robot Studio Setup Guide](./RobotStudioSetup.md) - [Network Configuration](./NetworkingConfiguration.md) diff --git a/docs/RWSQuickStart.md b/docs/RWSQuickStart.md index 5d27a3d..bb8c1e4 100644 --- a/docs/RWSQuickStart.md +++ b/docs/RWSQuickStart.md @@ -1,6 +1,17 @@ # Robot Web Services client -This documentation specified ROS services provided by `abb_rws_client` package for commanding ABB robots via the RWS interface. +## Overview + +`rws_client` node starts services for commanding ABB robots via RWS interfaces and publishers for polling system data from robot controllers. This node contains the following parameters: +* `robot_ip` - IP address to the robot controller's RWS server. +* `robot_port` - Port number of the robot controller's RWS server. +* `robot_nickname` - Arbitrary user nickname/identifier for the robot controller. +* `polling_rate` - The frequency [Hz] at which the controller state is collected. +* `no_connection_timeout` - Specifies whether the node is allowed to wait indefinitely for the robot controller during initialization. + +To launch only RWS communication: + + ros2 launch abb_bringup abb_rws_client.launch.py robot_ip:= ## List of core services From 451412792325809ff4d0eb6a59e0675d187bd7e2 Mon Sep 17 00:00:00 2001 From: Souphis Date: Mon, 20 Jun 2022 23:58:23 +0200 Subject: [PATCH 23/27] Create abb_common package --- ...ardware_interface.cpp.B90CF9C5D62E3421.idx | Bin 0 -> 6672 bytes ...ardware_interface.hpp.1C38C542CEC63B29.idx | Bin 0 -> 1654 bytes .../index/mapping.cpp.3144CF681799FF9A.idx | Bin 0 -> 10040 bytes .../index/mapping.cpp.CBFB4B495787DB8D.idx | Bin 0 -> 10014 bytes .../index/mapping.hpp.63A500840ABD1FA2.idx | Bin 0 -> 3250 bytes .../index/mapping.hpp.7EEBD7F4D74D9106.idx | Bin 0 -> 3204 bytes .../rws_client_node.cpp.B3BA3031F45F1705.idx | Bin 0 -> 1158 bytes ...vice_provider_ros.cpp.23257787CC1BB7A8.idx | Bin 0 -> 32970 bytes ...vice_provider_ros.hpp.9A12ED002ED022C2.idx | Bin 0 -> 7568 bytes ...ate_publisher_ros.cpp.B9C4118F896EFF34.idx | Bin 0 -> 3934 bytes ...ate_publisher_ros.hpp.5225916AA6207DAB.idx | Bin 0 -> 1376 bytes .../index/utilities.cpp.BC8AB2AD8B37CB17.idx | Bin 0 -> 2760 bytes .../index/utilities.cpp.FA6366B36AB7CB43.idx | Bin 0 -> 2758 bytes .../index/utilities.hpp.2C3FAE4039E1F841.idx | Bin 0 -> 244 bytes .../index/utilities.hpp.3EF3809EE830CF4D.idx | Bin 0 -> 1078 bytes .../visibility_control.h.6BF9DD9BAF8E623B.idx | Bin 0 -> 252 bytes abb_common/CMakeLists.txt | 78 ++++++++++++++++++ .../include/abb_common}/mapping.hpp | 0 .../include/abb_common}/utilities.hpp | 0 abb_common/package.xml | 25 ++++++ .../src/mapping.cpp | 2 +- .../src/utilities.cpp | 2 +- abb_hardware_interface/CMakeLists.txt | 2 +- abb_hardware_interface/package.xml | 4 +- .../src/abb_hardware_interface.cpp | 2 +- abb_rws_client/CMakeLists.txt | 3 +- abb_rws_client/package.xml | 8 +- .../src/rws_service_provider_ros.cpp | 4 +- .../src/rws_state_publisher_ros.cpp | 4 +- 29 files changed, 118 insertions(+), 16 deletions(-) create mode 100644 .clangd/index/abb_hardware_interface.cpp.B90CF9C5D62E3421.idx create mode 100644 .clangd/index/abb_hardware_interface.hpp.1C38C542CEC63B29.idx create mode 100644 .clangd/index/mapping.cpp.3144CF681799FF9A.idx create mode 100644 .clangd/index/mapping.cpp.CBFB4B495787DB8D.idx create mode 100644 .clangd/index/mapping.hpp.63A500840ABD1FA2.idx create mode 100644 .clangd/index/mapping.hpp.7EEBD7F4D74D9106.idx create mode 100644 .clangd/index/rws_client_node.cpp.B3BA3031F45F1705.idx create mode 100644 .clangd/index/rws_service_provider_ros.cpp.23257787CC1BB7A8.idx create mode 100644 .clangd/index/rws_service_provider_ros.hpp.9A12ED002ED022C2.idx create mode 100644 .clangd/index/rws_state_publisher_ros.cpp.B9C4118F896EFF34.idx create mode 100644 .clangd/index/rws_state_publisher_ros.hpp.5225916AA6207DAB.idx create mode 100644 .clangd/index/utilities.cpp.BC8AB2AD8B37CB17.idx create mode 100644 .clangd/index/utilities.cpp.FA6366B36AB7CB43.idx create mode 100644 .clangd/index/utilities.hpp.2C3FAE4039E1F841.idx create mode 100644 .clangd/index/utilities.hpp.3EF3809EE830CF4D.idx create mode 100644 .clangd/index/visibility_control.h.6BF9DD9BAF8E623B.idx create mode 100644 abb_common/CMakeLists.txt rename {abb_rws_client/include/abb_rws_client => abb_common/include/abb_common}/mapping.hpp (100%) rename {abb_hardware_interface/include/abb_hardware_interface => abb_common/include/abb_common}/utilities.hpp (100%) create mode 100644 abb_common/package.xml rename {abb_rws_client => abb_common}/src/mapping.cpp (99%) rename {abb_hardware_interface => abb_common}/src/utilities.cpp (98%) diff --git a/.clangd/index/abb_hardware_interface.cpp.B90CF9C5D62E3421.idx b/.clangd/index/abb_hardware_interface.cpp.B90CF9C5D62E3421.idx new file mode 100644 index 0000000000000000000000000000000000000000..e5f76b6c2b193e9e34245ff75032eef66797f78e GIT binary patch literal 6672 zcmc&2cU+U#_B-K|AtZzq2q6%*GUCTx0fDeVARrPaMFbIomLUpgl{%>uL{tR9@ete$ zQEQ7Rj#gU{3y4yvjJiOrMSY637T@`b@asQ)@BIhAaPGM`H|L&x&b<+VetwF&1R-7$ zxH=_1BbFoxLIwZRGt!pjFbHBuo*-72H_cwSqMOou{lTkdXpvdeFOb-spse)y?3Ddh zaWS7eTq}?rZob&Zw64;KPdS{#Fm3(%@xJ6fRgIuscMJQM{i>;QY*FElHzbmlV2>8t zecGa6e}yAfW#ym*jAAL~%Xy%U8#~a9c>F}=M zBx}*9DaLQBwl^35vCPKu@y2S|!=z6xow*sLa5i%^I&u3Y*K6OsT=_}&=4tt{*K8Aa zR7VXPmi9k0#Yshw783*Isb*Zmw5SdpyS|>#Lu>$T`B6yS4ww`LObb71xb9XXmdPF}uVIExLEo z?=!g-&g=Dv^sJP{nLrTA`n#RXyWL)}84i{N)diMaFhl6ha#tr5X?MjxLD9S7+u!c} znZuYiouCGR7zED8fgnHbnO1r$)~cjjna!|ADqJDgL1?39qccGxNGkIEaM7um&9KAo z8$s9zE<#r|SG|cHt9{j!@9?pKQsFbUg#q*D9fO=wFsqngcdL@K>t*$b4=ljW%~LFM}L!ddxY;R;N`+=8Gu zIvlIN06~0|_D;bnZ{fC`dTfRjQm6z;B_s)*?44#!Q0U3ZX?>uS@Q_KEAq8zcZKJ=y z1ckKtg!CLOf|#<^I;>`7Z=5_y#hJ$0kW?XP6@np2RfASFJ+^^X8$EV|RyRHN1E(L1 z#*GGyj}~Jt)pc5ST(4P-aq)N(=HfR*c#r`R%p3mbs70eA*K+aHj=Z2zE6Ql_LSo20B6)|w<` zFK>@4Zt`vjz2&_T2FeE_43`f_7%d--a1mn>lcbiCOOdUW@+);v9rD@8>LwsJ(X3to z#s$C~S3&+NsFBolAg==|WlT#X)d7qSU>X>c+xCf^PoafuS+)X_a^N~xl9UU}1#ywJ zXeLRa?;tL=7SA;O_hGxOFAg5X(7v*?^hf0%|O5tIW)~!%>VD)-Sm3*60;@JfgJeVg( zowofY@+MLm%dvFMoE@reK3F80f*C=kAj4#t4^#3%ndU~JfKHy3Fr|{7SAjwmFz3YX zntS44k1K8;qw#k){d@ME>*pcuYjBiDi+g%{hN7+G#pxs!?M?W!-n!b46+9}?ag|z6YUa7v=@`PnZVj7Ihj$XRHxG)K-e?#x`XZh=sR1h}^ ze-+9KMOOx1u-x6^-k1N37C|?G?J@an*vwgm4Kn6F(G zc6EvAs@E#msPXvNXqfTL5IXW5jj&PUyCd}B`ydSF2P2H&M(xho-{E~yUVC;soYrvw}^TMGg=r8|0sg{Y~ z+xMJRQ$wxsLUZn|VomF`F4hAujcj`qt%xja~ad3Z7mDvNFi1i`DYIHac+SVrVk?9XEtRo@E-T^rnuOCDKf1uGDa96!XJwD#fXao#E1vZ4P1m`=u2=#;wK44 zCF)BNm-C)=!pX5-Fskd;Hm6`$uzR9;`&MB7>5Vu&ox6nUbZ1)hkDXNnOI z)ekj5=G-M7XlMN>#HH?1kE@?aZ{6rTbPDrW7Z6=^3)TZlJ#_!q3q&tH9{{BR(7ayQ zXXHF>DKTkba&4$=eZ`<-8_Jv+pSko#Nb>v_caj)59kW=AUuS@Zzvv?ROD>SPz@{T! z@iHw*8!*~{MR&A}ZhGtoMnAA_X8hv&sQ2_Ys9l+v%oQWbDBbZ^gq&OZ&`$@EY#ckz zu@4s$47jQi30h=1Q=wgfO~5s5SzwcY#V5U}EkCm0o%rgc*Yn(o3$q^mVvI0Y$f9 zS?Kis^47cM>$DRS4%yedAmM%>=P90B1bRjEtJ@LKI|7Ce+YH z=uTAn=l@Dtj=@?21|@(AW)GO{p|e&E7}U`7S}>~xi|18mBVI3l!<#gnzZhD{SQYmp zUDFPL(gFHq?;I$d1Kx;C+!vFhv3WvE@A6(2JQsF{p-dR7SflB1W#Ju^4p$c5LFsU1 z;j7=fM_(P%&w84KB**gUm?OU5d9$wY_yB*>L?zPVWwG@8c6wS|`V1Pep~2YSU-Q3E zpq}~GtY4Fw7B459VM7SVcMwEe$`aXhoa&pK07H(PBCnvRG*wyGSl2*Tplit0R$;QV SG}To#)YyEUDaS}hkN6KmBk4E* literal 0 HcmV?d00001 diff --git a/.clangd/index/abb_hardware_interface.hpp.1C38C542CEC63B29.idx b/.clangd/index/abb_hardware_interface.hpp.1C38C542CEC63B29.idx new file mode 100644 index 0000000000000000000000000000000000000000..28a0a4c4fe968950f4fa392cf15715f1243c353f GIT binary patch literal 1654 zcmYLHYfuwc6yCjT64;PrlL#g;A`e5rXiOv|5XgW?ASm*(4p^ikK{CY(R$vCG+WxRA z7AB%)1jUiDsMu0LX~##Y1+*#!A=COOibNtZS_`eD0@9AsyV1?=%%1tqeBZtIobQ~B zq=bYbCW5TmoK#+zUz&>{2;vR@lG5UWdK5wIECeY(*1x{HXh`LK*Y@&#^vbe}V|TJy z;~tpNVm2T8u%bKL5n9-bng00Phv0c(Cp>mH-5%|*MTdIy~`u5w&M-m zVWQ5V%hS6YD#Z)?KHJrX{^qW_B{ClO7g^(LbWr?ih~L7lU43RYBq%KKxzE7pj_Pyg z?_H?v!l!bo%&f;Tzxh18*ZRXa^L+i9qUv=gw>bU3D`Kn~Uy#ML>344ZJD~i+rG&JI zWJPdAdtc{hTp9WSH|9c4+3#9w$fawQdSAun{4eG{S!5Zwdd~46w`JgA^K0`UHILPfL@*~JJDLs{dggx3U>ufwmC|zD@aoxabA-=R zqUxhU=ZUV&Q$Jp5P1??%A#M=emMsG|^NzTOGH1W@_J+?64zU}bIUEJqe*azDdpPvA zB($P1GlDPt=Gz*<;>X+fEbgu6DNY7qGVT87XP-&h>_?pGWn)>vZI9~HIlH&r>R8(n z?tR-@s?AwCWAPA(I=;4wMQfZ2cFI3BB^8BcE1VCba#?EYOhX2=)gm{qYX5w# zsBj{a3j*K^@uBevuHfcZXGI(5I(1zHSP0K|pvn$364&$fQnwO;& zH`<;|r`$RXP7@#yD(tAjj;iojZmiI)xRr3%ButF%bqI2axaVmZ{nP~aL=57YG5^5h9Nis4G2Ttu0PqAm;jj*Zj=?!-Evm}IFI zU`p1XoUq+;f4pV*9ZQWGo+Ss&%W2$by)sY>YmjHiH(|IMs0j?$13f|636-RYYZC7l z`~GqL4y-{Fs8I=;cq1FrgJxl>4pYZazCbbQ1~p8Wl0zK4|C4k2#7Gnr$8+ODD2o7a zSp%E$R~qawV+&)CmTzTZxC*GG7#;?~VAKLFjFBJ`#%K@?V+@FqHa6#GI7-`Yzzg-^ zdi}`R-jshIOiaR*bYN3<_nSZ0?bE_k7pPm&lq%cn?Z^s)sbZxf?Nq@FkEz(3@4?jQ zXABurFYQnQd3Zw>np+ zy&F?hRF}u(o+ssy)vn`TB^RCup=y&6@wM=%2NsWitGbfQ%;hmv0`<`rZHLVe1*r&_&^0A3anq$NUxC zmQyj~rDwN&VbZfj5q1$1rF|;3Y`=|bu(OXXYW(ERWiPDMP)d(g{^0F;efhYp?Zr~O zxa=D>;yD*QceyRnnl-R$@biZ`58YZK%BE(E1ZjNzP%)$Y=!gCGITjr8wd=Clg)*$$ znvU5P%qow_8L+#(_{Xms8w9B%XYY0e9rgalF-V0~kPW)M^0MPAccBn#u7QtV$zT1SedAiEy?mRcpR9ja zI_GX$S#(bSs|2|XSEZd}YR#ua%9d{nDd1h4>?=HYC^z0Tp-5VFxuI*s?B;0)dw5Z2 ziam>0)F&h?jh!(s%|tv?Ehw%y;)_bKsb;3Rzt0MXwv94{yyRmcaj*3L-X%HpfaKEk zdYW1iMVe_n0dcnaFEX?&=7;ZDbj(F%k?eGly*~=vrLxt6%s)hEs)hy3Q~2kky4kJ; z4zGU(d>q(cyk+h>sRH#_-`J*HNZMt?nO1r}`03sAfgWz=yAPc9Em%}5<+YAmdSvZg zdxdF|Vh`Bft8c#HI3EO5%bd68S+ESG3xOK;-A3nz8eC6er3~q1kz2?Fl z3V&5xzF(|+NzoCb_gd3c%RQ1UO#j+sS$}NdTk(3Woz`0i)rXEJd<~l#H`qC{-|vX@ zD@!$W`|CbMxkn3wzG}^~!b9^vUIQ8y$@$q$F+bS`n?Sp79r>GKb!6{rAL9(`T>OZ+aQ$s_s3YIlW_f+%+v*v(tZX z&Yb1gf5~P+)UM!>c0KJDkAtO1|?y*J{f5yBlu^vhIuG*!29V z{q?iOz10`vpUM_##2&RaF?h5$?$)?3P+PdRMf=9*`4wv|vKOj8OPs%6bEDFF+YztY zsY!RE6E+KSK8E`5zPf38bA9htzpryN{LRcAOWzID9I#ORT9uT|;UNHlWa^{x$1wY})9 zzIk=k?%q&U(`)(&?CYDe0EwoS~BE&ot)uJdg^IsPjG?sro@DFUs`byG#j@ytg-8CM3xE1z_H4 zo5T+*->;e5=)b#-sv z9hbFn>8)jz*KIP>0w%;uE{$6v)2Q)Op~#?ON%C>c-9AExoLr`uxP>aDX>mh>oejsy z4}JQQ(`mKrkjq;Bh-YD(N{W<(l+xpu+m}D~+M2xP_Ph%bb?4UHIP`Cz)U1EAErM+xmjCnTL*J2g zFJcB8IquoTUtVUfoWj5K<GMiTe3JE}pvAt5>(@X+@9AN{9Oo^?tJwqz=~!`S0~zlfn`bQhX=;XG>R}j-*g5 zY!NyRi7d%PmP$B;pkxTD2#JleHIPq)Ab@ZH?!fblDsN`KkQ9odwzp9F7RrW01xQzb zEMse`%#MdZVygV*+WRA)UUA1vqfjggCBxw=h+PFq#?)k@#2MH{OjRd4)I1PNv=}o@ zN9lCpwFIO~s8=IJkyGGLOm(_zJM7O07D)=l&8vDx@3<+H4Zq|iy~Z-eLtemHoDdhi)5 zORaHZ{%kXxPUU}&WZE4acnXTApj0^Ifp{KBF}9PHq~c&Vap^c)(M#lL-{~>aAea~g zOeZ%?+(0@xQ$y140I~C~@XSSfd;c-Jax^GM<8bHzgAOoeET^b&&cYsI>f_iwH<&x_ z;FxJQigu$!IP`#M4@fYkQ&nNCr$FzPRLX<8f54|3w>*+%`s8saypS>50?;o2qj0zY`WL{6>4HFa!p zP(4j8ZS>`K943}8e3SD0lcpC-3PsbIZw0AV&wr3j(C;jhQ>Yi2lF49-& z(wNV)D0vpy;gAiI*}!IOjk#i{A%HmTar^ZpVD51_vz z-O#?Z?bV0n49D!kS)$=A=7|o2=rDbv)A%^{M0c*=;QvxtNC+(w&%O3fpM>L%Ljp)7 zfHVVXsG5dqtdY?4Es0vGz(_*TFcj@r2THmu#`6k@Bp8%~L0v*&N%P>^6NyAJ2!cWI zkO*m?o09))2a$Y0(+_AR^+7y4#CF#*BI!o;Zq%3I-pQ|ioY*TxB}(1MXP_4qdr^gf zepKwIFo=qS6h5KiCkn%;G)#?0P;rDxexu@V3P)LrM_HtLI7=y+BuUpC2Ij0gL1+E50rMX!M>)VpygzEWyN;>C0q#(w&LKnrE#s z7I#>997bafqqvN+mvI6EnJAx$+_8XzjLm4UVO063n2$=6q=RN27p;6jp7L>&J&vjj zTw%#xVX5-H4AM336)zyFr!e~|xG>O+yk^u=ySsB!{}HQWq!Y(c@;I_JXYc!Dr$2iS zF+K(g$3T&RQz(84CA983dg`TpizTW$P^<$@20GEI6P`M z{QxKEopY5LdiA4_G%)~%129Y9YQ;{C#-u4kl8Z9A$TLxD)%LtI7)vC{z)uFl$ycA1 z9(or1l}OG4?<{CeZeLMgXxgAQj**lCrxcVKC<9Izg=(~`Ml!A%oLz&?CPIq)eyo;# zOZw9Q+y>BMpbG_E=wi2`7?%5cGq)g_(40%aoop zQauCM8KA(x9n`*qMi#0cE4GYZ{gJ3Hu!JwLL>Rcn628U~v2@)ma4)+pL{xWxeFx+j zC`G+eG_fAx>(rU_2NG2sSk-|O1D&YYiJD`P9GE#JQQWrj*H-_(ly?x*5-=+PYX+*2 zQ-!K_$>&R-=2*rNRRX9cfEoj7D3ONJb}fP5y@ynHkuh|DpabTOg>$l=MngHHiU&?S z9ZU+yrvP_uLxz&?aQzBW>k3Qq3XAQu+(V(gW+s)@;xP)-%AXZSTV&igJq;xX|R$M-Ui;JSYxn;6k80okiyTvj}$u$ zc90^#Ab=Em4EB&>pTRy-95gs+<+0$q>LW!7y3*2sod&Xu;s)y6Ks^tk2%Bc5juk9M zk`D6eKwijepm+@?F>niwZlU=iXVG+p!0RSt5KcTNy+!lobl%2V36tN6EWJdQiF-&w z*f06`3uI7Ff%lZIk7k_Rj4qx{uVjvm?DZf`7QoB`aA%+s#aoGy+wiNCi$>Hr2&*(#@0xGMs3Xh(@`UcR5=PWNh5WGZKNifXtDtx-BW})$K{) zsP0G#XLV;%%u}B?d6jC{8NJ1dJmSP#;Jw6a=av4QeTROrf_=OS44#5uhE&FcCPky)X4f!2{f)HHndv-I|qD{4jxXT6kT)JW(pz;Ic z`AO$=FSD^JCdQp$*a?=~Q=C$#d%f^9U?dCG7HTuaCiP7^Oc4Uy5V|}l9n_FOf zi^6R%ybY#|Bp38^!GwWga4rTn21-Cs0(K0P!lF`G#y}Z(l)+L4D!`+H!c%a4N}paO zEU1LVjH(KJs$e|>)iApn92uyAxiv74fjV%mqn;bUwSm@(LCF{-D>oJ;V=0_M$x{?E za6$%7WK`Et?mCjFo{e(Z6mFp04GP7mSd2VIRe}m7NCNBwlz)Iq3{;|4C0&eFIH?Lr zLZr@V{19a4OvAAeqKw7C)IqYNfLj(pgHo zCgg5*OY&Suj4RNn0}-_X)9!B2kn-XndF6A!CX5DRdyGgF+{AI#FSJO`w#A$VloX<>1dRW<_8~CrFiY#CrWz! z1x>%8VEeVj_r82SbB;9e7U1J`a9ya|g)_n@JBRIDeASxt?-+<50|^FBA@3BbgzMK#Ui~<64H?WH!Jfro!)3jT z+`om8fHYHRCfOt1h1^N8L1+Uhx>2Yb2@IpqFokfIP&iBE#HWo*2bRq+BW>IQ?OXH( zEJk)QDnxzxdEM!5w+2yV0XqvwUX+iz`Dk=9;zppI?!To()c`Xa=$_eyoGw(1zS@}7 zoAtSk^z0_^Z-U{e*JmHEIhJ-~)R@yiGn_7**@f0|HH*GZd22-D+6Wkq!0d!m=N}$u zP#;HTG6LiyXtEIrijj0m&!WLuG`*y`Y0fZzoF!?(hG(O8+4ZlP2O|zHAq}K}b_$IY znaIvWxwP$CS$~{1S0k!Y;FVHUHM&;gvMUd|PW{C?FoU#I01FGii-B^SR8HTz3RJ5= z!>gTc3ex6RpOcoZpx70Z%`kHt;0pcONhDD$(0Di`WO~4P>;NN z@o*Cd zl8}9q8@Jc{#`Tv(RR+8=&}Et`G%ScjyodR+UWTJK^>g7)RJ7Irq z|6J1FB-Vr^mO|c~xWMZ+Z(4{XjU|`HnlyH7Ba40X$X2-9<=1WQHV0zU1A-n{P$F>e z({S)jAWc+(YZZ7i(2BfPG%35fXu(&pP80GV)4?d6hKpM$e2a#QTolPg_T$NZ%g=jm zIZvur!;EUMWuOfe+mQcc`C5PL=N~r{RVJ`AX%?4|1nOD@Ma&oHBM$ zBvUYYNMvlXKrsuH#!j0w=cgx4>e=`am_Gl--Vr$`XfJUX1yWJKW*`w&5^++y&>^=D zEh9QRQJ@kR#%lXy7|A2BdqhtYkHPLSg>rB!ryJQ5aCrg?8Jh~Q zssMWip2Ezh^f_08WhITiRbW>|Yt8$fSd*jjmT-F(1e^O3eCuArqF_% z77DG%X+`C?4KJIXN2{JCqlgBnX!G6v=}?;lF1%D=6+L1R7uOK+D>c|P&xs*!<%z*PA-ga zCz9`A_#JHjP0P^`9xs|bcQGlgU&F8AE5Jt!Y|PI zMIi`vf@pvbL7fl^VW<;^Q+}n|>GLPYuty`0Y5@&O_kn*ONKRFb3(L`qb-L5FIojj* z=zhwnrfatbI5iY%fm2JN4mfob+Hh(c-8$NFdOO``I?$#A?HGrhIHMCSg`0!k8SV~z zO=c?#bhBun&qsDXP8ct-B0uWT#7{((0ooZoy%=39?I2 zUM{0|hG|KwfEXV|!=q@&S-;S)zx>@&BKZY^U$AKG#*r+E(c8wcdqwhcj@~IU#&u|1 zho&kWPRH`E-A*KJ)q-Lz-7q@Pz5|{4RZXt*W?a`No+Cju5_HveG=?0^Q=tJa3SU@2RBvClGuB5A7GPzB+fWn@+b|#hDt6 z!dlvzq-{3RHl(nVwj;$H={clul6F$kS-Sn;(le)(iT_N{%cQAl9Mtxb8u5wSO-!G_q9@?PKqK-RQP<$a@I=|TV7l?11eKF?KF*=kIb<6`WNWUzkq4<2 z5BzwV&|OA}%P2kN!m%%Q54Oq>RVt{ZQq^^2Uq{)gTKaP5^0-rpDg+cl=;j=Q;xQ;O zHLOHVUwlA?410-SiHo^GNGqFd8$^Cz1O7EIoN8Sr-m-W31R_ahi6pb6W=^tOHYujz zAL8y2xIUtrVIA`7kUw_QO3uflx2%j!0x)-nB(Jyx@|S=+c6%zq*o@wsGO9e}=FzZI ziri8PWymd~(0~>VNY3kxIIR(9GSGnr9cXM9_WkcNXYGBXqY@9HlNp1&7*uhtw_Sc+ zt9l(#Rf2sb&F5Q?*Md48vu@wMX0SDy=z@h~_q$}JjNa|~ zJl@?g-}NB9$=M>=Y$}bbePGxJf=!$o2?d|?Qb>%70D}m6#5#+@XOWCN0Ywr}YNO7THIZ}Y zeIxyIG;?(FwT$#qmz=$cH1Gs?PiThHh>IH0$4^$A*K^bPK5=&j^v=)_lY+u2D8@)q zQ6v>5b~eYie#9cT`J)C9k|Fpv(N;iLqNapb7XargddC7b^MANY$5DdY>ef#)*uq4oy@*>QSTmnd926X!pX9&b-&na-oGJC(tfflrEp&L~z+O?v~g&{Yeq*Wn@Nmo}2 zR(d8)Uu@?$%Yj}d4Ws%n8eZHpZ>720R(o;Aq7V6f^iVv2`~eCdkpF?g7vz7T@Duqz zDI8((kFdxII)ud!p%BI5M^T7j@na~QVe!wfOj0#m6?d5w9wkeq6y}uD%&HoB)u@;H zyEmL^OOGsr9FWhU`^-&Hyh&qmAsQ8;d0Np?4V89*C8>T9G%kV;0~yH9K+e@{o|--9 z?p89q4`BEKY%--{e*1(t&>OZOkPiYbqY4JaU?6)(6zWEyL6(2Z__h7x`NUxfa7uvO zHdo<{Dzv+q)LL~tR@Zv;)sjC0|6owEK;(oAzU($^&*DO~}houMAD@pI-d8h0fw=;%A>= z-=gB^KfTQi9dD4|&SuVT#oxvL4V+a+uU&J2ol8Ue1Jr+jCZz^W)|@Gl>&G#srC?nO z4h)omRT<4ytC3SpBYF*TYEZfS`0@C>C(_BI8Jl?rkc-MLFz=%93d~&yu zLYX4uRR(EY{x)&Yh8Q=1pn)diUC8Z1t!9%y#Jk_!1fogalx=l)QaEO8 zTTN8Afqk1!NC_I0py~7V1JCB14gNq>Cqe2Y&B4#1$~l}g_Jxb2N~2%57@Nmn{1{9- zHEg0!JTTf!mP`=n2GO)E3WcMPq?^$w5{=?r-pL!Em5G@X&y~Qdq)WI3?OV`o?28!L zg+{-Ib$y3WzK9q-wJZ}XbANrfjAyj>#CK9T9wg#{M48K|dKopwK9Z3%VDtkSqe?^B zH2T>k3+1zrJN9*qqyeK}#u%GS;AYY#eFwOADC7Y*k3u3u*XzrpY~%9Tc|JC@}WRV~=pf-?ghsMvuj!&-BdBqz1f9rz6xzG3p;!p!9| z87@nRaTz$2(fh_4nqF;5cZn(UH;Aig+$YK9Qba zGTvY&wF_mgkitOd#Q$3g1^19sqAh1hn>B{ z9LKp%&MvO=R%}?Ye#N>KJ}Wk@SiNG+inYttYXrl#fD(%Z#(n>+hE0< zZj{WBPJ21;vPH3GF^`kDH)dC)jnxbpF}15AM@{2aDwrnC)=+rRIDL=aTVJ8J;RkJ9jCTenJeuHS$V)fY*tDB4~d3-*EY(` z*)J$Lmi2!6Ero%>8<%0#tDwDJ{{F3e8(}!K)r%~A6DlG3BUZFfq(&&ez^fR}TRbL!&2Vu#)SMT@7q zuIo4*Sl6;*ZIr|Bdd2gJb<4C`t5JVf)r1v)J#%5cT1M*l5i`7U zZRB!|#2&I=uH5bRkLB|BEgfA#U$0_`_ULcbw_Y}D?-mU^a6>sDE7U%7Pu|_WUg^YN zyYfX#_lb4Rx_{U>LFc*h+vzJTT&}8E*7`3fb*LBnyuWXYwruM1@4+&sKD7Pb=i@KK zU8axDYg2ktlV2VBu*cw9@Uds!lYA1#?DJXI+I9BWYbT8<^GizC&E706J2HDmwM&`T zsa2X@tEGMFc85wPOcCXkEj8WiT7Gkl>a2G+A}cKfcgLz~kD9fwS18%$Y?60u$IYvK z4I59ZlzEP{=xy=PI`impn$_f+)z`BVOiG)kzCL~N*q#XySa7ms*T$J?xuTDpuBK)E zmiZJMaKtA^t*(1smP)LfEACmOl=oAv#YJtE$M|vf_7{K6ZFs-4;NDq z^sO-N{U=v?X2HFs+PfVLIxl+U-kVVOE{1zl@qEEMTkm9h{YK5@8E7d~;~p-bH}~J} zwYjx|$|VyI9#0;#FJVdf7lSR5Z>?|cbIh8%syjTUdzZ&$tMe1%N}ZmKDLv6&;H@(5 zi-ze$?0uEp`Sh6ga?g2VYvWqg=qc?&6;3f1C?U?8Z;JlP#WHSv;6JE#aH@k*ED(VusCockh>~TCv4) zrNrmkOFX@gbkzMDx$kuG{quV4$A`XNPl@oBDc`5+b+T6P-jBTeq(1-PZ3dUig;9-$ zTXu8_FYr4Ak4~`^KB|kcjT@bbVsOGJ^a$BEC`}z6WS_)6DWrfV) zZ8l$J6}>VFW$VQE$8?VnKyp3mpOi(cl)}3+QR6s-^4B(eyK^hINr8oxt8Z* zuXWi$VI}#qoy4We>m{t)owvR02+bNNx~1Cdv=3io&sfP9HxuOt5sPEjVF%|HkI-o}RBGXLN<^i#We4<;!csnWHSY*%xQ}1$2)J ztv9@3QKcO9Eq24dwcBrY!O=%M59~W8>0NV~C-zzKRlJ#g|8{wVeBW_rYJjlGD1bj}3k!)N9nyS^oP?`~1F`lX2IIK7W4jLN_tw z>xt;wg=gB9>xkcd6!qam|C0T>an&1ES?yU_7n6Q5*5mt4Zid-|tsC-}or=9XZA0ml z+!w#nUFH_3ZTQRjIm!CE$j-f+S0%7SM7Zz7t~9pi>B@*i!UmCGh-1mbvDAYg5M=^U zT|`pU)==p*9D*PKmG>_$sCS!p$cP-Lra35=g9<@V3UZ~Oz?hnkh}~sjH$^e=@YP%m}-olS@lpd&SKa!73ETi*CLQBqF#-;;!&`j znCf;`x6X(WER+$6pdE0LaNz}ky@WlF@n|)6#2GjY#LjxJpG~f$$;)Avp}-4;(Lu14 zw{`B-~T+W`(^$-u}JvnUZ52O5n>7@54Z_-I~ZJAAe#LlzS zEf;6Z*g0%hf`%nHE(lt|uocEJmJ`)EG4KyD^_tx|=ZK2vfnn25l;}k1Am{>#E|6wS zCuzWNPXjareDTtQ^24^~66TDhjf4%cv({w|+g%gNmy4c0**R=ifN}-oq1S?3Eq&+{ zcnYzwhcuse=hsCgwK;Xeru`_saS)sb zgY#g_bU~mua@#@TwbtU#g~Hh*9u8Zkf<`K6203E>AeJ4Q!#-nCCKlO2a2;f>1DmlO zry>~*JBZUR=fSVL=KQuDHjM$*7+~HcUsYf79$Ac$+q{q1ee+x0Qh7+xXxJ`@9 zsM=4Beu!zGj7B`GaB3ax>3MW|H6D)OwHh*iK%-Gwc zKLa2bfQ5?Xr9T#ZGX9rHqFAO;EWxPdsqXS!sSZS9&9l}X4m&IihM|zdD3Vbj8AmdZ zfl3*uG8}J^u^Earj4B_w`KUTt&fol)M0p2!%EwUQ7-}$ZiKTFfrNQ?wOx3 zV0sxiGVmOE&rwJ7&W`nchpmE0Cyt@aF=UUK?)TZwVEP_n90bZiz-8bBN}WJyojbGL z^izIB6IBgxYhVlmZD`eo_IhD94qZMTLZZrrF}a}6z(Zs|#F6@Eo#em09w;D9ya%KA zFwMYf*$(ac_=!Z4i}Jb1GZEqX4XjjnORCp_N*(Ah(2jz3bR6HZ?4FTnou()wDF#k4 zs4*Y}j*vnn+EpSMP8CkCLWl8}pA{c`cH}$p91FZy7-OQ^G}i6*hiD>60Db}(neknZ z&k*hXN+kEe=ss9YeieD+*?svCBIyG`AGla(d@9{IV&x~&pYtrS^DJ=&(pX|?EOARG zAAyVTmIzVZ2KH@GVxSoHi_ygTH($5Lq|cYAYQU-n>=|f7ZX1pnj@H0T9EsGn<%64c zURB#pOp9Pb5m+-&ft(7|uuC{sT$W{dim1+j#u?CLAO)pUP|mK=_owGKjekf-TS3qY zbB9AVSu{i8no*qw&S_9)AQ6-jL1j)|y6Wcs+GV8HC6>%37TbQQt8z<~xeAfoLCHI) zCd2$*Y`EBpDclX+NwM5;IVn61JxQ_3 za1|*w8g3-T7Q-#1*lxI;6uS&}kz$YG9#Z%j`jO&*;Q=dGkx-lGs;$dd%E`eu)2bE5rC#o{wmC*(F9H&1= zN4JL8@Zq=S8MM06&md^ z`ir1(nx!7aJ#${i$x1^INQV3HE>EbO%PC1Sl-tWoc9op+x$+d>e8f+4h%62?E z?R6*AUWe{q>Q5?{!pu_o%o>o_fO_lY%iAVr3d)J;cQE=6wmuFUTZ2b#2_};5g6%FF z{c@DXzgy5veg~o;5EpHZ^--~C*61ScazQDVPTWIOdx*R(a#@}3Ha3OCxDAZjz;aun zebN+<4mU$avOsgeSf*I7wO*Gg0zoB^E~=xTa+E?4s02|62Yxu6^9bNaP>2M6B!wv8 zM^U%{dKbW$@sk8&l4w9nhB3($QeaF9g>)E~4ig!h92l2F;T9O(0#ink3kJDh!ayN7 z6oNAYMIa~wI|hnjVKKNfAOu$-EMcG&TuUjGfm0cMdgU;`92POE3h=6cwG33k^h%h` zKo!iXg1HRTfI|)STnA2dv{n?#L?KzZ(I^v5;RMQ@ppcFu({U7|x`v9^kVN(CsCb>i z4OF~Ap%A%+$YWGRs9c03(mq6`hp5UxIqH(nVHuhcnz-G(iYwQ`X%NpnZ_r;dje$3tVO3m@3w&aE=A)~wBFO=Vpx~haexGlEHKUjGX@G! ztN_Vw{{Y1wAlrAs#jOvTkI~*_p=1^+?Oi&!X&@r-j|5{=36m;e3IkOzr3x$E5{K_YB zt4O!@2=*)r8SfChW6@=6GRh#33Ib^cP9X0Dst5NAdltI<2qXc?T*RDgpDrRUr0^E; zCPgQTbRvO%6zQiB!V(E#i68&GZpnN1sS}9L92lEJU%*0S7ou|b*FV?n?{sPtRVJ`A zf#gN`sF#n%5urDH?eu;X6IC6U*U{~?9XajDjl5hR-;?>JnRGfE_}O4|;!W(6RY55? zhKxCNG{b2}^LDg8RkiT@#J9#YuKfn1-!T2miF1$k*J+88=?Vpu2@zMJ-7aHar{6WT&g<2SN`lCJiLQ*hCsBGLW5tiYeQ4GB=zw(}D;lZ2z!Hq;Em>?kO$=nHZ z?S~IkB&!@cOwk(SYSHwjg-Vx_`d0~3BNEgj=^~9s*?44UtDM^FdE?qEq7nj62zm@u zp<@*;$#LtQD5b_^v5X`U*omOXKn9M@K>ggwH_z;=?wdpU8_yaU&r%*fqmiXObUw?Q zb;|deO?M-)Nnt6butpc`b{xE=vUMhrbb+7?<`)TEdbMY6K0}(Q0H+G@WS|LoO=u## zym0<^$u<-6AXC9Om4=5L6w9IEAs5ASk^N-+mZj(1Hl8EZD`9FS*fP+J+-BrIUAlUw z^@~qFM3n*T44UBOp?)5k3?C6mSBH*=H6z@-TP9u^ART*;rti_Jc7)g~$Hj#_QauOQ zIdtzTM598SSbKk+#Ff=Hmx<~z@E+56Sc6VAIDhz{NTy)ukjU6%0yh&>hfkX{=cgx4 zT7BGOFnuw|-X1o~e=l(u4zl6EW*`pL<8X9~$U)~;9b-B>;h-K)CoT?UbTQ&53D`+A%escT*HHhJO^!sFGMJxz)A(Ee9^b>4bb)Rcg&xrDq0k4qeH1=`?gt8=LH9F- zZ=m~)LO{z^SHC1DqNP z%{ZxNc`(qq6wg$$X{O(t4tb0`(}mtk0qBIb@4lN(-uHK5-^bz6S(7Fki;9 zrzC7m@GBzmM}a>slD}jMwusnY-#jDldCuWdPXSF}auFH-#|NFAk{Yc%qr zQC&y2!R6h(o0CZO&mi~=u46l1e|P9yGlg!qTyt$kVJ&A((l#488&cTG*^y$F+$>Vq z%h{{yF4=ZqNz6$#;y(lQGia)shwMC58osI|!z9;~1`7&|e|w$UO-!G{!l&THKt1y6 zQP1#r|0so1N9e{I0qPNSKF*@-S!5eQSW~Wnu`8){8u+Ja4wQ`2$tXARe9%|BhnwVy zDhV``sOlQBuc5*u9RtO)c`B2LDiD+d>E;}TQc);9$yzAYxOeGDGVBDFcmhk-%rLNt z&9?O?k~H9_fzhPkB1HqK_v%ElSg_d9e6*eW=%~7v#NA_XdQ3ON8sya=fB2%69G!uvO&+S`(XdmDD#a9ps3N3LhZc26j`H<5xgO0K zXhp+T9A_8&^QO>Ytl!Y6qyp(=Mj)g5YWmtNDUTtiglFr%F2^Nq-BL|xZuw{E2w zu2&|iJkZahQzS&T5S124&MerxRz8BL;#gvFERuSqu%uI13X4~sa?iNfY(XAD21_P` z#a?pCDtU`qqAD@I2xBkO_d65WnW(tb?9js(jxuy=3xQKeuXM^$P>#+X!F>b%e{(#D zpLP(m!vc>Do1!vps;&@85=%OX#rAr#yLFz^0eZW#QLu6D@O3X)IYU>yYiDluw5X4# zC&SyIf18e>7}>?BY5~D)FFq9s#Vo@v>$;i*3_!*R4r+aBt*qpgPNdIO}m~Fq=GR#9uX8L;4z*FEo zr5Q>+F04ndEecY+u55?<#9a*N$IuXyh+>H-$w-n=JPDHSBhnWlVs^OyL!jiYX(&Y{}< zqkNqz<%pyMj5@&f&_914H_7;HAQIaNwzChnzAwx3{rQWG=^PlJqj^s%ilx%LCk@5Z zkbQL7fko3|Ce!;qa~*T5kWUiEj_W4TbUPW?$#mzxj=I-TKcX5t9&PTU^WTf6y=W0t zoRqWAZRu0e;474Tg`=WBb(#1l2GU)0i(rfEsSbleoBJuf#3G(09?#;OEz?@|MU6vm z_Erg2&0`b?1PA8D@0|ZDT5*LaF?<6?Z@}i<-R!FGnL1`eX$9voO|+i?=Lv-p;FM5! z3Y@1DN`X^Kp$s@>6v}~9PN4!g6%=aFu7=(Y)}mc4g*tSuLvrA*N5^_3=}7}xH6Te( zo}>A5v}K?XEgR`Z)r59U=y?8{vse6zz(b^~%LU8b;-@UK+cIq?y=Ur2t$sARuxIXa zGv`e+q!^1{;F$l?c52xsxbDMYdO zQ50fW{1}!=(%+sC#-To$+bmGZqMJ!JaIL4dY;i@=hoE`at0&}ASU+3Co+e4VE`gL7vS8Qw=Q`Uo}|vQdA%0%y{DIe$>{ z2Ngzj1h_|l>>c5#7mkLRI~zx=?i;};4vTU3Pp^#kFWX>!DXmDF(=$ zLo9G(>69d*ej;qx zLvLhrft^c3`$IH%h$h8`_ST$!HvGW_=VsfY}EMpTX=ig>PW?jY2<| z^-~xCvjGZ&U^Ym>AI zXFDcJ6IBWDO2CMLI&`bU_2vFHSJwDF%OX$b0m?r>Ub(+c@{ds;Y>06k2&`hCw^bKU+K!qk3d*z^Uwv|M63)r{lgcPA+5t_bO`~KOi*drf_ zDgtC9XbyfB)z9MS;V)byRT}!b#n?Q7aZkXsP1`2&_(NkKvSj>0&!47c;V2f4B;AZe z@ko?v_e@y#OekqaJeLEnoG#%;oY9ER!(YV6t~2yCto(wQ;WO6-Q~?8AsfX^=h*B+4YCMlxy-e}sg?8)|jW|Hb9;8p_b z8K^^E9U2XPI3pRt&_^>yl>sUlbhY0GmD?2ZKqZet30RcS+li+z`6-YLp&AUUVO%%p z*X1Ane4I291+r1}!JR|(b2z&1L3n}F+r(33+77c!53?-aXC=JkUFvyAB!9u^FHG+< ziIx$!UrkS)rNAqtTU`UrY(SS!aohHC#q_g zQ4J0Zv?8|^)%$hksLG6PqC0Rm7v(bqh17bY%=l>rL{SPx{|Mz#~ zKOFcU4)_lT{f9&TpI2{QvuPaTXob-_yBRZQ&7NcL;OM^EeU1AncMo@OcTaaO_myr= XbLTBu=<2+{W&ZM|>ld$Gvh05V#5^iw literal 0 HcmV?d00001 diff --git a/.clangd/index/mapping.hpp.63A500840ABD1FA2.idx b/.clangd/index/mapping.hpp.63A500840ABD1FA2.idx new file mode 100644 index 0000000000000000000000000000000000000000..54ea1e9d333f8a67d825c8088710db30b1a21ab9 GIT binary patch literal 3250 zcmYL~c|4TcAIG2bm}v$>Ns}SQgc!?+vfLy_vP`#P&`rtmBy%NONb1@{Qc{!_+*^s3 zE3_JJW6RPV?W3Za>McjyIPvA{ zeHp6yM(tI)C{##$PD?Cr(>vDxhSZzb;oBrx%C9Zeof%Zx7*xD-VDX^mjA(Dq^Or0g z0;6QVSf3S`)rQATd>re!VW#6c6lvM8bs-gff6}qb?O=ejQJyq6K6NG3 z=XKatI@cHk?md@HX$xijFp(vv-c6c*rMr_AUY}v;d~t0aO=hC$-|V7io_lH8vg&ho zqekzW_cyca_mPs(jgl?2uJW;euV=;R#DsD`B&2vw7j#PmuNjeYMr}0bgsFOq$%*$# z{jAmUBl#AbI4Tt&{^M{?cD9}UTHb( zxTk~JG6vsvr0BI%x#wTKsP6t`;DvU%^r^Q6cAmILaSpomm|kO=B+5H5UqiN{C3pFa z;scbXyA9UMow{yrd%C~rZc?sy_E6dh^8=5X#lBw#r7h3Fi}-V^jNY9t4EWQ<;`f=$oh{~_-pGMRlSZ2(>x27)oqi3leWy`MgvTvSu>gqn{yDdMv=)>!W z3*B1^MdpFgnr|tEMYdY#^skCA(HAnqVic4HdPSYxP~`SNHp3{p488H1o+8@x+q-IN>cGJ5 z858BP;~InMZvEP~W{;%qbh*`@J<-GAts5}8x}z+=gD33L72Ms(kZld3xTN;iF8+A) z;j=H6Bdc?6{|E{5AL`3Xc04eLCaN@?lEd}N8~3xkyX(!%+k5Zm%{Sj&9J70*y?X8~ z2g&7MuNBjWP45*y_R8IszwzerVq>xEnYm+8#|{s+tU1H{XNT=QS!nG8P2(Gbr56OF zFAf%Ew7dS;(qeT2RE@PKwf;R>_c@CF>{olgi{xFe{~j}yYF`^ocpoSGkY&A;)Rq4% z^6FmyBF7s#Z+8D>qaVH}e)rC{JKsGA12SmwA2zgZNDzN9)P4{ji6m}~S?8;QAUdzf zC;OfX&1lGmCCIwNDzw8Y23QVC%RvngRg#+}ebX9%0mjI~zYLx)7^EQ)kh+L!UPQGp zG0+qPElAnUni|K4)T|F@-e!&sF$k&`)m4vP0V$@9$L)62!%hTs z3e`LXeYFA2Hia*a4kctj4BPapbmHl30X1c^mkw{b74 z&K)596af7KV2H)(#~DKA7b7*#0LXB;zmFXq*Ycww0_a6R6|gWrsvipy3+Ip&UfllX z6*rFWhH>zn9YxiSq8gYGs0o1vq-^vwVtk+ctXq3YN$pbi6d zNZB!gA}cI8DdU@VqYy=t+~H>o{xC;1M{P(Dvuvgdiy}^+MtE63U7(I}sa)K{A~O|* zhuV&5*GUIUWCS5XHAV20B|uZ6IOTczTJe4`8)4JeWAs_xy#ysksdAXjD4>oivavUu zsql6E;l-hjo5CD|x&kb&01j3GEGhs8Ms#7%_;oe(C2{)pSF6{Qc7i$un5V#OtN<_z zz-&mlnor}cg48{$xAsop{{J&C2h4IvWdUZEf^wWq_3($(qX~n;shB*O@O2I_&q1mL zFiR8^*JAq8Ku8V7lnE2d99wC~@9^&Wfkr==g9U2@&w=q4TagoSmB?JLzTO?9cZ~2< ziqcBasaPGL)q$yyvSz4mTn?#WpYI=%yeHiVYCq814-Bvry%f9#oJ=&me}l}&ZQ+k^ zWlXmsn0ys#zKS{~2UNM@tQ=UV;;a%P1c`O9u9V6HK%qFL%;1y|m+}Uo0l&FS=}3<- z<;z!;1P_Cg1?)+%B*<+*qoX>&_mk?Axp1KXa0>7RF(8Y9Ms85rO4t1kd4Pm*=Wv~O z$U9yJ@IU8Ffm4J_Az?g(2cLe3AAAl2WEjBrC_qN>w;UjHKv9YsrhrRXdCPE0+^xnt zwYnU)&8uOAVZa^+Ha?G^hfP$C#lc*7Y@QADZslh;jnU9}tNZXv6`W!X15-QV>2=g3tZkgjs_gGgC+%O8*qhOv=dN2ebIAvFZ2BMcK3mqDW@>bR~G!T`n6ecv_ zaym6a%Tpg~lQsi)zkanbY{h=%4!lU@^E#qwQ-IMEpy0WQ44sWJ48hd|) z<#^yXBcKZyB)C6zHLz4Rdq@#2UfD~af#@KyT59^k7nU}|Kc<+ca7a+oWFb&Z@L=>w zjJ9jTtmJ?#2MaHh_1~!7$6kbU^b}p3GZzAmvXY=bqJFkK=3Dk29ZZ8<3E-6AB9{QN z1ZXJx6C{bQ^u(B3w5y#Hg{RCGSmG&@s{u9j)r+g&c1+y}%~^n+g`aR6;IsjIm;*QZW-kgLda^RC|b8oqL+R` zx)|1dU4GGOYm{44WL?sVO*F}6&olFzU-SI&Jm-9$_wza5bI#{{9~YXfZ5$CntWVIQ zLjoe{SOh^}7hy(5{3wb;kV0hyi7xE)@C+L<-t>~0keV17w4g8kj;%pVy8nQH(W5!z zdwY?j+`xiNH8C~sGSbqUD0}ZiJ^h^#`N&W2=e@W^SyNk7UYed-KWdol{(;g{|MkoA z%L$C=-(oWfO};GR6p>ljrdTrcH@2VI;ncuB=v*B}WKQ!en#{+fiV)ha+|J*j|vdVKaS54!jy0L7YrJWdT`gz

Qk(Jy3eNdy0@^(V>>&14erPaPE~wbtWj&zn<^*fu+AW%#T8dDcCl;jP^zj$CO) zyJ3exsd=Tc$K`v;_%>hiy4u8_G@08jy8duIPHd`>$(xI~v+9N{(yDUcc*!)fm%B=UEaN8}|l(m??_V>erlFpo5mW}({ ze3P2nzUk#RgJ=Pz%hpS?;sd(thA)m)2QS*@D&nIqCKRmNKC7<&oNncCci*S?!+Wh; zGMltLf+auTGqVit`cdmSxDEYwCW&2+j~ z?M;u~b@;H$FEte^74;nq-5qQbH%Sd@cT&}CBI~au*2t<7CMRN}Qb)=rL`MR`(~2;` zdHuwpG9#0|>HW-`qnwpc$>n*`ls@?djpBG`xhKt3+vDDyxf4}xz}d1^gB$NG8?*iS zU=ogNCr)YHbM4q=-J1056kCGfUvEF1ZHZA>JK#_DZ%{7|JhsdDStH|gWBrxT%&oH? z7rba~9CKpn)YJmg>8R@An>BGBUWGnCc0Jp0&q@CP)&!S7pgSKsUODO@&24Te(Oxp; zOe(dnCf8~fTMvJci7!sYea`dD?r5f^Z8VYoDJML0*OOZV`aKJeB;&ZX-l;Q14<9eM z58o%0tT(lmcioei4b}OM6l-TmBqUuTPL+LsOMZx5vaQsJ;X+a$A&sOu_!fthhvZ#W z*L~t}N4-8vY*A{U&_>N&lZ#5}Dl%D)dv${An#SL_D3fF`v}c$&-tS6V!0jE!i*&Qr zl*eyIJy<^$e#fM-)c5V-9I?Lj+z&_U5oS!taUBr^k$;c7JvhqJBqD(aV4;K;Jq1Hd z!6+l5SSww*@MC}uNVCJgDo>e?5s?!DrUyv&0BOh=C~XXNhK$muJ0B81j+2C#av)j` zh>+Q-Ab#>NWK{HR{%jZh#Y~841Cnh#9f~~u$3u|OoOs4LaMi+%i2NWJi$zC9j~Fb57W zg$NGN<$xWK*`+KS;shB#y9xXABy7A8GYJTjKpZl=RRAv=`kBactFrYh42Eg_zdbM! zGm(V^zn83HLB{taNC|0B2~<>JpQZ>;p{hgb2{tchLWp1kNj7g~4Yx>#xxh?V4a+5R zO7{Ii%p4%h@iH;mx|yf*Wca~&M;|Lih$#X(MSudwve4S}-BGB+He3C*)ow$(5R(B^ zGQc*-SZYhr+#&Nq?}L#UcqyE55>QFvF(%sxHm;Bv`Kp|`k}?wa(E0?N9Ldh zWX3`YSj+;GRwBX>?4-AZw>lhYzaB0Eb;E?^@9%#OQ7jQssRqPqun{slNTNXwkePH` z`xI%vVkN{xD@LOZH&c_e{~i*HvHq`~o|DlNBDjFS<*kh|8N*wfhyVt&8lD(|y8xi0 zt`b-YcKH?(>=q25yOhY8?PW!OS;k=LNq~|BjIi`JfNKL19p!FLOQNrL!WS8Ul7YVH z0k|F@k?I+L#PX_f8o<)2>Qr-q51}6FzYE-scW%y~Q#Qc22o;Z|(-0cGyC5#`J_(RX z0H1RJnM0pkfN%j`u&Ypkznc>CV$~^Dr;oxBCV|!@(06<_<@dGhV;IbZrbW|-a(XVi zrAT%4PrHA4CxTMsNuYu1lIPGT7m&F?!v)Ep4k&Uwc{7m90LthLC_TW)Rn(>_BtYsC z)K9_SQZV9fhh;RUubAU_0qqpbPJuySN_=AoTm=JsHwg+84Dbum_3XmVxPDbE94$;P zObJV`2D;V2z~kk(RN6|63k(+l(<0!ErE>s|1C#|72@3Elk-%^;z&G0K?bNJ`?UW$+ zDMO2)i-jDn91sM@8gl&OEI7k3z(2bMCP%D8Ep5>0%mJ-AV0d%=T{?z5s|}TMfLso` z5^O+W10#Wf;isr^1#X31zDvv6N3$zL;`Z>ecP#=wX!ctjSH+B zkPFidGe9Sgs|Ml%XG02gbfv`Qb-xrFbVC?&3=%pat#Y6%sNay{*X>Ygu`QGL4>m(C zT05G8h0evXfT*B~K#pHMG{(l44o;jff%BxwQ@2OhkOtYR=Vf7+3$(ak@BM1 z?L&3sq7_gbZ5E&iP7~DOpQ5N&&bs|K#^NED11LGD)!6{Y1`>jr1WA4^68s`yfd6ZV zo0B<2Y=ex$TtmLi9>;2D{HJ9c{ZQ!4xvCnSjbD7`2loNdx-(=i$ zEqlh*$)1O%rN92VOyskT_|d2*H*X4RU0c|M1MfbEk7+&uoxwxuyMDHbb`MmDQ>J5jEPIYm_e~ z)lFOeXxbdn`InEL@QgSneV>Vc-+L+H9}hlSl>{+P4^_2NZ#&S-9T-*ZAk|qlf#c8) zjvcbXy}{eAf6!SOeu^ceUGCS1cV-e9`>r)~yU+EmI@!IiKsYccdrqfL!`+}aHm_sl z9X98_4>7s-m#s`FmD|M3$+})bb#g|Mb1lnVYu(rssVTfIU-%qXxrK?%_{9FXaZ+Pz z$FZwZ771cr zRp$zpevvNENR8*CQ)8}jZ{B^JBe_Vd8d-0|z-#1(KET4Kz)t=$SojUg7%G@Lc zVCv~OuesGjW9mU323-aQZB`am4lu#M07_m!P?VZh+|S6suzzax@uNF7)HAYZa|&=u zGOs-(W2g9v5y+Kfm*jRmKAZi(7njdWKv^zMJ|JnpY0_gaJMqDpqs2f$0e%4)7HvU( zL78Aq*S)!^0(~qj+T0f0b}ZVw?7X}{(w5g5s7y&fW2$(&m}8wt9nfTMV{S7Etq#7j zrN3_hxxyO4CJ$F`Syk!ADG20>vy1a9`$is`v{S(w$Q9ET(_fO;ruaim*$BvG=VIr} zHuapY(DLXiNLEx#>y6#?3y02bf6E3mnU|ZNMVp702T1a&@T#$B^U3ik03E<902C4A z734RO+_Gc7%5D{qMFQf|rJIG)w%d8Nft=0H4OGd)&jTcR)p*T;dKLH#w;3-KUDa>% z0H~hRjMH(4+tiA64$p6}1Jx^X8v@lU@>l@XyYl)2$w1y1pe}Phke9UtOn^2j3F_7U zt7^Lfqld`6MVb;;qV$g(3FeK-u klFE`wl5&!2lJb%Yl8O>MynLb}Lj1yl0y0t>VyfcO0ALZ3Q2+n{ literal 0 HcmV?d00001 diff --git a/.clangd/index/rws_service_provider_ros.cpp.23257787CC1BB7A8.idx b/.clangd/index/rws_service_provider_ros.cpp.23257787CC1BB7A8.idx new file mode 100644 index 0000000000000000000000000000000000000000..6a0b289b8da33f181c71d9377aedd1cb67f9a8e2 GIT binary patch literal 32970 zcmeFaXH->3)W_|aQ|1(vW~E3G1A+n~ma8b(&|m|_uCezLjYeaOh}Z}wiWNi@#e#wX zBt{eqc2Kc5uvb(hN&vCH{~cqJ56|=F)4SHY){`tVKW6SeRWkA5;&8)c zKK!Q&foV^lZ#}tq;h@W@_4DgK{QmutBOTeepYzMQIIMa6^1E9@&N@4U*Zfd%flox% zfZ3C+mR^7VP4vTK!&-V)J2j-%?N=cOI^7%H;BBh^jF*oWciptG;ODW;-Y$C>{LPui za}v%EYy4p3`K#HlOxA(5erVd~%qHi)50?9Wa38Cj|(2X@j^?bvTuFF6~<0(vHuzncMA( zUobv#ZdgY?;(67Kq_(H-4A|0g^zoSOZ33>}E<0T9_o}uD&z}3uMbAPu-Y(qYOhmej~;NHHJv}ZR1&!JiXAG#fsv_Wny*>tC!fz8a96AUDq&l=%JiSC_@<`&|y~zR}EM&;9jfvu?KV ze6nE7k|l+6Uj6>G=IgVz2d7^dJMny*sJW8|JPs)6S`sq&^5$m~Gf#h4Kk>yk&DPCL zu6XsP^fLV5qgR28t=81fdn7IR=1Qf7wWf}|eWa6^vSMSl|FiyeR-8JNo^~;?YRhl6 zS|iQGJKu@Xn<{U)_C;Xd7IK-d#mr@k?3}~C+4y2x{=*q9DqJ``ulrv=K}jQ71Fiz>qm0kA_DIpe)%zBL&@O% zYttV8l6AG|fm@wB-E7>u;=t;Q?|%rZCGFqX^!1#ynC>%27Y1DruQyv+UOlWu;SaMG zJQRlbbu9b6ft)k7{ciX1?wfyp7@FhNrc$B*@a&^!S5BE|S@=5Yr$#gGUKwz)!GRi+ z+{$l{Dzfh|T-~4;EEqCRG}|XyUC&aHm;U2E z)xS@yZDs$(9COwdGFK(rtCFkdF2;8;tH173!);OJshi*CRby_DX;{5sJge*L;&X8wi;Xy6p$u+w+RVuSj-( z-N(h|wlOe&bC5Y}1)2Gh?R?3_Gm7!3e|#sG{>2WfYA5$LXN@4Umf5aluAV;${3qe> z_pLkjJ2Ci8@+5=Rtx&9EYWS3=x&~&5)YNC{`IU@7ba%DYWJ;T&bmNmvu3+lbMwp> zdA|6!Ou){R>allb<37zGlPcP#igi8D3;ewBcirmvL(Hb=ucuWrXC}xj7j2h|Zl3!D zzEAl3KAk2_s$euZ+rgamgiMxho257O+$iylQmwzI%I8Trnuf8AGi%vm?c>{o2}D|I|WMII`e|0UCR(3e;5o{iXM&N@J5uWY+l zcJsW%_$BuD`wYwvi;G{r&DorFgv?vn_N`pk^C{y`+27x5==tAA&9=^%WzGgcW{F|D z#AxbySK@c2+J8N3*vMz4rFXx5XwLdV=8F~P@vML3^Ve0fd*rka;57 zJ`vqL7c#z(Rr~8cVO3{`J^5l#usQ1knLOP#Pj~nHRpP%&f6FXx)#lEjan;?-SrBBh zHQQ{hwr7FJ3&hHQ-6x{Rr+taX+@-%grYQqi2Xfy^Gsb`RRtHpaL8qit9T=b&l5##1p=Bz(t;tkt)w4G-XfA){Iv)g6qR~Bbhy)li2{iAO>9=zoJoz~wla~4Q4s%^aL>X|O`^nc_}?(#jycUo+DWX}8`^HH(=sJMB? zh&<*W?c)4zHE%!KJNCFa>jjxy-8NVE@=TU^vSjmDSzN4F^NCG({B(2X1DVT$?PZ~! z=W&4_7yj-G?=4w1cF@RfJIq;2$eb2zPYYh26ZnL`?{eSiyQ2X=Kiz50xEITmSW(`)@)Ma<+}WZO+<3qFk~q$M-(K_i+YF6Hkh-9ka;iIz873P z!v!Axk1^oQF`J|t6FXHmXWo#xE7;x@+&yRT8GqNVZ-$SUyz1M(M>i&UO?92xko`Hp z>3g2fSo^l^J}!Cvrr7}NPc>^;A*Mn5D((Z5EOZdAT}zTWIuB!u!lp?t9Uu*C1$RB2HW z3Agk{xAfMQ2@YGwmPh|AN?!3oaJ(>3LiTsPrVNn0t}9<&S9(?L&~y3v2X8OUl)UnV zFY<-PlGhEv?S{}y@_He7ybxMSUL}HC3B^kVk5Y>N$UJ^zU=(wUVn|=kJeE^DiFqUu zQfXNp8PU z{DtK4g5r^~N2ClcmED%gNM9y ziWkWqMZ{v+t(ek(mpy)`c%*`V{i#o`z!c|c&g%&s^Ifq6t`a#$e&a^PE!1| z;&z(i#fnEU#mf}8GK#-aJYG?J1NYd#!36G>z>&V0du*ooQSNb+c#^xFr1Wg=kxlUe z?omK2UN1fzpQ#( zrg(|!Q9>+N-O4Hbwd(Pj;%hXIH5wSJxy5QoU#EGjqj;v~kx4wHxgDbPEX^Z};x{yp z8^k-B+Z{^3t9jg|_&d$x9WhjQ3)PW6SNE8!BfdaK;YHz0a7QAKx;s*?u14fhTqn&AxJBTM+J6NsD!U1C}l!T zq%&m&1Jjt2Mm)!qbHpO16cHmuB~k>pi^_K55m7lpyeBI6h#y4d12INYVk9tCQc{WM zB;_3OrKG$hM#)N)4DOPZUBpYWa*0?XD<#C$in3Y(cPq+n;u%FbLo8R6a^e=QY~f%I zS8|9&Tqz>Ps7j0qUQv}R#5bz)h8U+QaT<77Qw|gFY05ofn68BBHJ#D}>+MM?G)LJU zS1gY!&dyD*PI1T@b{!?L%1~DsI^M`oR~vdAul?(LIwkhPIB;FCx-L{f_sYy7m^r!u z(QJcgUZ-Sh!$mLS6aUNef64RDIvuh&$Ti4^{i)W~EjT;v!tqBzD2l5>)2o8N$I13} zR-Kr|93`*zW7?0CyaGoDj+MMR5AQq@SB?l8C3$rp(H&vW;XRSkXH=gtl2`vx{Sgiv zIdHV(HTavsQzWlpqle+Dk;6wqX3U5&kRLyMJpP_IVj}*YJYq7!sl%rtW%{V;xOUd4 zSqSHhoP#@r3B$sK5om3~JN8BWg+aydtr4+_(AtnlA6Dd7O z7?UL6jdu!@chYscgbBNZiKx`V_}#+S=vag?2k7%GVN8}Vu0e%n={~_)(SJ4PUusT+ zHKvObb}gDkJu&ZB#)ta62s(Df@pfA@%24C0P-8GURKsnaQ6FgM7&bv_Lg(5od zPd0#79adCO2A*hwXZ+V`|G#zG?bOJDE&A5GNO^9UVvJ55(r-_=c%gj)N;z7Pq6PHH zn9;`);{_#Nu*4KiP!fn+1!XI7yP#|*CJRb3F;!4gsZUQA)O2E|pkz||K|whvSa!Yf zc+lI;#a~M(J68DttA-oMmAA`aj#@cK1y8A!PpQ?q4y$xDebJZO@oLvt;5F9mvrz=q zVQ|yI{_Ib?NVf{xioai!m&MV?@K#~G112lH{sQiUQH7f#I3}e(a{nKBdkmO7Ac}WJ z{p3EYcypR;8VTI;vylY%o$fllG5ga_(tqidx%#@;rT^8Tf9XmFR!q9JVZ)hzDA739 zD2^e+H!`P<49zu(8A(*asmw@a)rRzxsg!921Jjr(jd+fk&Jl~4sfZXUnj%GTyJ*@@JR+Ko5buem zd&Cc-=>suFGQ~(>s$@zfo|8=Hh%Y76OJbC4iju)yvS}Cbl5Dy}ERjtm#MO#vwF2%| zOuLC^6w?`Exne3OZsDda9L(XS9AXhS6%k`pQ;Z5;QB7BfZ&cG8Vw`4*)4;=;=`iu0 zX1YfV(@kM|mvKI0d`iwm3`8SLWPXXP9Zh!qP7oh5zlX$mqTf6b+#q(?Kwt2QX;hblkJbyySjrzvjYhA%fZ`RZS?lE20_U?|-eXjUCSA4$4* zoizSw*AowLodw&*1i8h2{kKP>3P;E$zt;}N~C485+53%k>>{+B(i zPg8=>@Vd})LCMSxg6G-BNbodyc3K$TVeGLB$u;og2dw%7h8nhAuDxCUf;t_y9JLX3 zI^L($MiCumher0CIRn?tGqibz5o!Cl`=WYRbzHef@>nF9Q0FA4NC}mDg=DOdP`RTe zBU-BV9|5z!%S6OC=6Wz3$)lGyn(Z$e;Nz_bu3cXGg98QdrP?~}W%+q3%Y zz8#0B;z`TJfy>2F8#+`P=Cj^80ttKNo_pm1@d;&(XIk8n8la+z_0Ndt3eSrT&WlZ< z?}|Q`=}C7*JFWSphXt{UYkkc-qzks9QdYCcOf$i-?#tOmJlTK#P#m!vgF zBDoaJltOapnol~(9ny?LBzIb?f12dZX${Vi+$GKD5`BJ0Gw#smgTIguGCp`R7YpOreBOS)fsp6gr{2_KbFAC*bTK6_hzz2sdh zlzE4M4n0snLi@WyPxK5zt9wGw&!Gn`dM&e8v?qchGl>#~m&>XNE#zm&K_uwOwuDpWlxpuZ>+9LofE>faq#Ffffd zrV-CE$8*FY=2%3G6dfZ)aJ%TZop?laJVLxDI^H9G5FI}dV{vovtvIe$z}<@DZsHlm@eHwCaV#fp;f`B4n8O`& zh(+A7h!~?f#;D*G)$t1Pjq3P@7^gYLY2aba@i6h8=6H`7raOk|?is!{T2J(u?T4JZ zF7WGuWk$vIuU*ESKa2!F=4W*OLbS~2@X+aEqZZF`MS0ptP-52CP@0q8(8BA5exv<>Etj^0BZX@qrgO1PLEsKe(G|N>QxL32>OU%JPTPdj@y~~~$9J9) zFe3yuVmTn6y2Tr^{|&jzxzL-Jg{7UAp}#%OY8kF~7YXsW zYIwl#U<`#)oB1?%SRl1nAa%I3r{S2GTO(vV<%1CNK^TzdFs5_ZhR#EfkT39jp>n=@ zq4&f#&uBbcrZ-xqw|ls)xbwjKhdhz+MyvfsYy2?QbMivt`-Mn|(;LOv9ch#02uFa=Chcp~w!!XFb?alVR!nVe@5?{I#H7^(6|72KopJ;Xwl7ZR6h ze5nSeYdoEJN#mD@B^oc$Y}ubnFGZ47_T*zH4r8D$XKv*TlZ$zx+dT0PHk(H__IYBb zd1BCS6}mO6>NWWh^0btXDdm%2gqE4U-`n*YBgLg?JO_o~gTereq-y7QwGWC%ZNE|N{%*yYl%ICowfm#*{Ljqzznd99 zZ}C7DCkpiv1rz&op9ia7XS79?9}nV#4WhO|tcu)O2BmaCZ*)Nq zsQ7wfpjo}+<&ZqiDj#Ps;VzadFP5uYw8(sSBV}DPNIug|&-6fR(}O%S2V z^b}X6wpXdAxF)r{CI#B`Xty{x#Kr~kp?qj4A7@v3#`&Y~ws+(A+O6>T71xR?RH+rhK zsdudF(Jep!^2acv^trAK_FBf{i@tBM7ZPQ9qcXkA=lvYWiSr^qFV+snOw;!l1@Y60 z?`dM0;#)>c;JyhQJjs1e5(~L+A#siByG8{sslJzp<*IKvF;?@9)xblV?;+wH&G!y5 zRQCY>Q0xAK6u@`%QRJNAordiX2M4CTC4Ihh&W@%ry*&KjzkLTL^f zuKI_oFf%Mt0~V>BsYCOLq&evt)mWoi`qWI{v)*~1Gw#?(YNR!)nIZisG-+R3^70?= z4?|{~UTx4DwC~;?lfS@jff(01cj=6(7SuHegH89Y-4XWe(i16tg8Oubc{aE|!ht~p zQ7s4e8;l-hShr!gYGjv@kQvi;4CKdm8IQjwcAbd7CwHBUaB7#SNSPiy9oNnZo`rBu z&>Y+$Oz0dYbj5cN`iBc&k$E;`Eloe;gpfGmCZWeBp%;cBp~n_tq7afu=}AKOBmr-{ zQ|P~wuG=N_+9lw7>=t_N7J8F;w)+A4JWJ@FCG;@WcX*jsvnlngtHegDL}Xfw=oBNO zeI$rRf{6B!C>n`kHB<7IzyU5JtdUuTvSp#{{CPJJqg&QHAYfSjv?ZveY4PB;Gi!K5 zGTLYqZM17$zvTJmw?PsA^`!q|w+WoC6sNhZZY+~wwo$B%!q_0&Y#^mLL3T=zQ7Fl> zkxZ7kG}%a#t9{WxH5|}zsN`khrb-faX|-RXcSecoEu(d` z`53)v46T-K)q8H$`=d7Lepx!K8HaV#VI8VWuI`(wqwVJEFdt38#8K~%r+2|rL~s9y z?o+IHFV;~jKjqdt(_5~J-BBM_al(eg(F>G4L#cmu5@+31)|%rLrS7$H3e zuk4c)pWh5k^?$P_|KDEv>mThKbL!oRz9`nm%y`Vq`ycBSxo%W(5?X7hVG(N7phX0W zb+2T_i|_UHbyky*c0E%DqjQlZ-DnNOPuZYwUg6>nPM^|-HK?0u{_JyuYSixs0-K{bA* z7_XFSi&uCnwSP-<{Et%o zj}p52d9u$u8G=h?W2tO8y^rUB>(45_#mlGZjnec^(>HJP-5-3NX&CFWj(Z=?03tU;sdX};Qvu>_WUuWKAEE3)eeclU0X03eaZ&fLU zAt720ik5rLt#h_Z@_;j!aPM;NTu!snaJ6>0idpF*weBL)YHB9fIcqc48EMQ_6gm-11OqitU$RB2ET37;0XBj=i8 zc1$W8$rMn%=hRo!w`kCo@uF1_ZyUyC~i2LxlN&R}gb z7zXjZtmR%7xbm*sA^!sjPtiX9>zw|leF-tI4>hxHm4Qtg*i>U$uLrJ8+`DeL)s)!( z>hix#5Y|pVoA$$6j|<4Te0gBLJZk;^Jh$XJ1!qwe3&pmDVn;F(_`D!{@;lLZCt7ZZ zwj6tAV%B6_v0UuATpSQTzT%r-x!q$VToKw|5rPu5KD&3YS;No!X^|KwxW$o@_i0n@)^-JhVmJLn9qb3W{s$Rda+u;1Mi%I$ zN~NWw9j#J~Rf=UoYPTNVtxHXKP8ka-W4%-B&uug0MR^Dk_Q^r}RzEs&u;!2IJ)W8glWe~4x>^kwa z#$FTm8GN5%_3QBN1*!A%gOOWNx+zNUwCC8A#(iR4OHm@BMw3v(mqzp^%MIUya`@?c zQnMfML93uvn46szdYl#pAIjeRe8bdz7g11eCAYVd2Q5vxMaX}!Sp=>1M97^Y#x3Wt9S+d_*<#bTM1R?qh#|@!t8mT>@<&N&ylhbNweo=vaw9AcH{l? zA6f@HCgF=N624d@)I%K;zF17$D_HLp9Bv*Po>bcVL=y;137CSMh?d(#)8b={+#*Kq za4R(_BeHy&6`sGAbz95&+_*cz+p3`DF$b!&*3ShSs22(A~c*Ap{D>kML^Xq`ta6|GB&%OvY%5|}7CB}!-@Cnf8X6n`vPKPE1ctryAk zxon+C%#p2gh|gr}XT*hy^+E;QsaWqM9#fo-DY#FeVqHk_wcL6w2eY_!7V#msen?!V zS}#+(`pio!7#A2d-U5&a5`tuQvML z9lv(ZA>oi(_mJA^Uh>#EoquYYiQ1US+%g$z;R)t;;uD*lpn2H|*69Qb`n(Ap z^{b6*8(;S4KJ*9I9W;xP^ZMY1alCdM_qhG=ayr(qCP%uKO%rs(x~vpFQg1lKUZ zoBg@t{Q3UIZL+n^RA*mHJzq-$i#G4>Ryw52=D(5aUq-H?`M(zZaQ%vaD)Qf?=zp3N zz1Y9-z(n7(?NGIzh=ZSqV~W<5x3*rqo~+_c8aD}ee)rkP2VXw7Lo`aQ6QwpR&A#9t z9$#w}61K~(+vWP7T@p}h16>2Lh2WD{!kcv#Ra1{1TL!uLQqX*<*M|l(MrAHZzaUaO z@DF9MkA*XzaMm1mW(FM8KG+!nMG+Gg;YJZmi=eSJl2wjmRv)y+rdz*8E^?H-+BvoJ z!osLi2ZSA+IwI`i)CFO%Q!v61rx1j_oO&Vb>(m$F0H*;62RRKwIK*iP!r@NC5sq>i zg>bCXScDUtCLo;TGzsAprzr@hIZZ=2!)XS>*-o<&h6+xh0ys}_nn#QloT7=bf>SIp zUT}^Vpl~J#&I!b=g7a45cENc&FhJ@8cX zm3wZ7p}2bm^a>&MHlUP&Wz4^fb*U6H`gG1nM_b5y_VDaqDel6LhdR8dg=mE05}|lo z#1)S@G~vX4bkwnO`&b(NHpuli&^#|e_JOl3*@ul(+0wFENSZv-w==FxGfZhl=PKR$ z-p=f`VGXYQAlrN(D^{4|6h`WQq*5tTfeB)nQfZk|@rliL(A;W=+-Zj#)Zm-u3)+0|RRy;zV|~lm&;~_&=UdOPu*K~fw`mN+ zSCjfpe0+*GcUd*{TYpHc7p&I{j;1dZv1XW915=w@a-&;h7`!Lj+@magBs)E#sZEh= z6w%b?ciH$|uGXy9%bc;w;Fl=$|GB&MO-rb>u1BSfctoC7J5Tfa?37uBcBt?(VpZCC z!uLtwEs5VE{^3dmZjku~8O)M-7V)0U?-4)9`~xvw;qeN%fb#_$OyN9*c!~2%#CM#( zBW_dqHWj?1@;k(EjfZQLuJLWe(;7cbEYx_RRuxvJKRiYKyM1d6O8t2Q-u#K!`-wR4 zv#ThwaF^h*OTZlAlfP)|H;rdKSf1ai5}7aEmyi=hv>p_#!w9}rZ?=`plUaJ_EWHPr zDLdurXcKvQy*wRN`;qSch~$g)CdFjV{GfOGK%Xx$x-BvKl3CI-o}4L?4bNm^hT)xI zG;3>Zi~Sd}{1Dv{)g zuu-hCk?LoxZWgPfEE09|L>+mMqFbiu)g`ZAb<1CgM|I<8JNWUlZZLYKZjVr{0oQ+ME?aMm>~Km5ciAz`-wM2 z|C_{e(Z8IyLh@fBfk~2o67iJee~S1_@_$B*l>H-RFj@9bCg#fixx^ybzla#Aw2o9d zp%p3qsS4sJ75|gOV#U9hxPkj`;NVg2f0S6j{R@aIRR0w!cuw^{M=VkOONeVU|1}zz zsrhFTZ)pBEi0?H2cUoY_o|VVe-97Ufa<-g%mXklyJ8tuiqrrr#E}^vfCS3Ihr_DEu zRG&q(`6g0ziX>al3e{Lan{J|2BN}^N`$nv9KeJ^`G^BO`?S_(SVt++|u60$Yc~xi} z{Nv-=?$#N-QLw8FpH&7d;HwRv)keGE+@P?htGld2k8n$Fe~Y@!dvg7I)NMYJeI8M_ zSu7jHvSoKxFzw*-`So#!B;AyxL(4d!n@;G#-KXCE@!k(7#-N_x6?)$l28Q&kH2LW@ z@0yU@#wu^4MbZMPa)DGmxmhnYX&h-bj>4{ims)^Ws>VM z(ytQfUkB1gTu)N`vE=%gxJY(gM4eQk?3zf-kzI3$&t%tU#D$9MLh?=9skrVW9#ilS z_bF6d3n~6wsr+0)S*_)+YiZ9}EUz3(WtYWWvnc+MyFMf?Q(c$QI$yTxnoWGEy1pc? z)Ld86p0NzgHG_Cv!#~{rwdVR-^Z%+=Rf_?BW4}XwWlNUXlHI_Z-n&`bwqzuUW4)fx#* zk*rdPXC$FCUC0+4xZ#zCy9mJs*t!wwOT_P)-I`5mx$%6RXH(Mvx?QgLz>kg;vLQE4lz`> z3Z>p{nOadc_OGTYAM?#HV`2r^GV7 zVi|G1QE|QjMjI8QiJOgzn~AAL#Z=;cqvC#}(l-HD`PG5nH%FW9640d^Y42^8hG{m=Py|!pDJm+XZIU0tar&`aa+E-H+ysP{kD+{P0 zkGRt#?(^+ez3YDCXa5cf`9jlt!Ec)7uzQ`(`q6aZD(iEV4VgA|NX&rTTm5y6BTGqF>1pjV#e}+J%x9XNz9n#*`sXYLrK<@|I+Ci>x8{B&U0{ zUG|w|JfrQhFC^oIRBfi^hlmFITF0Ts%9GmXN$9a|N%e0@K6HW4JqdUIO)`FyEN4GT z>6xx37Q#6ea}b6J7GVMyE;xph%k)~oYOUZ(mQ$-Z;wGW$ zCc%xC?yGJgCJI#(iAh4$B;rn?_D-QGO=qg_B5Txcq55v(0io&v`aDahnngSz$R`AA zGVsZ#iI)ZWGV!h;-zB~m+GINE)< zUy=6{uPO31;zvdPNKEE(GVMY<&*k&PQZAPg<5fAHb|c>&BSa? z&L%$5y1YaOqjfo&xJ8$@5VLeSiThh;iA`JKy)FBc=v6?Hr&a+H^qJ(WWE9E;d~d2HON946zA8 z*vqCD!oD_r5e~2!fN+q_AcR9~h9DenGaTV4n^6eI+Kfdw!Da%&Nj8%ZPO+JSaGK3D zgfnbrAe?P88)2wm6Dol71ej>dbGJeP3)2;_FS#JJ>H}|)fpXV ztk5-DCEX?A2=T)tao`(qz)WUvi%z;i7K3sCWK+ zh6h8tavcw+;7`YRtgn^OBPQ|s5y-t4g5C?gHU_k*TrcL16<+FpR%9?^{Lk4J%bc4J z--${TXEjBJK380yD^Olyxoa$Mn7DCXn}9N(p(v~&0YlJRJ`vkL5qn|~5?ehLgFYXE zqG6O)_#yH_PUk$GypFGNevSA*7y{zIovK+k_h zv^hfq>v_@syojFuvgmY~_GH}@jhnP5D?zeJprJfTGLmQr-zVAZqxeC|_8{f>5y|NY z4e_TW;}m@!uh_)XgnF}LvzeHvI3O$tr8)46>* zNBSP_vWG)y%H&R&wA=P5H;!`1Wpg8&c!}FwBKd3F{u;^O;4U{v{tkD#L-GaOC?L7# z+;~pBquSgdPlyMq{R0*91*%H{DP@JKQz0o~C8|+EO4w`Fcufq~Y{E6jFVgH6X^@Z9 zTp~5dFV&ouYLH)}8EZ7it<#Kk#BG|*Hj+=$?2|}7MRQ3Z`E<=Go#Zn$Ba`H^G$V_6 zTC+J#^5-=Bb0mLBbGk%wH#Fl0eSTLn?h*?%n?jO%q1nG6xf0E(gyi07#yk3au5QfL ztL+I``Q1+c$Jgp$;mX4V<4-f6W>}f^SNx%~wN_d?N?rj<051Ph`O-%6>ZEi+dRL`u z4auvU(hXq`r3X@aE4?w;^i%pF{7U%>Ep4ze7_;V~%1~T2LKy*>(aLDZk5k6s@2{1w z@%J~%HweE~zD3G+%6GVSrZN-Z_saLU!(2g`D`2t|E-2xodBg~640-FW6V!FYje@>W zsD+9m=$nb#1brK&?-2AIw1s`Apzjp$Mbm_eX*9z8B2@f^+(-5c`hNQSkf0wDZ1=Tn zyx@bsRE};uLvNIU#mcxXg<|$FlZvXVwn|W;i)~ZuZzI2z)75}< zwKHux_t`^xHIJ&=Q5Cw$HKKrSy<>CJ_ z>R&SI>WAaa$E8_D|Cdq!l2O;kEKb|7J%%hctyrrn*T3pAVgC81bG*cw{kaX{eJJ{PM?n{Loea)=iiO}c~aTuv&oP=*>y5Hk59*w z-5XMV)BYDJ70G@9eq@gmI-U@EK8^4zicYMs0uSA*oA&D6pE_j~-N=7W8tGkO@Lgd{ zVawI$4xjn;`9Zvfsg?=7V>9Pw7%cp3{Lq88vTcR_w4FmcCuj-|9T0YO=!me3Ll=a> z4#5aR96}KGa_EJyuR~vi0~`h*9ON(v;Sh%*2!}fiM>xu16vD9%V-Zepn1FDS!z6@L z9HtPr(izfuun=U`dVU z^$u84BMrhSo-_ie4+%u54_k>)AGQ;rK43|WGze!bsiF54oUx=v8iW&;)JTJH!jc+I z(yicWNZxfa9PG%xA;SlY%+)eZQN%<*aC|_E!w&@f!$AE&X#GHFi;02YP(bfdAb1zh zI$e?AS0uC|1{Db?;1`1SLNLgZrj-y&1+A1=CfLKH5#O8HW3iuD5B?v-mRR(}_{SXJ z2SW75;wLS1a;$X{-LNSD`NJw=&6CXM8vI1aLZ@MI6sj`Q;4gywV)iTOzH!Voj$tH^ zV-4YIPi%)RtQbd`16=Nj-q^~D2^VusB)LS^G?6tU1}3sj7+0AFS51t9OoMAaMnR@w z%PaDeX>ifUILqweiHZDVuGl9*Y?w*U$z<&^={bj(!y$UkA?AIEo^yh^Vjl&u=?Qwy z2^NTb6qu+n4X$=%{?~GdxlGF?o@Lru;yGpyPfw`C%oY1&i4F7UIeDyI9zEw4bGSv% zxy8J1(Q_U$SL~xDHhoCXdB_5>j}{hSreVV|%8O|Q#6qSO5}z~eIkAY@!;=&y1Lg{+ zFk-`UdQLfO2e(NySmyAKp7V}*!+jFoQ6&6T6j(A;^DGE2sOs6E$ocg!V0J?};BodwBGcDrXOEj#v*~_r#Wq$fg)6 zIl%j#=p8BHzEP4Rv^}Cnlmtun3Q2=kK3S%-kBcf^L+oJMSi zo$R!xS`(Ypi0;_Yj`}S-V6z(08#~*vVk5ia@B-9t*%iC>h)pA8JU2oP#BM$0yR2bT z8(H=>?0|W;Zj0uhh==!Yq=&|ONj1R&PV>s4sbCc zdSh81^;!M`yGm%;+7&C=#HKswxjW=QtYo9#mo>PepnPNv%m3)7WDPDUFj>m>@aRT; zmtAq91hL_MdhUL?-F|v*mRvK7o|`4RXVG(y$qvWpxyNMhWAt2@k+HcC3YqMRlPHKy zPt$Wx%YitFf|eDvTzbw0S-U{IC~Fsqmt^}(^xRvr>n*zOmfR34<-~Sae?vLSHL+q& zbjLazEy6iq<(%k^^*FQ>*|m_aE0miS((?-Cz(RUnq1+$--RQSu4J+)lQleqqj+WUq zth8g?k?l+9xgX@3*yKQT$2M4)fE5R9b|89VJ1ojese}C#C@;mp<_B77F|a)r<)s+d z1c81@(XdUH+}`cs`A!OZP3Y`IcO39QihE7y?nHMS^niXxaexj_^u~b?C9~r z8V-ISw|RSb&XZzq2i>0NiGv_W!PlVUBR>@l2ST8~QS9MakMUS>%2zN>=PUK$yFv8J zS6Yz+M;-WZ5S!d42afxS<9*sUcweappAKTn`wIGj$BF}dJBZ$o>3x1vyniFURJ51$ zoMJ_T&jdqnZJIBN*`%pF#7 zyyq(JjWdVP9{2$GJz?DD-tZtsd*Ipzj`vF78qOj@esgUzaSOM{i38}Dcum+wi0(K@ z1N}U=gN=mfi32srP*MlB5@Hh^tbzWYJHTc_^u_@jWH`}aJE0Xc4F_$I0Y!ri1>-We z$4LfcNT~^13eg=0aF9X84mK5{Cl2Bu!%7|4R)|e-AO{&(9AIN1dgEXY^iy1etp)X# zYdD~T3@#dME~vlU9w#Iqzqu29RfzSmFi!M?^CbFxUK0!CM0Yq*VxFYd!9qE)37jc0 zPf{J>+d`~|g>zy{I9FmEP+j2bLiEN$I) zng+263<)R~)e+7c#CkYggV+*=1(c8K0%s1QH%{9iwuPaAtPBn~b%W>)g9F-$+U^ip zA&#mXh6nUZD#vLY=$F(+r_?5BFRCk?LC_DWu5bpyxT0z}rGu;!8VnQ|pH&T~b z_Berp3|%#0>ms`2pcFEA*}>*T^u&QFC@-}RY+uACI5-96raHg|M)bx3Dr5-LU<*Sz zsTvMaA%mC(n;0EyVULq7P!3v6*v5$NIA8_&ui3#yM)br%E69JX4s2z_COB|~3}z0n znGwBl@Cq5uG}zA24m1r1u#f>wgAEPsL9@q+8OUd?CTwX$cO1-ueAet>QzLrffEMJh zRtL5cwdrgC_4f(2RIJkujZW?TEnEz<@IEe%OkX946H=;WZ zbRh$r9c*w!PaN!meAOIaiz9mDfEO~zX|Ty5KQ#>py^vu}gKZA|x@M0PJ&iR&H*+%qBjnNL4DUW*zQozbqxo@kO5DF4G;Z~ZjX~eKA!~5 zuzu*;8LJeZ4uk%^+K(%`cb!*JK>uJg+H3@r6_r|z`ugD$B($j6!t;a2l1(K;C-~zs zOvVaDcbaFlEfYI^tW_;>Ny9}WAh%EMyH6fkp=-ZJBi|0q7Exl7|00?ZU>X%EHK!Sq zu|~42AX+`G5c1PLT=7)w_EhX!p<~}~Di<3|B$|6zKA}VWB4o=5I=pX(Y`KGYTDCk5 zHh*>Qeg&HaxDqqaOtG4}cG=QC8?MCQN~kPxqzyqON&LiSiL~V!DoG*>(l3@)N^AOc zB3=qQMkcxALAN+W8$_Wq-BK_&ynV;6JXE+J1t0z!gm4Ytiy%GqnI#Wid${bAgj#Mlb7 z3o~9F7O#%CSi9g&?W5<$Ba3(FjdtjPvxwNNjy=b9b~)EVLLHd z=#WfI6#`SqnJ`@lOebav9Wp6BNA%Ajjq#M&?3CCQ)} z#t+y6SgJ4MAyZZRcwEJWOjDrs4C=TEJ!v-(!pBzeU4)Wov%f z8su^`Qw|+)_e5*=M8ow@HNU4?i0!_k-!_;%U=H#Udh;p~c?o@ZgNUII`tSx)ouLnJ z5c|~P&M!K2FLp*L{G?a?Nv~yps*8{F$mYW^`1(8f!vxgEXk&&w7)E=9fkq(0&PHd1 zK}Hb5?nZZnJ&m3S`xt!?_BZ+?9B2$gIM`+|I_+V`F#J8z7>RIM+;Wz0f2$C!gKOfbR(FkG++C&SiSq0(Bx0@*E8iX(0k%r*&Dvoo98nMlIrJyJ@RCG8M*~OtL@0Xmf}TA%QU_hYlfu z5#}tb_W4(1aJ!MNBQf55`r#Ot-(R>i@JWfr4V!gt7E;$f{};bzE_9f%ubpp0w>Cvh zm+qD{T-4aRaVu;gwr%3>b|mI?qtOvfA@gZ{ydF=PKC~z&83{3RV2s?Y{zA_q>vS6( zjp2V=j{R?Cog9ekOr43Wn0$RR>iRuTj+UMWg(Mi4Hw@D3(;5>q+ z>3cZeL%hNH4PvOuLutB~r1B(UfyxVrks6PrX-|sAQ#42R=MVQZ{V6_sX@;l>=v4&g z^@59Oq=WOLITpScMd+lHPitqWO!m!C`hL~?Y*2Blw}Lt4|1TR^B83{TP-B`Z)PRMW z%+obsp{7px|BDSS)J7`9LQRttYgmrSylV{$FPUGhVS&YTlv%?{KWouY6$gE%u%L17LtYHx#b>12pJ*n%~(AZJ26l-YCq?TGkGetMTt)W4Z znr977kJKn@Xi}txSVI#bb-@}M15N9#F|()Xw>4(qG;OxV%$cUU)|m17oqcnNwV5yv z_2!7=WIYW(_p@s|5 zKh(guGS8?uk2Xs!H)<}Y^yP;Ca-&O|S1t3WB?lO|BkYc4V*hq0*78FoZGT5X!{!bB z0&e$hxw`)h>f5eKovukC{#{4Z=(M-=E)xFuxh2cbzvzVSuD@%491i^HN1ZzT^e|^s z?+dFTm#enSReN;VH|5tmGf%rCAz$v9FAoUXk?>8AW#P2fklc$u|5_976D~9jr?VG6 z{bW;*pM%y}J=-=MA8azJZZe#3M5IyWXT!1I#pIS(w;%5LUyu1O%XR&J|5)~gS3UTP?U$jD&&T*Xs|A$XMYBhLdg_%#wDtP{vq5qPhpMS{}UPw$JM%9plHga zZsk&+N$#d8JC+5#K|(C+8OsJv-s-Y)mT!oTgjc%hmEL3O!ru>{?Hfm<$ve6CJ9+T* zXWK^Fw4R)Xt;MkI?xzj?u<2%zHxg{Q$H@E%8*Q$PfeyCWi*mIYKm69px@$>C6u*B> ze+)LQYqzd5v)B4t7RALjP_`3Ua3aGL_yh|+L43%99}?$@!Sh6LgV=Y2IEWP9;3pE| z5pr;Z4DOJFcMwm@!KaCZa&RH>SKatkx0vNur}1}F6DuQ6uoO}#wxHDyrx&!kf~Agf z8i%pO@m{PpYo1?&gx?>0#OrNiHMY_6Q-M^c02^oSk6Kw`#Rn>wH47}8rjtME{3q(| zZs^Jl9Ro&z&I>5M$>5s|@MlB$*|3^poX&LE@_XKY75iT*c4+sjJL^m<Iz^Ol_GVA{?ne-oIrZBv%eyiX$!0YEgywSwDPI%wq6uK+H0d9cGa)}9<}BA87C`(llI=IrlFX3+1Qt!4ezvSHEg zE!RIOe-?rStPRf>&0|hE_50n%ssIVAjQ^*-YyXMj3ZvY457^S{0=nQ6En)(WVt?=z zdt-b+Nog#bQWg*eR`CTYL>qz?BqaosHYnPzuS#__K(IlrT7jx0J}??%jL~SYK{2wz zuC^A`7-P=|+4h$v{Rf;M&Y8J8ugrWibN4%E=3BHYByCS>RYvaHF)Oiks2%q-2wYGz z9+JQTwc@EZOFG5$ipNW2!gz%EY4hh^WiDu&KlDJOnlZ20Wn=H1;;Cflq z6SvEvo%oF`-VnPL;a0%U6!DC>Min(G_?Rk=5#LnBP2%UOcuriS&8yLpNg)w0G)#MR z;nBezy67PG>B2|sHiX*%Uohrgpp5k`L)@b2SB7{+yw4Q-Oz?SAoG0!wMHg{-uqY2s zYUmxc{m0Z<-{3I&ndN5`^m4+0JhySt<~?DxQ|S{k)mm7!Hooa$%q7+N^F|yqI5N5! zb`4I99$Es9i@(_LV-I_4=BJeVFaxXtcPXg_i@<$K7ee~)lZFRsC}LZsv8Cv-4V6(m zwawd8=s*7T;4Vb^se3;lj~7xgvm4K zT^xr!gayRUoUKveOSX0tmKf;A>ef~r@*OmzO7f#ZE2<_RDzu?*^_jSi^^dmeACvqO zy^CZHXgvqWj|z>)qeryO_TEfCv-=d*3=!a*k@A~<=4Ddkic&N{wb*VXpS$Nzi#ghz zfQHwqcN4(r0bL#u(!RMS+ zFHNWCoOOx#kz_q0u8^&YA=AN(1M;BAYNvmKPJ4pEB$w2tUxhNMBb{{RWN=H)#JSU-S5#e zVpjycduspBQ~T7i3SD`$(0oOS%u2;ksbmGpkz&z2c%tr8Vh3KQ9!lfEW4w%B{i9MFF#-Nnb|+lXpYMe4U1?(T z$tyQ8?J<{o%t8v7><;?$z1MVk&4SmVx7V(FQ92f<2sXlQhCV;+gFRHJ3O2!K2@MoJ_uOFh3^ zvuxucN+OXAfd3mdu3yOziNrutBKhuE^&B6+r{-*R`UB&AMdPgvOmMEcSMub!iBGe% z|BAEoEou4nzs@wzdP_sP;auSPn4H!hJFK^i^0V{#`M%xZ?U^xKJ0mi^UR}txd+b*B zY50+x6w5_}Lg!zx;O5aU)H=p}UqeiSbLNI-uDo10H*4XDOM%Jf@^+BQSnriVD}End ze`?022a9XdjD~$vaeL;ltdqMMLj0Fi8?DTEQ5LCptb5(W|E6zSva5cmXPZ-~Nm{(7 z+Q*=|Ro9nh&N#px%;i^^zq>}?{kL?D`LUvI*E+|WF^#g+_s{&p7X3PV@ayOPXUbJ} zHS`?Gt*i_Gd;gJldws5t-4fuv=j?R9!;>NS?WVavZoK-(K zbmh&}rn@v-2pf3dcN^|`XW>9d8OkHTs`>4=^Lr#oBjL7 znK!C*7Dn%zH2HW)gVu5F_`&9uk5*Dk5*B9EMU*Ct%951@TEzVO`RwYHx%pb`hn&xq zFW!Hkl4cz>Ke0l6y~Kkre!Fmbv`feT3O;jsbMALHX-#R|)a+VdxGHGA=Xvea)eEeK zr;Hsu@c#N*yU6ktqYlNDnsJXhUtjs}N`YELqG7|YEs5UwuNHO6YD@BJbj_?oR+kJ) zn4tUVw}Yp#@1ZM(=?el#YQoP0vP^%FzdgL`-J?$n1N}>9UHi7!A#MlTrM`G`=Tymt zEo&B^P?bo~#g{8etkl(5>`qC(Zc*i0R1Ntu!jzG(B&x#Ufe*giR?+csO}hrBDG4v5 zO=YxQZ_$TQduH-LYsuXsEOr1tM``XTtENh8peBh{)`IsErX|EOabP_+T8Y z)AyY7$T)n>I<4O{aHK(FtHRDOX>6bF|)tlob>0t=MRm|o5Ny5z@%a>6&vtLh)F`q@lF`` zjb4eRiz(`)Yp9&n-#q7^BsfjG_V=$RWv<3njYO-^kHn%HXXp< zqy(_o0{ql5TpeS;cOj;$-=jt*gQ zAYc-tT!Pey-$^k$sUdxRIjOIClf7y=rGc$rJh}AvT-vs`P-5!WmHy+lNrlB8;3rd! z%TzPsn+VfHlz!aL=Os*nQpqe2E=C1c&H+`BFZQmz_SkcC$8%$3s5{2zP)O@g;~ULCUdsfBUUO z-MZF;#WMj@CgsYc7W^rSIYo`?^E1P8blAtj#_cRN2h1(P-6FbtGh&+2pgv6CicjYA z4F73ku{U6@sBl+Q#_>A|vy-rWn7Io*??0~nA&13IfVoU_muVxu0W%F)Ii3YgyN;hc zkfY0DSHN`BTsLjVw_~OqE7xX8-QVAA8(zGX#q$7@pw1m%tuy&uH4PkaUOnA7f z2A%->5KkM%)9$@RA13PQHz^;qm<1Zx7cd$0*bLgdx9G!c`!8~L1ADrP!H7tBKNY_b zU%n)2ioAq)v}?$=U9a>O&R}s6jOL+~dnh&LFHy`TN;#UnPA+ZN!*q;T>;;%AHLgl+ zEdP=)FNsE9Pd~i1oR@DJ3ehzUFwtsUw3-25Lzo((JjDku8Kik>9`j=HM8M=RTpnZ0 zcOa$%Df>#(Jl}dY>capQ+X1GC;))<+CVvx77 z%Rf6uYG7+v;obDG-SoKLqHo^6=qHB`u0He^i=Dww6U{Y2bhTopwO@1<4@m!4Kdi1? z1N(uWWZE^E4(cuX{FF!dS>6nqkwHQBl^aC*JRkM5iuvXu-E`FjfiVRCVT~A zDvNxZtOd-P6yA2@y?gdSO4UXB?#9<0Q~M4ZC!(u(aJVxAO zWXwl0k;;>>e%bO34lEo3qSY=5Oe#SXzX#jz!EPdPL8zCmh%5!+UT)GeN;@~fV$X7D z(umy}v9HKcpoxN+NWE^`rWCdA!W0aCLOyb!_yS~HfNa!XdmdA%ta=Ph>ySeoau=x! zG*u9mftAm~3YWhh4v1J}6^rZ#HfuE2nQS`-hE(F3O1uY+u)TS=#;5_DXCl)~WJB>; z$RG<@u<>DCxyK|NAPb3KA(^9jyQt_$b%!PxE@1l$*i|!w&tCoU=y_sU9E|1dsPgP2Dj5TT}4WhHcxh z%hwO49n|)IYX^n~?A3q+L{z_HAx2RY^T)^%Zu%E%2Wg$_A<$r=9fdnLw zd4?}*H`iA@_Xk5I@~%XICO7?VWSzh00ER^3nn=9I8>tp#G*gGbP>O6zk&DUZw0C;< zY*v8bDt5n${mfUZUeY_~zXqmIhs^5`ta3dvsz=r$gM{%Yc;kd4Hh04>?AZ!UbBKEm z@tv^VcDKuR^RK{AfZPg@uhq%r_IhSIJHgP7J=*aMkzs-l1+Nt8Bp4JV(t7D8sxjaH zDKxo-9d2O{kxasoQZPx86+#mQ7Zj-^7!(B3p|ttxjD|n;LVQGNNF2t?voXA5->^DTtg7YIp}V1|o?XE*HukYGe;J zPGt2kWCfRZ>ZPAxP>@cy%2ek12iL!08-n$M!ErP#jixo+Tjx$aJTFq%;X-U(h#f>u z3Jn!ZR3xAfZm=K_B(Vr5<_vmTbJ# z7InuM46WFy6?^zC9eAT~kLMXMWFf08WN*UcZ&~v8Rvs8`VXIr%UZkGThk|g5d=(4| zmKvbuc4f^nHc<;E=n?EIto+2C)MR1h4dW>@p`0C0&8PUol+j_zT-X7lQ;IV16g5}a z3H>~3yif+@QNhBFSX`pu%$89T%LG5Ssj0UqIP3Q)!+V0idsM(Z0r!|PdrVmgW$


yW>DI`sz0PD59v$gLFlifkL2DmeDSC-Fn;4rzu0 zq6)iKVV}iztBqXtIW~i#4tdm}86x?HCJM^E^t|-^3+;fxfVhh7uVUB530CHt-|h(j zL)5e=f02np0|ozHH7fd)@LY!6WymjV=Ka{7)zyo^aFIA(BpxC$hb9U-{;jdi z#-H~2cL5?9IVB^n_3rnX`wO<)!W5H`SrUQ-nT!mRk=2GV4L>HXi{CXscsba$2rq%x z$mKPfF1!pJyAiy8j$_B;7|LAikP93clK#|AxG{iaZy&8l@=oQ%Q%LTPwZiMFnK(BS zFCm%Rz9MjxJBd>#@f3vt1iL~NZ2aZ#_8%@C-T-4vAYKV%Mnv4-<+XEcyL4dh z&6-P}c-J}zc`XyUW+I=cvIJ8XuG}6B`N%0Bd2DS-FHB>tSA!u2xyB%$ZC-!Y&)=fg z2!<@=kcB)%9YNtQ`T>F--i*|j^G5OW)#vkDQ~q$&8ki5)39y5 zVwFQ&j~JJ3+x{Uk1bikT_ax*eEBf)nvDl~v>uSH z*sB!>h`I-QSE!w|qQkW%Kb1!Sq6B%Bpn&vI89}n#2fu7G(0xiubm>D$DS#AS{0%Ti&Trxid z{Qjm!cL*3{BtS;yiP{Rrp-@!0r@nV_@3dS3Q;5S8<3L0MeKgsFZSyQIJFQLlEIWhzJ=4lP>7uhu~)(PXqUzB zJ_drJ5!*Im7g2UW=qNOosIkDQLRpD|3J?l4b$PPt)5d{&ieW6t^ps>8&PxjInnL@O ztPPyEr{HY>JSagEN(6pdii}H<%@x}*6LNpA78pzp@y{W_R~sL+jJh!RS3t_>u`=33 zNMB>qX_ISo%$+CHlz2k%;f~?nf@iA~+6hiF4gXB8r9@TUEXv;j?Sf5$Au~tQY&1RW zdeht4dgq=^1pn>Wp&h%6;teLDkZk2>-Sm3<`N7aI2AReP>^2q|#3G9uvb~u_(b8kk zv;*68U?))H~ zpVw%XkdVB(QGk$;ypDsogM{Rn3)e7^kUTo!>I@Rnv}gipzMM=iCxJpj@~S0(YbM^! zBuGd|Zm$Tu@jA)$P7-)+r_^NgXq|i*$~A0#4M>k`#+{RImQI6dwc-h_Lddsa<2G#b z+ups0i>fq^1G12~7ZRU4V~gHCG3?w2V{Asw%?OfT2lDI?UNK$By$ksW4B9;nBp)0J zw;Z_Q0mkeqhpSI`hq>$&j$Ijz%CIWMPNt|8^M_o>)$%$|Ers~dc zEwlO1b1Je%Fs-ZD z?5en(;D%#fhd+Ct`$o8L8xzdY~AE@fRG`38FKyI!tSESZ}Wt#Z~$8! z!1gUSmz|Z*skDaPs<3I5(AzC+a0^>JqBfNk`_EtixtrG5O%HATqj7f4i#j1_WW-BG zW;`CW^4ware|5k3ayWoJo-F>@GWsG_0Fl0I(lRIEESV(J))ZuLoeX-6D6wIt3Slj( zaxg3dEiTG<_)`$?qS}T(6&m}+QTj|A|HmNcuM*9wLYI5jFp~T-@ndDNX zmMLubHSBZ^d;NL8W29{Ppjt5GBd>fE@NQ?P&GyTF>%owUoKlgOsK>#FLWRHI@i6k} z@Ezm7MCbHo1Sg>b&FnxSLUj6dp*ccy`lZ435k#kN4oH3I+(!-~TL}oM*;C?TO*Gu6<$%((51dA#kdRA!r4;jBX|DnnXo1TemGm-P3l9^M6 zm~VIvhHMg)O+sJyUNArt#kGQX3jhW|`*)=c9#U}Q=00e!AKUK7&fVr}1HMrk;6XAiO{TSl^d?QAwclNdySmP<)(u?5VedE`Bw4>K zY>{x4wqgB}4J!~-gdYWaKV!v;L^4!a9jL4hQC7z&tHP~B??+p#NF?z4qWBpsRwNSm zMN<6eiWP}OOIaPJtbV1eswu1L%Ia`sRjRD=;X|@K9S={n7&%sV%&5^S>Wr$IbihE3 zLF`~nt*?e?>kJ(>d;~XAGD6veQC3GQs~XBGr>v?dtAmtP_ytM)=!g}GWR$Y{f5vp$ AO8@`> literal 0 HcmV?d00001 diff --git a/.clangd/index/rws_state_publisher_ros.cpp.B9C4118F896EFF34.idx b/.clangd/index/rws_state_publisher_ros.cpp.B9C4118F896EFF34.idx new file mode 100644 index 0000000000000000000000000000000000000000..4dc3bfd7d8fb15a6a9712d4a97b49e80e3135590 GIT binary patch literal 3934 zcmY*c30MpT64Y7oY7J8%%xgme_B0OlcOIoNvwd z*0y%Alw0ym&%&o#apPE5>-jO$bq*h%zj)V%R+tB`?=L#pD7I-_VdSk9*EP~Q++;P> zu|IC?DY876?ec2p1bJZalgv%wO=I5r_KAt~!^8OW%!K7(j_%OT;jI~m4TADJdKL`* zXBy1oVp^?E+Vcm_11-OKny!88$cE~K=21VcYZo_W$zPt03uF!{?{56Zjn^{ftz(T9&z_onZFW5#z1k7~YOblF zed0;oYp>Z53hOjEfoynVRzKRvQby8x<0Jjs!X5v<+{pEzwo+VK9qjbSlM0QLM-f_v zm$tijyT8o2ft|S|z37n@o7PcrHEC?DGv8|0g=Mbpj3NHsH7hsu?OA?O+SxaICMW5) zChy;UpAGFQX&p&A^%Fm@U+NLx(q7J7_`!aSLbQv=)092IbM-yrMw(a56gXPKgii*h ztFL}sU&ISP{G;O`bM?Z^yqL83Hq{@7j_tJR_1z(NwpcxD^{`i_)9I>aQKW0lt3kQ@ zmkZlehNIkmO`%kZ8E>>;_dUnC$hc23&^pZ55F7j?ch{MiCQ5U zo;~sY$hAGs{(Z`zf@Re+eHZWRO}(NSUQ#=JYvOvd{}<7R#wL3D&g$Du>nYj%eDdA6 zYo?^s?4-!AfnlZ#W6wVn?O&xvwpmKTLs_8~)&hBfCP{&yApFg|QoDEr*T_^RS&~S& zt-7u59~TnoulJv4*{cqATE3-|EnvMP-Oh-})^vv8gfym2ar}H`$lFA`F+1 zB?{!tmM>*Xv7NFQp3F`*#qbn^6iW;*LIy<$?&Zj|9N`##5crAgWU0~d4$-7Luyz;X z>_T1(Azwlcjd$%=#&BoMnS$Z&WOsQC=P`J?81AX(X^i1QO(7G*MRXAh!-EupKvPT? z!?R?GL=D43R6=MN9-$sV$M8t~ND~Y{id2pwn!=81N%q6zn((El*r<(^liW=4r)_2c z^A+=H3Ow2HtkxPUfF+1gf~?fVpNS z0LC|HY%tJGWvw*cx{?V_3TZ+ONUDZN6T<_w0<{fgr!q9y%u>)42n4H){5r>0ui(otIkY*jy!SLfq`#91wJ-t;` zY86?Ei%j9ZC;M;xC%^`TBC-hRRENlQh-S&3a@yOBQ9$fs>*9ss zt~#zuxl^sh%p7$cLdbU!f{^2C&n3BBvJaw6EwXC+q6@njVH^WN#OcLZ+cPd*ks4nk zGDt98|Jh?)Iw#55$}PqR^>QR^@~Iy8EnURQv< zahz*3Xa-vZb9j5sZJUWd%mU2-c7Pj(??LQ62=4WWU60&6J>zET-l=~D+SSOW8VNkV zs|l|9=)V~RfLpp{{p;p!!*B*|^KPY7tBR1X!k3lrOc}YOAa9818A9;;(H@0Mr}8I&2gP$1e6hZp0Wf9Pjz=n7eK2B zX%-><;O_%#X%nZ2eaWO{>W4&Bg`PXs=K_$(Sm*_$(v&zj12zJ&KqxB55q2EW*Yz}d z^qy%CSrkav-p7TCwKaPe3Bx5{tb1NMn1j7aq*IAZ!;~ziXCB592R=d#3RN5_cYKb7 zFIp7VN=sa-<{1P!xr|)1s1h}<^Hj9LUp~d`E!^(id7MZpKY%Yus@|yW(x*EL8Ol@5 zgBny9#I32X5h$cmh^d@R-i-&Lr2;3>|%#2MX>wY)=mm|Oe z#R5jA__63zwGClBPccs=gKWY5*8@%`KnX>nnDcgbY1C`lCxG#W@#Z-{x(U@|>n8vf zBTg}L&&@C%O2U}(AgD&7Y7~;Q^NkmC)q8&kPZTAJfs&mNv?(p{*cz7wl{0b}?nU+j zvh!{Du&2IU-vD5rd%#)@-;E4*BM*Xo?)7MG!IFE|^-sKewkS#4S}wNk@8Xt0+{E@n zsj&C<1b$%QYK01YQx@q{)8K}S$R(^u*F#_aZoV480=oi-!hunvYXxKzfW#ITugDFn zdMihq#Dj=+5Lr|dIv+W^d2ZvPuT>=Id}z?%5-ozD<-Xe?PG9HVm|a(eTJ!A<>k00k-n^{N5OHqV<4;{b^d9zES!8$(O0S!DmaX0}c&nYFf4Q=q-f@XH^w-;F zhl_`DA5IGXf-U#C`PYw}tpk|N$#%N3yejLw=c^~s&fHn<7T~Kj54PFU-qRntkiQU$ zlPFLW0Xz`}#ew%r#m-kH4cqZ2%YGrE)eHf)M4Cl%Z+vmHo#Y-Nc9?MK=BS-Qw9MQx z430X<5n35BuRvkLgZUU9DjUkUCAL(*!H zK@Ea=L5d8e2A^N^g>paoza zJ&$?kNttTcvH^l;Dclr?f9~lwbTW@4E!w7ARk?RMu3RVp9Y>y{;BL;b-+F5g5GQCK z;_O4N_vYX8VkSjJAn?-nGI;QnjBEGU(_;XAReTM9?cU%QdoCqrk;#X`$%#Ea)b>Tf z2T37rHoeM39Xo&=4j|W_oV1b~PKQJwATstidu?_V<>O<3JWrlq@8_Rg6E9K^FS7CE zwaVE`ABsPNj)W_5e`+!Q**JcZ3OYib&=2~UMx1VcTUhLnADswbqs~Ty0eS3}u||Uh zp+go@iFtrri>QNgH(g` zMxN7^p9g2TfPRE_gaOeGHIE|Qkw>N1ZR6+t;bQ_hfzs&X;MAh}jmZF$Imz6S^!OID zVtYB_EmfdBre+_ce*e`?fK^DT3TccRSrv^MSrOw;4WiZ{?MaV=zqbF<@)~M~ySzJ0 zn><~fK9JGa6ZT)o6vFr-Vu{$`l5&tLkdY;ZXNj5w!U~~bRqQi2HA{<686hB_!N)&ITRLAlYN!KD)=t)0D77pxyM4wIU^P;z zM)ZZsUoPx9JHTG#;om<75c!Xj^<}!Vr+#Zo0xTl9MA{OQ7(x7|NZk^ZiW3jk#O2RF z&fgCtgl`>qIx&BK?M4}Ejupx3e=kT;NzsWm0NK`Nh%AH2%E>EG6qhiJ8Ac34hAzXD bp~ui?7-%agt7vLaRcY#KI!trAi5Ba>7{Lk9 literal 0 HcmV?d00001 diff --git a/.clangd/index/rws_state_publisher_ros.hpp.5225916AA6207DAB.idx b/.clangd/index/rws_state_publisher_ros.hpp.5225916AA6207DAB.idx new file mode 100644 index 0000000000000000000000000000000000000000..22cd916e0f5cfc25381ad088c838f4f760ed44a4 GIT binary patch literal 1376 zcmWIYbaRVfWngel@vO*AElFfyU|`?@;^LB`%p^tzhO0nk8yD;~YyICq=Mg{E7~K_cn%jqlCvc>6kUy5i&0H!M#xU;0+5 zzTmZpY(!?d;gkGlX`c@luJrV*-ppqnbV{*mip+77h-vK})qV>Cujy&7U_PC<<($cE zg~-J>v<;52J>8k^IdN^_s^bkTmXj`N#`@~%dnTW_w)oMhOw%PL;*)P2{UhGEeoou% zA1M$1?sxvop8nWB6W{nJe*II1e_EukX72{{CNn27F9nK>hKK@j+k$F7KiEQ})bJ`wx6f0zmm} z$!t|H0hf>5z{s~b=g}uVCSjm_ns-_(n1IWd1T2iO`op)1k4Xq9AF3JZ1}5P04cj;E znsnN*laEORC?6mhpb947@~bxWr!U^gXvDCt1Oq43|NEX9bEGhTGi7ID zWM<&9V6%_{6EJy3F2;xKEc;bNmT2-Z@dIs$vW@Zu6L1^;g#8bj@#^#>J|;n+yqA=h zJeYvX|NAQIKmDZE2Qel_UD$5w))uk(R* z=HuHy*=)XS30T4d8U;#q8#@<7>}uc44{|V9lrYdhu6Q7s#+4=vOF}@Ep!5TaFCZ5b zS+$qt`Vzac_W_Od=JFPXr3WS^a5?}64lu6vPpv+FbjOBzQ1EIynE-=Vz)P|yH7602 zq>77@i?cxtuIFznlmnmfcXROZ@N#gnvavI8g2W*JRQy2!AB@4kz=mM*BACFE69(8} K3^UfVc~0VIvAQy!ot(v?PLh!fP*z)3BHO2ivQ& zcF44W40=jDd1EXzKc~r4o#j|j7lhT1o0yj#9+mll>4muT)k*qaFnnWWhBvp~4MAwhwlg}!iHa9yTGCzOW*o&h4Mr=>E?`i$4K%YwOKeY^% zlz3We)o8)Fm_#^Q)QUIns7?Nr2Ymf>B8xhePBOAea|_DWz5d10Ay@<2qQ;D*r ziZ&*xT+du-{+_3kbwTmVXWI?3E>k6=(*rCaL8_^;ZyVGMq$<@* zXJCu;tOSiN29)JooR^o`{d$=;Dqa$C-VcI!#N4Q>zUfPJ^zWv)N?z!zD?UZ>fW0y# z+uWOx!Y0nYbEkSboawrr5BV{69Pv*e3j&Hrz$ZBTdpl~ZA&1oJxLso{PH6_t6UmN z%(YUnb5h^(7OH`bv{?3aLLtE&OSqvVi`*NCA;Gr5Q#<{g`FsyjYF|8SJ-q%x73b0Q zZJ5#0lz@9V=JKON6Rs3@qBBn_xFyt}(E0+w! zZ{!U7ox4w)lt3nq>Fl?!pDcS4E>Jk(af1Ej*?ik_SpgcU5Y@C4JMzx0+~j*|&!j~V zD=UqZHJPcuvvOyt`Z5taC(WfwF?`ffm+wy`1_4*OYPi zwmhY!jgWE)cr+fZPF5BLtKxy7U#CR?Q;_%P^G9JE`5aN81B{Q?+!%CNFI`$d zZ0Re(0W_!}@DYT6hF=a5RDWg__`dN)eS6Oolpp4SV(CyiBIWywX*cJ!BoN|-@cUrN zSKXp|OC%srth>FtGZgD(@8z7HV3Jo6&ZhA~v1Aw-3B`KCJi*9GhX)`J2UQ$+{y(=I zL_t6tn&kjOngh*IqG_YIAPzMPx{;m8E>P@o^W&DeMn@qMCUh#krU$uaxOuTr4iUE$5Qb}nV=*#|ox%J*i$c3U znQTtB1lK3YUSNYL$9=%oo4bQg+}+&CyS?@__XMAKnR{`fn->}DTbBQ(ig%DxLXse7 z;y9Kv@elhY2sw>t+`;M1>EQkz)xvE%!RTUs6aBl_n!n!7(xtqN9LG_wlLO1iXxKJZo^J$jO@|6%M zmWg7@gVCPpIto40{HK$%0H=_iHICATs(?kZF(9NUQ#5@7fS4IJfac=no3dBeWWf&x zy8Zt!e(m+QHafA52h%ynf1#w#W%V>0#U*`rVu6k3jH}I@u7{Zw;|IAYe-nPwAXmEl zo(ly;Q0YFL3CoP|WuiHYBb@Nx3%9!fc(6fmDyRaLcw rghk+@d-m=V6W_0>si>x?u6Rg6PC^nPa}XtU04c4aq%ErbQ_%D$8eNpEQ( zm8HB2SsT41TUkmK>~1~1VE7=8>gL{pvi+!~e&#-iM0c@NQtOWaK-)s*kSAOl-E^)C53 zO1_3`tEEtD+MeU8UK(@|R>Nk-SPqC8d{26jnyNeZPSVbCn`noR(ppZ+)y`qg2z}RP z_GY+ojgH%%)>Kk&{DhoG;MUCU&1J zvXmU9qj7GxCbTrawM&aQ+Uzn}UrHi3=3vCTBjR&s_33Ar_*-7j3=B^zVz2dipgpJ6 zS~>&c9fp`kUnEU8ksbWeF{MU7-G8Ki_TD|yv@qn%ecIvpZRpUImm90kZ7*oZeo+If zvx|F@lq=UEHjEce+|(iVLwHDA92wLW;td3TO5R^e>cB**lt@a}R3VYUvrDqm`jPG1KHCe;mds3AIRb^PsaWXzrJpl6sLgW0xabv3(cuVTz* zwOI~T|3TBlI&POSeO;`kUEC5@eg;m?1WeBG&Q5SjaLw8}%P7^JQg-)k)2N3Z$lPe~ zXe85eW!m80Higq_6seRfnFrPx1r`P)PnAEuWWAq8k1U7xJvo8&QE91+GMcwE(b>(* zJbBaj`FXWf&STS^&o&?bb&DN-P;tKDZO>s+V{r1r^c6PTM-zLwR%(J8_Fy$=k~w&R zSo=A;1ZGnu8Z1`tG#(kvCY(t78XITfw5!Oi?}Kg;@0hLXw+G?)dLEY)@u@`nxU8Qo z!~9w6!B*CD0aQyU8}>g*J92;8TsHgkRE-Bt2h7MEy~KBC(^ADHaeiy zs7HzISpie=ty=HzyuedE^#6YN_|n~ew9UpBUhB%JOcQyXLc`++;BDxAli?oi`@)Eq z>Q^grunWdveugUWS(cCkJ5eK-$xDi!M!Dq)GAdDjx+UHU%-B(z-tXhTMe@|*A*N+qHM0wT?vbvDV*E4t z+=<*+r7Q;ivBb?#uZ<7uH03vB{*_$NNm1NR{)_$GG}*Ix2hG<#GPyMp`P` zn+C>IUo{k*McCq&tE+<2m@V{3PG9g#zbE!*^^C%1CF-{y^Q2O9_nk~*fN%@!MN zye41Q?e!&wE4{q?#zz8|99S@EUf`UW?>cdJ>v-45?Kdi^WBnb4i0_YqBg_8ybgOSd|*+d*0vxNUDE2n6Gq0QN4n9P0 z9=C+SovUKnR=e+u*2lKCNYOC0%Oj~G^`4sAt3oRG4;TQPqoI4Jpx&gfF?`1wr%RCr zaN7XT9%*laCm~5DfFw*DCS+zVgcrh;MfcK5&buN2Q%HeT!kYdL0Kji=(6znYEN|eK zt2_cQfp{w!E5qO64{x1$J^o8j9#R@0Kzz7pxE7u+O4ouaNQwz>w}2{4ftwoUe#Nj6 zz*a~>k|SY$hd&NW^WWry4!)a}2CN~TCCWnL-9_Dzkb{J%hz%BU_;KaSywdVkEd;Oy zQjkT-Qoq9=hX^K%Qv-c(d}*I-RB@%b5DW}~g(#))p3Hhtzb8SE1ShSRNY3>-+FPM0 z3R1Nxaar#ozqX}> zgn#d+%_+vMMQ|isK%xnNt23iY&I_P!FFPi1ti0p-f47dIR9F6dSnBDq_Ye%W4|cw7 zoP7*eK(>ZpxM4W{?)F<3V|wQt1o+&y%QeJFwzAZFqIQ50+ z2gLjr;A?YEBhZM@*oWo^trug5KeQ7Fbm$G;i%wfxdS8Ms^u~|i$B$lqGPk)WoU{woEK;rA=k7-0I`noU-TOk597OD zmi_i!DwzSgmzh32=bU)fzZGpond1SsRAIvY_}z77eXfCy%Y zKfl9rA_6$Z&{GIhs6A{JrJdg;g152+toYpjF3Yt60O0=}288YlF@m5L#t1GYjaVlm pyIu}ufHFksqqI?*Q93AHl%9sXg5pM`$_7~;#rZKT9U{DWb*)VaY<2TKadt=WMHV6)7!h7@2~-f>u2NG<|%7s ze=Ca>cJ#iQeqdVt{@!*C=Qb~%JJk;9w=6GkGt~64%!>ZF=ECNhEeli+l$xr}Tz9}z zyUjqV=%Posu;D^w%LTl-i>oU*H_!hkw(7=2mDfgM{hLZfjOJ*atc!`?YrZ3tFJ@-R zx21EQEi1CSb^OymUK_{N1x1&|T_jT1G89+lCIOwrP?VZh454!pL3D9Za~=5|deGyKiEHEk3A-7G39fA$%kJ$nm(LfG zIr#UG$C-zREZ1bEAIx-kePq#;Z48Vn!?=Rgw?67%SS)_)<4WUQIu~oU6cn4Ycc-lc|hVXIcJ3N#X(w`c0Q8=mrc5|)#4lseDYY+m4G6yoPVmB<6zj3o%~vcAgN9 z>%0wL-?cc-uzvW#Ye{Pehj`?-%xATM(p#8~x_N9M6;M{$|hKb?sQ`wcXeFl7D#02JMo)oRVR)J}+|J$?q{MR1dw^ ze|Yoyhc`7mU#huy-dH|#X_H|3=XqK!`Mpuf>BlF%wQhgiZ@P2uQjMYm3uHL_`sSZY zj+(mqt5h$W^;es=$ICr^n76MJUbOb9h`aT*BhB{f57uc|%l@yqnMn#x><{Z?(5l58z=Cx zV-#kz?_bmKDPyKI4}%0yMImdUif{yLgbGjvCmRzlKTt(tSxNn0;hj5}n8dh&MgoDb z373g5Pz8kd?cG=5jQpoBc^JfjCZw^ZNelb4`bz`lIarw`1%M_LrKS~E02K%CDF_fN zx^;_@Mc7}--zb>Vb#HE}Kp&9n9OfKza~;#rZKT9U{DWb*)VaY<2TGLUWp;)*$?U7mam3Oo#z6Mb!dNgfJv zQVzP*bmYGD&g$7GdptuvFf^PIZ~BxmQ$+3b%CoF2&-dnD^<$m7!6)K7>rKx&eiwq? zYP{UNvdu{8-_zMsY(!u6^TzBhxVfp4F}uXDl%cpXHwkDBLs4p4u{V%zuai7^+dOg? zBNL-Bhq3zc7r)zH`mD$Va`ia$6uCVQmn;gs)ehupb7(6~YkqWXvO!K3kgLU^rF75! osjS1SiX0$UmqS+xXl70#$n4^x + $ +) + +ament_export_include_directories(include) +ament_export_libraries(${PROJECT_NAME}) +ament_export_targets(${PROJECT_NAME}) +ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) + +install( + TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin + INCLUDES DESTINATION include +) + +install( + DIRECTORY include/ + DESTINATION include +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # uncomment the line when a copyright and license is not present in all source files + #set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # uncomment the line when this package is not in a git repo + #set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/abb_rws_client/include/abb_rws_client/mapping.hpp b/abb_common/include/abb_common/mapping.hpp similarity index 100% rename from abb_rws_client/include/abb_rws_client/mapping.hpp rename to abb_common/include/abb_common/mapping.hpp diff --git a/abb_hardware_interface/include/abb_hardware_interface/utilities.hpp b/abb_common/include/abb_common/utilities.hpp similarity index 100% rename from abb_hardware_interface/include/abb_hardware_interface/utilities.hpp rename to abb_common/include/abb_common/utilities.hpp diff --git a/abb_common/package.xml b/abb_common/package.xml new file mode 100644 index 0000000..da1cd2e --- /dev/null +++ b/abb_common/package.xml @@ -0,0 +1,25 @@ + + + + abb_common + 0.0.0 + TODO: Package description + souphis + TODO: License declaration + + ament_cmake + + rclcpp + abb_egm_rws_managers + abb_egm_msgs + abb_rapid_msgs + abb_rapid_sm_addin_msgs + abb_robot_msgs + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/abb_rws_client/src/mapping.cpp b/abb_common/src/mapping.cpp similarity index 99% rename from abb_rws_client/src/mapping.cpp rename to abb_common/src/mapping.cpp index f368da4..46f7bd2 100644 --- a/abb_rws_client/src/mapping.cpp +++ b/abb_common/src/mapping.cpp @@ -37,7 +37,7 @@ // This file is a modified copy from // https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/mapping.cpp -#include +#include #include #include diff --git a/abb_hardware_interface/src/utilities.cpp b/abb_common/src/utilities.cpp similarity index 98% rename from abb_hardware_interface/src/utilities.cpp rename to abb_common/src/utilities.cpp index 5a94675..ce7c91d 100644 --- a/abb_hardware_interface/src/utilities.cpp +++ b/abb_common/src/utilities.cpp @@ -39,7 +39,7 @@ // https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/initialization.cpp // https://github.com/ros-industrial/abb_robot_driver/blob/master/abb_robot_cpp_utilities/src/verification.cpp -#include +#include #include #include diff --git a/abb_hardware_interface/CMakeLists.txt b/abb_hardware_interface/CMakeLists.txt index 9761ab1..2740586 100644 --- a/abb_hardware_interface/CMakeLists.txt +++ b/abb_hardware_interface/CMakeLists.txt @@ -19,6 +19,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") endif() set(THIS_PACKAGE_INCLUDE_DEPENDS + abb_common abb_egm_rws_managers hardware_interface pluginlib @@ -41,7 +42,6 @@ add_library( ${PROJECT_NAME} SHARED src/abb_hardware_interface.cpp - src/utilities.cpp ) ament_target_dependencies(${PROJECT_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS}) target_include_directories( diff --git a/abb_hardware_interface/package.xml b/abb_hardware_interface/package.xml index e518439..d12e31f 100644 --- a/abb_hardware_interface/package.xml +++ b/abb_hardware_interface/package.xml @@ -12,10 +12,10 @@ BSD-3-Clause Dmitri Ignakov - Jon Tjerngren + Jon Tjerngren ament_cmake + abb_common abb_egm_rws_managers hardware_interface pluginlib diff --git a/abb_hardware_interface/src/abb_hardware_interface.cpp b/abb_hardware_interface/src/abb_hardware_interface.cpp index 7be74ad..d907949 100644 --- a/abb_hardware_interface/src/abb_hardware_interface.cpp +++ b/abb_hardware_interface/src/abb_hardware_interface.cpp @@ -14,7 +14,7 @@ // limitations under the License. #include -#include +#include using namespace std::chrono_literals; diff --git a/abb_rws_client/CMakeLists.txt b/abb_rws_client/CMakeLists.txt index 1299ea3..05ddb6d 100644 --- a/abb_rws_client/CMakeLists.txt +++ b/abb_rws_client/CMakeLists.txt @@ -19,12 +19,12 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") endif() set(THIS_PACKAGE_INCLUDE_DEPENDS + abb_common abb_egm_rws_managers abb_egm_msgs abb_robot_msgs abb_rapid_msgs abb_rapid_sm_addin_msgs - abb_hardware_interface rclcpp sensor_msgs ) @@ -43,7 +43,6 @@ endforeach() add_library(rws_client_lib src/rws_service_provider_ros.cpp src/rws_state_publisher_ros.cpp - src/mapping.cpp ) ament_target_dependencies(rws_client_lib ${THIS_PACKAGE_INCLUDE_DEPENDS}) target_include_directories( diff --git a/abb_rws_client/package.xml b/abb_rws_client/package.xml index a167d0c..9e3d714 100644 --- a/abb_rws_client/package.xml +++ b/abb_rws_client/package.xml @@ -7,14 +7,14 @@ Grzegorz Bartyzel Apache2 - rclcpp + abb_common abb_egm_rws_managers - sensor_msgs abb_egm_msgs abb_rapid_msgs - abb_robot_msgs abb_rapid_sm_addin_msgs - abb_hardware_interface + abb_robot_msgs + rclcpp + sensor_msgs ament_cmake_gtest diff --git a/abb_rws_client/src/rws_service_provider_ros.cpp b/abb_rws_client/src/rws_service_provider_ros.cpp index 1b5008e..ba1a97d 100644 --- a/abb_rws_client/src/rws_service_provider_ros.cpp +++ b/abb_rws_client/src/rws_service_provider_ros.cpp @@ -42,8 +42,8 @@ #include -#include -#include +#include +#include using RAPIDSymbols = abb::rws::RWSStateMachineInterface::ResourceIdentifiers::RAPID::Symbols; diff --git a/abb_rws_client/src/rws_state_publisher_ros.cpp b/abb_rws_client/src/rws_state_publisher_ros.cpp index 73e9572..568519e 100644 --- a/abb_rws_client/src/rws_state_publisher_ros.cpp +++ b/abb_rws_client/src/rws_state_publisher_ros.cpp @@ -40,8 +40,8 @@ #include -#include -#include +#include +#include namespace { From 557ac2baf14cf97876cfd296dbe7ae3175c7179c Mon Sep 17 00:00:00 2001 From: Souphis Date: Sat, 25 Jun 2022 15:49:19 +0200 Subject: [PATCH 24/27] Updated gitignore --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index c276ad4..282879d 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,4 @@ .cache/ +.clangd/ compile_commands.json *.pyc From 44b17592965de1f6b64a8a262bf4b2f74fa2a519 Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Thu, 30 Jun 2022 10:20:13 +0200 Subject: [PATCH 25/27] Updated package.xml files --- abb_common/package.xml | 10 +++++++--- abb_rws_client/package.xml | 8 +++++++- 2 files changed, 14 insertions(+), 4 deletions(-) diff --git a/abb_common/package.xml b/abb_common/package.xml index da1cd2e..3ed0ee0 100644 --- a/abb_common/package.xml +++ b/abb_common/package.xml @@ -3,10 +3,14 @@ abb_common 0.0.0 - TODO: Package description - souphis - TODO: License declaration + Package providing common function for abb_ros2 + Grzegorz Bartyzel + + Apache2 + BSD-3-Clause + + Jon Tjerngren ament_cmake rclcpp diff --git a/abb_rws_client/package.xml b/abb_rws_client/package.xml index 9e3d714..265711a 100644 --- a/abb_rws_client/package.xml +++ b/abb_rws_client/package.xml @@ -3,9 +3,15 @@ abb_rws_client 0.0.0 - TODO: Package description + Package for receiving data and sending commands from ABB robots via RWS interface. + Grzegorz Bartyzel + Apache2 + BSD-3-Clause + + Jon Tjerngren + ament_cmake abb_common abb_egm_rws_managers From 4640a0e0955c144c25bf0ec3d39baf6c90dac6c0 Mon Sep 17 00:00:00 2001 From: Grzegorz Bartyzel Date: Thu, 30 Jun 2022 10:36:06 +0200 Subject: [PATCH 26/27] Removed .clangd --- ..._hardware_interface.cpp.B90CF9C5D62E3421.idx | Bin 6672 -> 0 bytes ..._hardware_interface.hpp.1C38C542CEC63B29.idx | Bin 1654 -> 0 bytes .clangd/index/mapping.cpp.3144CF681799FF9A.idx | Bin 10040 -> 0 bytes .clangd/index/mapping.cpp.CBFB4B495787DB8D.idx | Bin 10014 -> 0 bytes .clangd/index/mapping.hpp.63A500840ABD1FA2.idx | Bin 3250 -> 0 bytes .clangd/index/mapping.hpp.7EEBD7F4D74D9106.idx | Bin 3204 -> 0 bytes .../rws_client_node.cpp.B3BA3031F45F1705.idx | Bin 1158 -> 0 bytes ...ervice_provider_ros.cpp.23257787CC1BB7A8.idx | Bin 32970 -> 0 bytes ...ervice_provider_ros.hpp.9A12ED002ED022C2.idx | Bin 7568 -> 0 bytes ...state_publisher_ros.cpp.B9C4118F896EFF34.idx | Bin 3934 -> 0 bytes ...state_publisher_ros.hpp.5225916AA6207DAB.idx | Bin 1376 -> 0 bytes .../index/utilities.cpp.BC8AB2AD8B37CB17.idx | Bin 2760 -> 0 bytes .../index/utilities.cpp.FA6366B36AB7CB43.idx | Bin 2758 -> 0 bytes .../index/utilities.hpp.2C3FAE4039E1F841.idx | Bin 244 -> 0 bytes .../index/utilities.hpp.3EF3809EE830CF4D.idx | Bin 1078 -> 0 bytes .../visibility_control.h.6BF9DD9BAF8E623B.idx | Bin 252 -> 0 bytes 16 files changed, 0 insertions(+), 0 deletions(-) delete mode 100644 .clangd/index/abb_hardware_interface.cpp.B90CF9C5D62E3421.idx delete mode 100644 .clangd/index/abb_hardware_interface.hpp.1C38C542CEC63B29.idx delete mode 100644 .clangd/index/mapping.cpp.3144CF681799FF9A.idx delete mode 100644 .clangd/index/mapping.cpp.CBFB4B495787DB8D.idx delete mode 100644 .clangd/index/mapping.hpp.63A500840ABD1FA2.idx delete mode 100644 .clangd/index/mapping.hpp.7EEBD7F4D74D9106.idx delete mode 100644 .clangd/index/rws_client_node.cpp.B3BA3031F45F1705.idx delete mode 100644 .clangd/index/rws_service_provider_ros.cpp.23257787CC1BB7A8.idx delete mode 100644 .clangd/index/rws_service_provider_ros.hpp.9A12ED002ED022C2.idx delete mode 100644 .clangd/index/rws_state_publisher_ros.cpp.B9C4118F896EFF34.idx delete mode 100644 .clangd/index/rws_state_publisher_ros.hpp.5225916AA6207DAB.idx delete mode 100644 .clangd/index/utilities.cpp.BC8AB2AD8B37CB17.idx delete mode 100644 .clangd/index/utilities.cpp.FA6366B36AB7CB43.idx delete mode 100644 .clangd/index/utilities.hpp.2C3FAE4039E1F841.idx delete mode 100644 .clangd/index/utilities.hpp.3EF3809EE830CF4D.idx delete mode 100644 .clangd/index/visibility_control.h.6BF9DD9BAF8E623B.idx diff --git a/.clangd/index/abb_hardware_interface.cpp.B90CF9C5D62E3421.idx b/.clangd/index/abb_hardware_interface.cpp.B90CF9C5D62E3421.idx deleted file mode 100644 index e5f76b6c2b193e9e34245ff75032eef66797f78e..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6672 zcmc&2cU+U#_B-K|AtZzq2q6%*GUCTx0fDeVARrPaMFbIomLUpgl{%>uL{tR9@ete$ zQEQ7Rj#gU{3y4yvjJiOrMSY637T@`b@asQ)@BIhAaPGM`H|L&x&b<+VetwF&1R-7$ zxH=_1BbFoxLIwZRGt!pjFbHBuo*-72H_cwSqMOou{lTkdXpvdeFOb-spse)y?3Ddh zaWS7eTq}?rZob&Zw64;KPdS{#Fm3(%@xJ6fRgIuscMJQM{i>;QY*FElHzbmlV2>8t zecGa6e}yAfW#ym*jAAL~%Xy%U8#~a9c>F}=M zBx}*9DaLQBwl^35vCPKu@y2S|!=z6xow*sLa5i%^I&u3Y*K6OsT=_}&=4tt{*K8Aa zR7VXPmi9k0#Yshw783*Isb*Zmw5SdpyS|>#Lu>$T`B6yS4ww`LObb71xb9XXmdPF}uVIExLEo z?=!g-&g=Dv^sJP{nLrTA`n#RXyWL)}84i{N)diMaFhl6ha#tr5X?MjxLD9S7+u!c} znZuYiouCGR7zED8fgnHbnO1r$)~cjjna!|ADqJDgL1?39qccGxNGkIEaM7um&9KAo z8$s9zE<#r|SG|cHt9{j!@9?pKQsFbUg#q*D9fO=wFsqngcdL@K>t*$b4=ljW%~LFM}L!ddxY;R;N`+=8Gu zIvlIN06~0|_D;bnZ{fC`dTfRjQm6z;B_s)*?44#!Q0U3ZX?>uS@Q_KEAq8zcZKJ=y z1ckKtg!CLOf|#<^I;>`7Z=5_y#hJ$0kW?XP6@np2RfASFJ+^^X8$EV|RyRHN1E(L1 z#*GGyj}~Jt)pc5ST(4P-aq)N(=HfR*c#r`R%p3mbs70eA*K+aHj=Z2zE6Ql_LSo20B6)|w<` zFK>@4Zt`vjz2&_T2FeE_43`f_7%d--a1mn>lcbiCOOdUW@+);v9rD@8>LwsJ(X3to z#s$C~S3&+NsFBolAg==|WlT#X)d7qSU>X>c+xCf^PoafuS+)X_a^N~xl9UU}1#ywJ zXeLRa?;tL=7SA;O_hGxOFAg5X(7v*?^hf0%|O5tIW)~!%>VD)-Sm3*60;@JfgJeVg( zowofY@+MLm%dvFMoE@reK3F80f*C=kAj4#t4^#3%ndU~JfKHy3Fr|{7SAjwmFz3YX zntS44k1K8;qw#k){d@ME>*pcuYjBiDi+g%{hN7+G#pxs!?M?W!-n!b46+9}?ag|z6YUa7v=@`PnZVj7Ihj$XRHxG)K-e?#x`XZh=sR1h}^ ze-+9KMOOx1u-x6^-k1N37C|?G?J@an*vwgm4Kn6F(G zc6EvAs@E#msPXvNXqfTL5IXW5jj&PUyCd}B`ydSF2P2H&M(xho-{E~yUVC;soYrvw}^TMGg=r8|0sg{Y~ z+xMJRQ$wxsLUZn|VomF`F4hAujcj`qt%xja~ad3Z7mDvNFi1i`DYIHac+SVrVk?9XEtRo@E-T^rnuOCDKf1uGDa96!XJwD#fXao#E1vZ4P1m`=u2=#;wK44 zCF)BNm-C)=!pX5-Fskd;Hm6`$uzR9;`&MB7>5Vu&ox6nUbZ1)hkDXNnOI z)ekj5=G-M7XlMN>#HH?1kE@?aZ{6rTbPDrW7Z6=^3)TZlJ#_!q3q&tH9{{BR(7ayQ zXXHF>DKTkba&4$=eZ`<-8_Jv+pSko#Nb>v_caj)59kW=AUuS@Zzvv?ROD>SPz@{T! z@iHw*8!*~{MR&A}ZhGtoMnAA_X8hv&sQ2_Ys9l+v%oQWbDBbZ^gq&OZ&`$@EY#ckz zu@4s$47jQi30h=1Q=wgfO~5s5SzwcY#V5U}EkCm0o%rgc*Yn(o3$q^mVvI0Y$f9 zS?Kis^47cM>$DRS4%yedAmM%>=P90B1bRjEtJ@LKI|7Ce+YH z=uTAn=l@Dtj=@?21|@(AW)GO{p|e&E7}U`7S}>~xi|18mBVI3l!<#gnzZhD{SQYmp zUDFPL(gFHq?;I$d1Kx;C+!vFhv3WvE@A6(2JQsF{p-dR7SflB1W#Ju^4p$c5LFsU1 z;j7=fM_(P%&w84KB**gUm?OU5d9$wY_yB*>L?zPVWwG@8c6wS|`V1Pep~2YSU-Q3E zpq}~GtY4Fw7B459VM7SVcMwEe$`aXhoa&pK07H(PBCnvRG*wyGSl2*Tplit0R$;QV SG}To#)YyEUDaS}hkN6KmBk4E* diff --git a/.clangd/index/abb_hardware_interface.hpp.1C38C542CEC63B29.idx b/.clangd/index/abb_hardware_interface.hpp.1C38C542CEC63B29.idx deleted file mode 100644 index 28a0a4c4fe968950f4fa392cf15715f1243c353f..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1654 zcmYLHYfuwc6yCjT64;PrlL#g;A`e5rXiOv|5XgW?ASm*(4p^ikK{CY(R$vCG+WxRA z7AB%)1jUiDsMu0LX~##Y1+*#!A=COOibNtZS_`eD0@9AsyV1?=%%1tqeBZtIobQ~B zq=bYbCW5TmoK#+zUz&>{2;vR@lG5UWdK5wIECeY(*1x{HXh`LK*Y@&#^vbe}V|TJy z;~tpNVm2T8u%bKL5n9-bng00Phv0c(Cp>mH-5%|*MTdIy~`u5w&M-m zVWQ5V%hS6YD#Z)?KHJrX{^qW_B{ClO7g^(LbWr?ih~L7lU43RYBq%KKxzE7pj_Pyg z?_H?v!l!bo%&f;Tzxh18*ZRXa^L+i9qUv=gw>bU3D`Kn~Uy#ML>344ZJD~i+rG&JI zWJPdAdtc{hTp9WSH|9c4+3#9w$fawQdSAun{4eG{S!5Zwdd~46w`JgA^K0`UHILPfL@*~JJDLs{dggx3U>ufwmC|zD@aoxabA-=R zqUxhU=ZUV&Q$Jp5P1??%A#M=emMsG|^NzTOGH1W@_J+?64zU}bIUEJqe*azDdpPvA zB($P1GlDPt=Gz*<;>X+fEbgu6DNY7qGVT87XP-&h>_?pGWn)>vZI9~HIlH&r>R8(n z?tR-@s?AwCWAPA(I=;4wMQfZ2cFI3BB^8BcE1VCba#?EYOhX2=)gm{qYX5w# zsBj{a3j*K^@uBevuHfcZXGI(5I(1zHSP0K|pvn$364&$fQnwO;& zH`<;|r`$RXP7@#yD(tAjj;iojZmiI)xRr3%ButF%bqI2axaVmZ{nP~aL=57YG5^5h9Nis4G2Ttu0PqAm;jj*Zj=?!-Evm}IFI zU`p1XoUq+;f4pV*9ZQWGo+Ss&%W2$by)sY>YmjHiH(|IMs0j?$13f|636-RYYZC7l z`~GqL4y-{Fs8I=;cq1FrgJxl>4pYZazCbbQ1~p8Wl0zK4|C4k2#7Gnr$8+ODD2o7a zSp%E$R~qawV+&)CmTzTZxC*GG7#;?~VAKLFjFBJ`#%K@?V+@FqHa6#GI7-`Yzzg-^ zdi}`R-jshIOiaR*bYN3<_nSZ0?bE_k7pPm&lq%cn?Z^s)sbZxf?Nq@FkEz(3@4?jQ zXABurFYQnQd3Zw>np+ zy&F?hRF}u(o+ssy)vn`TB^RCup=y&6@wM=%2NsWitGbfQ%;hmv0`<`rZHLVe1*r&_&^0A3anq$NUxC zmQyj~rDwN&VbZfj5q1$1rF|;3Y`=|bu(OXXYW(ERWiPDMP)d(g{^0F;efhYp?Zr~O zxa=D>;yD*QceyRnnl-R$@biZ`58YZK%BE(E1ZjNzP%)$Y=!gCGITjr8wd=Clg)*$$ znvU5P%qow_8L+#(_{Xms8w9B%XYY0e9rgalF-V0~kPW)M^0MPAccBn#u7QtV$zT1SedAiEy?mRcpR9ja zI_GX$S#(bSs|2|XSEZd}YR#ua%9d{nDd1h4>?=HYC^z0Tp-5VFxuI*s?B;0)dw5Z2 ziam>0)F&h?jh!(s%|tv?Ehw%y;)_bKsb;3Rzt0MXwv94{yyRmcaj*3L-X%HpfaKEk zdYW1iMVe_n0dcnaFEX?&=7;ZDbj(F%k?eGly*~=vrLxt6%s)hEs)hy3Q~2kky4kJ; z4zGU(d>q(cyk+h>sRH#_-`J*HNZMt?nO1r}`03sAfgWz=yAPc9Em%}5<+YAmdSvZg zdxdF|Vh`Bft8c#HI3EO5%bd68S+ESG3xOK;-A3nz8eC6er3~q1kz2?Fl z3V&5xzF(|+NzoCb_gd3c%RQ1UO#j+sS$}NdTk(3Woz`0i)rXEJd<~l#H`qC{-|vX@ zD@!$W`|CbMxkn3wzG}^~!b9^vUIQ8y$@$q$F+bS`n?Sp79r>GKb!6{rAL9(`T>OZ+aQ$s_s3YIlW_f+%+v*v(tZX z&Yb1gf5~P+)UM!>c0KJDkAtO1|?y*J{f5yBlu^vhIuG*!29V z{q?iOz10`vpUM_##2&RaF?h5$?$)?3P+PdRMf=9*`4wv|vKOj8OPs%6bEDFF+YztY zsY!RE6E+KSK8E`5zPf38bA9htzpryN{LRcAOWzID9I#ORT9uT|;UNHlWa^{x$1wY})9 zzIk=k?%q&U(`)(&?CYDe0EwoS~BE&ot)uJdg^IsPjG?sro@DFUs`byG#j@ytg-8CM3xE1z_H4 zo5T+*->;e5=)b#-sv z9hbFn>8)jz*KIP>0w%;uE{$6v)2Q)Op~#?ON%C>c-9AExoLr`uxP>aDX>mh>oejsy z4}JQQ(`mKrkjq;Bh-YD(N{W<(l+xpu+m}D~+M2xP_Ph%bb?4UHIP`Cz)U1EAErM+xmjCnTL*J2g zFJcB8IquoTUtVUfoWj5K<GMiTe3JE}pvAt5>(@X+@9AN{9Oo^?tJwqz=~!`S0~zlfn`bQhX=;XG>R}j-*g5 zY!NyRi7d%PmP$B;pkxTD2#JleHIPq)Ab@ZH?!fblDsN`KkQ9odwzp9F7RrW01xQzb zEMse`%#MdZVygV*+WRA)UUA1vqfjggCBxw=h+PFq#?)k@#2MH{OjRd4)I1PNv=}o@ zN9lCpwFIO~s8=IJkyGGLOm(_zJM7O07D)=l&8vDx@3<+H4Zq|iy~Z-eLtemHoDdhi)5 zORaHZ{%kXxPUU}&WZE4acnXTApj0^Ifp{KBF}9PHq~c&Vap^c)(M#lL-{~>aAea~g zOeZ%?+(0@xQ$y140I~C~@XSSfd;c-Jax^GM<8bHzgAOoeET^b&&cYsI>f_iwH<&x_ z;FxJQigu$!IP`#M4@fYkQ&nNCr$FzPRLX<8f54|3w>*+%`s8saypS>50?;o2qj0zY`WL{6>4HFa!p zP(4j8ZS>`K943}8e3SD0lcpC-3PsbIZw0AV&wr3j(C;jhQ>Yi2lF49-& z(wNV)D0vpy;gAiI*}!IOjk#i{A%HmTar^ZpVD51_vz z-O#?Z?bV0n49D!kS)$=A=7|o2=rDbv)A%^{M0c*=;QvxtNC+(w&%O3fpM>L%Ljp)7 zfHVVXsG5dqtdY?4Es0vGz(_*TFcj@r2THmu#`6k@Bp8%~L0v*&N%P>^6NyAJ2!cWI zkO*m?o09))2a$Y0(+_AR^+7y4#CF#*BI!o;Zq%3I-pQ|ioY*TxB}(1MXP_4qdr^gf zepKwIFo=qS6h5KiCkn%;G)#?0P;rDxexu@V3P)LrM_HtLI7=y+BuUpC2Ij0gL1+E50rMX!M>)VpygzEWyN;>C0q#(w&LKnrE#s z7I#>997bafqqvN+mvI6EnJAx$+_8XzjLm4UVO063n2$=6q=RN27p;6jp7L>&J&vjj zTw%#xVX5-H4AM336)zyFr!e~|xG>O+yk^u=ySsB!{}HQWq!Y(c@;I_JXYc!Dr$2iS zF+K(g$3T&RQz(84CA983dg`TpizTW$P^<$@20GEI6P`M z{QxKEopY5LdiA4_G%)~%129Y9YQ;{C#-u4kl8Z9A$TLxD)%LtI7)vC{z)uFl$ycA1 z9(or1l}OG4?<{CeZeLMgXxgAQj**lCrxcVKC<9Izg=(~`Ml!A%oLz&?CPIq)eyo;# zOZw9Q+y>BMpbG_E=wi2`7?%5cGq)g_(40%aoop zQauCM8KA(x9n`*qMi#0cE4GYZ{gJ3Hu!JwLL>Rcn628U~v2@)ma4)+pL{xWxeFx+j zC`G+eG_fAx>(rU_2NG2sSk-|O1D&YYiJD`P9GE#JQQWrj*H-_(ly?x*5-=+PYX+*2 zQ-!K_$>&R-=2*rNRRX9cfEoj7D3ONJb}fP5y@ynHkuh|DpabTOg>$l=MngHHiU&?S z9ZU+yrvP_uLxz&?aQzBW>k3Qq3XAQu+(V(gW+s)@;xP)-%AXZSTV&igJq;xX|R$M-Ui;JSYxn;6k80okiyTvj}$u$ zc90^#Ab=Em4EB&>pTRy-95gs+<+0$q>LW!7y3*2sod&Xu;s)y6Ks^tk2%Bc5juk9M zk`D6eKwijepm+@?F>niwZlU=iXVG+p!0RSt5KcTNy+!lobl%2V36tN6EWJdQiF-&w z*f06`3uI7Ff%lZIk7k_Rj4qx{uVjvm?DZf`7QoB`aA%+s#aoGy+wiNCi$>Hr2&*(#@0xGMs3Xh(@`UcR5=PWNh5WGZKNifXtDtx-BW})$K{) zsP0G#XLV;%%u}B?d6jC{8NJ1dJmSP#;Jw6a=av4QeTROrf_=OS44#5uhE&FcCPky)X4f!2{f)HHndv-I|qD{4jxXT6kT)JW(pz;Ic z`AO$=FSD^JCdQp$*a?=~Q=C$#d%f^9U?dCG7HTuaCiP7^Oc4Uy5V|}l9n_FOf zi^6R%ybY#|Bp38^!GwWga4rTn21-Cs0(K0P!lF`G#y}Z(l)+L4D!`+H!c%a4N}paO zEU1LVjH(KJs$e|>)iApn92uyAxiv74fjV%mqn;bUwSm@(LCF{-D>oJ;V=0_M$x{?E za6$%7WK`Et?mCjFo{e(Z6mFp04GP7mSd2VIRe}m7NCNBwlz)Iq3{;|4C0&eFIH?Lr zLZr@V{19a4OvAAeqKw7C)IqYNfLj(pgHo zCgg5*OY&Suj4RNn0}-_X)9!B2kn-XndF6A!CX5DRdyGgF+{AI#FSJO`w#A$VloX<>1dRW<_8~CrFiY#CrWz! z1x>%8VEeVj_r82SbB;9e7U1J`a9ya|g)_n@JBRIDeASxt?-+<50|^FBA@3BbgzMK#Ui~<64H?WH!Jfro!)3jT z+`om8fHYHRCfOt1h1^N8L1+Uhx>2Yb2@IpqFokfIP&iBE#HWo*2bRq+BW>IQ?OXH( zEJk)QDnxzxdEM!5w+2yV0XqvwUX+iz`Dk=9;zppI?!To()c`Xa=$_eyoGw(1zS@}7 zoAtSk^z0_^Z-U{e*JmHEIhJ-~)R@yiGn_7**@f0|HH*GZd22-D+6Wkq!0d!m=N}$u zP#;HTG6LiyXtEIrijj0m&!WLuG`*y`Y0fZzoF!?(hG(O8+4ZlP2O|zHAq}K}b_$IY znaIvWxwP$CS$~{1S0k!Y;FVHUHM&;gvMUd|PW{C?FoU#I01FGii-B^SR8HTz3RJ5= z!>gTc3ex6RpOcoZpx70Z%`kHt;0pcONhDD$(0Di`WO~4P>;NN z@o*Cd zl8}9q8@Jc{#`Tv(RR+8=&}Et`G%ScjyodR+UWTJK^>g7)RJ7Irq z|6J1FB-Vr^mO|c~xWMZ+Z(4{XjU|`HnlyH7Ba40X$X2-9<=1WQHV0zU1A-n{P$F>e z({S)jAWc+(YZZ7i(2BfPG%35fXu(&pP80GV)4?d6hKpM$e2a#QTolPg_T$NZ%g=jm zIZvur!;EUMWuOfe+mQcc`C5PL=N~r{RVJ`AX%?4|1nOD@Ma&oHBM$ zBvUYYNMvlXKrsuH#!j0w=cgx4>e=`am_Gl--Vr$`XfJUX1yWJKW*`w&5^++y&>^=D zEh9QRQJ@kR#%lXy7|A2BdqhtYkHPLSg>rB!ryJQ5aCrg?8Jh~Q zssMWip2Ezh^f_08WhITiRbW>|Yt8$fSd*jjmT-F(1e^O3eCuArqF_% z77DG%X+`C?4KJIXN2{JCqlgBnX!G6v=}?;lF1%D=6+L1R7uOK+D>c|P&xs*!<%z*PA-ga zCz9`A_#JHjP0P^`9xs|bcQGlgU&F8AE5Jt!Y|PI zMIi`vf@pvbL7fl^VW<;^Q+}n|>GLPYuty`0Y5@&O_kn*ONKRFb3(L`qb-L5FIojj* z=zhwnrfatbI5iY%fm2JN4mfob+Hh(c-8$NFdOO``I?$#A?HGrhIHMCSg`0!k8SV~z zO=c?#bhBun&qsDXP8ct-B0uWT#7{((0ooZoy%=39?I2 zUM{0|hG|KwfEXV|!=q@&S-;S)zx>@&BKZY^U$AKG#*r+E(c8wcdqwhcj@~IU#&u|1 zho&kWPRH`E-A*KJ)q-Lz-7q@Pz5|{4RZXt*W?a`No+Cju5_HveG=?0^Q=tJa3SU@2RBvClGuB5A7GPzB+fWn@+b|#hDt6 z!dlvzq-{3RHl(nVwj;$H={clul6F$kS-Sn;(le)(iT_N{%cQAl9Mtxb8u5wSO-!G_q9@?PKqK-RQP<$a@I=|TV7l?11eKF?KF*=kIb<6`WNWUzkq4<2 z5BzwV&|OA}%P2kN!m%%Q54Oq>RVt{ZQq^^2Uq{)gTKaP5^0-rpDg+cl=;j=Q;xQ;O zHLOHVUwlA?410-SiHo^GNGqFd8$^Cz1O7EIoN8Sr-m-W31R_ahi6pb6W=^tOHYujz zAL8y2xIUtrVIA`7kUw_QO3uflx2%j!0x)-nB(Jyx@|S=+c6%zq*o@wsGO9e}=FzZI ziri8PWymd~(0~>VNY3kxIIR(9GSGnr9cXM9_WkcNXYGBXqY@9HlNp1&7*uhtw_Sc+ zt9l(#Rf2sb&F5Q?*Md48vu@wMX0SDy=z@h~_q$}JjNa|~ zJl@?g-}NB9$=M>=Y$}bbePGxJf=!$o2?d|?Qb>%70D}m6#5#+@XOWCN0Ywr}YNO7THIZ}Y zeIxyIG;?(FwT$#qmz=$cH1Gs?PiThHh>IH0$4^$A*K^bPK5=&j^v=)_lY+u2D8@)q zQ6v>5b~eYie#9cT`J)C9k|Fpv(N;iLqNapb7XargddC7b^MANY$5DdY>ef#)*uq4oy@*>QSTmnd926X!pX9&b-&na-oGJC(tfflrEp&L~z+O?v~g&{Yeq*Wn@Nmo}2 zR(d8)Uu@?$%Yj}d4Ws%n8eZHpZ>720R(o;Aq7V6f^iVv2`~eCdkpF?g7vz7T@Duqz zDI8((kFdxII)ud!p%BI5M^T7j@na~QVe!wfOj0#m6?d5w9wkeq6y}uD%&HoB)u@;H zyEmL^OOGsr9FWhU`^-&Hyh&qmAsQ8;d0Np?4V89*C8>T9G%kV;0~yH9K+e@{o|--9 z?p89q4`BEKY%--{e*1(t&>OZOkPiYbqY4JaU?6)(6zWEyL6(2Z__h7x`NUxfa7uvO zHdo<{Dzv+q)LL~tR@Zv;)sjC0|6owEK;(oAzU($^&*DO~}houMAD@pI-d8h0fw=;%A>= z-=gB^KfTQi9dD4|&SuVT#oxvL4V+a+uU&J2ol8Ue1Jr+jCZz^W)|@Gl>&G#srC?nO z4h)omRT<4ytC3SpBYF*TYEZfS`0@C>C(_BI8Jl?rkc-MLFz=%93d~&yu zLYX4uRR(EY{x)&Yh8Q=1pn)diUC8Z1t!9%y#Jk_!1fogalx=l)QaEO8 zTTN8Afqk1!NC_I0py~7V1JCB14gNq>Cqe2Y&B4#1$~l}g_Jxb2N~2%57@Nmn{1{9- zHEg0!JTTf!mP`=n2GO)E3WcMPq?^$w5{=?r-pL!Em5G@X&y~Qdq)WI3?OV`o?28!L zg+{-Ib$y3WzK9q-wJZ}XbANrfjAyj>#CK9T9wg#{M48K|dKopwK9Z3%VDtkSqe?^B zH2T>k3+1zrJN9*qqyeK}#u%GS;AYY#eFwOADC7Y*k3u3u*XzrpY~%9Tc|JC@}WRV~=pf-?ghsMvuj!&-BdBqz1f9rz6xzG3p;!p!9| z87@nRaTz$2(fh_4nqF;5cZn(UH;Aig+$YK9Qba zGTvY&wF_mgkitOd#Q$3g1^19sqAh1hn>B{ z9LKp%&MvO=R%}?Ye#N>KJ}Wk@SiNG+inYttYXrl#fD(%Z#(n>+hE0< zZj{WBPJ21;vPH3GF^`kDH)dC)jnxbpF}15AM@{2aDwrnC)=+rRIDL=aTVJ8J;RkJ9jCTenJeuHS$V)fY*tDB4~d3-*EY(` z*)J$Lmi2!6Ero%>8<%0#tDwDJ{{F3e8(}!K)r%~A6DlG3BUZFfq(&&ez^fR}TRbL!&2Vu#)SMT@7q zuIo4*Sl6;*ZIr|Bdd2gJb<4C`t5JVf)r1v)J#%5cT1M*l5i`7U zZRB!|#2&I=uH5bRkLB|BEgfA#U$0_`_ULcbw_Y}D?-mU^a6>sDE7U%7Pu|_WUg^YN zyYfX#_lb4Rx_{U>LFc*h+vzJTT&}8E*7`3fb*LBnyuWXYwruM1@4+&sKD7Pb=i@KK zU8axDYg2ktlV2VBu*cw9@Uds!lYA1#?DJXI+I9BWYbT8<^GizC&E706J2HDmwM&`T zsa2X@tEGMFc85wPOcCXkEj8WiT7Gkl>a2G+A}cKfcgLz~kD9fwS18%$Y?60u$IYvK z4I59ZlzEP{=xy=PI`impn$_f+)z`BVOiG)kzCL~N*q#XySa7ms*T$J?xuTDpuBK)E zmiZJMaKtA^t*(1smP)LfEACmOl=oAv#YJtE$M|vf_7{K6ZFs-4;NDq z^sO-N{U=v?X2HFs+PfVLIxl+U-kVVOE{1zl@qEEMTkm9h{YK5@8E7d~;~p-bH}~J} zwYjx|$|VyI9#0;#FJVdf7lSR5Z>?|cbIh8%syjTUdzZ&$tMe1%N}ZmKDLv6&;H@(5 zi-ze$?0uEp`Sh6ga?g2VYvWqg=qc?&6;3f1C?U?8Z;JlP#WHSv;6JE#aH@k*ED(VusCockh>~TCv4) zrNrmkOFX@gbkzMDx$kuG{quV4$A`XNPl@oBDc`5+b+T6P-jBTeq(1-PZ3dUig;9-$ zTXu8_FYr4Ak4~`^KB|kcjT@bbVsOGJ^a$BEC`}z6WS_)6DWrfV) zZ8l$J6}>VFW$VQE$8?VnKyp3mpOi(cl)}3+QR6s-^4B(eyK^hINr8oxt8Z* zuXWi$VI}#qoy4We>m{t)owvR02+bNNx~1Cdv=3io&sfP9HxuOt5sPEjVF%|HkI-o}RBGXLN<^i#We4<;!csnWHSY*%xQ}1$2)J ztv9@3QKcO9Eq24dwcBrY!O=%M59~W8>0NV~C-zzKRlJ#g|8{wVeBW_rYJjlGD1bj}3k!)N9nyS^oP?`~1F`lX2IIK7W4jLN_tw z>xt;wg=gB9>xkcd6!qam|C0T>an&1ES?yU_7n6Q5*5mt4Zid-|tsC-}or=9XZA0ml z+!w#nUFH_3ZTQRjIm!CE$j-f+S0%7SM7Zz7t~9pi>B@*i!UmCGh-1mbvDAYg5M=^U zT|`pU)==p*9D*PKmG>_$sCS!p$cP-Lra35=g9<@V3UZ~Oz?hnkh}~sjH$^e=@YP%m}-olS@lpd&SKa!73ETi*CLQBqF#-;;!&`j znCf;`x6X(WER+$6pdE0LaNz}ky@WlF@n|)6#2GjY#LjxJpG~f$$;)Avp}-4;(Lu14 zw{`B-~T+W`(^$-u}JvnUZ52O5n>7@54Z_-I~ZJAAe#LlzS zEf;6Z*g0%hf`%nHE(lt|uocEJmJ`)EG4KyD^_tx|=ZK2vfnn25l;}k1Am{>#E|6wS zCuzWNPXjareDTtQ^24^~66TDhjf4%cv({w|+g%gNmy4c0**R=ifN}-oq1S?3Eq&+{ zcnYzwhcuse=hsCgwK;Xeru`_saS)sb zgY#g_bU~mua@#@TwbtU#g~Hh*9u8Zkf<`K6203E>AeJ4Q!#-nCCKlO2a2;f>1DmlO zry>~*JBZUR=fSVL=KQuDHjM$*7+~HcUsYf79$Ac$+q{q1ee+x0Qh7+xXxJ`@9 zsM=4Beu!zGj7B`GaB3ax>3MW|H6D)OwHh*iK%-Gwc zKLa2bfQ5?Xr9T#ZGX9rHqFAO;EWxPdsqXS!sSZS9&9l}X4m&IihM|zdD3Vbj8AmdZ zfl3*uG8}J^u^Earj4B_w`KUTt&fol)M0p2!%EwUQ7-}$ZiKTFfrNQ?wOx3 zV0sxiGVmOE&rwJ7&W`nchpmE0Cyt@aF=UUK?)TZwVEP_n90bZiz-8bBN}WJyojbGL z^izIB6IBgxYhVlmZD`eo_IhD94qZMTLZZrrF}a}6z(Zs|#F6@Eo#em09w;D9ya%KA zFwMYf*$(ac_=!Z4i}Jb1GZEqX4XjjnORCp_N*(Ah(2jz3bR6HZ?4FTnou()wDF#k4 zs4*Y}j*vnn+EpSMP8CkCLWl8}pA{c`cH}$p91FZy7-OQ^G}i6*hiD>60Db}(neknZ z&k*hXN+kEe=ss9YeieD+*?svCBIyG`AGla(d@9{IV&x~&pYtrS^DJ=&(pX|?EOARG zAAyVTmIzVZ2KH@GVxSoHi_ygTH($5Lq|cYAYQU-n>=|f7ZX1pnj@H0T9EsGn<%64c zURB#pOp9Pb5m+-&ft(7|uuC{sT$W{dim1+j#u?CLAO)pUP|mK=_owGKjekf-TS3qY zbB9AVSu{i8no*qw&S_9)AQ6-jL1j)|y6Wcs+GV8HC6>%37TbQQt8z<~xeAfoLCHI) zCd2$*Y`EBpDclX+NwM5;IVn61JxQ_3 za1|*w8g3-T7Q-#1*lxI;6uS&}kz$YG9#Z%j`jO&*;Q=dGkx-lGs;$dd%E`eu)2bE5rC#o{wmC*(F9H&1= zN4JL8@Zq=S8MM06&md^ z`ir1(nx!7aJ#${i$x1^INQV3HE>EbO%PC1Sl-tWoc9op+x$+d>e8f+4h%62?E z?R6*AUWe{q>Q5?{!pu_o%o>o_fO_lY%iAVr3d)J;cQE=6wmuFUTZ2b#2_};5g6%FF z{c@DXzgy5veg~o;5EpHZ^--~C*61ScazQDVPTWIOdx*R(a#@}3Ha3OCxDAZjz;aun zebN+<4mU$avOsgeSf*I7wO*Gg0zoB^E~=xTa+E?4s02|62Yxu6^9bNaP>2M6B!wv8 zM^U%{dKbW$@sk8&l4w9nhB3($QeaF9g>)E~4ig!h92l2F;T9O(0#ink3kJDh!ayN7 z6oNAYMIa~wI|hnjVKKNfAOu$-EMcG&TuUjGfm0cMdgU;`92POE3h=6cwG33k^h%h` zKo!iXg1HRTfI|)STnA2dv{n?#L?KzZ(I^v5;RMQ@ppcFu({U7|x`v9^kVN(CsCb>i z4OF~Ap%A%+$YWGRs9c03(mq6`hp5UxIqH(nVHuhcnz-G(iYwQ`X%NpnZ_r;dje$3tVO3m@3w&aE=A)~wBFO=Vpx~haexGlEHKUjGX@G! ztN_Vw{{Y1wAlrAs#jOvTkI~*_p=1^+?Oi&!X&@r-j|5{=36m;e3IkOzr3x$E5{K_YB zt4O!@2=*)r8SfChW6@=6GRh#33Ib^cP9X0Dst5NAdltI<2qXc?T*RDgpDrRUr0^E; zCPgQTbRvO%6zQiB!V(E#i68&GZpnN1sS}9L92lEJU%*0S7ou|b*FV?n?{sPtRVJ`A zf#gN`sF#n%5urDH?eu;X6IC6U*U{~?9XajDjl5hR-;?>JnRGfE_}O4|;!W(6RY55? zhKxCNG{b2}^LDg8RkiT@#J9#YuKfn1-!T2miF1$k*J+88=?Vpu2@zMJ-7aHar{6WT&g<2SN`lCJiLQ*hCsBGLW5tiYeQ4GB=zw(}D;lZ2z!Hq;Em>?kO$=nHZ z?S~IkB&!@cOwk(SYSHwjg-Vx_`d0~3BNEgj=^~9s*?44UtDM^FdE?qEq7nj62zm@u zp<@*;$#LtQD5b_^v5X`U*omOXKn9M@K>ggwH_z;=?wdpU8_yaU&r%*fqmiXObUw?Q zb;|deO?M-)Nnt6butpc`b{xE=vUMhrbb+7?<`)TEdbMY6K0}(Q0H+G@WS|LoO=u## zym0<^$u<-6AXC9Om4=5L6w9IEAs5ASk^N-+mZj(1Hl8EZD`9FS*fP+J+-BrIUAlUw z^@~qFM3n*T44UBOp?)5k3?C6mSBH*=H6z@-TP9u^ART*;rti_Jc7)g~$Hj#_QauOQ zIdtzTM598SSbKk+#Ff=Hmx<~z@E+56Sc6VAIDhz{NTy)ukjU6%0yh&>hfkX{=cgx4 zT7BGOFnuw|-X1o~e=l(u4zl6EW*`pL<8X9~$U)~;9b-B>;h-K)CoT?UbTQ&53D`+A%escT*HHhJO^!sFGMJxz)A(Ee9^b>4bb)Rcg&xrDq0k4qeH1=`?gt8=LH9F- zZ=m~)LO{z^SHC1DqNP z%{ZxNc`(qq6wg$$X{O(t4tb0`(}mtk0qBIb@4lN(-uHK5-^bz6S(7Fki;9 zrzC7m@GBzmM}a>slD}jMwusnY-#jDldCuWdPXSF}auFH-#|NFAk{Yc%qr zQC&y2!R6h(o0CZO&mi~=u46l1e|P9yGlg!qTyt$kVJ&A((l#488&cTG*^y$F+$>Vq z%h{{yF4=ZqNz6$#;y(lQGia)shwMC58osI|!z9;~1`7&|e|w$UO-!G{!l&THKt1y6 zQP1#r|0so1N9e{I0qPNSKF*@-S!5eQSW~Wnu`8){8u+Ja4wQ`2$tXARe9%|BhnwVy zDhV``sOlQBuc5*u9RtO)c`B2LDiD+d>E;}TQc);9$yzAYxOeGDGVBDFcmhk-%rLNt z&9?O?k~H9_fzhPkB1HqK_v%ElSg_d9e6*eW=%~7v#NA_XdQ3ON8sya=fB2%69G!uvO&+S`(XdmDD#a9ps3N3LhZc26j`H<5xgO0K zXhp+T9A_8&^QO>Ytl!Y6qyp(=Mj)g5YWmtNDUTtiglFr%F2^Nq-BL|xZuw{E2w zu2&|iJkZahQzS&T5S124&MerxRz8BL;#gvFERuSqu%uI13X4~sa?iNfY(XAD21_P` z#a?pCDtU`qqAD@I2xBkO_d65WnW(tb?9js(jxuy=3xQKeuXM^$P>#+X!F>b%e{(#D zpLP(m!vc>Do1!vps;&@85=%OX#rAr#yLFz^0eZW#QLu6D@O3X)IYU>yYiDluw5X4# zC&SyIf18e>7}>?BY5~D)FFq9s#Vo@v>$;i*3_!*R4r+aBt*qpgPNdIO}m~Fq=GR#9uX8L;4z*FEo zr5Q>+F04ndEecY+u55?<#9a*N$IuXyh+>H-$w-n=JPDHSBhnWlVs^OyL!jiYX(&Y{}< zqkNqz<%pyMj5@&f&_914H_7;HAQIaNwzChnzAwx3{rQWG=^PlJqj^s%ilx%LCk@5Z zkbQL7fko3|Ce!;qa~*T5kWUiEj_W4TbUPW?$#mzxj=I-TKcX5t9&PTU^WTf6y=W0t zoRqWAZRu0e;474Tg`=WBb(#1l2GU)0i(rfEsSbleoBJuf#3G(09?#;OEz?@|MU6vm z_Erg2&0`b?1PA8D@0|ZDT5*LaF?<6?Z@}i<-R!FGnL1`eX$9voO|+i?=Lv-p;FM5! z3Y@1DN`X^Kp$s@>6v}~9PN4!g6%=aFu7=(Y)}mc4g*tSuLvrA*N5^_3=}7}xH6Te( zo}>A5v}K?XEgR`Z)r59U=y?8{vse6zz(b^~%LU8b;-@UK+cIq?y=Ur2t$sARuxIXa zGv`e+q!^1{;F$l?c52xsxbDMYdO zQ50fW{1}!=(%+sC#-To$+bmGZqMJ!JaIL4dY;i@=hoE`at0&}ASU+3Co+e4VE`gL7vS8Qw=Q`Uo}|vQdA%0%y{DIe$>{ z2Ngzj1h_|l>>c5#7mkLRI~zx=?i;};4vTU3Pp^#kFWX>!DXmDF(=$ zLo9G(>69d*ej;qx zLvLhrft^c3`$IH%h$h8`_ST$!HvGW_=VsfY}EMpTX=ig>PW?jY2<| z^-~xCvjGZ&U^Ym>AI zXFDcJ6IBWDO2CMLI&`bU_2vFHSJwDF%OX$b0m?r>Ub(+c@{ds;Y>06k2&`hCw^bKU+K!qk3d*z^Uwv|M63)r{lgcPA+5t_bO`~KOi*drf_ zDgtC9XbyfB)z9MS;V)byRT}!b#n?Q7aZkXsP1`2&_(NkKvSj>0&!47c;V2f4B;AZe z@ko?v_e@y#OekqaJeLEnoG#%;oY9ER!(YV6t~2yCto(wQ;WO6-Q~?8AsfX^=h*B+4YCMlxy-e}sg?8)|jW|Hb9;8p_b z8K^^E9U2XPI3pRt&_^>yl>sUlbhY0GmD?2ZKqZet30RcS+li+z`6-YLp&AUUVO%%p z*X1Ane4I291+r1}!JR|(b2z&1L3n}F+r(33+77c!53?-aXC=JkUFvyAB!9u^FHG+< ziIx$!UrkS)rNAqtTU`UrY(SS!aohHC#q_g zQ4J0Zv?8|^)%$hksLG6PqC0Rm7v(bqh17bY%=l>rL{SPx{|Mz#~ zKOFcU4)_lT{f9&TpI2{QvuPaTXob-_yBRZQ&7NcL;OM^EeU1AncMo@OcTaaO_myr= XbLTBu=<2+{W&ZM|>ld$Gvh05V#5^iw diff --git a/.clangd/index/mapping.hpp.63A500840ABD1FA2.idx b/.clangd/index/mapping.hpp.63A500840ABD1FA2.idx deleted file mode 100644 index 54ea1e9d333f8a67d825c8088710db30b1a21ab9..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 3250 zcmYL~c|4TcAIG2bm}v$>Ns}SQgc!?+vfLy_vP`#P&`rtmBy%NONb1@{Qc{!_+*^s3 zE3_JJW6RPV?W3Za>McjyIPvA{ zeHp6yM(tI)C{##$PD?Cr(>vDxhSZzb;oBrx%C9Zeof%Zx7*xD-VDX^mjA(Dq^Or0g z0;6QVSf3S`)rQATd>re!VW#6c6lvM8bs-gff6}qb?O=ejQJyq6K6NG3 z=XKatI@cHk?md@HX$xijFp(vv-c6c*rMr_AUY}v;d~t0aO=hC$-|V7io_lH8vg&ho zqekzW_cyca_mPs(jgl?2uJW;euV=;R#DsD`B&2vw7j#PmuNjeYMr}0bgsFOq$%*$# z{jAmUBl#AbI4Tt&{^M{?cD9}UTHb( zxTk~JG6vsvr0BI%x#wTKsP6t`;DvU%^r^Q6cAmILaSpomm|kO=B+5H5UqiN{C3pFa z;scbXyA9UMow{yrd%C~rZc?sy_E6dh^8=5X#lBw#r7h3Fi}-V^jNY9t4EWQ<;`f=$oh{~_-pGMRlSZ2(>x27)oqi3leWy`MgvTvSu>gqn{yDdMv=)>!W z3*B1^MdpFgnr|tEMYdY#^skCA(HAnqVic4HdPSYxP~`SNHp3{p488H1o+8@x+q-IN>cGJ5 z858BP;~InMZvEP~W{;%qbh*`@J<-GAts5}8x}z+=gD33L72Ms(kZld3xTN;iF8+A) z;j=H6Bdc?6{|E{5AL`3Xc04eLCaN@?lEd}N8~3xkyX(!%+k5Zm%{Sj&9J70*y?X8~ z2g&7MuNBjWP45*y_R8IszwzerVq>xEnYm+8#|{s+tU1H{XNT=QS!nG8P2(Gbr56OF zFAf%Ew7dS;(qeT2RE@PKwf;R>_c@CF>{olgi{xFe{~j}yYF`^ocpoSGkY&A;)Rq4% z^6FmyBF7s#Z+8D>qaVH}e)rC{JKsGA12SmwA2zgZNDzN9)P4{ji6m}~S?8;QAUdzf zC;OfX&1lGmCCIwNDzw8Y23QVC%RvngRg#+}ebX9%0mjI~zYLx)7^EQ)kh+L!UPQGp zG0+qPElAnUni|K4)T|F@-e!&sF$k&`)m4vP0V$@9$L)62!%hTs z3e`LXeYFA2Hia*a4kctj4BPapbmHl30X1c^mkw{b74 z&K)596af7KV2H)(#~DKA7b7*#0LXB;zmFXq*Ycww0_a6R6|gWrsvipy3+Ip&UfllX z6*rFWhH>zn9YxiSq8gYGs0o1vq-^vwVtk+ctXq3YN$pbi6d zNZB!gA}cI8DdU@VqYy=t+~H>o{xC;1M{P(Dvuvgdiy}^+MtE63U7(I}sa)K{A~O|* zhuV&5*GUIUWCS5XHAV20B|uZ6IOTczTJe4`8)4JeWAs_xy#ysksdAXjD4>oivavUu zsql6E;l-hjo5CD|x&kb&01j3GEGhs8Ms#7%_;oe(C2{)pSF6{Qc7i$un5V#OtN<_z zz-&mlnor}cg48{$xAsop{{J&C2h4IvWdUZEf^wWq_3($(qX~n;shB*O@O2I_&q1mL zFiR8^*JAq8Ku8V7lnE2d99wC~@9^&Wfkr==g9U2@&w=q4TagoSmB?JLzTO?9cZ~2< ziqcBasaPGL)q$yyvSz4mTn?#WpYI=%yeHiVYCq814-Bvry%f9#oJ=&me}l}&ZQ+k^ zWlXmsn0ys#zKS{~2UNM@tQ=UV;;a%P1c`O9u9V6HK%qFL%;1y|m+}Uo0l&FS=}3<- z<;z!;1P_Cg1?)+%B*<+*qoX>&_mk?Axp1KXa0>7RF(8Y9Ms85rO4t1kd4Pm*=Wv~O z$U9yJ@IU8Ffm4J_Az?g(2cLe3AAAl2WEjBrC_qN>w;UjHKv9YsrhrRXdCPE0+^xnt zwYnU)&8uOAVZa^+Ha?G^hfP$C#lc*7Y@QADZslh;jnU9}tNZXv6`W!X15-QV>2=g3tZkgjs_gGgC+%O8*qhOv=dN2ebIAvFZ2BMcK3mqDW@>bR~G!T`n6ecv_ zaym6a%Tpg~lQsi)zkanbY{h=%4!lU@^E#qwQ-IMEpy0WQ44sWJ48hd|) z<#^yXBcKZyB)C6zHLz4Rdq@#2UfD~af#@KyT59^k7nU}|Kc<+ca7a+oWFb&Z@L=>w zjJ9jTtmJ?#2MaHh_1~!7$6kbU^b}p3GZzAmvXY=bqJFkK=3Dk29ZZ8<3E-6AB9{QN z1ZXJx6C{bQ^u(B3w5y#Hg{RCGSmG&@s{u9j)r+g&c1+y}%~^n+g`aR6;IsjIm;*QZW-kgLda^RC|b8oqL+R` zx)|1dU4GGOYm{44WL?sVO*F}6&olFzU-SI&Jm-9$_wza5bI#{{9~YXfZ5$CntWVIQ zLjoe{SOh^}7hy(5{3wb;kV0hyi7xE)@C+L<-t>~0keV17w4g8kj;%pVy8nQH(W5!z zdwY?j+`xiNH8C~sGSbqUD0}ZiJ^h^#`N&W2=e@W^SyNk7UYed-KWdol{(;g{|MkoA z%L$C=-(oWfO};GR6p>ljrdTrcH@2VI;ncuB=v*B}WKQ!en#{+fiV)ha+|J*j|vdVKaS54!jy0L7YrJWdT`gz

Qk(Jy3eNdy0@^(V>>&14erPaPE~wbtWj&zn<^*fu+AW%#T8dDcCl;jP^zj$CO) zyJ3exsd=Tc$K`v;_%>hiy4u8_G@08jy8duIPHd`>$(xI~v+9N{(yDUcc*!)fm%B=UEaN8}|l(m??_V>erlFpo5mW}({ ze3P2nzUk#RgJ=Pz%hpS?;sd(thA)m)2QS*@D&nIqCKRmNKC7<&oNncCci*S?!+Wh; zGMltLf+auTGqVit`cdmSxDEYwCW&2+j~ z?M;u~b@;H$FEte^74;nq-5qQbH%Sd@cT&}CBI~au*2t<7CMRN}Qb)=rL`MR`(~2;` zdHuwpG9#0|>HW-`qnwpc$>n*`ls@?djpBG`xhKt3+vDDyxf4}xz}d1^gB$NG8?*iS zU=ogNCr)YHbM4q=-J1056kCGfUvEF1ZHZA>JK#_DZ%{7|JhsdDStH|gWBrxT%&oH? z7rba~9CKpn)YJmg>8R@An>BGBUWGnCc0Jp0&q@CP)&!S7pgSKsUODO@&24Te(Oxp; zOe(dnCf8~fTMvJci7!sYea`dD?r5f^Z8VYoDJML0*OOZV`aKJeB;&ZX-l;Q14<9eM z58o%0tT(lmcioei4b}OM6l-TmBqUuTPL+LsOMZx5vaQsJ;X+a$A&sOu_!fthhvZ#W z*L~t}N4-8vY*A{U&_>N&lZ#5}Dl%D)dv${An#SL_D3fF`v}c$&-tS6V!0jE!i*&Qr zl*eyIJy<^$e#fM-)c5V-9I?Lj+z&_U5oS!taUBr^k$;c7JvhqJBqD(aV4;K;Jq1Hd z!6+l5SSww*@MC}uNVCJgDo>e?5s?!DrUyv&0BOh=C~XXNhK$muJ0B81j+2C#av)j` zh>+Q-Ab#>NWK{HR{%jZh#Y~841Cnh#9f~~u$3u|OoOs4LaMi+%i2NWJi$zC9j~Fb57W zg$NGN<$xWK*`+KS;shB#y9xXABy7A8GYJTjKpZl=RRAv=`kBactFrYh42Eg_zdbM! zGm(V^zn83HLB{taNC|0B2~<>JpQZ>;p{hgb2{tchLWp1kNj7g~4Yx>#xxh?V4a+5R zO7{Ii%p4%h@iH;mx|yf*Wca~&M;|Lih$#X(MSudwve4S}-BGB+He3C*)ow$(5R(B^ zGQc*-SZYhr+#&Nq?}L#UcqyE55>QFvF(%sxHm;Bv`Kp|`k}?wa(E0?N9Ldh zWX3`YSj+;GRwBX>?4-AZw>lhYzaB0Eb;E?^@9%#OQ7jQssRqPqun{slNTNXwkePH` z`xI%vVkN{xD@LOZH&c_e{~i*HvHq`~o|DlNBDjFS<*kh|8N*wfhyVt&8lD(|y8xi0 zt`b-YcKH?(>=q25yOhY8?PW!OS;k=LNq~|BjIi`JfNKL19p!FLOQNrL!WS8Ul7YVH z0k|F@k?I+L#PX_f8o<)2>Qr-q51}6FzYE-scW%y~Q#Qc22o;Z|(-0cGyC5#`J_(RX z0H1RJnM0pkfN%j`u&Ypkznc>CV$~^Dr;oxBCV|!@(06<_<@dGhV;IbZrbW|-a(XVi zrAT%4PrHA4CxTMsNuYu1lIPGT7m&F?!v)Ep4k&Uwc{7m90LthLC_TW)Rn(>_BtYsC z)K9_SQZV9fhh;RUubAU_0qqpbPJuySN_=AoTm=JsHwg+84Dbum_3XmVxPDbE94$;P zObJV`2D;V2z~kk(RN6|63k(+l(<0!ErE>s|1C#|72@3Elk-%^;z&G0K?bNJ`?UW$+ zDMO2)i-jDn91sM@8gl&OEI7k3z(2bMCP%D8Ep5>0%mJ-AV0d%=T{?z5s|}TMfLso` z5^O+W10#Wf;isr^1#X31zDvv6N3$zL;`Z>ecP#=wX!ctjSH+B zkPFidGe9Sgs|Ml%XG02gbfv`Qb-xrFbVC?&3=%pat#Y6%sNay{*X>Ygu`QGL4>m(C zT05G8h0evXfT*B~K#pHMG{(l44o;jff%BxwQ@2OhkOtYR=Vf7+3$(ak@BM1 z?L&3sq7_gbZ5E&iP7~DOpQ5N&&bs|K#^NED11LGD)!6{Y1`>jr1WA4^68s`yfd6ZV zo0B<2Y=ex$TtmLi9>;2D{HJ9c{ZQ!4xvCnSjbD7`2loNdx-(=i$ zEqlh*$)1O%rN92VOyskT_|d2*H*X4RU0c|M1MfbEk7+&uoxwxuyMDHbb`MmDQ>J5jEPIYm_e~ z)lFOeXxbdn`InEL@QgSneV>Vc-+L+H9}hlSl>{+P4^_2NZ#&S-9T-*ZAk|qlf#c8) zjvcbXy}{eAf6!SOeu^ceUGCS1cV-e9`>r)~yU+EmI@!IiKsYccdrqfL!`+}aHm_sl z9X98_4>7s-m#s`FmD|M3$+})bb#g|Mb1lnVYu(rssVTfIU-%qXxrK?%_{9FXaZ+Pz z$FZwZ771cr zRp$zpevvNENR8*CQ)8}jZ{B^JBe_Vd8d-0|z-#1(KET4Kz)t=$SojUg7%G@Lc zVCv~OuesGjW9mU323-aQZB`am4lu#M07_m!P?VZh+|S6suzzax@uNF7)HAYZa|&=u zGOs-(W2g9v5y+Kfm*jRmKAZi(7njdWKv^zMJ|JnpY0_gaJMqDpqs2f$0e%4)7HvU( zL78Aq*S)!^0(~qj+T0f0b}ZVw?7X}{(w5g5s7y&fW2$(&m}8wt9nfTMV{S7Etq#7j zrN3_hxxyO4CJ$F`Syk!ADG20>vy1a9`$is`v{S(w$Q9ET(_fO;ruaim*$BvG=VIr} zHuapY(DLXiNLEx#>y6#?3y02bf6E3mnU|ZNMVp702T1a&@T#$B^U3ik03E<902C4A z734RO+_Gc7%5D{qMFQf|rJIG)w%d8Nft=0H4OGd)&jTcR)p*T;dKLH#w;3-KUDa>% z0H~hRjMH(4+tiA64$p6}1Jx^X8v@lU@>l@XyYl)2$w1y1pe}Phke9UtOn^2j3F_7U zt7^Lfqld`6MVb;;qV$g(3FeK-u klFE`wl5&!2lJb%Yl8O>MynLb}Lj1yl0y0t>VyfcO0ALZ3Q2+n{ diff --git a/.clangd/index/rws_service_provider_ros.cpp.23257787CC1BB7A8.idx b/.clangd/index/rws_service_provider_ros.cpp.23257787CC1BB7A8.idx deleted file mode 100644 index 6a0b289b8da33f181c71d9377aedd1cb67f9a8e2..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 32970 zcmeFaXH->3)W_|aQ|1(vW~E3G1A+n~ma8b(&|m|_uCezLjYeaOh}Z}wiWNi@#e#wX zBt{eqc2Kc5uvb(hN&vCH{~cqJ56|=F)4SHY){`tVKW6SeRWkA5;&8)c zKK!Q&foV^lZ#}tq;h@W@_4DgK{QmutBOTeepYzMQIIMa6^1E9@&N@4U*Zfd%flox% zfZ3C+mR^7VP4vTK!&-V)J2j-%?N=cOI^7%H;BBh^jF*oWciptG;ODW;-Y$C>{LPui za}v%EYy4p3`K#HlOxA(5erVd~%qHi)50?9Wa38Cj|(2X@j^?bvTuFF6~<0(vHuzncMA( zUobv#ZdgY?;(67Kq_(H-4A|0g^zoSOZ33>}E<0T9_o}uD&z}3uMbAPu-Y(qYOhmej~;NHHJv}ZR1&!JiXAG#fsv_Wny*>tC!fz8a96AUDq&l=%JiSC_@<`&|y~zR}EM&;9jfvu?KV ze6nE7k|l+6Uj6>G=IgVz2d7^dJMny*sJW8|JPs)6S`sq&^5$m~Gf#h4Kk>yk&DPCL zu6XsP^fLV5qgR28t=81fdn7IR=1Qf7wWf}|eWa6^vSMSl|FiyeR-8JNo^~;?YRhl6 zS|iQGJKu@Xn<{U)_C;Xd7IK-d#mr@k?3}~C+4y2x{=*q9DqJ``ulrv=K}jQ71Fiz>qm0kA_DIpe)%zBL&@O% zYttV8l6AG|fm@wB-E7>u;=t;Q?|%rZCGFqX^!1#ynC>%27Y1DruQyv+UOlWu;SaMG zJQRlbbu9b6ft)k7{ciX1?wfyp7@FhNrc$B*@a&^!S5BE|S@=5Yr$#gGUKwz)!GRi+ z+{$l{Dzfh|T-~4;EEqCRG}|XyUC&aHm;U2E z)xS@yZDs$(9COwdGFK(rtCFkdF2;8;tH173!);OJshi*CRby_DX;{5sJge*L;&X8wi;Xy6p$u+w+RVuSj-( z-N(h|wlOe&bC5Y}1)2Gh?R?3_Gm7!3e|#sG{>2WfYA5$LXN@4Umf5aluAV;${3qe> z_pLkjJ2Ci8@+5=Rtx&9EYWS3=x&~&5)YNC{`IU@7ba%DYWJ;T&bmNmvu3+lbMwp> zdA|6!Ou){R>allb<37zGlPcP#igi8D3;ewBcirmvL(Hb=ucuWrXC}xj7j2h|Zl3!D zzEAl3KAk2_s$euZ+rgamgiMxho257O+$iylQmwzI%I8Trnuf8AGi%vm?c>{o2}D|I|WMII`e|0UCR(3e;5o{iXM&N@J5uWY+l zcJsW%_$BuD`wYwvi;G{r&DorFgv?vn_N`pk^C{y`+27x5==tAA&9=^%WzGgcW{F|D z#AxbySK@c2+J8N3*vMz4rFXx5XwLdV=8F~P@vML3^Ve0fd*rka;57 zJ`vqL7c#z(Rr~8cVO3{`J^5l#usQ1knLOP#Pj~nHRpP%&f6FXx)#lEjan;?-SrBBh zHQQ{hwr7FJ3&hHQ-6x{Rr+taX+@-%grYQqi2Xfy^Gsb`RRtHpaL8qit9T=b&l5##1p=Bz(t;tkt)w4G-XfA){Iv)g6qR~Bbhy)li2{iAO>9=zoJoz~wla~4Q4s%^aL>X|O`^nc_}?(#jycUo+DWX}8`^HH(=sJMB? zh&<*W?c)4zHE%!KJNCFa>jjxy-8NVE@=TU^vSjmDSzN4F^NCG({B(2X1DVT$?PZ~! z=W&4_7yj-G?=4w1cF@RfJIq;2$eb2zPYYh26ZnL`?{eSiyQ2X=Kiz50xEITmSW(`)@)Ma<+}WZO+<3qFk~q$M-(K_i+YF6Hkh-9ka;iIz873P z!v!Axk1^oQF`J|t6FXHmXWo#xE7;x@+&yRT8GqNVZ-$SUyz1M(M>i&UO?92xko`Hp z>3g2fSo^l^J}!Cvrr7}NPc>^;A*Mn5D((Z5EOZdAT}zTWIuB!u!lp?t9Uu*C1$RB2HW z3Agk{xAfMQ2@YGwmPh|AN?!3oaJ(>3LiTsPrVNn0t}9<&S9(?L&~y3v2X8OUl)UnV zFY<-PlGhEv?S{}y@_He7ybxMSUL}HC3B^kVk5Y>N$UJ^zU=(wUVn|=kJeE^DiFqUu zQfXNp8PU z{DtK4g5r^~N2ClcmED%gNM9y ziWkWqMZ{v+t(ek(mpy)`c%*`V{i#o`z!c|c&g%&s^Ifq6t`a#$e&a^PE!1| z;&z(i#fnEU#mf}8GK#-aJYG?J1NYd#!36G>z>&V0du*ooQSNb+c#^xFr1Wg=kxlUe z?omK2UN1fzpQ#( zrg(|!Q9>+N-O4Hbwd(Pj;%hXIH5wSJxy5QoU#EGjqj;v~kx4wHxgDbPEX^Z};x{yp z8^k-B+Z{^3t9jg|_&d$x9WhjQ3)PW6SNE8!BfdaK;YHz0a7QAKx;s*?u14fhTqn&AxJBTM+J6NsD!U1C}l!T zq%&m&1Jjt2Mm)!qbHpO16cHmuB~k>pi^_K55m7lpyeBI6h#y4d12INYVk9tCQc{WM zB;_3OrKG$hM#)N)4DOPZUBpYWa*0?XD<#C$in3Y(cPq+n;u%FbLo8R6a^e=QY~f%I zS8|9&Tqz>Ps7j0qUQv}R#5bz)h8U+QaT<77Qw|gFY05ofn68BBHJ#D}>+MM?G)LJU zS1gY!&dyD*PI1T@b{!?L%1~DsI^M`oR~vdAul?(LIwkhPIB;FCx-L{f_sYy7m^r!u z(QJcgUZ-Sh!$mLS6aUNef64RDIvuh&$Ti4^{i)W~EjT;v!tqBzD2l5>)2o8N$I13} zR-Kr|93`*zW7?0CyaGoDj+MMR5AQq@SB?l8C3$rp(H&vW;XRSkXH=gtl2`vx{Sgiv zIdHV(HTavsQzWlpqle+Dk;6wqX3U5&kRLyMJpP_IVj}*YJYq7!sl%rtW%{V;xOUd4 zSqSHhoP#@r3B$sK5om3~JN8BWg+aydtr4+_(AtnlA6Dd7O z7?UL6jdu!@chYscgbBNZiKx`V_}#+S=vag?2k7%GVN8}Vu0e%n={~_)(SJ4PUusT+ zHKvObb}gDkJu&ZB#)ta62s(Df@pfA@%24C0P-8GURKsnaQ6FgM7&bv_Lg(5od zPd0#79adCO2A*hwXZ+V`|G#zG?bOJDE&A5GNO^9UVvJ55(r-_=c%gj)N;z7Pq6PHH zn9;`);{_#Nu*4KiP!fn+1!XI7yP#|*CJRb3F;!4gsZUQA)O2E|pkz||K|whvSa!Yf zc+lI;#a~M(J68DttA-oMmAA`aj#@cK1y8A!PpQ?q4y$xDebJZO@oLvt;5F9mvrz=q zVQ|yI{_Ib?NVf{xioai!m&MV?@K#~G112lH{sQiUQH7f#I3}e(a{nKBdkmO7Ac}WJ z{p3EYcypR;8VTI;vylY%o$fllG5ga_(tqidx%#@;rT^8Tf9XmFR!q9JVZ)hzDA739 zD2^e+H!`P<49zu(8A(*asmw@a)rRzxsg!921Jjr(jd+fk&Jl~4sfZXUnj%GTyJ*@@JR+Ko5buem zd&Cc-=>suFGQ~(>s$@zfo|8=Hh%Y76OJbC4iju)yvS}Cbl5Dy}ERjtm#MO#vwF2%| zOuLC^6w?`Exne3OZsDda9L(XS9AXhS6%k`pQ;Z5;QB7BfZ&cG8Vw`4*)4;=;=`iu0 zX1YfV(@kM|mvKI0d`iwm3`8SLWPXXP9Zh!qP7oh5zlX$mqTf6b+#q(?Kwt2QX;hblkJbyySjrzvjYhA%fZ`RZS?lE20_U?|-eXjUCSA4$4* zoizSw*AowLodw&*1i8h2{kKP>3P;E$zt;}N~C485+53%k>>{+B(i zPg8=>@Vd})LCMSxg6G-BNbodyc3K$TVeGLB$u;og2dw%7h8nhAuDxCUf;t_y9JLX3 zI^L($MiCumher0CIRn?tGqibz5o!Cl`=WYRbzHef@>nF9Q0FA4NC}mDg=DOdP`RTe zBU-BV9|5z!%S6OC=6Wz3$)lGyn(Z$e;Nz_bu3cXGg98QdrP?~}W%+q3%Y zz8#0B;z`TJfy>2F8#+`P=Cj^80ttKNo_pm1@d;&(XIk8n8la+z_0Ndt3eSrT&WlZ< z?}|Q`=}C7*JFWSphXt{UYkkc-qzks9QdYCcOf$i-?#tOmJlTK#P#m!vgF zBDoaJltOapnol~(9ny?LBzIb?f12dZX${Vi+$GKD5`BJ0Gw#smgTIguGCp`R7YpOreBOS)fsp6gr{2_KbFAC*bTK6_hzz2sdh zlzE4M4n0snLi@WyPxK5zt9wGw&!Gn`dM&e8v?qchGl>#~m&>XNE#zm&K_uwOwuDpWlxpuZ>+9LofE>faq#Ffffd zrV-CE$8*FY=2%3G6dfZ)aJ%TZop?laJVLxDI^H9G5FI}dV{vovtvIe$z}<@DZsHlm@eHwCaV#fp;f`B4n8O`& zh(+A7h!~?f#;D*G)$t1Pjq3P@7^gYLY2aba@i6h8=6H`7raOk|?is!{T2J(u?T4JZ zF7WGuWk$vIuU*ESKa2!F=4W*OLbS~2@X+aEqZZF`MS0ptP-52CP@0q8(8BA5exv<>Etj^0BZX@qrgO1PLEsKe(G|N>QxL32>OU%JPTPdj@y~~~$9J9) zFe3yuVmTn6y2Tr^{|&jzxzL-Jg{7UAp}#%OY8kF~7YXsW zYIwl#U<`#)oB1?%SRl1nAa%I3r{S2GTO(vV<%1CNK^TzdFs5_ZhR#EfkT39jp>n=@ zq4&f#&uBbcrZ-xqw|ls)xbwjKhdhz+MyvfsYy2?QbMivt`-Mn|(;LOv9ch#02uFa=Chcp~w!!XFb?alVR!nVe@5?{I#H7^(6|72KopJ;Xwl7ZR6h ze5nSeYdoEJN#mD@B^oc$Y}ubnFGZ47_T*zH4r8D$XKv*TlZ$zx+dT0PHk(H__IYBb zd1BCS6}mO6>NWWh^0btXDdm%2gqE4U-`n*YBgLg?JO_o~gTereq-y7QwGWC%ZNE|N{%*yYl%ICowfm#*{Ljqzznd99 zZ}C7DCkpiv1rz&op9ia7XS79?9}nV#4WhO|tcu)O2BmaCZ*)Nq zsQ7wfpjo}+<&ZqiDj#Ps;VzadFP5uYw8(sSBV}DPNIug|&-6fR(}O%S2V z^b}X6wpXdAxF)r{CI#B`Xty{x#Kr~kp?qj4A7@v3#`&Y~ws+(A+O6>T71xR?RH+rhK zsdudF(Jep!^2acv^trAK_FBf{i@tBM7ZPQ9qcXkA=lvYWiSr^qFV+snOw;!l1@Y60 z?`dM0;#)>c;JyhQJjs1e5(~L+A#siByG8{sslJzp<*IKvF;?@9)xblV?;+wH&G!y5 zRQCY>Q0xAK6u@`%QRJNAordiX2M4CTC4Ihh&W@%ry*&KjzkLTL^f zuKI_oFf%Mt0~V>BsYCOLq&evt)mWoi`qWI{v)*~1Gw#?(YNR!)nIZisG-+R3^70?= z4?|{~UTx4DwC~;?lfS@jff(01cj=6(7SuHegH89Y-4XWe(i16tg8Oubc{aE|!ht~p zQ7s4e8;l-hShr!gYGjv@kQvi;4CKdm8IQjwcAbd7CwHBUaB7#SNSPiy9oNnZo`rBu z&>Y+$Oz0dYbj5cN`iBc&k$E;`Eloe;gpfGmCZWeBp%;cBp~n_tq7afu=}AKOBmr-{ zQ|P~wuG=N_+9lw7>=t_N7J8F;w)+A4JWJ@FCG;@WcX*jsvnlngtHegDL}Xfw=oBNO zeI$rRf{6B!C>n`kHB<7IzyU5JtdUuTvSp#{{CPJJqg&QHAYfSjv?ZveY4PB;Gi!K5 zGTLYqZM17$zvTJmw?PsA^`!q|w+WoC6sNhZZY+~wwo$B%!q_0&Y#^mLL3T=zQ7Fl> zkxZ7kG}%a#t9{WxH5|}zsN`khrb-faX|-RXcSecoEu(d` z`53)v46T-K)q8H$`=d7Lepx!K8HaV#VI8VWuI`(wqwVJEFdt38#8K~%r+2|rL~s9y z?o+IHFV;~jKjqdt(_5~J-BBM_al(eg(F>G4L#cmu5@+31)|%rLrS7$H3e zuk4c)pWh5k^?$P_|KDEv>mThKbL!oRz9`nm%y`Vq`ycBSxo%W(5?X7hVG(N7phX0W zb+2T_i|_UHbyky*c0E%DqjQlZ-DnNOPuZYwUg6>nPM^|-HK?0u{_JyuYSixs0-K{bA* z7_XFSi&uCnwSP-<{Et%o zj}p52d9u$u8G=h?W2tO8y^rUB>(45_#mlGZjnec^(>HJP-5-3NX&CFWj(Z=?03tU;sdX};Qvu>_WUuWKAEE3)eeclU0X03eaZ&fLU zAt720ik5rLt#h_Z@_;j!aPM;NTu!snaJ6>0idpF*weBL)YHB9fIcqc48EMQ_6gm-11OqitU$RB2ET37;0XBj=i8 zc1$W8$rMn%=hRo!w`kCo@uF1_ZyUyC~i2LxlN&R}gb z7zXjZtmR%7xbm*sA^!sjPtiX9>zw|leF-tI4>hxHm4Qtg*i>U$uLrJ8+`DeL)s)!( z>hix#5Y|pVoA$$6j|<4Te0gBLJZk;^Jh$XJ1!qwe3&pmDVn;F(_`D!{@;lLZCt7ZZ zwj6tAV%B6_v0UuATpSQTzT%r-x!q$VToKw|5rPu5KD&3YS;No!X^|KwxW$o@_i0n@)^-JhVmJLn9qb3W{s$Rda+u;1Mi%I$ zN~NWw9j#J~Rf=UoYPTNVtxHXKP8ka-W4%-B&uug0MR^Dk_Q^r}RzEs&u;!2IJ)W8glWe~4x>^kwa z#$FTm8GN5%_3QBN1*!A%gOOWNx+zNUwCC8A#(iR4OHm@BMw3v(mqzp^%MIUya`@?c zQnMfML93uvn46szdYl#pAIjeRe8bdz7g11eCAYVd2Q5vxMaX}!Sp=>1M97^Y#x3Wt9S+d_*<#bTM1R?qh#|@!t8mT>@<&N&ylhbNweo=vaw9AcH{l? zA6f@HCgF=N624d@)I%K;zF17$D_HLp9Bv*Po>bcVL=y;137CSMh?d(#)8b={+#*Kq za4R(_BeHy&6`sGAbz95&+_*cz+p3`DF$b!&*3ShSs22(A~c*Ap{D>kML^Xq`ta6|GB&%OvY%5|}7CB}!-@Cnf8X6n`vPKPE1ctryAk zxon+C%#p2gh|gr}XT*hy^+E;QsaWqM9#fo-DY#FeVqHk_wcL6w2eY_!7V#msen?!V zS}#+(`pio!7#A2d-U5&a5`tuQvML z9lv(ZA>oi(_mJA^Uh>#EoquYYiQ1US+%g$z;R)t;;uD*lpn2H|*69Qb`n(Ap z^{b6*8(;S4KJ*9I9W;xP^ZMY1alCdM_qhG=ayr(qCP%uKO%rs(x~vpFQg1lKUZ zoBg@t{Q3UIZL+n^RA*mHJzq-$i#G4>Ryw52=D(5aUq-H?`M(zZaQ%vaD)Qf?=zp3N zz1Y9-z(n7(?NGIzh=ZSqV~W<5x3*rqo~+_c8aD}ee)rkP2VXw7Lo`aQ6QwpR&A#9t z9$#w}61K~(+vWP7T@p}h16>2Lh2WD{!kcv#Ra1{1TL!uLQqX*<*M|l(MrAHZzaUaO z@DF9MkA*XzaMm1mW(FM8KG+!nMG+Gg;YJZmi=eSJl2wjmRv)y+rdz*8E^?H-+BvoJ z!osLi2ZSA+IwI`i)CFO%Q!v61rx1j_oO&Vb>(m$F0H*;62RRKwIK*iP!r@NC5sq>i zg>bCXScDUtCLo;TGzsAprzr@hIZZ=2!)XS>*-o<&h6+xh0ys}_nn#QloT7=bf>SIp zUT}^Vpl~J#&I!b=g7a45cENc&FhJ@8cX zm3wZ7p}2bm^a>&MHlUP&Wz4^fb*U6H`gG1nM_b5y_VDaqDel6LhdR8dg=mE05}|lo z#1)S@G~vX4bkwnO`&b(NHpuli&^#|e_JOl3*@ul(+0wFENSZv-w==FxGfZhl=PKR$ z-p=f`VGXYQAlrN(D^{4|6h`WQq*5tTfeB)nQfZk|@rliL(A;W=+-Zj#)Zm-u3)+0|RRy;zV|~lm&;~_&=UdOPu*K~fw`mN+ zSCjfpe0+*GcUd*{TYpHc7p&I{j;1dZv1XW915=w@a-&;h7`!Lj+@magBs)E#sZEh= z6w%b?ciH$|uGXy9%bc;w;Fl=$|GB&MO-rb>u1BSfctoC7J5Tfa?37uBcBt?(VpZCC z!uLtwEs5VE{^3dmZjku~8O)M-7V)0U?-4)9`~xvw;qeN%fb#_$OyN9*c!~2%#CM#( zBW_dqHWj?1@;k(EjfZQLuJLWe(;7cbEYx_RRuxvJKRiYKyM1d6O8t2Q-u#K!`-wR4 zv#ThwaF^h*OTZlAlfP)|H;rdKSf1ai5}7aEmyi=hv>p_#!w9}rZ?=`plUaJ_EWHPr zDLdurXcKvQy*wRN`;qSch~$g)CdFjV{GfOGK%Xx$x-BvKl3CI-o}4L?4bNm^hT)xI zG;3>Zi~Sd}{1Dv{)g zuu-hCk?LoxZWgPfEE09|L>+mMqFbiu)g`ZAb<1CgM|I<8JNWUlZZLYKZjVr{0oQ+ME?aMm>~Km5ciAz`-wM2 z|C_{e(Z8IyLh@fBfk~2o67iJee~S1_@_$B*l>H-RFj@9bCg#fixx^ybzla#Aw2o9d zp%p3qsS4sJ75|gOV#U9hxPkj`;NVg2f0S6j{R@aIRR0w!cuw^{M=VkOONeVU|1}zz zsrhFTZ)pBEi0?H2cUoY_o|VVe-97Ufa<-g%mXklyJ8tuiqrrr#E}^vfCS3Ihr_DEu zRG&q(`6g0ziX>al3e{Lan{J|2BN}^N`$nv9KeJ^`G^BO`?S_(SVt++|u60$Yc~xi} z{Nv-=?$#N-QLw8FpH&7d;HwRv)keGE+@P?htGld2k8n$Fe~Y@!dvg7I)NMYJeI8M_ zSu7jHvSoKxFzw*-`So#!B;AyxL(4d!n@;G#-KXCE@!k(7#-N_x6?)$l28Q&kH2LW@ z@0yU@#wu^4MbZMPa)DGmxmhnYX&h-bj>4{ims)^Ws>VM z(ytQfUkB1gTu)N`vE=%gxJY(gM4eQk?3zf-kzI3$&t%tU#D$9MLh?=9skrVW9#ilS z_bF6d3n~6wsr+0)S*_)+YiZ9}EUz3(WtYWWvnc+MyFMf?Q(c$QI$yTxnoWGEy1pc? z)Ld86p0NzgHG_Cv!#~{rwdVR-^Z%+=Rf_?BW4}XwWlNUXlHI_Z-n&`bwqzuUW4)fx#* zk*rdPXC$FCUC0+4xZ#zCy9mJs*t!wwOT_P)-I`5mx$%6RXH(Mvx?QgLz>kg;vLQE4lz`> z3Z>p{nOadc_OGTYAM?#HV`2r^GV7 zVi|G1QE|QjMjI8QiJOgzn~AAL#Z=;cqvC#}(l-HD`PG5nH%FW9640d^Y42^8hG{m=Py|!pDJm+XZIU0tar&`aa+E-H+ysP{kD+{P0 zkGRt#?(^+ez3YDCXa5cf`9jlt!Ec)7uzQ`(`q6aZD(iEV4VgA|NX&rTTm5y6BTGqF>1pjV#e}+J%x9XNz9n#*`sXYLrK<@|I+Ci>x8{B&U0{ zUG|w|JfrQhFC^oIRBfi^hlmFITF0Ts%9GmXN$9a|N%e0@K6HW4JqdUIO)`FyEN4GT z>6xx37Q#6ea}b6J7GVMyE;xph%k)~oYOUZ(mQ$-Z;wGW$ zCc%xC?yGJgCJI#(iAh4$B;rn?_D-QGO=qg_B5Txcq55v(0io&v`aDahnngSz$R`AA zGVsZ#iI)ZWGV!h;-zB~m+GINE)< zUy=6{uPO31;zvdPNKEE(GVMY<&*k&PQZAPg<5fAHb|c>&BSa? z&L%$5y1YaOqjfo&xJ8$@5VLeSiThh;iA`JKy)FBc=v6?Hr&a+H^qJ(WWE9E;d~d2HON946zA8 z*vqCD!oD_r5e~2!fN+q_AcR9~h9DenGaTV4n^6eI+Kfdw!Da%&Nj8%ZPO+JSaGK3D zgfnbrAe?P88)2wm6Dol71ej>dbGJeP3)2;_FS#JJ>H}|)fpXV ztk5-DCEX?A2=T)tao`(qz)WUvi%z;i7K3sCWK+ zh6h8tavcw+;7`YRtgn^OBPQ|s5y-t4g5C?gHU_k*TrcL16<+FpR%9?^{Lk4J%bc4J z--${TXEjBJK380yD^Olyxoa$Mn7DCXn}9N(p(v~&0YlJRJ`vkL5qn|~5?ehLgFYXE zqG6O)_#yH_PUk$GypFGNevSA*7y{zIovK+k_h zv^hfq>v_@syojFuvgmY~_GH}@jhnP5D?zeJprJfTGLmQr-zVAZqxeC|_8{f>5y|NY z4e_TW;}m@!uh_)XgnF}LvzeHvI3O$tr8)46>* zNBSP_vWG)y%H&R&wA=P5H;!`1Wpg8&c!}FwBKd3F{u;^O;4U{v{tkD#L-GaOC?L7# z+;~pBquSgdPlyMq{R0*91*%H{DP@JKQz0o~C8|+EO4w`Fcufq~Y{E6jFVgH6X^@Z9 zTp~5dFV&ouYLH)}8EZ7it<#Kk#BG|*Hj+=$?2|}7MRQ3Z`E<=Go#Zn$Ba`H^G$V_6 zTC+J#^5-=Bb0mLBbGk%wH#Fl0eSTLn?h*?%n?jO%q1nG6xf0E(gyi07#yk3au5QfL ztL+I``Q1+c$Jgp$;mX4V<4-f6W>}f^SNx%~wN_d?N?rj<051Ph`O-%6>ZEi+dRL`u z4auvU(hXq`r3X@aE4?w;^i%pF{7U%>Ep4ze7_;V~%1~T2LKy*>(aLDZk5k6s@2{1w z@%J~%HweE~zD3G+%6GVSrZN-Z_saLU!(2g`D`2t|E-2xodBg~640-FW6V!FYje@>W zsD+9m=$nb#1brK&?-2AIw1s`Apzjp$Mbm_eX*9z8B2@f^+(-5c`hNQSkf0wDZ1=Tn zyx@bsRE};uLvNIU#mcxXg<|$FlZvXVwn|W;i)~ZuZzI2z)75}< zwKHux_t`^xHIJ&=Q5Cw$HKKrSy<>CJ_ z>R&SI>WAaa$E8_D|Cdq!l2O;kEKb|7J%%hctyrrn*T3pAVgC81bG*cw{kaX{eJJ{PM?n{Loea)=iiO}c~aTuv&oP=*>y5Hk59*w z-5XMV)BYDJ70G@9eq@gmI-U@EK8^4zicYMs0uSA*oA&D6pE_j~-N=7W8tGkO@Lgd{ zVawI$4xjn;`9Zvfsg?=7V>9Pw7%cp3{Lq88vTcR_w4FmcCuj-|9T0YO=!me3Ll=a> z4#5aR96}KGa_EJyuR~vi0~`h*9ON(v;Sh%*2!}fiM>xu16vD9%V-Zepn1FDS!z6@L z9HtPr(izfuun=U`dVU z^$u84BMrhSo-_ie4+%u54_k>)AGQ;rK43|WGze!bsiF54oUx=v8iW&;)JTJH!jc+I z(yicWNZxfa9PG%xA;SlY%+)eZQN%<*aC|_E!w&@f!$AE&X#GHFi;02YP(bfdAb1zh zI$e?AS0uC|1{Db?;1`1SLNLgZrj-y&1+A1=CfLKH5#O8HW3iuD5B?v-mRR(}_{SXJ z2SW75;wLS1a;$X{-LNSD`NJw=&6CXM8vI1aLZ@MI6sj`Q;4gywV)iTOzH!Voj$tH^ zV-4YIPi%)RtQbd`16=Nj-q^~D2^VusB)LS^G?6tU1}3sj7+0AFS51t9OoMAaMnR@w z%PaDeX>ifUILqweiHZDVuGl9*Y?w*U$z<&^={bj(!y$UkA?AIEo^yh^Vjl&u=?Qwy z2^NTb6qu+n4X$=%{?~GdxlGF?o@Lru;yGpyPfw`C%oY1&i4F7UIeDyI9zEw4bGSv% zxy8J1(Q_U$SL~xDHhoCXdB_5>j}{hSreVV|%8O|Q#6qSO5}z~eIkAY@!;=&y1Lg{+ zFk-`UdQLfO2e(NySmyAKp7V}*!+jFoQ6&6T6j(A;^DGE2sOs6E$ocg!V0J?};BodwBGcDrXOEj#v*~_r#Wq$fg)6 zIl%j#=p8BHzEP4Rv^}Cnlmtun3Q2=kK3S%-kBcf^L+oJMSi zo$R!xS`(Ypi0;_Yj`}S-V6z(08#~*vVk5ia@B-9t*%iC>h)pA8JU2oP#BM$0yR2bT z8(H=>?0|W;Zj0uhh==!Yq=&|ONj1R&PV>s4sbCc zdSh81^;!M`yGm%;+7&C=#HKswxjW=QtYo9#mo>PepnPNv%m3)7WDPDUFj>m>@aRT; zmtAq91hL_MdhUL?-F|v*mRvK7o|`4RXVG(y$qvWpxyNMhWAt2@k+HcC3YqMRlPHKy zPt$Wx%YitFf|eDvTzbw0S-U{IC~Fsqmt^}(^xRvr>n*zOmfR34<-~Sae?vLSHL+q& zbjLazEy6iq<(%k^^*FQ>*|m_aE0miS((?-Cz(RUnq1+$--RQSu4J+)lQleqqj+WUq zth8g?k?l+9xgX@3*yKQT$2M4)fE5R9b|89VJ1ojese}C#C@;mp<_B77F|a)r<)s+d z1c81@(XdUH+}`cs`A!OZP3Y`IcO39QihE7y?nHMS^niXxaexj_^u~b?C9~r z8V-ISw|RSb&XZzq2i>0NiGv_W!PlVUBR>@l2ST8~QS9MakMUS>%2zN>=PUK$yFv8J zS6Yz+M;-WZ5S!d42afxS<9*sUcweappAKTn`wIGj$BF}dJBZ$o>3x1vyniFURJ51$ zoMJ_T&jdqnZJIBN*`%pF#7 zyyq(JjWdVP9{2$GJz?DD-tZtsd*Ipzj`vF78qOj@esgUzaSOM{i38}Dcum+wi0(K@ z1N}U=gN=mfi32srP*MlB5@Hh^tbzWYJHTc_^u_@jWH`}aJE0Xc4F_$I0Y!ri1>-We z$4LfcNT~^13eg=0aF9X84mK5{Cl2Bu!%7|4R)|e-AO{&(9AIN1dgEXY^iy1etp)X# zYdD~T3@#dME~vlU9w#Iqzqu29RfzSmFi!M?^CbFxUK0!CM0Yq*VxFYd!9qE)37jc0 zPf{J>+d`~|g>zy{I9FmEP+j2bLiEN$I) zng+263<)R~)e+7c#CkYggV+*=1(c8K0%s1QH%{9iwuPaAtPBn~b%W>)g9F-$+U^ip zA&#mXh6nUZD#vLY=$F(+r_?5BFRCk?LC_DWu5bpyxT0z}rGu;!8VnQ|pH&T~b z_Berp3|%#0>ms`2pcFEA*}>*T^u&QFC@-}RY+uACI5-96raHg|M)bx3Dr5-LU<*Sz zsTvMaA%mC(n;0EyVULq7P!3v6*v5$NIA8_&ui3#yM)br%E69JX4s2z_COB|~3}z0n znGwBl@Cq5uG}zA24m1r1u#f>wgAEPsL9@q+8OUd?CTwX$cO1-ueAet>QzLrffEMJh zRtL5cwdrgC_4f(2RIJkujZW?TEnEz<@IEe%OkX946H=;WZ zbRh$r9c*w!PaN!meAOIaiz9mDfEO~zX|Ty5KQ#>py^vu}gKZA|x@M0PJ&iR&H*+%qBjnNL4DUW*zQozbqxo@kO5DF4G;Z~ZjX~eKA!~5 zuzu*;8LJeZ4uk%^+K(%`cb!*JK>uJg+H3@r6_r|z`ugD$B($j6!t;a2l1(K;C-~zs zOvVaDcbaFlEfYI^tW_;>Ny9}WAh%EMyH6fkp=-ZJBi|0q7Exl7|00?ZU>X%EHK!Sq zu|~42AX+`G5c1PLT=7)w_EhX!p<~}~Di<3|B$|6zKA}VWB4o=5I=pX(Y`KGYTDCk5 zHh*>Qeg&HaxDqqaOtG4}cG=QC8?MCQN~kPxqzyqON&LiSiL~V!DoG*>(l3@)N^AOc zB3=qQMkcxALAN+W8$_Wq-BK_&ynV;6JXE+J1t0z!gm4Ytiy%GqnI#Wid${bAgj#Mlb7 z3o~9F7O#%CSi9g&?W5<$Ba3(FjdtjPvxwNNjy=b9b~)EVLLHd z=#WfI6#`SqnJ`@lOebav9Wp6BNA%Ajjq#M&?3CCQ)} z#t+y6SgJ4MAyZZRcwEJWOjDrs4C=TEJ!v-(!pBzeU4)Wov%f z8su^`Qw|+)_e5*=M8ow@HNU4?i0!_k-!_;%U=H#Udh;p~c?o@ZgNUII`tSx)ouLnJ z5c|~P&M!K2FLp*L{G?a?Nv~yps*8{F$mYW^`1(8f!vxgEXk&&w7)E=9fkq(0&PHd1 zK}Hb5?nZZnJ&m3S`xt!?_BZ+?9B2$gIM`+|I_+V`F#J8z7>RIM+;Wz0f2$C!gKOfbR(FkG++C&SiSq0(Bx0@*E8iX(0k%r*&Dvoo98nMlIrJyJ@RCG8M*~OtL@0Xmf}TA%QU_hYlfu z5#}tb_W4(1aJ!MNBQf55`r#Ot-(R>i@JWfr4V!gt7E;$f{};bzE_9f%ubpp0w>Cvh zm+qD{T-4aRaVu;gwr%3>b|mI?qtOvfA@gZ{ydF=PKC~z&83{3RV2s?Y{zA_q>vS6( zjp2V=j{R?Cog9ekOr43Wn0$RR>iRuTj+UMWg(Mi4Hw@D3(;5>q+ z>3cZeL%hNH4PvOuLutB~r1B(UfyxVrks6PrX-|sAQ#42R=MVQZ{V6_sX@;l>=v4&g z^@59Oq=WOLITpScMd+lHPitqWO!m!C`hL~?Y*2Blw}Lt4|1TR^B83{TP-B`Z)PRMW z%+obsp{7px|BDSS)J7`9LQRttYgmrSylV{$FPUGhVS&YTlv%?{KWouY6$gE%u%L17LtYHx#b>12pJ*n%~(AZJ26l-YCq?TGkGetMTt)W4Z znr977kJKn@Xi}txSVI#bb-@}M15N9#F|()Xw>4(qG;OxV%$cUU)|m17oqcnNwV5yv z_2!7=WIYW(_p@s|5 zKh(guGS8?uk2Xs!H)<}Y^yP;Ca-&O|S1t3WB?lO|BkYc4V*hq0*78FoZGT5X!{!bB z0&e$hxw`)h>f5eKovukC{#{4Z=(M-=E)xFuxh2cbzvzVSuD@%491i^HN1ZzT^e|^s z?+dFTm#enSReN;VH|5tmGf%rCAz$v9FAoUXk?>8AW#P2fklc$u|5_976D~9jr?VG6 z{bW;*pM%y}J=-=MA8azJZZe#3M5IyWXT!1I#pIS(w;%5LUyu1O%XR&J|5)~gS3UTP?U$jD&&T*Xs|A$XMYBhLdg_%#wDtP{vq5qPhpMS{}UPw$JM%9plHga zZsk&+N$#d8JC+5#K|(C+8OsJv-s-Y)mT!oTgjc%hmEL3O!ru>{?Hfm<$ve6CJ9+T* zXWK^Fw4R)Xt;MkI?xzj?u<2%zHxg{Q$H@E%8*Q$PfeyCWi*mIYKm69px@$>C6u*B> ze+)LQYqzd5v)B4t7RALjP_`3Ua3aGL_yh|+L43%99}?$@!Sh6LgV=Y2IEWP9;3pE| z5pr;Z4DOJFcMwm@!KaCZa&RH>SKatkx0vNur}1}F6DuQ6uoO}#wxHDyrx&!kf~Agf z8i%pO@m{PpYo1?&gx?>0#OrNiHMY_6Q-M^c02^oSk6Kw`#Rn>wH47}8rjtME{3q(| zZs^Jl9Ro&z&I>5M$>5s|@MlB$*|3^poX&LE@_XKY75iT*c4+sjJL^m<Iz^Ol_GVA{?ne-oIrZBv%eyiX$!0YEgywSwDPI%wq6uK+H0d9cGa)}9<}BA87C`(llI=IrlFX3+1Qt!4ezvSHEg zE!RIOe-?rStPRf>&0|hE_50n%ssIVAjQ^*-YyXMj3ZvY457^S{0=nQ6En)(WVt?=z zdt-b+Nog#bQWg*eR`CTYL>qz?BqaosHYnPzuS#__K(IlrT7jx0J}??%jL~SYK{2wz zuC^A`7-P=|+4h$v{Rf;M&Y8J8ugrWibN4%E=3BHYByCS>RYvaHF)Oiks2%q-2wYGz z9+JQTwc@EZOFG5$ipNW2!gz%EY4hh^WiDu&KlDJOnlZ20Wn=H1;;Cflq z6SvEvo%oF`-VnPL;a0%U6!DC>Min(G_?Rk=5#LnBP2%UOcuriS&8yLpNg)w0G)#MR z;nBezy67PG>B2|sHiX*%Uohrgpp5k`L)@b2SB7{+yw4Q-Oz?SAoG0!wMHg{-uqY2s zYUmxc{m0Z<-{3I&ndN5`^m4+0JhySt<~?DxQ|S{k)mm7!Hooa$%q7+N^F|yqI5N5! zb`4I99$Es9i@(_LV-I_4=BJeVFaxXtcPXg_i@<$K7ee~)lZFRsC}LZsv8Cv-4V6(m zwawd8=s*7T;4Vb^se3;lj~7xgvm4K zT^xr!gayRUoUKveOSX0tmKf;A>ef~r@*OmzO7f#ZE2<_RDzu?*^_jSi^^dmeACvqO zy^CZHXgvqWj|z>)qeryO_TEfCv-=d*3=!a*k@A~<=4Ddkic&N{wb*VXpS$Nzi#ghz zfQHwqcN4(r0bL#u(!RMS+ zFHNWCoOOx#kz_q0u8^&YA=AN(1M;BAYNvmKPJ4pEB$w2tUxhNMBb{{RWN=H)#JSU-S5#e zVpjycduspBQ~T7i3SD`$(0oOS%u2;ksbmGpkz&z2c%tr8Vh3KQ9!lfEW4w%B{i9MFF#-Nnb|+lXpYMe4U1?(T z$tyQ8?J<{o%t8v7><;?$z1MVk&4SmVx7V(FQ92f<2sXlQhCV;+gFRHJ3O2!K2@MoJ_uOFh3^ zvuxucN+OXAfd3mdu3yOziNrutBKhuE^&B6+r{-*R`UB&AMdPgvOmMEcSMub!iBGe% z|BAEoEou4nzs@wzdP_sP;auSPn4H!hJFK^i^0V{#`M%xZ?U^xKJ0mi^UR}txd+b*B zY50+x6w5_}Lg!zx;O5aU)H=p}UqeiSbLNI-uDo10H*4XDOM%Jf@^+BQSnriVD}End ze`?022a9XdjD~$vaeL;ltdqMMLj0Fi8?DTEQ5LCptb5(W|E6zSva5cmXPZ-~Nm{(7 z+Q*=|Ro9nh&N#px%;i^^zq>}?{kL?D`LUvI*E+|WF^#g+_s{&p7X3PV@ayOPXUbJ} zHS`?Gt*i_Gd;gJldws5t-4fuv=j?R9!;>NS?WVavZoK-(K zbmh&}rn@v-2pf3dcN^|`XW>9d8OkHTs`>4=^Lr#oBjL7 znK!C*7Dn%zH2HW)gVu5F_`&9uk5*Dk5*B9EMU*Ct%951@TEzVO`RwYHx%pb`hn&xq zFW!Hkl4cz>Ke0l6y~Kkre!Fmbv`feT3O;jsbMALHX-#R|)a+VdxGHGA=Xvea)eEeK zr;Hsu@c#N*yU6ktqYlNDnsJXhUtjs}N`YELqG7|YEs5UwuNHO6YD@BJbj_?oR+kJ) zn4tUVw}Yp#@1ZM(=?el#YQoP0vP^%FzdgL`-J?$n1N}>9UHi7!A#MlTrM`G`=Tymt zEo&B^P?bo~#g{8etkl(5>`qC(Zc*i0R1Ntu!jzG(B&x#Ufe*giR?+csO}hrBDG4v5 zO=YxQZ_$TQduH-LYsuXsEOr1tM``XTtENh8peBh{)`IsErX|EOabP_+T8Y z)AyY7$T)n>I<4O{aHK(FtHRDOX>6bF|)tlob>0t=MRm|o5Ny5z@%a>6&vtLh)F`q@lF`` zjb4eRiz(`)Yp9&n-#q7^BsfjG_V=$RWv<3njYO-^kHn%HXXp< zqy(_o0{ql5TpeS;cOj;$-=jt*gQ zAYc-tT!Pey-$^k$sUdxRIjOIClf7y=rGc$rJh}AvT-vs`P-5!WmHy+lNrlB8;3rd! z%TzPsn+VfHlz!aL=Os*nQpqe2E=C1c&H+`BFZQmz_SkcC$8%$3s5{2zP)O@g;~ULCUdsfBUUO z-MZF;#WMj@CgsYc7W^rSIYo`?^E1P8blAtj#_cRN2h1(P-6FbtGh&+2pgv6CicjYA z4F73ku{U6@sBl+Q#_>A|vy-rWn7Io*??0~nA&13IfVoU_muVxu0W%F)Ii3YgyN;hc zkfY0DSHN`BTsLjVw_~OqE7xX8-QVAA8(zGX#q$7@pw1m%tuy&uH4PkaUOnA7f z2A%->5KkM%)9$@RA13PQHz^;qm<1Zx7cd$0*bLgdx9G!c`!8~L1ADrP!H7tBKNY_b zU%n)2ioAq)v}?$=U9a>O&R}s6jOL+~dnh&LFHy`TN;#UnPA+ZN!*q;T>;;%AHLgl+ zEdP=)FNsE9Pd~i1oR@DJ3ehzUFwtsUw3-25Lzo((JjDku8Kik>9`j=HM8M=RTpnZ0 zcOa$%Df>#(Jl}dY>capQ+X1GC;))<+CVvx77 z%Rf6uYG7+v;obDG-SoKLqHo^6=qHB`u0He^i=Dww6U{Y2bhTopwO@1<4@m!4Kdi1? z1N(uWWZE^E4(cuX{FF!dS>6nqkwHQBl^aC*JRkM5iuvXu-E`FjfiVRCVT~A zDvNxZtOd-P6yA2@y?gdSO4UXB?#9<0Q~M4ZC!(u(aJVxAO zWXwl0k;;>>e%bO34lEo3qSY=5Oe#SXzX#jz!EPdPL8zCmh%5!+UT)GeN;@~fV$X7D z(umy}v9HKcpoxN+NWE^`rWCdA!W0aCLOyb!_yS~HfNa!XdmdA%ta=Ph>ySeoau=x! zG*u9mftAm~3YWhh4v1J}6^rZ#HfuE2nQS`-hE(F3O1uY+u)TS=#;5_DXCl)~WJB>; z$RG<@u<>DCxyK|NAPb3KA(^9jyQt_$b%!PxE@1l$*i|!w&tCoU=y_sU9E|1dsPgP2Dj5TT}4WhHcxh z%hwO49n|)IYX^n~?A3q+L{z_HAx2RY^T)^%Zu%E%2Wg$_A<$r=9fdnLw zd4?}*H`iA@_Xk5I@~%XICO7?VWSzh00ER^3nn=9I8>tp#G*gGbP>O6zk&DUZw0C;< zY*v8bDt5n${mfUZUeY_~zXqmIhs^5`ta3dvsz=r$gM{%Yc;kd4Hh04>?AZ!UbBKEm z@tv^VcDKuR^RK{AfZPg@uhq%r_IhSIJHgP7J=*aMkzs-l1+Nt8Bp4JV(t7D8sxjaH zDKxo-9d2O{kxasoQZPx86+#mQ7Zj-^7!(B3p|ttxjD|n;LVQGNNF2t?voXA5->^DTtg7YIp}V1|o?XE*HukYGe;J zPGt2kWCfRZ>ZPAxP>@cy%2ek12iL!08-n$M!ErP#jixo+Tjx$aJTFq%;X-U(h#f>u z3Jn!ZR3xAfZm=K_B(Vr5<_vmTbJ# z7InuM46WFy6?^zC9eAT~kLMXMWFf08WN*UcZ&~v8Rvs8`VXIr%UZkGThk|g5d=(4| zmKvbuc4f^nHc<;E=n?EIto+2C)MR1h4dW>@p`0C0&8PUol+j_zT-X7lQ;IV16g5}a z3H>~3yif+@QNhBFSX`pu%$89T%LG5Ssj0UqIP3Q)!+V0idsM(Z0r!|PdrVmgW$


yW>DI`sz0PD59v$gLFlifkL2DmeDSC-Fn;4rzu0 zq6)iKVV}iztBqXtIW~i#4tdm}86x?HCJM^E^t|-^3+;fxfVhh7uVUB530CHt-|h(j zL)5e=f02np0|ozHH7fd)@LY!6WymjV=Ka{7)zyo^aFIA(BpxC$hb9U-{;jdi z#-H~2cL5?9IVB^n_3rnX`wO<)!W5H`SrUQ-nT!mRk=2GV4L>HXi{CXscsba$2rq%x z$mKPfF1!pJyAiy8j$_B;7|LAikP93clK#|AxG{iaZy&8l@=oQ%Q%LTPwZiMFnK(BS zFCm%Rz9MjxJBd>#@f3vt1iL~NZ2aZ#_8%@C-T-4vAYKV%Mnv4-<+XEcyL4dh z&6-P}c-J}zc`XyUW+I=cvIJ8XuG}6B`N%0Bd2DS-FHB>tSA!u2xyB%$ZC-!Y&)=fg z2!<@=kcB)%9YNtQ`T>F--i*|j^G5OW)#vkDQ~q$&8ki5)39y5 zVwFQ&j~JJ3+x{Uk1bikT_ax*eEBf)nvDl~v>uSH z*sB!>h`I-QSE!w|qQkW%Kb1!Sq6B%Bpn&vI89}n#2fu7G(0xiubm>D$DS#AS{0%Ti&Trxid z{Qjm!cL*3{BtS;yiP{Rrp-@!0r@nV_@3dS3Q;5S8<3L0MeKgsFZSyQIJFQLlEIWhzJ=4lP>7uhu~)(PXqUzB zJ_drJ5!*Im7g2UW=qNOosIkDQLRpD|3J?l4b$PPt)5d{&ieW6t^ps>8&PxjInnL@O ztPPyEr{HY>JSagEN(6pdii}H<%@x}*6LNpA78pzp@y{W_R~sL+jJh!RS3t_>u`=33 zNMB>qX_ISo%$+CHlz2k%;f~?nf@iA~+6hiF4gXB8r9@TUEXv;j?Sf5$Au~tQY&1RW zdeht4dgq=^1pn>Wp&h%6;teLDkZk2>-Sm3<`N7aI2AReP>^2q|#3G9uvb~u_(b8kk zv;*68U?))H~ zpVw%XkdVB(QGk$;ypDsogM{Rn3)e7^kUTo!>I@Rnv}gipzMM=iCxJpj@~S0(YbM^! zBuGd|Zm$Tu@jA)$P7-)+r_^NgXq|i*$~A0#4M>k`#+{RImQI6dwc-h_Lddsa<2G#b z+ups0i>fq^1G12~7ZRU4V~gHCG3?w2V{Asw%?OfT2lDI?UNK$By$ksW4B9;nBp)0J zw;Z_Q0mkeqhpSI`hq>$&j$Ijz%CIWMPNt|8^M_o>)$%$|Ers~dc zEwlO1b1Je%Fs-ZD z?5en(;D%#fhd+Ct`$o8L8xzdY~AE@fRG`38FKyI!tSESZ}Wt#Z~$8! z!1gUSmz|Z*skDaPs<3I5(AzC+a0^>JqBfNk`_EtixtrG5O%HATqj7f4i#j1_WW-BG zW;`CW^4ware|5k3ayWoJo-F>@GWsG_0Fl0I(lRIEESV(J))ZuLoeX-6D6wIt3Slj( zaxg3dEiTG<_)`$?qS}T(6&m}+QTj|A|HmNcuM*9wLYI5jFp~T-@ndDNX zmMLubHSBZ^d;NL8W29{Ppjt5GBd>fE@NQ?P&GyTF>%owUoKlgOsK>#FLWRHI@i6k} z@Ezm7MCbHo1Sg>b&FnxSLUj6dp*ccy`lZ435k#kN4oH3I+(!-~TL}oM*;C?TO*Gu6<$%((51dA#kdRA!r4;jBX|DnnXo1TemGm-P3l9^M6 zm~VIvhHMg)O+sJyUNArt#kGQX3jhW|`*)=c9#U}Q=00e!AKUK7&fVr}1HMrk;6XAiO{TSl^d?QAwclNdySmP<)(u?5VedE`Bw4>K zY>{x4wqgB}4J!~-gdYWaKV!v;L^4!a9jL4hQC7z&tHP~B??+p#NF?z4qWBpsRwNSm zMN<6eiWP}OOIaPJtbV1eswu1L%Ia`sRjRD=;X|@K9S={n7&%sV%&5^S>Wr$IbihE3 zLF`~nt*?e?>kJ(>d;~XAGD6veQC3GQs~XBGr>v?dtAmtP_ytM)=!g}GWR$Y{f5vp$ AO8@`> diff --git a/.clangd/index/rws_state_publisher_ros.cpp.B9C4118F896EFF34.idx b/.clangd/index/rws_state_publisher_ros.cpp.B9C4118F896EFF34.idx deleted file mode 100644 index 4dc3bfd7d8fb15a6a9712d4a97b49e80e3135590..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 3934 zcmY*c30MpT64Y7oY7J8%%xgme_B0OlcOIoNvwd z*0y%Alw0ym&%&o#apPE5>-jO$bq*h%zj)V%R+tB`?=L#pD7I-_VdSk9*EP~Q++;P> zu|IC?DY876?ec2p1bJZalgv%wO=I5r_KAt~!^8OW%!K7(j_%OT;jI~m4TADJdKL`* zXBy1oVp^?E+Vcm_11-OKny!88$cE~K=21VcYZo_W$zPt03uF!{?{56Zjn^{ftz(T9&z_onZFW5#z1k7~YOblF zed0;oYp>Z53hOjEfoynVRzKRvQby8x<0Jjs!X5v<+{pEzwo+VK9qjbSlM0QLM-f_v zm$tijyT8o2ft|S|z37n@o7PcrHEC?DGv8|0g=Mbpj3NHsH7hsu?OA?O+SxaICMW5) zChy;UpAGFQX&p&A^%Fm@U+NLx(q7J7_`!aSLbQv=)092IbM-yrMw(a56gXPKgii*h ztFL}sU&ISP{G;O`bM?Z^yqL83Hq{@7j_tJR_1z(NwpcxD^{`i_)9I>aQKW0lt3kQ@ zmkZlehNIkmO`%kZ8E>>;_dUnC$hc23&^pZ55F7j?ch{MiCQ5U zo;~sY$hAGs{(Z`zf@Re+eHZWRO}(NSUQ#=JYvOvd{}<7R#wL3D&g$Du>nYj%eDdA6 zYo?^s?4-!AfnlZ#W6wVn?O&xvwpmKTLs_8~)&hBfCP{&yApFg|QoDEr*T_^RS&~S& zt-7u59~TnoulJv4*{cqATE3-|EnvMP-Oh-})^vv8gfym2ar}H`$lFA`F+1 zB?{!tmM>*Xv7NFQp3F`*#qbn^6iW;*LIy<$?&Zj|9N`##5crAgWU0~d4$-7Luyz;X z>_T1(Azwlcjd$%=#&BoMnS$Z&WOsQC=P`J?81AX(X^i1QO(7G*MRXAh!-EupKvPT? z!?R?GL=D43R6=MN9-$sV$M8t~ND~Y{id2pwn!=81N%q6zn((El*r<(^liW=4r)_2c z^A+=H3Ow2HtkxPUfF+1gf~?fVpNS z0LC|HY%tJGWvw*cx{?V_3TZ+ONUDZN6T<_w0<{fgr!q9y%u>)42n4H){5r>0ui(otIkY*jy!SLfq`#91wJ-t;` zY86?Ei%j9ZC;M;xC%^`TBC-hRRENlQh-S&3a@yOBQ9$fs>*9ss zt~#zuxl^sh%p7$cLdbU!f{^2C&n3BBvJaw6EwXC+q6@njVH^WN#OcLZ+cPd*ks4nk zGDt98|Jh?)Iw#55$}PqR^>QR^@~Iy8EnURQv< zahz*3Xa-vZb9j5sZJUWd%mU2-c7Pj(??LQ62=4WWU60&6J>zET-l=~D+SSOW8VNkV zs|l|9=)V~RfLpp{{p;p!!*B*|^KPY7tBR1X!k3lrOc}YOAa9818A9;;(H@0Mr}8I&2gP$1e6hZp0Wf9Pjz=n7eK2B zX%-><;O_%#X%nZ2eaWO{>W4&Bg`PXs=K_$(Sm*_$(v&zj12zJ&KqxB55q2EW*Yz}d z^qy%CSrkav-p7TCwKaPe3Bx5{tb1NMn1j7aq*IAZ!;~ziXCB592R=d#3RN5_cYKb7 zFIp7VN=sa-<{1P!xr|)1s1h}<^Hj9LUp~d`E!^(id7MZpKY%Yus@|yW(x*EL8Ol@5 zgBny9#I32X5h$cmh^d@R-i-&Lr2;3>|%#2MX>wY)=mm|Oe z#R5jA__63zwGClBPccs=gKWY5*8@%`KnX>nnDcgbY1C`lCxG#W@#Z-{x(U@|>n8vf zBTg}L&&@C%O2U}(AgD&7Y7~;Q^NkmC)q8&kPZTAJfs&mNv?(p{*cz7wl{0b}?nU+j zvh!{Du&2IU-vD5rd%#)@-;E4*BM*Xo?)7MG!IFE|^-sKewkS#4S}wNk@8Xt0+{E@n zsj&C<1b$%QYK01YQx@q{)8K}S$R(^u*F#_aZoV480=oi-!hunvYXxKzfW#ITugDFn zdMihq#Dj=+5Lr|dIv+W^d2ZvPuT>=Id}z?%5-ozD<-Xe?PG9HVm|a(eTJ!A<>k00k-n^{N5OHqV<4;{b^d9zES!8$(O0S!DmaX0}c&nYFf4Q=q-f@XH^w-;F zhl_`DA5IGXf-U#C`PYw}tpk|N$#%N3yejLw=c^~s&fHn<7T~Kj54PFU-qRntkiQU$ zlPFLW0Xz`}#ew%r#m-kH4cqZ2%YGrE)eHf)M4Cl%Z+vmHo#Y-Nc9?MK=BS-Qw9MQx z430X<5n35BuRvkLgZUU9DjUkUCAL(*!H zK@Ea=L5d8e2A^N^g>paoza zJ&$?kNttTcvH^l;Dclr?f9~lwbTW@4E!w7ARk?RMu3RVp9Y>y{;BL;b-+F5g5GQCK z;_O4N_vYX8VkSjJAn?-nGI;QnjBEGU(_;XAReTM9?cU%QdoCqrk;#X`$%#Ea)b>Tf z2T37rHoeM39Xo&=4j|W_oV1b~PKQJwATstidu?_V<>O<3JWrlq@8_Rg6E9K^FS7CE zwaVE`ABsPNj)W_5e`+!Q**JcZ3OYib&=2~UMx1VcTUhLnADswbqs~Ty0eS3}u||Uh zp+go@iFtrri>QNgH(g` zMxN7^p9g2TfPRE_gaOeGHIE|Qkw>N1ZR6+t;bQ_hfzs&X;MAh}jmZF$Imz6S^!OID zVtYB_EmfdBre+_ce*e`?fK^DT3TccRSrv^MSrOw;4WiZ{?MaV=zqbF<@)~M~ySzJ0 zn><~fK9JGa6ZT)o6vFr-Vu{$`l5&tLkdY;ZXNj5w!U~~bRqQi2HA{<686hB_!N)&ITRLAlYN!KD)=t)0D77pxyM4wIU^P;z zM)ZZsUoPx9JHTG#;om<75c!Xj^<}!Vr+#Zo0xTl9MA{OQ7(x7|NZk^ZiW3jk#O2RF z&fgCtgl`>qIx&BK?M4}Ejupx3e=kT;NzsWm0NK`Nh%AH2%E>EG6qhiJ8Ac34hAzXD bp~ui?7-%agt7vLaRcY#KI!trAi5Ba>7{Lk9 diff --git a/.clangd/index/rws_state_publisher_ros.hpp.5225916AA6207DAB.idx b/.clangd/index/rws_state_publisher_ros.hpp.5225916AA6207DAB.idx deleted file mode 100644 index 22cd916e0f5cfc25381ad088c838f4f760ed44a4..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1376 zcmWIYbaRVfWngel@vO*AElFfyU|`?@;^LB`%p^tzhO0nk8yD;~YyICq=Mg{E7~K_cn%jqlCvc>6kUy5i&0H!M#xU;0+5 zzTmZpY(!?d;gkGlX`c@luJrV*-ppqnbV{*mip+77h-vK})qV>Cujy&7U_PC<<($cE zg~-J>v<;52J>8k^IdN^_s^bkTmXj`N#`@~%dnTW_w)oMhOw%PL;*)P2{UhGEeoou% zA1M$1?sxvop8nWB6W{nJe*II1e_EukX72{{CNn27F9nK>hKK@j+k$F7KiEQ})bJ`wx6f0zmm} z$!t|H0hf>5z{s~b=g}uVCSjm_ns-_(n1IWd1T2iO`op)1k4Xq9AF3JZ1}5P04cj;E znsnN*laEORC?6mhpb947@~bxWr!U^gXvDCt1Oq43|NEX9bEGhTGi7ID zWM<&9V6%_{6EJy3F2;xKEc;bNmT2-Z@dIs$vW@Zu6L1^;g#8bj@#^#>J|;n+yqA=h zJeYvX|NAQIKmDZE2Qel_UD$5w))uk(R* z=HuHy*=)XS30T4d8U;#q8#@<7>}uc44{|V9lrYdhu6Q7s#+4=vOF}@Ep!5TaFCZ5b zS+$qt`Vzac_W_Od=JFPXr3WS^a5?}64lu6vPpv+FbjOBzQ1EIynE-=Vz)P|yH7602 zq>77@i?cxtuIFznlmnmfcXROZ@N#gnvavI8g2W*JRQy2!AB@4kz=mM*BACFE69(8} K3^UfVc~0VIvAQy!ot(v?PLh!fP*z)3BHO2ivQ& zcF44W40=jDd1EXzKc~r4o#j|j7lhT1o0yj#9+mll>4muT)k*qaFnnWWhBvp~4MAwhwlg}!iHa9yTGCzOW*o&h4Mr=>E?`i$4K%YwOKeY^% zlz3We)o8)Fm_#^Q)QUIns7?Nr2Ymf>B8xhePBOAea|_DWz5d10Ay@<2qQ;D*r ziZ&*xT+du-{+_3kbwTmVXWI?3E>k6=(*rCaL8_^;ZyVGMq$<@* zXJCu;tOSiN29)JooR^o`{d$=;Dqa$C-VcI!#N4Q>zUfPJ^zWv)N?z!zD?UZ>fW0y# z+uWOx!Y0nYbEkSboawrr5BV{69Pv*e3j&Hrz$ZBTdpl~ZA&1oJxLso{PH6_t6UmN z%(YUnb5h^(7OH`bv{?3aLLtE&OSqvVi`*NCA;Gr5Q#<{g`FsyjYF|8SJ-q%x73b0Q zZJ5#0lz@9V=JKON6Rs3@qBBn_xFyt}(E0+w! zZ{!U7ox4w)lt3nq>Fl?!pDcS4E>Jk(af1Ej*?ik_SpgcU5Y@C4JMzx0+~j*|&!j~V zD=UqZHJPcuvvOyt`Z5taC(WfwF?`ffm+wy`1_4*OYPi zwmhY!jgWE)cr+fZPF5BLtKxy7U#CR?Q;_%P^G9JE`5aN81B{Q?+!%CNFI`$d zZ0Re(0W_!}@DYT6hF=a5RDWg__`dN)eS6Oolpp4SV(CyiBIWywX*cJ!BoN|-@cUrN zSKXp|OC%srth>FtGZgD(@8z7HV3Jo6&ZhA~v1Aw-3B`KCJi*9GhX)`J2UQ$+{y(=I zL_t6tn&kjOngh*IqG_YIAPzMPx{;m8E>P@o^W&DeMn@qMCUh#krU$uaxOuTr4iUE$5Qb}nV=*#|ox%J*i$c3U znQTtB1lK3YUSNYL$9=%oo4bQg+}+&CyS?@__XMAKnR{`fn->}DTbBQ(ig%DxLXse7 z;y9Kv@elhY2sw>t+`;M1>EQkz)xvE%!RTUs6aBl_n!n!7(xtqN9LG_wlLO1iXxKJZo^J$jO@|6%M zmWg7@gVCPpIto40{HK$%0H=_iHICATs(?kZF(9NUQ#5@7fS4IJfac=no3dBeWWf&x zy8Zt!e(m+QHafA52h%ynf1#w#W%V>0#U*`rVu6k3jH}I@u7{Zw;|IAYe-nPwAXmEl zo(ly;Q0YFL3CoP|WuiHYBb@Nx3%9!fc(6fmDyRaLcw rghk+@d-m=V6W_0>si>x?u6Rg6PC^nPa}XtU04c4aq%ErbQ_%D$8eNpEQ( zm8HB2SsT41TUkmK>~1~1VE7=8>gL{pvi+!~e&#-iM0c@NQtOWaK-)s*kSAOl-E^)C53 zO1_3`tEEtD+MeU8UK(@|R>Nk-SPqC8d{26jnyNeZPSVbCn`noR(ppZ+)y`qg2z}RP z_GY+ojgH%%)>Kk&{DhoG;MUCU&1J zvXmU9qj7GxCbTrawM&aQ+Uzn}UrHi3=3vCTBjR&s_33Ar_*-7j3=B^zVz2dipgpJ6 zS~>&c9fp`kUnEU8ksbWeF{MU7-G8Ki_TD|yv@qn%ecIvpZRpUImm90kZ7*oZeo+If zvx|F@lq=UEHjEce+|(iVLwHDA92wLW;td3TO5R^e>cB**lt@a}R3VYUvrDqm`jPG1KHCe;mds3AIRb^PsaWXzrJpl6sLgW0xabv3(cuVTz* zwOI~T|3TBlI&POSeO;`kUEC5@eg;m?1WeBG&Q5SjaLw8}%P7^JQg-)k)2N3Z$lPe~ zXe85eW!m80Higq_6seRfnFrPx1r`P)PnAEuWWAq8k1U7xJvo8&QE91+GMcwE(b>(* zJbBaj`FXWf&STS^&o&?bb&DN-P;tKDZO>s+V{r1r^c6PTM-zLwR%(J8_Fy$=k~w&R zSo=A;1ZGnu8Z1`tG#(kvCY(t78XITfw5!Oi?}Kg;@0hLXw+G?)dLEY)@u@`nxU8Qo z!~9w6!B*CD0aQyU8}>g*J92;8TsHgkRE-Bt2h7MEy~KBC(^ADHaeiy zs7HzISpie=ty=HzyuedE^#6YN_|n~ew9UpBUhB%JOcQyXLc`++;BDxAli?oi`@)Eq z>Q^grunWdveugUWS(cCkJ5eK-$xDi!M!Dq)GAdDjx+UHU%-B(z-tXhTMe@|*A*N+qHM0wT?vbvDV*E4t z+=<*+r7Q;ivBb?#uZ<7uH03vB{*_$NNm1NR{)_$GG}*Ix2hG<#GPyMp`P` zn+C>IUo{k*McCq&tE+<2m@V{3PG9g#zbE!*^^C%1CF-{y^Q2O9_nk~*fN%@!MN zye41Q?e!&wE4{q?#zz8|99S@EUf`UW?>cdJ>v-45?Kdi^WBnb4i0_YqBg_8ybgOSd|*+d*0vxNUDE2n6Gq0QN4n9P0 z9=C+SovUKnR=e+u*2lKCNYOC0%Oj~G^`4sAt3oRG4;TQPqoI4Jpx&gfF?`1wr%RCr zaN7XT9%*laCm~5DfFw*DCS+zVgcrh;MfcK5&buN2Q%HeT!kYdL0Kji=(6znYEN|eK zt2_cQfp{w!E5qO64{x1$J^o8j9#R@0Kzz7pxE7u+O4ouaNQwz>w}2{4ftwoUe#Nj6 zz*a~>k|SY$hd&NW^WWry4!)a}2CN~TCCWnL-9_Dzkb{J%hz%BU_;KaSywdVkEd;Oy zQjkT-Qoq9=hX^K%Qv-c(d}*I-RB@%b5DW}~g(#))p3Hhtzb8SE1ShSRNY3>-+FPM0 z3R1Nxaar#ozqX}> zgn#d+%_+vMMQ|isK%xnNt23iY&I_P!FFPi1ti0p-f47dIR9F6dSnBDq_Ye%W4|cw7 zoP7*eK(>ZpxM4W{?)F<3V|wQt1o+&y%QeJFwzAZFqIQ50+ z2gLjr;A?YEBhZM@*oWo^trug5KeQ7Fbm$G;i%wfxdS8Ms^u~|i$B$lqGPk)WoU{woEK;rA=k7-0I`noU-TOk597OD zmi_i!DwzSgmzh32=bU)fzZGpond1SsRAIvY_}z77eXfCy%Y zKfl9rA_6$Z&{GIhs6A{JrJdg;g152+toYpjF3Yt60O0=}288YlF@m5L#t1GYjaVlm pyIu}ufHFksqqI?*Q93AHl%9sXg5pM`$_7~;#rZKT9U{DWb*)VaY<2TKadt=WMHV6)7!h7@2~-f>u2NG<|%7s ze=Ca>cJ#iQeqdVt{@!*C=Qb~%JJk;9w=6GkGt~64%!>ZF=ECNhEeli+l$xr}Tz9}z zyUjqV=%Posu;D^w%LTl-i>oU*H_!hkw(7=2mDfgM{hLZfjOJ*atc!`?YrZ3tFJ@-R zx21EQEi1CSb^OymUK_{N1x1&|T_jT1G89+lCIOwrP?VZh454!pL3D9Za~=5|deGyKiEHEk3A-7G39fA$%kJ$nm(LfG zIr#UG$C-zREZ1bEAIx-kePq#;Z48Vn!?=Rgw?67%SS)_)<4WUQIu~oU6cn4Ycc-lc|hVXIcJ3N#X(w`c0Q8=mrc5|)#4lseDYY+m4G6yoPVmB<6zj3o%~vcAgN9 z>%0wL-?cc-uzvW#Ye{Pehj`?-%xATM(p#8~x_N9M6;M{$|hKb?sQ`wcXeFl7D#02JMo)oRVR)J}+|J$?q{MR1dw^ ze|Yoyhc`7mU#huy-dH|#X_H|3=XqK!`Mpuf>BlF%wQhgiZ@P2uQjMYm3uHL_`sSZY zj+(mqt5h$W^;es=$ICr^n76MJUbOb9h`aT*BhB{f57uc|%l@yqnMn#x><{Z?(5l58z=Cx zV-#kz?_bmKDPyKI4}%0yMImdUif{yLgbGjvCmRzlKTt(tSxNn0;hj5}n8dh&MgoDb z373g5Pz8kd?cG=5jQpoBc^JfjCZw^ZNelb4`bz`lIarw`1%M_LrKS~E02K%CDF_fN zx^;_@Mc7}--zb>Vb#HE}Kp&9n9OfKza~;#rZKT9U{DWb*)VaY<2TGLUWp;)*$?U7mam3Oo#z6Mb!dNgfJv zQVzP*bmYGD&g$7GdptuvFf^PIZ~BxmQ$+3b%CoF2&-dnD^<$m7!6)K7>rKx&eiwq? zYP{UNvdu{8-_zMsY(!u6^TzBhxVfp4F}uXDl%cpXHwkDBLs4p4u{V%zuai7^+dOg? zBNL-Bhq3zc7r)zH`mD$Va`ia$6uCVQmn;gs)ehupb7(6~YkqWXvO!K3kgLU^rF75! osjS1SiX0$UmqS+xXl70#$n4^x Date: Thu, 30 Jun 2022 10:44:30 +0200 Subject: [PATCH 27/27] Applied formatter --- abb_bringup/config/abb_controllers.yaml | 8 ++++---- abb_bringup/launch/abb_moveit_no_rviz.launch.py | 6 ++---- .../config/moveit_controllers.yaml | 4 +--- 3 files changed, 7 insertions(+), 11 deletions(-) diff --git a/abb_bringup/config/abb_controllers.yaml b/abb_bringup/config/abb_controllers.yaml index 124aa2d..240dfb6 100644 --- a/abb_bringup/config/abb_controllers.yaml +++ b/abb_bringup/config/abb_controllers.yaml @@ -7,7 +7,7 @@ controller_manager: joint_trajectory_controller: type: joint_trajectory_controller/JointTrajectoryController - + joint_traj_compliance_controller: type: joint_traj_compliance_controller/JointTrajComplianceController @@ -36,7 +36,7 @@ joint_trajectory_controller: stopped_velocity_tolerance: 0.0 goal_time: 0.0 - + joint_traj_compliance_controller: ros__parameters: joints: @@ -71,8 +71,8 @@ joint_traj_compliance_controller: ff_velocity_scale/joint_3: 1.0 ff_velocity_scale/joint_4: 1.0 ff_velocity_scale/joint_5: 1.0 - ff_velocity_scale/joint_6: 1.0 - + ff_velocity_scale/joint_6: 1.0 + forward_command_controller_position: ros__parameters: joints: diff --git a/abb_bringup/launch/abb_moveit_no_rviz.launch.py b/abb_bringup/launch/abb_moveit_no_rviz.launch.py index d0b97e0..8d185d3 100644 --- a/abb_bringup/launch/abb_moveit_no_rviz.launch.py +++ b/abb_bringup/launch/abb_moveit_no_rviz.launch.py @@ -84,9 +84,7 @@ def launch_setup(context, *args, **kwargs): "moveit_simple_controller_manager": moveit_simple_controllers_yaml, "moveit_controller_manager": "moveit_simple_controller_manager/MoveItSimpleControllerManager", } - publish_robot_description_semantic = { - 'publish_robot_description_semantic': True - } + publish_robot_description_semantic = {"publish_robot_description_semantic": True} trajectory_execution = { # MoveIt does not handle controller switching automatically @@ -116,7 +114,7 @@ def launch_setup(context, *args, **kwargs): trajectory_execution, moveit_controllers, planning_scene_monitor_parameters, - publish_robot_description_semantic + publish_robot_description_semantic, ], ) diff --git a/robot_specific_config/abb_irb1200_5_90_moveit_config/config/moveit_controllers.yaml b/robot_specific_config/abb_irb1200_5_90_moveit_config/config/moveit_controllers.yaml index c7c2c1e..69c839f 100644 --- a/robot_specific_config/abb_irb1200_5_90_moveit_config/config/moveit_controllers.yaml +++ b/robot_specific_config/abb_irb1200_5_90_moveit_config/config/moveit_controllers.yaml @@ -20,7 +20,7 @@ joint_trajectory_controller: - joint_4 - joint_5 - joint_6 - + joint_traj_compliance_controller: action_ns: follow_joint_trajectory type: FollowJointTrajectory @@ -32,5 +32,3 @@ joint_traj_compliance_controller: - joint_4 - joint_5 - joint_6 - -