From c5397685a81fe874d108307d4cb53cadd500d999 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Sat, 31 Aug 2024 00:13:52 +0200 Subject: [PATCH 01/67] add some generated packages as samples --- samples/ros2_cpp_component_pkg/CMakeLists.txt | 50 ++++ samples/ros2_cpp_component_pkg/README.md | 62 +++++ .../ros2_cpp_component_pkg/config/params.yml | 3 + .../ros2_cpp_component_pkg/ros2_cpp_node.hpp | 58 ++++ .../launch/ros2_cpp_node_launch.py | 33 +++ samples/ros2_cpp_component_pkg/package.xml | 24 ++ .../src/ros2_cpp_node.cpp | 156 +++++++++++ samples/ros2_cpp_lifecycle_pkg/CMakeLists.txt | 43 +++ samples/ros2_cpp_lifecycle_pkg/README.md | 62 +++++ .../ros2_cpp_lifecycle_pkg/config/params.yml | 3 + .../ros2_cpp_lifecycle_node.hpp | 76 ++++++ .../launch/ros2_cpp_lifecycle_node_launch.py | 47 ++++ samples/ros2_cpp_lifecycle_pkg/package.xml | 24 ++ .../src/ros2_cpp_lifecycle_node.cpp | 254 ++++++++++++++++++ samples/ros2_cpp_pkg/CMakeLists.txt | 41 +++ samples/ros2_cpp_pkg/README.md | 62 +++++ samples/ros2_cpp_pkg/config/params.yml | 3 + .../include/ros2_cpp_pkg/ros2_cpp_node.hpp | 58 ++++ .../launch/ros2_cpp_node_launch.py | 33 +++ samples/ros2_cpp_pkg/package.xml | 23 ++ samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp | 163 +++++++++++ samples/ros2_interfaces_pkg/CMakeLists.txt | 15 ++ .../ros2_interfaces_pkg/action/Action.action | 5 + samples/ros2_interfaces_pkg/msg/Message.msg | 1 + samples/ros2_interfaces_pkg/package.xml | 24 ++ samples/ros2_interfaces_pkg/srv/Service.srv | 3 + 26 files changed, 1326 insertions(+) create mode 100644 samples/ros2_cpp_component_pkg/CMakeLists.txt create mode 100644 samples/ros2_cpp_component_pkg/README.md create mode 100644 samples/ros2_cpp_component_pkg/config/params.yml create mode 100644 samples/ros2_cpp_component_pkg/include/ros2_cpp_component_pkg/ros2_cpp_node.hpp create mode 100644 samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py create mode 100644 samples/ros2_cpp_component_pkg/package.xml create mode 100644 samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp create mode 100644 samples/ros2_cpp_lifecycle_pkg/CMakeLists.txt create mode 100644 samples/ros2_cpp_lifecycle_pkg/README.md create mode 100644 samples/ros2_cpp_lifecycle_pkg/config/params.yml create mode 100644 samples/ros2_cpp_lifecycle_pkg/include/ros2_cpp_lifecycle_pkg/ros2_cpp_lifecycle_node.hpp create mode 100644 samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_lifecycle_node_launch.py create mode 100644 samples/ros2_cpp_lifecycle_pkg/package.xml create mode 100644 samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_lifecycle_node.cpp create mode 100644 samples/ros2_cpp_pkg/CMakeLists.txt create mode 100644 samples/ros2_cpp_pkg/README.md create mode 100644 samples/ros2_cpp_pkg/config/params.yml create mode 100644 samples/ros2_cpp_pkg/include/ros2_cpp_pkg/ros2_cpp_node.hpp create mode 100644 samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py create mode 100644 samples/ros2_cpp_pkg/package.xml create mode 100644 samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp create mode 100644 samples/ros2_interfaces_pkg/CMakeLists.txt create mode 100644 samples/ros2_interfaces_pkg/action/Action.action create mode 100644 samples/ros2_interfaces_pkg/msg/Message.msg create mode 100644 samples/ros2_interfaces_pkg/package.xml create mode 100644 samples/ros2_interfaces_pkg/srv/Service.srv diff --git a/samples/ros2_cpp_component_pkg/CMakeLists.txt b/samples/ros2_cpp_component_pkg/CMakeLists.txt new file mode 100644 index 0000000..a73587b --- /dev/null +++ b/samples/ros2_cpp_component_pkg/CMakeLists.txt @@ -0,0 +1,50 @@ +cmake_minimum_required(VERSION 3.8) +project(ros2_cpp_component_pkg) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_components REQUIRED) +find_package(std_msgs REQUIRED) + +set(TARGET_NAME ros2_cpp_node_component) + +add_library(${TARGET_NAME} SHARED src/ros2_cpp_node.cpp) + +rclcpp_components_register_node(${TARGET_NAME} + PLUGIN "ros2_cpp_component_pkg::Ros2CppNode" + EXECUTABLE ros2_cpp_node +) + +target_include_directories(${TARGET_NAME} PUBLIC + $ + $ +) +target_compile_features(${TARGET_NAME} PUBLIC c_std_99 cxx_std_17) + +ament_target_dependencies(${TARGET_NAME} + rclcpp + rclcpp_components + std_msgs +) + +install(TARGETS ${TARGET_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME} + OPTIONAL +) + +install(DIRECTORY config + DESTINATION share/${PROJECT_NAME} + OPTIONAL +) + +ament_package() diff --git a/samples/ros2_cpp_component_pkg/README.md b/samples/ros2_cpp_component_pkg/README.md new file mode 100644 index 0000000..97c3167 --- /dev/null +++ b/samples/ros2_cpp_component_pkg/README.md @@ -0,0 +1,62 @@ +# ros2_cpp_component_pkg + +TODO + +- [Container Images](#container-images) +- [ros2_cpp_node](#ros2_cpp_node) +- [Official Documentation](#official-documentation) + + +## Container Images + +| Description | Image | Command | +| --- | --- | -- | +| | ` + +| Topic | Type | Description | +| --- | --- | --- | +| `` | `/msg/` | \ | + +### Published Topics + + + +| Topic | Type | Description | +| --- | --- | --- | +| `` | `/msg/` | \ | + +### Services + + + +| Service | Type | Description | +| --- | --- | --- | +| `` | `/srv/` | \ | + +### Actions + + + +| Action | Type | Description | +| --- | --- | --- | +| `` | `/action/` | \ | + +### Parameters + + + +| Parameter | Type | Description | +| --- | --- | --- | +| `` | `` | \ | + + +## Official Documentation + +\ \ No newline at end of file diff --git a/samples/ros2_cpp_component_pkg/config/params.yml b/samples/ros2_cpp_component_pkg/config/params.yml new file mode 100644 index 0000000..809c91b --- /dev/null +++ b/samples/ros2_cpp_component_pkg/config/params.yml @@ -0,0 +1,3 @@ +/**/*: + ros__parameters: + param: 1.0 \ No newline at end of file diff --git a/samples/ros2_cpp_component_pkg/include/ros2_cpp_component_pkg/ros2_cpp_node.hpp b/samples/ros2_cpp_component_pkg/include/ros2_cpp_component_pkg/ros2_cpp_node.hpp new file mode 100644 index 0000000..9ebb459 --- /dev/null +++ b/samples/ros2_cpp_component_pkg/include/ros2_cpp_component_pkg/ros2_cpp_node.hpp @@ -0,0 +1,58 @@ +#pragma once + +#include +#include +#include + +#include +#include + + +namespace ros2_cpp_component_pkg { + +template struct is_vector : std::false_type {}; +template struct is_vector< std::vector > : std::true_type {}; +template inline constexpr bool is_vector_v = is_vector::value; + + +class Ros2CppNode : public rclcpp::Node { + + public: + + explicit Ros2CppNode(const rclcpp::NodeOptions& options); + + private: + + template + void declareAndLoadParameter(const std::string &name, + T ¶m, + const std::string &description, + const bool add_to_auto_reconfigurable_params = true, + const bool is_required = false, + const bool read_only = false, + const std::optional &from_value = std::nullopt, + const std::optional &to_value = std::nullopt, + const std::optional &step_value = std::nullopt, + const std::string &additional_constraints = ""); + + rcl_interfaces::msg::SetParametersResult parametersCallback(const std::vector& parameters); + + void setup(); + + void topicCallback(const std_msgs::msg::Int32& msg); + + private: + + std::vector>> auto_reconfigurable_params_; + + OnSetParametersCallbackHandle::SharedPtr parameters_callback_; + + rclcpp::Subscription::SharedPtr subscriber_; + + rclcpp::Publisher::SharedPtr publisher_; + + double param_ = 1.0; +}; + + +} diff --git a/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py new file mode 100644 index 0000000..cf54c4b --- /dev/null +++ b/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py @@ -0,0 +1,33 @@ +#!/usr/bin/env python3 + +import os + +from ament_index_python import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + + +def generate_launch_description(): + + arg_name = DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name") + arg_namespace = DeclareLaunchArgument("namespace", default_value="", description="node namespace") + + node = Node( + package="ros2_cpp_component_pkg", + executable="ros2_cpp_node", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), + parameters=[ + os.path.join(get_package_share_directory("ros2_cpp_component_pkg"), "config", "params.yml"), + ], + output="screen", + emulate_tty=True, + ) + + return LaunchDescription([ + arg_name, + arg_namespace, + node + ]) diff --git a/samples/ros2_cpp_component_pkg/package.xml b/samples/ros2_cpp_component_pkg/package.xml new file mode 100644 index 0000000..09e4c63 --- /dev/null +++ b/samples/ros2_cpp_component_pkg/package.xml @@ -0,0 +1,24 @@ + + + + + ros2_cpp_component_pkg + 0.0.0 + TODO + + TODO + TODO + + TODO + + ament_cmake + + rclcpp + rclcpp_components + std_msgs + + + ament_cmake + + + diff --git a/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp new file mode 100644 index 0000000..67d06b4 --- /dev/null +++ b/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp @@ -0,0 +1,156 @@ +#include + +#include + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(ros2_cpp_component_pkg::Ros2CppNode) + + +namespace ros2_cpp_component_pkg { + + +/** + * @brief Constructor + * + * @param options node options + */ +Ros2CppNode::Ros2CppNode(const rclcpp::NodeOptions& options) : Node("ros2_cpp_node", options) { + + this->declareAndLoadParameter("param", param_, "TODO", true, false, false, 0.0, 10.0, 1.0); + this->setup(); +} + + +/** + * @brief Declares and loads a ROS parameter + * + * @param name name + * @param param parameter variable to load into + * @param description description + * @param add_to_auto_reconfigurable_params enable reconfiguration of parameter + * @param is_required whether failure to load parameter will stop node + * @param read_only set parameter to read-only + * @param from_value parameter range minimum + * @param to_value parameter range maximum + * @param step_value parameter range step + * @param additional_constraints additional constraints description + */ +template +void Ros2CppNode::declareAndLoadParameter(const std::string& name, + T& param, + const std::string& description, + const bool add_to_auto_reconfigurable_params, + const bool is_required, + const bool read_only, + const std::optional& from_value, + const std::optional& to_value, + const std::optional& step_value, + const std::string& additional_constraints) { + + rcl_interfaces::msg::ParameterDescriptor param_desc; + param_desc.description = description; + param_desc.additional_constraints = additional_constraints; + param_desc.read_only = read_only; + + auto type = rclcpp::ParameterValue(param).get_type(); + + if (from_value.has_value() && to_value.has_value()) { + if constexpr (std::is_integral_v) { + rcl_interfaces::msg::IntegerRange range; + T step = static_cast(step_value.has_value() ? step_value.value() : 0); + range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); + param_desc.integer_range = {range}; + } else if constexpr (std::is_floating_point_v) { + rcl_interfaces::msg::FloatingPointRange range; + T step = static_cast(step_value.has_value() ? step_value.value() : 0.0); + range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); + param_desc.floating_point_range = {range}; + } else { + RCLCPP_WARN(this->get_logger(), "Parameter type does not support specifying a range"); + } + } + + this->declare_parameter(name, type, param_desc); + + try { + param = this->get_parameter(name).get_value(); + } catch (rclcpp::exceptions::ParameterUninitializedException&) { + if (is_required) { + RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); + exit(EXIT_FAILURE); + } else { + std::stringstream ss; + ss << "Missing parameter '" << name << "', using default value: "; + if constexpr (is_vector_v) { + ss << "["; + for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); + } else { + ss << param; + } + RCLCPP_WARN_STREAM(this->get_logger(), ss.str()); + } + } + + if (add_to_auto_reconfigurable_params) { + std::function setter = [¶m](const rclcpp::Parameter& p) { + param = p.get_value(); + }; + auto_reconfigurable_params_.push_back(std::make_tuple(name, setter)); + } +} + + +/** + * @brief Handles reconfiguration when a parameter value is changed + * + * @param parameters parameters + * @return parameter change result + */ +rcl_interfaces::msg::SetParametersResult Ros2CppNode::parametersCallback(const std::vector& parameters) { + + for (const auto& param : parameters) { + for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { + if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { + std::get<1>(auto_reconfigurable_param)(param); + } + } + } + + // mark parameter change successful + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + + return result; +} + + +/** + * @brief Sets up subscribers, publishers, etc. to configure the node + */ +void Ros2CppNode::setup() { + + // callback for dynamic parameter configuration + parameters_callback_ = this->add_on_set_parameters_callback(std::bind(&Ros2CppNode::parametersCallback, this, std::placeholders::_1)); + + // subscriber for handling incoming messages + subscriber_ = this->create_subscription("~/input", 10, std::bind(&Ros2CppNode::topicCallback, this, std::placeholders::_1)); + RCLCPP_INFO(this->get_logger(), "Subscribed to '%s'", subscriber_->get_topic_name()); + + // publisher for publishing outgoing messages + publisher_ = this->create_publisher("~/output", 10); + RCLCPP_INFO(this->get_logger(), "Publishing to '%s'", publisher_->get_topic_name()); +} + + +/** + * @brief Processes messages received by a subscriber + * + * @param msg message + */ +void Ros2CppNode::topicCallback(const std_msgs::msg::Int32& msg) { + + RCLCPP_INFO(this->get_logger(), "Message received: '%d'", msg.data); +} + + +} diff --git a/samples/ros2_cpp_lifecycle_pkg/CMakeLists.txt b/samples/ros2_cpp_lifecycle_pkg/CMakeLists.txt new file mode 100644 index 0000000..4188128 --- /dev/null +++ b/samples/ros2_cpp_lifecycle_pkg/CMakeLists.txt @@ -0,0 +1,43 @@ +cmake_minimum_required(VERSION 3.8) +project(ros2_cpp_lifecycle_pkg) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_lifecycle REQUIRED) +find_package(std_msgs REQUIRED) + +set(TARGET_NAME ros2_cpp_lifecycle_node) + +add_executable(${TARGET_NAME} src/ros2_cpp_lifecycle_node.cpp) + +target_include_directories(${TARGET_NAME} PUBLIC + $ + $ +) +target_compile_features(${TARGET_NAME} PUBLIC c_std_99 cxx_std_17) + +ament_target_dependencies(${TARGET_NAME} + rclcpp + rclcpp_lifecycle + std_msgs +) + +install(TARGETS ${TARGET_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME} + OPTIONAL +) + +install(DIRECTORY config + DESTINATION share/${PROJECT_NAME} + OPTIONAL +) + +ament_package() diff --git a/samples/ros2_cpp_lifecycle_pkg/README.md b/samples/ros2_cpp_lifecycle_pkg/README.md new file mode 100644 index 0000000..b3d5e1d --- /dev/null +++ b/samples/ros2_cpp_lifecycle_pkg/README.md @@ -0,0 +1,62 @@ +# ros2_cpp_lifecycle_pkg + +TODO + +- [Container Images](#container-images) +- [ros2_cpp_lifecycle_node](#ros2_cpp_lifecycle_node) +- [Official Documentation](#official-documentation) + + +## Container Images + +| Description | Image | Command | +| --- | --- | -- | +| | ` + +| Topic | Type | Description | +| --- | --- | --- | +| `` | `/msg/` | \ | + +### Published Topics + + + +| Topic | Type | Description | +| --- | --- | --- | +| `` | `/msg/` | \ | + +### Services + + + +| Service | Type | Description | +| --- | --- | --- | +| `` | `/srv/` | \ | + +### Actions + + + +| Action | Type | Description | +| --- | --- | --- | +| `` | `/action/` | \ | + +### Parameters + + + +| Parameter | Type | Description | +| --- | --- | --- | +| `` | `` | \ | + + +## Official Documentation + +\ \ No newline at end of file diff --git a/samples/ros2_cpp_lifecycle_pkg/config/params.yml b/samples/ros2_cpp_lifecycle_pkg/config/params.yml new file mode 100644 index 0000000..809c91b --- /dev/null +++ b/samples/ros2_cpp_lifecycle_pkg/config/params.yml @@ -0,0 +1,3 @@ +/**/*: + ros__parameters: + param: 1.0 \ No newline at end of file diff --git a/samples/ros2_cpp_lifecycle_pkg/include/ros2_cpp_lifecycle_pkg/ros2_cpp_lifecycle_node.hpp b/samples/ros2_cpp_lifecycle_pkg/include/ros2_cpp_lifecycle_pkg/ros2_cpp_lifecycle_node.hpp new file mode 100644 index 0000000..02aff1b --- /dev/null +++ b/samples/ros2_cpp_lifecycle_pkg/include/ros2_cpp_lifecycle_pkg/ros2_cpp_lifecycle_node.hpp @@ -0,0 +1,76 @@ +#pragma once + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + + +namespace ros2_cpp_lifecycle_pkg { + +template struct is_vector : std::false_type {}; +template struct is_vector< std::vector > : std::true_type {}; +template inline constexpr bool is_vector_v = is_vector::value; + + +class Ros2CppLifecycleNode : public rclcpp_lifecycle::LifecycleNode { + + public: + + Ros2CppLifecycleNode(); + + protected: + + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(const rclcpp_lifecycle::State& state) override; + + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(const rclcpp_lifecycle::State& state) override; + + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State& state) override; + + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State& state) override; + + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State& state) override; + + private: + + template + void declareAndLoadParameter(const std::string &name, + T ¶m, + const std::string &description, + const bool add_to_auto_reconfigurable_params = true, + const bool is_required = false, + const bool read_only = false, + const std::optional &from_value = std::nullopt, + const std::optional &to_value = std::nullopt, + const std::optional &step_value = std::nullopt, + const std::string &additional_constraints = ""); + + rcl_interfaces::msg::SetParametersResult parametersCallback(const std::vector& parameters); + + void setup(); + + void cleanUp(); + + void topicCallback(const std_msgs::msg::Int32& msg); + + private: + + std::vector>> auto_reconfigurable_params_; + + OnSetParametersCallbackHandle::SharedPtr parameters_callback_; + + rclcpp::Subscription::SharedPtr subscriber_; + + rclcpp_lifecycle::LifecyclePublisher::SharedPtr publisher_; + + double param_ = 1.0; +}; + + +} diff --git a/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_lifecycle_node_launch.py b/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_lifecycle_node_launch.py new file mode 100644 index 0000000..693b511 --- /dev/null +++ b/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_lifecycle_node_launch.py @@ -0,0 +1,47 @@ +#!/usr/bin/env python3 + +import os + +from ament_index_python import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, GroupAction +from launch.conditions import LaunchConfigurationNotEquals +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import LifecycleNode, SetParameter + + +def generate_launch_description(): + + arg_name = DeclareLaunchArgument("name", default_value="ros2_cpp_lifecycle_node", description="node name") + arg_namespace = DeclareLaunchArgument("namespace", default_value="", description="node namespace") + arg_startup_state = DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state") + + node = LifecycleNode( + package="ros2_cpp_lifecycle_pkg", + executable="ros2_cpp_lifecycle_node", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), + parameters=[ + os.path.join(get_package_share_directory("ros2_cpp_lifecycle_pkg"), "config", "params.yml"), + ], + output="screen", + emulate_tty=True, + ) + + node_with_startup_state = GroupAction( + actions=[ + SetParameter( + name="startup_state", + value=LaunchConfiguration("startup_state"), + condition=LaunchConfigurationNotEquals("startup_state", "None") + ), + node + ] + ) + + return LaunchDescription([ + arg_name, + arg_namespace, + arg_startup_state, + node_with_startup_state, + ]) diff --git a/samples/ros2_cpp_lifecycle_pkg/package.xml b/samples/ros2_cpp_lifecycle_pkg/package.xml new file mode 100644 index 0000000..569c6d0 --- /dev/null +++ b/samples/ros2_cpp_lifecycle_pkg/package.xml @@ -0,0 +1,24 @@ + + + + + ros2_cpp_lifecycle_pkg + 0.0.0 + TODO + + TODO + TODO + + TODO + + ament_cmake + + rclcpp + rclcpp_lifecycle + std_msgs + + + ament_cmake + + + diff --git a/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_lifecycle_node.cpp b/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_lifecycle_node.cpp new file mode 100644 index 0000000..b79f4a0 --- /dev/null +++ b/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_lifecycle_node.cpp @@ -0,0 +1,254 @@ +#include +#include + +#include + + +namespace ros2_cpp_lifecycle_pkg { + + +/** + * @brief Constructor + * + * @param options node options + */ +Ros2CppLifecycleNode::Ros2CppLifecycleNode() : rclcpp_lifecycle::LifecycleNode("ros2_cpp_lifecycle_node") { + + int startup_state = lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE; + this->declareAndLoadParameter("startup_state", startup_state, "Initial lifecycle state", false, false, false); + if (startup_state > lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED) + this->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE); + if (startup_state > lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) + this->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE); +} + + +/** + * @brief Declares and loads a ROS parameter + * + * @param name name + * @param param parameter variable to load into + * @param description description + * @param add_to_auto_reconfigurable_params enable reconfiguration of parameter + * @param is_required whether failure to load parameter will stop node + * @param read_only set parameter to read-only + * @param from_value parameter range minimum + * @param to_value parameter range maximum + * @param step_value parameter range step + * @param additional_constraints additional constraints description + */ +template +void Ros2CppLifecycleNode::declareAndLoadParameter(const std::string& name, + T& param, + const std::string& description, + const bool add_to_auto_reconfigurable_params, + const bool is_required, + const bool read_only, + const std::optional& from_value, + const std::optional& to_value, + const std::optional& step_value, + const std::string& additional_constraints) { + + rcl_interfaces::msg::ParameterDescriptor param_desc; + param_desc.description = description; + param_desc.additional_constraints = additional_constraints; + param_desc.read_only = read_only; + + auto type = rclcpp::ParameterValue(param).get_type(); + + if (from_value.has_value() && to_value.has_value()) { + if constexpr (std::is_integral_v) { + rcl_interfaces::msg::IntegerRange range; + T step = static_cast(step_value.has_value() ? step_value.value() : 0); + range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); + param_desc.integer_range = {range}; + } else if constexpr (std::is_floating_point_v) { + rcl_interfaces::msg::FloatingPointRange range; + T step = static_cast(step_value.has_value() ? step_value.value() : 0.0); + range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); + param_desc.floating_point_range = {range}; + } else { + RCLCPP_WARN(this->get_logger(), "Parameter type does not support specifying a range"); + } + } + + this->declare_parameter(name, type, param_desc); + + try { + param = this->get_parameter(name).get_value(); + } catch (rclcpp::exceptions::ParameterUninitializedException&) { + if (is_required) { + RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); + exit(EXIT_FAILURE); + } else { + std::stringstream ss; + ss << "Missing parameter '" << name << "', using default value: "; + if constexpr (is_vector_v) { + ss << "["; + for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); + } else { + ss << param; + } + RCLCPP_WARN_STREAM(this->get_logger(), ss.str()); + } + } + + if (add_to_auto_reconfigurable_params) { + std::function setter = [¶m](const rclcpp::Parameter& p) { + param = p.get_value(); + }; + auto_reconfigurable_params_.push_back(std::make_tuple(name, setter)); + } +} + + +/** + * @brief Handles reconfiguration when a parameter value is changed + * + * @param parameters parameters + * @return parameter change result + */ +rcl_interfaces::msg::SetParametersResult Ros2CppLifecycleNode::parametersCallback(const std::vector& parameters) { + + for (const auto& param : parameters) { + for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { + if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { + std::get<1>(auto_reconfigurable_param)(param); + } + } + } + + // mark parameter change successful + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + + return result; +} + + +/** + * @brief Sets up subscribers, publishers, etc. to configure the node + */ +void Ros2CppLifecycleNode::setup() { + + // callback for dynamic parameter configuration + parameters_callback_ = this->add_on_set_parameters_callback(std::bind(&Ros2CppLifecycleNode::parametersCallback, this, std::placeholders::_1)); + + // subscriber for handling incoming messages + subscriber_ = this->create_subscription("~/input", 10, std::bind(&Ros2CppLifecycleNode::topicCallback, this, std::placeholders::_1)); + RCLCPP_INFO(this->get_logger(), "Subscribed to '%s'", subscriber_->get_topic_name()); + + // publisher for publishing outgoing messages + publisher_ = this->create_publisher("~/output", 10); + RCLCPP_INFO(this->get_logger(), "Publishing to '%s'", publisher_->get_topic_name()); +} + + +/** + * @brief Processes messages received by a subscriber + * + * @param msg message + */ +void Ros2CppLifecycleNode::topicCallback(const std_msgs::msg::Int32& msg) { + + RCLCPP_INFO(this->get_logger(), "Message received: '%d'", msg.data); +} + + +/** + * @brief Processes 'configuring' transitions to 'inactive' state + * + * @param state previous state + * @return transition result + */ +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppLifecycleNode::on_configure(const rclcpp_lifecycle::State& state) { + + RCLCPP_INFO(get_logger(), "Configuring to enter 'inactive' state from '%s' state", state.label().c_str()); + + this->declareAndLoadParameter("param", param_, "TODO", true, false, false, 0.0, 10.0, 1.0); + setup(); + + return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; +} + + +/** + * @brief Processes 'activating' transitions to 'active' state + * + * @param state previous state + * @return transition result + */ +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppLifecycleNode::on_activate(const rclcpp_lifecycle::State& state) { + + RCLCPP_INFO(get_logger(), "Activating to enter 'active' state from '%s' state", state.label().c_str()); + + publisher_->on_activate(); + + return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; +} + + +/** + * @brief Processes 'deactivating' transitions to 'inactive' state + * + * @param state previous state + * @return transition result + */ +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppLifecycleNode::on_deactivate(const rclcpp_lifecycle::State& state) { + + RCLCPP_INFO(get_logger(), "Deactivating to enter 'inactive' state from '%s' state", state.label().c_str()); + + publisher_->on_deactivate(); + + return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; +} + + +/** + * @brief Processes 'cleningup' transitions to 'unconfigured' state + * + * @param state previous state + * @return transition result + */ +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppLifecycleNode::on_cleanup(const rclcpp_lifecycle::State& state) { + + RCLCPP_INFO(get_logger(), "Cleaning up to enter 'unconfigured' state from '%s' state", state.label().c_str()); + + subscriber_.reset(); + publisher_.reset(); + parameters_callback_.reset(); + + return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; +} + + +/** + * @brief Processes 'shuttingdown' transitions to 'finalized' state + * + * @param state previous state + * @return transition result + */ +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppLifecycleNode::on_shutdown(const rclcpp_lifecycle::State& state) { + + RCLCPP_INFO(get_logger(), "Shutting down to enter 'finalized' state from '%s' state", state.label().c_str()); + + if (state.id() >= lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) + on_deactivate(state); + if (state.id() >= lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) + on_cleanup(state); + + return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; +} + + +} + + +int main(int argc, char *argv[]) { + + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()->get_node_base_interface()); + rclcpp::shutdown(); + + return 0; +} diff --git a/samples/ros2_cpp_pkg/CMakeLists.txt b/samples/ros2_cpp_pkg/CMakeLists.txt new file mode 100644 index 0000000..b77fc8e --- /dev/null +++ b/samples/ros2_cpp_pkg/CMakeLists.txt @@ -0,0 +1,41 @@ +cmake_minimum_required(VERSION 3.8) +project(ros2_cpp_pkg) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) + +set(TARGET_NAME ros2_cpp_node) + +add_executable(${TARGET_NAME} src/ros2_cpp_node.cpp) + +target_include_directories(${TARGET_NAME} PUBLIC + $ + $ +) +target_compile_features(${TARGET_NAME} PUBLIC c_std_99 cxx_std_17) + +ament_target_dependencies(${TARGET_NAME} + rclcpp + std_msgs +) + +install(TARGETS ${TARGET_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME} + OPTIONAL +) + +install(DIRECTORY config + DESTINATION share/${PROJECT_NAME} + OPTIONAL +) + +ament_package() diff --git a/samples/ros2_cpp_pkg/README.md b/samples/ros2_cpp_pkg/README.md new file mode 100644 index 0000000..55c8b62 --- /dev/null +++ b/samples/ros2_cpp_pkg/README.md @@ -0,0 +1,62 @@ +# ros2_cpp_pkg + +TODO + +- [Container Images](#container-images) +- [ros2_cpp_node](#ros2_cpp_node) +- [Official Documentation](#official-documentation) + + +## Container Images + +| Description | Image | Command | +| --- | --- | -- | +| | ` + +| Topic | Type | Description | +| --- | --- | --- | +| `` | `/msg/` | \ | + +### Published Topics + + + +| Topic | Type | Description | +| --- | --- | --- | +| `` | `/msg/` | \ | + +### Services + + + +| Service | Type | Description | +| --- | --- | --- | +| `` | `/srv/` | \ | + +### Actions + + + +| Action | Type | Description | +| --- | --- | --- | +| `` | `/action/` | \ | + +### Parameters + + + +| Parameter | Type | Description | +| --- | --- | --- | +| `` | `` | \ | + + +## Official Documentation + +\ \ No newline at end of file diff --git a/samples/ros2_cpp_pkg/config/params.yml b/samples/ros2_cpp_pkg/config/params.yml new file mode 100644 index 0000000..809c91b --- /dev/null +++ b/samples/ros2_cpp_pkg/config/params.yml @@ -0,0 +1,3 @@ +/**/*: + ros__parameters: + param: 1.0 \ No newline at end of file diff --git a/samples/ros2_cpp_pkg/include/ros2_cpp_pkg/ros2_cpp_node.hpp b/samples/ros2_cpp_pkg/include/ros2_cpp_pkg/ros2_cpp_node.hpp new file mode 100644 index 0000000..4f63b85 --- /dev/null +++ b/samples/ros2_cpp_pkg/include/ros2_cpp_pkg/ros2_cpp_node.hpp @@ -0,0 +1,58 @@ +#pragma once + +#include +#include +#include + +#include +#include + + +namespace ros2_cpp_pkg { + +template struct is_vector : std::false_type {}; +template struct is_vector< std::vector > : std::true_type {}; +template inline constexpr bool is_vector_v = is_vector::value; + + +class Ros2CppNode : public rclcpp::Node { + + public: + + Ros2CppNode(); + + private: + + template + void declareAndLoadParameter(const std::string &name, + T ¶m, + const std::string &description, + const bool add_to_auto_reconfigurable_params = true, + const bool is_required = false, + const bool read_only = false, + const std::optional &from_value = std::nullopt, + const std::optional &to_value = std::nullopt, + const std::optional &step_value = std::nullopt, + const std::string &additional_constraints = ""); + + rcl_interfaces::msg::SetParametersResult parametersCallback(const std::vector& parameters); + + void setup(); + + void topicCallback(const std_msgs::msg::Int32& msg); + + private: + + std::vector>> auto_reconfigurable_params_; + + OnSetParametersCallbackHandle::SharedPtr parameters_callback_; + + rclcpp::Subscription::SharedPtr subscriber_; + + rclcpp::Publisher::SharedPtr publisher_; + + double param_ = 1.0; +}; + + +} diff --git a/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py new file mode 100644 index 0000000..d530982 --- /dev/null +++ b/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py @@ -0,0 +1,33 @@ +#!/usr/bin/env python3 + +import os + +from ament_index_python import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + + +def generate_launch_description(): + + arg_name = DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name") + arg_namespace = DeclareLaunchArgument("namespace", default_value="", description="node namespace") + + node = Node( + package="ros2_cpp_pkg", + executable="ros2_cpp_node", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), + parameters=[ + os.path.join(get_package_share_directory("ros2_cpp_pkg"), "config", "params.yml"), + ], + output="screen", + emulate_tty=True, + ) + + return LaunchDescription([ + arg_name, + arg_namespace, + node + ]) diff --git a/samples/ros2_cpp_pkg/package.xml b/samples/ros2_cpp_pkg/package.xml new file mode 100644 index 0000000..e9ce970 --- /dev/null +++ b/samples/ros2_cpp_pkg/package.xml @@ -0,0 +1,23 @@ + + + + + ros2_cpp_pkg + 0.0.0 + TODO + + TODO + TODO + + TODO + + ament_cmake + + rclcpp + std_msgs + + + ament_cmake + + + diff --git a/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp new file mode 100644 index 0000000..0670004 --- /dev/null +++ b/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp @@ -0,0 +1,163 @@ +#include + +#include + + +namespace ros2_cpp_pkg { + + +/** + * @brief Constructor + * + * @param options node options + */ +Ros2CppNode::Ros2CppNode() : Node("ros2_cpp_node") { + + this->declareAndLoadParameter("param", param_, "TODO", true, false, false, 0.0, 10.0, 1.0); + this->setup(); +} + + +/** + * @brief Declares and loads a ROS parameter + * + * @param name name + * @param param parameter variable to load into + * @param description description + * @param add_to_auto_reconfigurable_params enable reconfiguration of parameter + * @param is_required whether failure to load parameter will stop node + * @param read_only set parameter to read-only + * @param from_value parameter range minimum + * @param to_value parameter range maximum + * @param step_value parameter range step + * @param additional_constraints additional constraints description + */ +template +void Ros2CppNode::declareAndLoadParameter(const std::string& name, + T& param, + const std::string& description, + const bool add_to_auto_reconfigurable_params, + const bool is_required, + const bool read_only, + const std::optional& from_value, + const std::optional& to_value, + const std::optional& step_value, + const std::string& additional_constraints) { + + rcl_interfaces::msg::ParameterDescriptor param_desc; + param_desc.description = description; + param_desc.additional_constraints = additional_constraints; + param_desc.read_only = read_only; + + auto type = rclcpp::ParameterValue(param).get_type(); + + if (from_value.has_value() && to_value.has_value()) { + if constexpr (std::is_integral_v) { + rcl_interfaces::msg::IntegerRange range; + T step = static_cast(step_value.has_value() ? step_value.value() : 0); + range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); + param_desc.integer_range = {range}; + } else if constexpr (std::is_floating_point_v) { + rcl_interfaces::msg::FloatingPointRange range; + T step = static_cast(step_value.has_value() ? step_value.value() : 0.0); + range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); + param_desc.floating_point_range = {range}; + } else { + RCLCPP_WARN(this->get_logger(), "Parameter type does not support specifying a range"); + } + } + + this->declare_parameter(name, type, param_desc); + + try { + param = this->get_parameter(name).get_value(); + } catch (rclcpp::exceptions::ParameterUninitializedException&) { + if (is_required) { + RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); + exit(EXIT_FAILURE); + } else { + std::stringstream ss; + ss << "Missing parameter '" << name << "', using default value: "; + if constexpr (is_vector_v) { + ss << "["; + for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); + } else { + ss << param; + } + RCLCPP_WARN_STREAM(this->get_logger(), ss.str()); + } + } + + if (add_to_auto_reconfigurable_params) { + std::function setter = [¶m](const rclcpp::Parameter& p) { + param = p.get_value(); + }; + auto_reconfigurable_params_.push_back(std::make_tuple(name, setter)); + } +} + + +/** + * @brief Handles reconfiguration when a parameter value is changed + * + * @param parameters parameters + * @return parameter change result + */ +rcl_interfaces::msg::SetParametersResult Ros2CppNode::parametersCallback(const std::vector& parameters) { + + for (const auto& param : parameters) { + for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { + if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { + std::get<1>(auto_reconfigurable_param)(param); + } + } + } + + // mark parameter change successful + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + + return result; +} + + +/** + * @brief Sets up subscribers, publishers, etc. to configure the node + */ +void Ros2CppNode::setup() { + + // callback for dynamic parameter configuration + parameters_callback_ = this->add_on_set_parameters_callback(std::bind(&Ros2CppNode::parametersCallback, this, std::placeholders::_1)); + + // subscriber for handling incoming messages + subscriber_ = this->create_subscription("~/input", 10, std::bind(&Ros2CppNode::topicCallback, this, std::placeholders::_1)); + RCLCPP_INFO(this->get_logger(), "Subscribed to '%s'", subscriber_->get_topic_name()); + + // publisher for publishing outgoing messages + publisher_ = this->create_publisher("~/output", 10); + RCLCPP_INFO(this->get_logger(), "Publishing to '%s'", publisher_->get_topic_name()); +} + + +/** + * @brief Processes messages received by a subscriber + * + * @param msg message + */ +void Ros2CppNode::topicCallback(const std_msgs::msg::Int32& msg) { + + RCLCPP_INFO(this->get_logger(), "Message received: '%d'", msg.data); +} + + +} + + +int main(int argc, char *argv[]) { + + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + + return 0; +} diff --git a/samples/ros2_interfaces_pkg/CMakeLists.txt b/samples/ros2_interfaces_pkg/CMakeLists.txt new file mode 100644 index 0000000..a4c1359 --- /dev/null +++ b/samples/ros2_interfaces_pkg/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 3.8) +project(ros2_interfaces_pkg) + +find_package(rosidl_default_generators REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + msg/Message.msg + srv/Service.srv + action/Action.action + DEPENDENCIES +) + +ament_export_dependencies(rosidl_default_runtime) + +ament_package() diff --git a/samples/ros2_interfaces_pkg/action/Action.action b/samples/ros2_interfaces_pkg/action/Action.action new file mode 100644 index 0000000..8e9bc7f --- /dev/null +++ b/samples/ros2_interfaces_pkg/action/Action.action @@ -0,0 +1,5 @@ +int32 goal +--- +int32 feedback +--- +int32 result \ No newline at end of file diff --git a/samples/ros2_interfaces_pkg/msg/Message.msg b/samples/ros2_interfaces_pkg/msg/Message.msg new file mode 100644 index 0000000..0ecfe35 --- /dev/null +++ b/samples/ros2_interfaces_pkg/msg/Message.msg @@ -0,0 +1 @@ +int32 data \ No newline at end of file diff --git a/samples/ros2_interfaces_pkg/package.xml b/samples/ros2_interfaces_pkg/package.xml new file mode 100644 index 0000000..2ed88d0 --- /dev/null +++ b/samples/ros2_interfaces_pkg/package.xml @@ -0,0 +1,24 @@ + + + + + ros2_interfaces_pkg + 0.0.0 + TODO + + TODO + TODO + + TODO + + ament_cmake + rosidl_default_generators + rosidl_default_runtime + + rosidl_interface_packages + + + ament_cmake + + + diff --git a/samples/ros2_interfaces_pkg/srv/Service.srv b/samples/ros2_interfaces_pkg/srv/Service.srv new file mode 100644 index 0000000..3ad5501 --- /dev/null +++ b/samples/ros2_interfaces_pkg/srv/Service.srv @@ -0,0 +1,3 @@ +int32 request +--- +int32 response \ No newline at end of file From 65aecfb5e4a0282d063ffd2946e26962b4d2c74c Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Sat, 31 Aug 2024 00:18:54 +0200 Subject: [PATCH 02/67] make naming of package-name arg to cli consistent with other args --- README.md | 4 ++-- ros2-pkg-create/src/ros2_pkg_create/__main__.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index f214da6..9b1a2f9 100644 --- a/README.md +++ b/README.md @@ -13,7 +13,7 @@ eval "$(register-python-argcomplete ros2-pkg-create)" ### Usage ``` -usage: ros2-pkg-create [-h] [--defaults] --template {ros2_cpp_pkg,ros2_interfaces_pkg} [--package_name PACKAGE_NAME] [--description DESCRIPTION] [--maintainer MAINTAINER] +usage: ros2-pkg-create [-h] [--defaults] --template {ros2_cpp_pkg,ros2_interfaces_pkg} [--package-name PACKAGE_NAME] [--description DESCRIPTION] [--maintainer MAINTAINER] [--maintainer-email MAINTAINER_EMAIL] [--author AUTHOR] [--author-email AUTHOR_EMAIL] [--license {Apache-2.0,BSL-1.0,BSD-2.0,BSD-2-Clause,BSD-3-Clause,GPL-3.0-only,LGPL-2.1-only,LGPL-3.0-only,MIT,MIT-0}] [--node-name NODE_NAME] [--node-class-name NODE_CLASS_NAME] [--is-component] [--no-is-component] [--is-lifecycle] [--no-is-lifecycle] [--has-launch-file] [--no-has-launch-file] @@ -33,7 +33,7 @@ options: --defaults Use defaults for all options --template {ros2_cpp_pkg,ros2_interfaces_pkg} Template - --package_name PACKAGE_NAME + --package-name PACKAGE_NAME Package name --description DESCRIPTION Description diff --git a/ros2-pkg-create/src/ros2_pkg_create/__main__.py b/ros2-pkg-create/src/ros2_pkg_create/__main__.py index 78d3ab2..15aaeee 100644 --- a/ros2-pkg-create/src/ros2_pkg_create/__main__.py +++ b/ros2-pkg-create/src/ros2_pkg_create/__main__.py @@ -15,7 +15,7 @@ def parseArguments() -> argparse.Namespace: parser.add_argument("--defaults", action="store_true", help="Use defaults for all options") parser.add_argument("--template", type=str, default=None, choices=["ros2_cpp_pkg", "ros2_interfaces_pkg"], required=True, help="Template") - parser.add_argument("--package_name", type=str, default=None, help="Package name") + parser.add_argument("--package-name", type=str, default=None, help="Package name") parser.add_argument("--description", type=str, default=None, help="Description") parser.add_argument("--maintainer", type=str, default=None, help="Maintainer") parser.add_argument("--maintainer-email", type=str, default=None, help="Maintainer email") From 9dda70d87a31efbeee4b07797582a31d479073e6 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Sat, 31 Aug 2024 00:31:56 +0200 Subject: [PATCH 03/67] auto-read available template configs from templates folder --- ros2-pkg-create/src/ros2_pkg_create/__main__.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ros2-pkg-create/src/ros2_pkg_create/__main__.py b/ros2-pkg-create/src/ros2_pkg_create/__main__.py index 15aaeee..4a00813 100644 --- a/ros2-pkg-create/src/ros2_pkg_create/__main__.py +++ b/ros2-pkg-create/src/ros2_pkg_create/__main__.py @@ -9,12 +9,12 @@ def parseArguments() -> argparse.Namespace: - parser = argparse.ArgumentParser(description="Creates a ROS2 package from templates") + parser = argparse.ArgumentParser(description="Creates a ROS 2 package from templates") parser.add_argument("destination", type=str, help="Destination directory") parser.add_argument("--defaults", action="store_true", help="Use defaults for all options") - parser.add_argument("--template", type=str, default=None, choices=["ros2_cpp_pkg", "ros2_interfaces_pkg"], required=True, help="Template") + parser.add_argument("--template", type=str, default=None, choices=os.listdir(os.path.join(os.path.dirname(__file__), os.pardir, os.pardir, os.pardir, "templates")), required=True, help="Template") parser.add_argument("--package-name", type=str, default=None, help="Package name") parser.add_argument("--description", type=str, default=None, help="Description") parser.add_argument("--maintainer", type=str, default=None, help="Maintainer") From 3f94051e2c3e8d0e16ae4e20bd825f67c99658cc Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Sat, 31 Aug 2024 00:33:01 +0200 Subject: [PATCH 04/67] add flag to choose between local and remote templates --- README.md | 17 ++++++++--------- ros2-pkg-create/src/ros2_pkg_create/__main__.py | 8 ++++++-- 2 files changed, 14 insertions(+), 11 deletions(-) diff --git a/README.md b/README.md index 9b1a2f9..5fc3bd2 100644 --- a/README.md +++ b/README.md @@ -13,17 +13,14 @@ eval "$(register-python-argcomplete ros2-pkg-create)" ### Usage ``` -usage: ros2-pkg-create [-h] [--defaults] --template {ros2_cpp_pkg,ros2_interfaces_pkg} [--package-name PACKAGE_NAME] [--description DESCRIPTION] [--maintainer MAINTAINER] - [--maintainer-email MAINTAINER_EMAIL] [--author AUTHOR] [--author-email AUTHOR_EMAIL] - [--license {Apache-2.0,BSL-1.0,BSD-2.0,BSD-2-Clause,BSD-3-Clause,GPL-3.0-only,LGPL-2.1-only,LGPL-3.0-only,MIT,MIT-0}] [--node-name NODE_NAME] - [--node-class-name NODE_CLASS_NAME] [--is-component] [--no-is-component] [--is-lifecycle] [--no-is-lifecycle] [--has-launch-file] [--no-has-launch-file] - [--launch-file-type {xml,py,yml}] [--has-params] [--no-has-params] [--has-subscriber] [--no-has-subscriber] [--has-publisher] [--no-has-publisher] - [--has-service-server] [--no-has-service-server] [--has-action-server] [--no-has-action-server] [--has-timer] [--no-has-timer] [--auto-shutdown] - [--no-auto-shutdown] [--interface-types {Message,Service,Action}] [--msg-name MSG_NAME] [--srv-name SRV_NAME] [--action-name ACTION_NAME] [--has-docker-ros] - [--version] +usage: ros2-pkg-create [-h] [--defaults] [--use-local-templates] --template {ros2_cpp_pkg,ros2_interfaces_pkg} [--package-name PACKAGE_NAME] [--description DESCRIPTION] [--maintainer MAINTAINER] [--maintainer-email MAINTAINER_EMAIL] + [--author AUTHOR] [--author-email AUTHOR_EMAIL] [--license {Apache-2.0,BSL-1.0,BSD-2.0,BSD-2-Clause,BSD-3-Clause,GPL-3.0-only,LGPL-2.1-only,LGPL-3.0-only,MIT,MIT-0}] [--node-name NODE_NAME] + [--node-class-name NODE_CLASS_NAME] [--is-component] [--no-is-component] [--is-lifecycle] [--no-is-lifecycle] [--has-launch-file] [--no-has-launch-file] [--launch-file-type {xml,py,yml}] [--has-params] + [--no-has-params] [--has-subscriber] [--no-has-subscriber] [--has-publisher] [--no-has-publisher] [--has-service-server] [--no-has-service-server] [--has-action-server] [--no-has-action-server] [--has-timer] + [--no-has-timer] [--auto-shutdown] [--no-auto-shutdown] [--interface-types {Message,Service,Action}] [--msg-name MSG_NAME] [--srv-name SRV_NAME] [--action-name ACTION_NAME] [--has-docker-ros] [--version] destination -Creates a ROS2 package from templates +Creates a ROS 2 package from templates positional arguments: destination Destination directory @@ -31,6 +28,8 @@ positional arguments: options: -h, --help show this help message and exit --defaults Use defaults for all options + --use-local-templates + Use locally installed templates instead of remotely pulling most recent ones --template {ros2_cpp_pkg,ros2_interfaces_pkg} Template --package-name PACKAGE_NAME diff --git a/ros2-pkg-create/src/ros2_pkg_create/__main__.py b/ros2-pkg-create/src/ros2_pkg_create/__main__.py index 4a00813..80f70ed 100644 --- a/ros2-pkg-create/src/ros2_pkg_create/__main__.py +++ b/ros2-pkg-create/src/ros2_pkg_create/__main__.py @@ -13,6 +13,7 @@ def parseArguments() -> argparse.Namespace: parser.add_argument("destination", type=str, help="Destination directory") parser.add_argument("--defaults", action="store_true", help="Use defaults for all options") + parser.add_argument("--use-local-templates", action="store_true", help="Use locally installed templates instead of remotely pulling most recent ones") parser.add_argument("--template", type=str, default=None, choices=os.listdir(os.path.join(os.path.dirname(__file__), os.pardir, os.pardir, os.pardir, "templates")), required=True, help="Template") parser.add_argument("--package-name", type=str, default=None, help="Package name") @@ -65,8 +66,11 @@ def main(): # run copier try: - # local use: os.path.join(os.path.dirname(__file__), os.pardir, os.pardir, os.pardir), - copier.run_copy("https://gitlab.ika.rwth-aachen.de/fb-fi/ops/templates/ros2/ros2-pkg-create.git", + if args.use_local_templates: + template_location = os.path.join(os.path.dirname(__file__), os.pardir, os.pardir, os.pardir) + else: + template_location = "https://gitlab.ika.rwth-aachen.de/fb-fi/ops/templates/ros2/ros2-pkg-create.git" + copier.run_copy(template_location, os.path.join(os.getcwd(), args.destination), data=answers, defaults=args.defaults, From 5121d06812151fe2d87f60bd2644e0069bb152c6 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 2 Sep 2024 23:47:47 +0200 Subject: [PATCH 05/67] prepare readme for github release --- README.md | 87 ++++++++++++++++++++++++++++++++++++++++++++++--- assets/cli.png | Bin 0 -> 143582 bytes 2 files changed, 82 insertions(+), 5 deletions(-) create mode 100644 assets/cli.png diff --git a/README.md b/README.md index 5fc3bd2..b98dcca 100644 --- a/README.md +++ b/README.md @@ -1,16 +1,93 @@ -# ros2-pkg-create +# *ros2-pkg-create* – Powerful ROS 2 Package Generator -### Installation +

+ + + +

+ +*ros2-pkg-create* is an interactive CLI tool for quickly generating ROS 2 packages from basic pub/sub nodes to complex lifecycle components. It is meant to replace the official [`ros2 pkg create`](https://docs.ros.org/en/latest/Tutorials/Beginner-Client-Libraries/Creating-Your-First-ROS2-Package.html#create-a-package) command. + +- [Quick Demo](#quick-demo) +- [Templates \& Features](#templates-features) +- [Installation](#installation) +- [Usage](#usage) + +> [!IMPORTANT] +> This repository is open-sourced and maintained by the [**Institute for Automotive Engineering (ika) at RWTH Aachen University**](https://www.ika.rwth-aachen.de/). +> **ROS is the backbone** of many research topics within our [*Vehicle Intelligence & Automated Driving*](https://www.ika.rwth-aachen.de/en/competences/fields-of-research/vehicle-intelligence-automated-driving.html) domain. +> If you would like to learn more about how we can support your advanced driver assistance and automated driving efforts, feel free to reach out to us! +> :email: ***opensource@ika.rwth-aachen.de*** + + +## Quick Demo + +```bash +ros2-pkg-create --template ros2_cpp_pkg . +``` + + + + +## Templates & Features + +*ros2-pkg-create* provides multiple templates, each covering a different questionnaire for generating all the components you need. See below for the list of options. Note that all options can also be passed directly to the command, bypassing the interactive questionnaire (see [Usage](#usage)). + +- [C++ Package](#c-package-template-ros2_cpp_pkg) +- [Interfaces Package](#interfaces-package-template-ros2_interfaces_pkg) + +### C++ Package (`--template ros2_cpp_pkg`) + +- Package name +- Description +- Maintainer | Maintainer email +- Author | Author email +- License +- Node name +- Class name of node +- Make it a component? +- Make it a lifecycle node? +- Add a launch file? | Type of launch file +- Add parameter loading? +- Add a subscriber? +- Add a publisher? +- Add a service server? +- Add an action server? +- Add a timer callback? +- Add the docker-ros CI integration? + +### Interfaces Package (`--template ros2_interfaces_pkg`) + +- Package name +- Description +- Maintainer | Maintainer email +- Author | Author email +- License +- Interfaces types +- Message name +- Service name +- Action name +- Add the docker-ros CI integration? + +## Installation ```bash -pip install --extra-index-url https://test.pypi.org/simple/ ros2-pkg-create +pip install ros2-pkg-create -# bash-completion +# (optional) bash auto-completion activate-global-python-argcomplete eval "$(register-python-argcomplete ros2-pkg-create)" ``` -### Usage +> **Warning** +> Outside of a virtual environment, *pip* may default to a user-site installation of executables to `~/.local/bin`, which may not be present in your shell's `PATH`. If running `ros2-pkg-create` errors with `ros2-pkg-create: command not found`, add the directory to your path. [*(More information)*](https://packaging.python.org/en/latest/tutorials/installing-packages/#installing-to-the-user-site) +> ```bash +> echo "export PATH=\$HOME/.local/bin:\$PATH" >> ~/.bashrc +> source ~/.bashrc +> ``` + + +## Usage ``` usage: ros2-pkg-create [-h] [--defaults] [--use-local-templates] --template {ros2_cpp_pkg,ros2_interfaces_pkg} [--package-name PACKAGE_NAME] [--description DESCRIPTION] [--maintainer MAINTAINER] [--maintainer-email MAINTAINER_EMAIL] diff --git a/assets/cli.png b/assets/cli.png new file mode 100644 index 0000000000000000000000000000000000000000..150e79d1c9c4e6b8c70e70e23806fb37355b322f GIT binary patch literal 143582 zcmb5W19WBEwgnnhY}+;}wo|cfn-#Mvwv&o&+jc5W#kOt#UGKho-mUZRX}|r})^2-k zBx|lY2l^bN_Z=!PD-H*Z4GjbY1ouTkL=gxG+#Co9tPm0e@J@kgogv@}*hx`b2&i%b z_XzMp#6y=;(we+q7%4f^kM zu)^P8Y)`x400I&K`XVBz>;`h(m05sC~=V}AVit-KrM=>3@-S|6YHnC*wFeA zSCT`2R0m(1zlkz#qM(96zAGeeLcs01r?+0Mor~;*&B6LA`t=$?SG)7QhS^!i$H6Mg zg->NiqoXUWcA}lh{J8q#^4SN7_Oz*n*!Qa^odIPGu-k;xJF8JNA^N(o}GDLxd&Tc08qt_j*I$y7)%;5Th z-df)y8f{k45fKRsy(Tyh7B7FEKRY#TMWW|CHr8+|f|LH;24=x%5hpwXMeeYf3rge+ zodiUrq{7YIb*oN)?e}S=(S*x97+lhRE#QAUk{cH5St_gQ^jL3qNBqHNyV~q@AnX5L zxe;VRG$K*q@;wv>+&09R263@s>^Y) zc;Mbjq4=7uY|?*BJzx#GL&56bL+)^0P1hdl5wl+;$>GMMbX@PH-^kR82Zx&fAujmK^K#ysieiKHlu~ z^z?R@Bk*~-I5{;ka|M69$~@BM${?3*d)S{N@B=F+&;G(Ot2S=zD`R^ulV|o6Fu?Zy zoFjGyJM%++Tt0?|g~e%iI97d3MMHzrVY@#&n-FUWdZ)CkQYaI{nAW(GDEX|sZbHZ& zRar=|Y(dvk2Ft!b1j*@OB2ayy&Glk+brlo>-s|P8NfN>$k7t%FSsNJ*4Gj}hT}MYp zTf5!;W?#?eNtBE5=jqiDL2~endY8}Jl39~vWO1WWpgsA1t=VK|d3kvt42EGh92}f@ z6s|_6m%FZR=IKB{jeZYExru+@Mb}4^pro9La7zAw^;x!FGe(&k&DPBd$ z1O_Iy;d_qpxeYgAq`4`)s0Os@8%%Vw93@r7>QXQRP$ zbbTCKC;Di!DR&8L`rDtY(|rfkJTx?vhF<_RC+(gicikFvMw37{X#I*EOg+82>NPEj zA(O#%_YDHy?Pi=^tx6ZpH{tnQa?S;{vR9}YU^IIN2f`Zi@IYJ>bWN+onzpS+XSv`QXA1nK;~e42zKL@(0rlHrlZM;#t_qa!1s z5fRFjw*K%Tyb$;2Yc&4au4~SSKkOmn;xchL6ADkNx^%g^E_-20CC>nhj?Zq3iwiJI zZfiSgUOHxb8iux0W>|G+G}39aEN|7N;w${|bk3Xm6+1OqTtUVMHC^{lT3?3!1c*?X zmWW{?Z4h{GW7^XgI&P6g6ceMb5pm)wwVGrb%};fnx!0?QB08UsX&4w7_OuDj@;+_X znv1leWLg?n`SK+K53B{hhqvWfW4JuDreSC8+Fmsxy*7A-H*C0`Wj@P&uR%X!(%Gso zw??<7_%l2l>Vl0Kr{6(GDOOBDc{$9QSqGt#521Qo zLRf<2G&e9Xs3qm}!G)fKHCc|r=hakF0wsbH{*Ev@sOL1!TAMc#PXRLri%k$$7Zdr3 z9Si{hA$dB#u9L~@(SEuZ)#G+ex~YF~uot+lTYhJmZz>Mo^OR|{wBZ z%{y8i`0c#y0{wm1Q%IUL!(jIZ_q~CHlvI3~Va+gxt;A>l-Vg-qWp8 z+|r7Qz{ppsoNVBdYba?sIgHH5vJO}G&>gt83CQjqL>%pqDr#f%RmpPh!T9KB@4&!7 z$If})tZT=_X}pWVBZ?NB4jbBMbgQn5WnL8o|4`u*L$1dPbHi62(LZzbR0re_l!+kO zX%2$&rCVIC0{0=wy7w5yOMmUxN2U|&Ku~3zeDaRR?QjWKtpbxcj54T^>(VW6>(hRk1Lrx?V58Ln{WPBHHQ(!HA0{;$ zbz<#u6dtz^Al9MLa20T^yB}l>vj?2}n`msK#`#|g;;x#kT46Tl47$wyT5rSrq4d6N zC#D_;Z)1Ono zg!iiYnaMGe_-`ic0`|-5L>Z+UKeZGcC3t)}U7-m^FxyXmEmB?daBItexE!shIy_5x z+@3R^hE~}BTh`k!=l5^9ri!e6M9OTh1LEcGsBCdo0XerKFkv<}OSPiu%=Zr$z8`HI zWF$B@pI0g)F6XuE1haa{hQnsM5GAraj;V4|i4>#?QguAf8iWX6wt@))EQ25^A%dcP zD9`95l#ysY6LCN^GVR4il3%$+XOIYW@0S}jFm^qnG%bJL4@;|{b7UUA*w4;-0epT0@bU7MsGR7 zQxCJe?^9~Qlc>v&5mh>>E8!y5^FyHxuW5bs%Pb{ElxDh#`ymLtbs*oWZpn~=bcNvV*JX#5g9~hyC(e9yq+9YzM}wmnXp!1i=a&zHnJmT^M$-M1GckIya7FH_J6*H3+@zc^!f}|Md>JVfC zQY@;IB`cWuk)Qo?8Yv8*Q023%XEV`?mV&yV_k|)~j^5v1!d(==Y|d9(2)u8Rf~vy& z`nulls(v8Bo=%6#5UIeYvD=Al(W&GeBRZzlijJb!B00YW!d*$w=f#`V{7^XU4L#P+ zRZZq0n`yWWWWkd6(EKc$lfNj>fpYSh2@{neURV)}dF?doiU%#8 zr)KPG?q4d`W^W-A&FCU6;+t|Ef$IOj_I_X^iCiI_mf%5lolk{}hlJGBk`3R0 zz6y+KmcWMns7**a?ag%%`YzHM#;hba$Yk)NS^P0EeDtJHB&$blY?*G5nP)W{vxs?TL zSw-5{5j6KKm8U^L)K~!FX3M46pNvwqm|70U5S4NWaro~SSYiZIs@#vUOlo@^6-bZ? z!_>2!ikIB>SAryKJ3?v3z&R}FxKhbE56tTYK#IZwi|Qs)*A|}!krfENbDxyg4MyS7 zc<)X=eu*a^5yQ+Ai&Vtdv^+RC*g*!0W&K4PnSGu7AaUxL%~i&eP_U$2nqv8VR4RYW zpnNg?em&73!<^ey44pSCn^cTOZIY@b!^2gHPpa~xvF28*{H@dKL75M>&?ejv5MwC^ zqYaZ6!&SYK=(J2d6nUin3>TZVU}I2bi37SLzUElGtEn_vqGWXh`AL|!v0dp8=WA9| zIVX{hzS1gUGwGa80dcu{mr`?7Y=_DXo0kzR6V2zXC;IvW+Z_+i_HS( zI`+qFbrHQWC(pI`5AwZw%a8)3^7LUMnr(=1Tv7Y<^PPtB~ZKAr^gq3p9q@O6xg z>#&lQPl;4wDYG<}$fj_J6wtj|4~jn$Zb@OPA3PrBMW;4bpA=>93vBcN6-uXEpEYf; zv9cPZP|7nHCT2=FAm*Nq8+E&l9h3n)Bb;#+oak;r}?S$cPo4q%d9u)JL$JkhjV6oqB9W;>cE-?D)wp{xn&9jsG#(Gp8JiKZ{v@;V6t* z4na@?s8)-exeIEOck6BQWrX7$mEa%xn~0GdCb5=5x0Pr#ssisZX?aB7V4z{~9JsnlS}|XCiyVs<0}>rT~mS2*$^0szT`yBIF3zIFcnrhhFXAhpq(F zaohn4L_fJ6~EEisxkoY9Sr`#J8 zY*?$ADTjuB$`-z@w+$YubS?IEsI8>8Al3S}_uu}@`%9-%IDR23tz*ogoK!av4_2LO zTBQBJmW%xp2{aP|KRiCVQNY8Lu_~a#!jP&}Xzpzq=))1l4agVa7KH3FGrckC2M-DQ zgB$RVE-x>mP{GgS*}yDo_=7``jTnO{);7t)lvq6FWEl$=h;+KHNA{5^TM;sM`Cv7T{}QM|jl zDeuSKUCWFir74WQQOYzgz5E(Y)RY>wzzvlj-{f&U*LL`_pu*Dst=e462I)9W0~nqd zj}M!|Ha0D3oeui&s~PwBaM0udl{Ur>;!y#SXxaBC$+3Vx#T5gh@?2CA zHga7Q1xxJu%(XHLP5)pjI(DjGrCBEkm}QbTzlG-`MHGc5bx}2P0Kzc8~icY%>*Jq2^BW5 zOuphNA;+RG6w*LyUZ&}bF{;T>R5}t8(&C}Ot7V{Z&^W|-*N0D9zgbMCa5w&>*<_B{ zLW-d{NQ+tJQdBi>hz3D{|NV>Y{A`#*YGes+saTqwXk_-G*dO_nH_0!a9pbQNHG|t> zH^U%H=9jJT5!pdhK*w)T>PLgPsWpvu4l?v-d756ruNN?nsPLhG7MT9319v}xd2sqd z;sXB}CjP^^oAH66%_?2xIEeoiuK#+8LAbd)4y^6xH&3L^WRIxLzPn$jrefI<nR(HvVF*it{KMd=(BGY#(K187oox!1HqtMN#2$5NM;gG!Fb^tGrTPUS>Mu zNS>N_uaWr$tQz`+kf*2KYGHaNCBsFlec_%)EqwV=nf9xO5Msg0)8{% z7G}z-e4S23wV&=^ectHt8G*z^g?BR2*h(ix*Qa$Cex>Vb#A@osYHD<{b_wi_2!F|5 z>FC%Sw)mrA;pYs7OPwwg5^`xN#ej{E{k$_0v9o6~Di{qD4S92?()g8udv)lbuEmLI zpRCQLa$=%!Wb+JZmK^lNFh+bZ5~FnKs&=N&q=MV?oQm?)P+HeE)$fE~>P1R2nfwB+ zuGwgpvY^t^!_suJ^?h|*c1zhg!9`x8_-h&- zP6hJBZpp>6?!_A@2>7Q@By?O%l#h9wP5?u(P&0_V%>f4S^1NaC&;HRNpt(YxE)y1Y zba1c{`5ym%@`7;Neb9%m6m@5%GZi)&^&P(zKWsA24d`(p7ECs!s4~Cu{H;&CKAW4H zUbeYFErI01TGg7s2*bydhqcN(^i3~_REN_IlD^&ZS8>_=du2gh=1yOe>txG9I@NzT zp&#ic*j9N-3)Y$u-aM;tT;_U*7W}{uqzeLj&97e-C91oUDWIotsj1F9mPnK>dRnKy zee0nzDd2{_c11xV>p95i$;j$-F;a@onj z<|*hXDCH7K8foz=Gc7LB_AFNmGe0mX5Xr#6#a>?K*x2xCXk@5p*j1UOcUGC&&GouI zU3tGeLj*iMCe6+5&&}EX9REavLc;D~X`96d@^jcFzvv;f!qyx$8JCV>O-(zuUHhju zKQB4k)Cx^Q?zR4xnrlr|w&T6?&aUQ1;{sa>h-q%yhxfR+qv`4RT;iQK&}fyUD#=Nn zdH0d(5Kze-5)z0{V0cxOE2+t@?LToq%-xfw8VYulCzi8qj_OFiZ=S@UVlxvGQWmv7 zOSm5)SWqPPOh$ymTwkwiDKnCgn~JzSZpFpzSy*It@Ss!lQv?R#QBkRmqTF19xqINz zQc)F`WuT#O^AWdqwz&H`graT0>|xgP+}!_YbA&y(lS2$HXt>kyqO$Of6OG31N^|iz zuI~~~XvVe6nl3`%qARb|^|dX zWLSP=Wla&FC_IlHqXhfbeu|4J5N@E{U&|Ax3%Ouu^Jik^0{4whO5$txE-SSlB~Y&^vWa zOH?kp^NSfaJd+Fz7YqBj>P!4C^T@QV?ak_Tl^pi)%p)_uFSGFyUy+y#oO%*YZK7`}N_(ao{Z&mjcSWFGR>}OZMN;>h#*Rz(3>?kI$ViiK#O9<_xbl)>b zw75BW$@f>3Z+`Z5arg+e&mBQ`Lt8oUbq7k){REiH+WaE$V)ny>R*^4jT|(=``@J~A0SFfyMtQCX@h zbk!|n#@FKv%O!*snYLnM0^|>$*RYE8YMVj=;pLRm-{Y6SFTFb_|77&rnn z{3vO9tSRE16_k?L&I->`cu43Tya3=vR+-j_I-O5=q1N}!7ly@7%V4v81qCnR&5348&fVwHx*bc`&HT{*S{Q#uTq*$RvRK_@%hlb*=^o`S@;I4b3G6; zRJBi(=&x6-e8PNmYkgpzDqZ+YMy+_t@T~|{!}O7BM{vM*W{No7UdE$lr8K5m?XV*bg{b%p5l^3|L zOB$E40`16RIKG!3rFUt(FW7+e5%^|-e?FAeRem+|2cv=Kvus9+W)MASqq#1vHfs2EhOt_)##LpKp z8Ye4VpCKJ?kJDOU&{z{cf-rUEKx-HW$(L0M@dj$iN1j^mG*UldS}N$fds}X!t1Mpv zZtBXOT0)}q4yVIxY9d*V#huQdTRzUTqV%Ng-n)>Lh7y@V%b$|$p|b`;E3h?eRrazL zD$(d33*IKiX5sjVn9DVUf7a#08oH!QnxQm`PR_g;X(|<8Mz)#sfwvr;v6oobO{Rw) zZE$(@E48_dbh7Ol^Vc|0!24>s(Z8Ql4x?DmZp%MyhD!NJ%6S&(kacDIZqt#76QjTd zq2Y*_d+ndGyF&F`1&MCRr13j1ZxAKLxxd`bvg&?cNOc=je$OhxediE;i0dgyVXEmh z(DFHn>KNwM!rahncUQ*1=AkVs6Bc(X!{M=NRoJ-+B}8A7na#lFSz#wEF6}(;q|=IS zWRQryzDf+=Yw+D@=<0xj_mBL8@-bBbW&SMpaQ|b=Ox)S(FlN(;@qKDDhLYbmz4yXK zqXatG4)<3DiuNyZd(8HE^&QT)XQ-zgf0Ez=1U5?bl`c7vx`uhf*IUo2oGuwtg~)`d*yHdC=wsw`kC zC@Dd4&Ho$0F$d}w_Fkpe#8NDHqNKU{Jqvo-Ux`pk9;pqid^e^$5)e`c^bB9y4Z1E0 zmx^S4xLXHaoJ=F=M-*1`##>r?1zPCoTq~L@(QT((8aT?l>iM(o+tM5*K2{r)N=?m0 zkS1A|mKa;7Sr`t4{u2)Rfu##|r|NxT!=jW-d&^7=MWrKsB#f5kHzn|0!%k_?sQA$9 zeBBhP5!Kvqfp8x!Ct~P9z$v&1N>2}j3LQ%x>$V~;0JV?_)R#c{KccOlai2Y=;ftIO$DlHxsW_#deP50 zc@D0%FQ`xzk8Y|=$&@&02-@rkLkL_oU+k$dY-iqkjPGW-Pm{}4Wbn9)#^*&w-qL)& zf@6L?Z!QzC1x)omru6_sogNBT>&c4qdexgwraTDn;KQLF>X$CNrP2*u+c$Z0i?4N#fFN7A_f)^JhT11!+fdVPO_S-)$%_4_f#yMS z$Z&w}$wlQ0aP(DOl|fK=dwdoh;4SQEmKHpym9(cRFB6p^qs39yF}$yi_6711`5rN& z(FL=ofzi~nwdJrQR*%uH7OC1aTa=b2>h!^N*RLWRC$EL=e4E^e)*(s9pcR|>?yZ?h z-8qhM=CH9xcvI$_8*PmgWX7O#Y+|hym-me#zg5#YR0m-^Y8JnP0{kd|Mfsc^oqu#e z9NNrzJR^bmG?A*Z)XsvneI+(b>EctXyY@#qQMc%>`hE#FVa^bI}$> z=r7*vcNeigzQ4Mt-@?~?eO`oAZ!mDs5bo$9T;xzs5i*%FbFr>BA1eKFnj=6Q3`LH$$1d3 z`Vt_*y-(a!9e@z;xA^dRcZUh=H$DK6hELT;L@6AIOaacUU9BF*?lY^GZFb_hH{i1nq*AHqb3g$bW1eWXT%>tVa~+3fz*VWrMYUmpmaolfE~n)q4$ z?e_2y>frsg4%W)4FZX4AwUJt$Ho0y@;(7%={K%?S9mp#Fu@aXwuU65TrPO3aP>KS% z5`rsk!yTPLk$&G{FXOV`fE-|p4 z^>G4Rp5j*um&zC%TkMmQT#+^3;iY9=;_)9vK5cW8MgA9sI$amf>WhEYXx5SiC@My& zW*;{%iEhJ{$w@y`LD;vq3*piqZ|E)YvGGW|;Zs@7InX{^(+p$0C&OVEw@BF)-!^0n8?qHP1y_coNRG{XkZs(xT+qy@EU3z?HU^`wxhkZ~79hWu=<$~Ye=SyS z^0V^kl6CGxKQ5@aM+f6xs$cX8bi!w z1)0S^@ui;shPg0f|NS682Lk~&z*h|xpZKMA;&40u^v8wi!UoZNPt7egX+o$J0D!-2 z_dD!$@n35`%=dqM{}Ho5Aug&t)o8+^tfOsZaiPkSRZ5TR#D4bdtu`JK{D+SKpaF*- z$BLe!W4m<64*n0r*;Y8tiWiHhsF0Yh-5Tqg5h#>TSCi2iukqv!xx_8ih{==3D6T(; zk%p*-<`Jm6%2Biho?3XuZ)nbe0NO~uFK)z!p~o(!-=u!lFF!-;{pTCUh;}IMxe;E0V@kbinMf*r1aXU>92zkMby~ovv>k=zmv>TIiQ!H?)GpUg8;hETGE1Pyo7$3VZ zLcI3n_=UJIbgV~5rZ23dGS9KZ)&`@Mq9lWZhvZ_|B7zDBF&@r!GS;5;Y-!)rZ@nzL z(vskX!@B?>K@(hn;LrL6I#_y^1Gw~JfkOUMw<cWyQVvID&!(^P-aTha+SsNWN zZCYWQwH-7;OFtfL*J%-RFmh4_AzoJo?{Ynqm86D(a+VJ|8wk6qHPy~wK+*+(RqakU z7Vbu`90kan@4!dQyDk~u`&s-2xAja-p3c(P!m8=QTEe$a=xl3mWO-?LoAxl) z>n!}UgTLE`gobXkS@_eN7M;}NL;8`o@73jdr<3Pmahu$0^aef-dIL5^gahodUPn{E zOI}YPWaj*7-_t~YwYd3;3+gtN% zJx3cS|77;cx9$18MQ>2e52?^o9XBDT4TYHC1K;=2#Q73a;;8!rrI$6-Sh}||uMeDd z)t3hyZTc?%!S!`;PXm(ws6qlkeYFBPzq-0wGXzm*!`xnbQP*&njg+0L*{VkJI;zKl zblYj&sKFfxip4{xo?l=fqRg(WnZC7kc-~=RdYD>Y_kMlt^L+W$@Oe*JwLtBt(P|38 zunRr%!Q0r}Jf`WPkf)D7u>uEwbdU`E6CMMNe~g(R z+aQv}{(BG41LT`+yn|_3+SblilwP~=P~^u;^Hs4(kf<>+vm{lAZ?iMi64mR`h!cOH z9Zk_bDhR`w%^GHYea=Lyv|Ld{%SpyH-i&il#Gl2wiZ#4`v=-XI$pXtsC#b1hW*cuN*&yk+OfkQUm`s-;PQ5?lM+%rnz5P6k9jDpf z2x@-~HapNyieU~G8eUdfIwC5xq^#_xgdD%aYjYCSbnu^7|Em!OD7MLVJF`p#!Q-&G zk0vw+1SA#iCncF$f3!INOkyolbM>D1`*i$uK>-j`sAluQrPog|^c~xy@kdw#qM!IO zGtbY@@8IC_#G-92Ej1rrE=G7k1HoJnl zI-u9)u$PbXHJ2U??W2e;s;_UpJDw}6%{A=y1E!G6l$MfdIG>2bVLt~De^qtEMY9VE z3dqRFXw)iKJ3O1N6UNVc-ku||Si}P0prCT>O`UpSCH`on{bh)3q?=*ASicH(hN3YN zlVnmE-OsU{-tDcH+Fb3Fl#FC#;CAbLym!jcCkWL(fq_w8Z87rj;L-tF*#TbnmwgBa zdwW!Pe<#WPbwjt(Ae4Cfnps4`!DA_&re6TuH{P~|_vf2w{}&4B^aMtG0S5&G9UU8Q z-Xv?bWs815YgUf;E+OMP3++Elk-!7-rY4pdpp6R{GE8&?&sqH}Te)6xyYI#pNpM_H z1pCeo|(pElU3|!%B-2h2vCQT-^8X-$llThljCPOsyBId&qSdA^-6@ zWSg43Sm+k_*VnpNJJEgM@F7sq!#^h(D57-A7u5|AaM+}w&5A?W%qG%{i;KIv1pth2WnmghO7#XyG|3kn+`a%PltQ_z z^)BC!&CSiy(o%qa0>BnA_;`N<&oJ3}I>=)16vqHiiV8RiIvx%W52ff^j1Q-B=;-J$ zR{#nI0@ysejm{ANGt_n85AP+62!%W`0M(v_i3!OOz*gT1MWOI{y&8Ib^(u&VdD&01 zL!SVUpa2RYt!Dcz0JkU>vl*bb08o@f(1uPUVs2fJ3X-==0ZIZ<5s|S>-nRC3uccZO zPEJntbvF{~RfBE-^K}V8OiGNk;U+OLUjEC7{_})4#qYOlD}2oNF=Pv{M3XesB^BlN zR+g7HFt;$U)Re<^wzja4uwf@CY6=RCrsJvGxrSvBUV~U>s{l6j_B9^23lBgA)7yE! zY&FS!!DAqN@I1u-4h&#gZv+vNVXOE?JgBArSCs&xQ1ztu!%c)PjMt zLAU`_Qh}h29EdBZ+P-ghzZpMj-hgSCTDC9la6L5nP0315PKE^;hlfrr-*@TxgfXmy z!1uVhI}*Q_!Wa|M?oZ?R_8QqyWARZhGJm#ggoLuHqY*u(F> ze~=&k9XCB_fs+v@goK32xlZcXmcs)$8%ah(>rQ3J<13 z&Mj=1MzvhNa;p8fw9FXyBw}<_5+V8qqx+#BEcT@M4 z8Sm`y^mO+CB>%$76vwC-ooaey3;9xMN=V&aII>oNex~e~En%?tWe-Gg-zNx@xK!pB z*kt{!{8Nbpp7>w@S$rzZw)G2s=gkB+Wd=Edf%)khfC-wQR-xO0J+N%=HiYMz&Go|? zW6*g)he9ifK@ULu%i2Ml?KxJE2(BjT7Ccad6V}Zg5a{Y=wOOtQu%F}}gM)*A!mv(A zJPVfxREOmA)MuMxJ3b5O=2t&GKj%&Zv&8x5{Et%XKOOh?`4lJ=hX%*Z-Hq@X(}!R8 zTH6CU20F&xen5a|zNu+pKCX}t^8Cr({@&72r9N=>sb-v73KVWyWEj3M_VG~T1#>cHgjtE5-FMTgE*V#6|jtVd(@E~G)0#H7FYNW ziHRAE33)5Mdq_OX>0D8ce%csv@)ZSdz2ziq00~UU7);o`LcX~_XAld@EG9rfRh1kb z2OC>|I47+7J~Q?(^&c&j0>-RJhPy&;qmxrZW3jQew9!S}(NW&s+`_`a#6;9d2_|fn z`*cu1N@y_25meGx!a$iEJSHZ_5Bnp=EwlqWxPKDt5tJE^9H)ztAGc47#^Y}MdZcLd;JMlT?HV7=-KMrLN_&c|&Sj%aLF=wNj~@!cPR@8z_vSKRZ0@&yeYoxD=0p_!rU6`2io zI`=i)nnNS}?6<@&)6uWOTWlF(XBEqWfa32ww|~WzRw`hf5>N3cK58z@>s>1ORA#xt z0+I#TQVqYZq9Sp3jh66Y)9f7Wr^5~M;~a;r-oVJ2b`HB<;ka#-wjRJIu`U{mhF_R)LKi(m8qB;OEJNFWu&CBb&krP@l_sH2}O45)2GLl zY|9|eCxEUlCA{S*sisj{7fp@Edro0 zK!g$Tpw9c9I^_7@zN#d8u*ioP0<@_}$%Gw0Hyh+TjbE0`vf!A0=B^`s0EAfR+yTTj zRsi&<4oq!UgiDHU1i*!F0P%1wx5clyIgJ_?Kj!9{B!fN1&l3`8BF>a~U;6f0;z)}A zYc3G@pCSN!9^wiG8xL)HesOVqd3kB;puw9<0SRd;9QNnp>T3J9D$xvyfBzQ1^BwjM zAupVAP0tl#}zP4LZfEDJ0g@BdS+{~L7x-f1NP4u&>cLy9?xc0Zaa*xK5XIO4M31gagW zF4!MSVc81;*U->t+VE*Rnfy-jH^%0$t<0LjdHSeAD6r9&-cp+wf-LcV+}5 zGf&5tGBvc2BRj6+m$@Xr%!uz!f0NbzYnJVa0slM7p8#d%^5972MqG_TjMbx_#x#+& zqY?MyZP-`HQK|!%9Tnre#7=!D_Y13`Uri4k>V)>AuET$uR{JoNO+}fZwaqe9AmAbo<^p-wn%h(<8{>*<`!3dOWd(-qtqsew(BS8`Uc%v6%yMMZE zF~Cngu!IfDQZ(Y7dG~q7Lb>)wdve&0TyGY-RKSL_A4FF)Diy*0P5SazT|l4eTc-NX z>G#mYHxeAd(vp&eva;`DgL7Fdm6rQcn)RoXmmV)oo42`9jz&g1Clgp&ENq>8iyLS9 zNkjL_RVFz8u!_2jjnC;d4Gsnkf_(S`Dl+aSd^n2js$?%{D#ynu-c5ZU8)+c5;m%{> zG`#B?I6RHMJFgBZ#GCp3sgv^%*szra4u*zjuS|0!+s8Y-tJgHCvbzuOr_tTJW9!?? zL^XGqIn~J*mp7O8U0#+05k!$G1LsxVJ_9v*g|8#cn2pzhShDXlCV!eOVMgfJ7;rvDv8{ublIA#ZOBQYGi4 zKb@a-eN`OaT?)}}(!(EyK`_@dI@-VQ>u7raAh=<^`hO9B-5rm&P*DYr*p}>?{s`$ypOAW zlqOu?hzK#N7R-^#swvZ(# zT#-gu@M#b&f^c?ZcCB_3Qc=u;zoYBue#zSaO}4ol%9qv-Yw@a?W~dTria^awmSt+M z07wi`)=Fe8qB(t~$K#}=_V${5P_NeD@yH-87vq&PpDomYY;$??{~-zKkm^fn9T^_l zI=DM$tmGyeMeVwUPaEp}`~s>eTI`#yM>T|icN}^lanw(8O#c5MXvP2E~|R5sgfq4;^VQf0fvSTA!8wj=FK&D z5-&?^gpeiZ7bzAt&~4AsWIuXB!-Vlh+%4h9JWYGY+61n`&B`~~<#-plr4kKc&#@c_ zXS$CxuTy=&?61~WdT(HCBzH9S6=md%1GznSAbkQ zsjBg-wfGc&so*oDa9h!_5K8c}5%^0}h>&%N%f~?uV7EqBL*!hGkrH%2*T{w@pPBs+ zBcBJ1ym#p$n2SvPOT-p17u1)ARmX*qDBKPM2d*vCJYvZD>KpQ3-fm7kp#?`5dU~{= zr4e*;y8>v)ktTPRR5fMZ{P*56!?(Pzl z?(ST4cY`7zN=OSVN~D`b*Fx!5y1QGtxs!9hv(MQZe7<}AgJf=6UbL-WUOSc@VV zeVc6QoXx(_NRb|w9=hKEofohAl!$?Zp>BYC|n2;Z2J!NxBWcOnxCA}FNQ@(nlSVkKqM=qw@8>Uh}nAs|XzHx>P z<>yycYVEw~hZ^h4p>3#!WQ^z`qZnv z7O$|#Nb!U82jMo($L4c?fW@n%LH&rHKW7>j(?f_q~|{-4pi91y>(-o&I6tI7vO<`gk!>2f-I+f+#e%79o@fAt0qw30GDMUuafv; zKp>&?sPzQiY1ZZ2Fx#T`g6lnOB5U<-#wc%Bhys@?-tJ&%gKU$e2VIgjFO#(M_U>dz zFy2K`=40k6FQ*ZMPh1O!ZPKQHGsu5M);?*7TsZjZZVOo(q2omz8A>0u=%4L}J2%#|eQ~j>FvQm!j|`ocnx<_eq4#sF>ed$=&AcWP5FsE|>76 z{eW}B6vh$cJNS1sPt+9!W9jm8UZ?%0&>CBhj+XXZNnjt{J}G$ngf5s)(YUZuZ(GN5 zzYo6Nw(vaw#w9;S!ZrbHd{3L!PXAVu>Zg@S?(mcG@wmtL%Dr(&?@V&aWPClZnmSxx zN|i&T%^0RGXq@w|KJRg7Os{-h{`OA!P-LUYjcYm3>7wTp6 zg}a9Ad8Vnc`j$Z@k}{w6t`(w3VUocsLxrSiH~NC;y;lVWu8Eat2~ct#9P6(Ibcv&3 zqZ*C;mNpyp%O~sl1*xvuqHma=mgWEQoV1stc*kaLGLa%#FyDEA$jNKHk?0nKXURaw zTs_P@gMKHOjd-7NI5B+UbTE{=nV&92IsG(Bd0$v-n8G>nM$f14vyYx$(+`r2y3b%nQxO?wA%-M}Qhc73yM~%^2?bU#sBFb%Vq^m%C## zcnOwkMk^fU1f@d}IM}^*QKe~taq7xj?@28PhSO)Ie|=EDPh z?GWOewa{ID4bSofh9vT37l-w*o1P-M`eC68k*sqpJSP~IIc~q<Ix|JMx_46aWFjqEuoYy$%Jg-j zgctHyY_@4__UnmXu{YjP1k)xolwI~itq7<-yb+SWihBf-e6l)Ucv_eJ^^X7iAb{~~ zx>thL_nq&fM~_ks^jB9`0XQZ@z&|Opc|Sw!W;g!jv;#tZwW9rUpsz8% z^{<(`7wJ`PR1{gM3>Isy)gHhvbexyG4@76ou1RV!FlkBn$dBMgm}S zuy3*Z_(pte&jul%0t(31#iQSIuhSqAWRi*Q%~1YvbpZYYITlr*6Lp-cGsThP2Lrs| z%QtNrM2{c$7wEtNMnb1vVzMz>YF+c&pXc=*L?XB46rkdO@>n8N711_}TU-2IXBFG6 zt$otmmJKJ4ZKsEXe0CJ3!xSBW-`W}-4eH!mU$=-K4+Yq~cSkfWvfl)G>esKrozw+2@}$sU zJXSM+3k3!Sst&2Cs=9!(Vq)(zMt*)B?+3e!T|&26GpzwO1N3SDecsmA2EV*;my-*t z+x?4|^`>yP>F(+}2jJSl)>OfsW`&I&&`13Bjuw+)6!XO!z>>NjZO@pzb*r!#VNx{q z4d!_IZRgdn`@uRUEMfzIcufnl+W?9E{&nasDh`Rdtt}%INFAE5xB{-#-`{`M20-P- zzh%5n9wCvS|JwS9P5mB}{^J_&E&qZUb-l{tlKqj#Y+`p5y{Jscqz9l6r zHuXyT`}t7QOJ+FG2NlJ*LF553VA{0>ZPr0Hstp8G?L51j}kb(O|Q5NSpcv@*MbUoRb)i_u_ZoK1drZtg{1Z1--6- zQhZhaN4Wv`EUfNin*=~H&(ipRgz|-% z-TU=04zK&8iH!h!a&j`;XZh8^J40SdsOh?vu>17ed+E{%R4-D^X+n7~&vpTZCsuiU ztDlQgdhbK5o7-w)@B8=ffplhvZ950c&A?DS5hAFh%*1A#o1OK4K)g7&3nYlo(NE@~jGF8pbb}rRij`F-dm8m!5;K`&S9 z@8hDj>Fm%HZ_mf|_4g~{DjRGG`9HwrwEI?bzdBt%kV1L!V?Uco*yoMHzzm1aZy*rT z@Lx80ia$Sx0^v`#6@eRRS|7x9;rinrxXL2kP|iEp-~V@(mhr>G!g zVB%H3QeYIRVv+XDr?i`xn7DupgJ+Y02OmBl(|}snkHvvi7Mbw}tuI0|=~!Hl(a=$e zQohfu1HS7Q$gFuPn=Xrp_Id>5ib&aFN79)1{dhylglzUh`C?$W+OAsu^Ob#g_>zkY z&r^`q7Y!nXt2}xo-V;5-a;fp60gK=!!F^9xaYHu2*l=3WZg3o7qB9b`6lil&tO%e* z{rbHb2_e(dKZv1>qmtcgV|#lT$Q@8?6+1#^KZjo_qA@*|?@1m3RR$KE zZhM(PDgy4hYgB3KBahhsR6I4FDM>ohsN$gkhu!=Kngstyb|os@_oA6b+v6ps5$nj+ z_eJCX^gf~BePDg*34 za2?9mfjNZ;nBhN*AsvPfAvpMUS%%d(LW58GW-SIq+Hj5?dWjuR(kwL^8XANU8{-rp zh7hEr@mGpm$wttUKgE~6C>*qN7Tce{&ozhAQ&ZBmwn@duBIs|s;eqaX=a^5@Wn3pTMZ)8$H=w@a0K9^C;&f>$f@)F19I3`l6)2*W2cgUnryZU)Fn#%%n_Y^@+dUqJVRx48Ar z8W+c2)l`bNX{*)3nV?@$~vPP#z@m-{JL8ef5BaXl<;=E-3;}^Qp4jLRP3BCa+ZTz6 zL<^9G5XG*=o}^GuDt@5*1H8BPv2Bn_g3L`zEA_OMut7Sm_x2k}$dDkU5Z( zQwT(BT|uyE+b&coj!8Q*LOABj2OMR21))yh7Px}bafhlJPxbMYDq$+B#R6rEkC26V z@_Ko4vH(#cI2`5VnFN!T;tC)QGC(O8T@}R08pP)=5Bp`10$gN zqX8QW6S~LTCl5pYcy}@7sE26jp z53%9l&v{w#%7J9mmADs7llWu9uT&8UQw)5CNt*_=Y#(6!uC%Tw6gF&dtf*GRUrq(0 z8W5WxAWKIXLFZYRmBPFP61xwPE^qX`Kl^-oX!94_ ztD!zFA4=RM%6ogDlfJ%(GCP*fa~;J7h^Mt3%+AgN!d{-}Rm6|FB#L|K1#x1;^FQ}j z`tF^Yz7l@4#%Oy#Q1M~lH<>qYnlCR7`N5)IQTQ=)l(Qd($3JaF zrWhw9FhmWauRD6>itIj7<=8%ZZi30UfD?n-=H9Fj zQkp@<)lgM5vElBhs^VJczD3dPCwpShP~g_ldVIcVb%J`s+xyrQDIva*s^DwsUB?3Jq| zlq|AF*7^B?3PtU>mW}#0m*$mM7(hyIL!xX)_LQg&|FP4vmZ$rf7#!^eW?F^rIo_z<+d(| z1$3e3DgRyx`4>|sfN+9HP^G8|>6VY_k}5=$HBr@zuW!hz%1!C8X$`t^kj2ssW+p|u85_QeXOmyl2Ql;Azd5u8-|PAS-1Cm?u<%WR+P~fl zh}}QOgO?8*%LjNzHkq))30Dp@PIdpS# zJxbi0?43zGPE&y@)1l+X*D^_{hb$fP#jWk{YQsDA8(g}YBftOQbh?GY@ksz@wKZyNJkr|l1=zSdJ8p*) z`zmFWG%9NS_`5{Le+_lZ6e*Cg&(7hDoHSSuSS;F}VaDws#tG6Y)cC&Lgu;=^MH}k7mXp&b{ z^PeEhs=7-~G@bpizd`qlpZRwk(fJm* z1Z+e*wI>sUsDRKty_oc{ZS#9%PIM;!h0vS$gv()9j+o$b=kP4Wwsf{p;R()V$rwhN zBO~|MzCSK#lG}6xEDufr^t{t}nTPuDU^9Zx4^m}hZCzgU+p$*!(&mjPO z*3d}P7bcQFB)gK_zV{Fi?@#SA;dHoY8AAm98+UHGiXt|ToMet8PeEyZ?9t0NZX) zD#HxEDudx@C#lY%>It*>H-**#h|vnYVV>#yEz8p(nxzrPc^zzEP~cDgXq$!uuSgKx zoK*+I`4jP(CpbTgc$jk4TSPFo00s>?eHoAw>QX?zR3?s~km5 zc|g#}!Xts;@XHbU3{7f9>c?1z&&~bc@IaZh+mB5*N!-tWI08QV)S@`F3LR`_xi`sl zFVo)h_!ViV7jTb-RCqbsOn+iwaIOw48XjlYFiEAHJZJvsu_{H_Cq^Z$?azN2<$OeS z=9HsfsVJp>_*B8^=|2<$M>q`YZvJP zm02nrdDEHjEN{X=uei!n%;m}-Y6|u(`7y!wHHxL%Ha(l+`h8<;jgi3=ss}v_&tyEF zPyyG*L8(U=wWO?{r(g=>=!%7yO)IKQ%NyvL7cr1rk@-V#ELyLII6gNwmoVVWzUtik zIc|8mxvRy4`IBW?#Q+gwHKsgz)XlS?2?ay-1TIKG^rz)xkGwaY7S}z~rTr&Rx(ekg z$!PwK?Uz4o$`DepDT``G@UPvZ{u1WA^jk@3=|_vqt3_9mM{g0a7F|E%W=|vQ=L~#O z*te`b7+iC#XbMxw8sI8Z{x+xrEj^i0&uRLoxu%$s{6U!IHi|;4=%Oo;%;b_`LN3f6 ztMyr18>gw)(i}M-NW)61J#gL~+Ep{RM0_Z4>+Q4W0y7pLYAE~zZy_L)`276`Lj}mE zLK=#%e)f+qu6})hd7Ivu$XL{5xx#i1INtGbad!50(uRf=yC%5!*DvN%4-fYddG+d@ zJ73Q{r2-C(=F_Av!;?l<*6bbq6}3RsHMED%zUNoAoKzf(X@fr+)nu*v;bK?(gnfw+ z1iG2kk_jI8_SIAW^+Wdya>YszObIyI3#>y%OY_k&QAe(>t}ZSteLFm7Mp8RRfp2GuD#_7}jR`ER z*wQ@eNEsDgsR*r+8b>EojiKNl{6_slJru#}9R}#oSe*AE#?jLek-_bok+2392QE382@rbi14yDiz0Lx=^`9D9ZggCSF5Bo6r0EJ6Gebg4{f@k=?W<cG%Y6<5%726|hJLTqPeM_yiDvCQ-I08Mf9b`P^+Gv_ph^sDQyRBwCxkP3Pi38_1Q zo1BTt48Wk(&Kr{4F4Nm#dw~i@F2PS{mey316gKpj07S=e;gYdJY0hli`NbB%!dVI# ziRojw2~<>6ZhOB(dX}+b9Ehmq98l2NU;k&`|NSY_#~r)dFf2Wzyyw7jEd3>U)0+?) zDmpq!>YUMX_LnbNUUIZ%6fv^Xlk@X?Cu=9>4uX_x+k|wjML-VZYF09FadB~Qs2Wu( z0U9JS(gWaGrlzLNiGYcS!h;sQo(1(Lo1jHbv3bo(dc5MNadv8I^R75nX5(%PE34>k zpio=2>9G){as^`Q+1V9a)hvJglr9yYj&5&nUv52>FH>m-b-T55)Dc5Z%xDwqKX?x(;&#xmj8uYt6&9*D<5c4svJwD+6{EDZ1z@CY9lKeZs;Nm@SeTnjC_!G!$?2(^se|0{2|rJ6#fTKp zJj!d^mpJo*{KsO6g|#*Fp|2Qe9%Vph)^j*OxAO~Qm03Dn435EZ+iz$-;nE`+o?ml? zX>_gwN-A2QuTX~DLxX{JMNbovf3L3pSQ<@=X;8oY<3|Gy4V0KTsnDV=yz$p>TF25U z&zP#qvGV|Q@2w?nZW^Ai6`9*(=clOm?<0w?PJj1hdLda1%$eAQvWiN1*}-<#+k*oq zHOC6?%L_o_U|@uT#AjN~3fbV9a0$9F6s0Sh=d7R*(a4k_z8I3#tbI8+I7r0r<#DpN zQuU5(_ZLW_HLsMdO9bYE@~xzNgwj{4C>jGAYH9^rP^)skUq>a_{$PDXUWg@R1|Zx! zxUy>F*?0xjn_RpA8rAg-%w3B_8!{}-y-*f9v?}?h#RrRx4%5bShK7Vh_jm_V?5QfO z>L}?lJULMvYH0Z8O^dMb8y0pJ0#T{`J-je)yZQrGg?9JDOemFoqFfyO_CiOH!o|-CWw)O6JeJIVu)U;Jk?7#mh4ph1?JsmqMt6To7f93Qu} z-2Ud9E1)=GXyJ6;vs_qLryVtarJn7XLKJFc`_g8HBW*NIgd&Nf0+f6$$Ql|lC0NOb zi}w~Wf(BRY4g->-kX5zNebzbB#%qVKPrdH_iVB-Dm$q5CRFNl89!gZKH9UNU-riTQ z8mOr|%+1X^EjJt;9lK$l2VwvVs(cJ-Rz3U?+d1Fc@zR~ZKes*dC2!(tX;BL#!;`wX z(grFo(=S8C9k(+4G&9S%83%i71eW3cg7*5YeNK@pif!0DoA(-R=fppKqHY&AR5F4% z2FH}EXj?hOSLWpp29h$TU4puTyLa!3ji1AA^&SD-e^{w&9u{AW5m#PbPG`MR+jg?e ztBc+M3u)Z1)RyaY672@Mc$>(g(a**A&5pNhlZdBFsD&o#( zV9U^}7RnCtEJBPIS~Z!o;_lvca}CbS&vuH)jx}k0Ol65REY}~=z-m5tbaJwKAczdW zuRSg00&PM1v?N=f}DUF zy9M!q{Br(?hFE6f)#5M@f!$_&>vb>70$N~hs$?`Z$ALRGK)`ZbRu8IvsWLRVyFn|T z698|@=CCfjxOG*X=^+E0E~)gCed9YE=dCx54C-AZ$7VHEm*Ma<2?(8vQFGCF=OcMm zROI_M4cW0Zp(;9_N^op7^h(g9k0{5emz;z|fJ$W5m#>G)ZCU_%D7}s%GAe4SS-KSRe=PX_e9~RM|G;bpNTG^-lyy~8 z8;K>qFW&JwuddAN=Xy{MUa)&W*6n2&)#r}`pxMKEoo8%fqSt&YCa-RkuukS!^}X!S z-|1kJZ7~j1Ij#YR2oDc0C}ug4jyR(;yLv6Z+U-o(2$=7QnA>}W`!62dU|y}Lr^7yf zW-#&ngpd6M7gG+D^{FW-sZ24L9B%Xk8-5)D9wVq$cHS5rNaE?P8zgMz1Qm`~xVwB8 zaQJF!c#iS1U`cUjH>|l`M5I!i#hMlp=Ie_dtc^R=44D$F_nejug{~iQ4+ZL7fwvDe zmN2@$IYFF21L6c^IFEnG^(99#%>yEyZW!rJx2=DOlWfEGUWZ8NhI93yO(KZ5mPW#H z|8nX7^JKcnsInaRKj=eKUR?KqkU3;P#^$a?+YMWQgyH?&8vpI#9*<>8jD5ypt^i4qNx_f5wP`po8c?O{--7@H3_3@pPD0?hzV z+VNQVV`l)~TgSQ`?9hw95h+RBX%BhSyOF+|bMf2zQ_#doY~PoUPj48+`YZ$>BD#?w z%(?GHC#gNeq39T-9<>g=E0SPN! zkLKcPxu57D9hG>wG01Xh@>C0sD)n?e-x__>^N=4F5U}6-A-QbMZ!%mqgs{i7_RHl> zabksZG7Npb3iH8Yg0(BH_|#^t!oyCNz-pkOJ1GvUvY68sXb&OrK01PP_Ab;I2=Ac zu)7q{eHwy!U}Wz5kOsjbBYu_wWwiY(p@UP2R&kN9ucwmyAV zSCHhRfF)U$KMSddohoN{-NvF=5celdCC#RcU;`S5p5~x`t z<9@B6?_Z&ROHF#xdKT!OMwu9|733jSwBKV&T{MRR&@LPVcM7_1RTqZZq zwACk=h8l^k#j_4>zf%Uadgp%xVMzq$U2?h;QRm$>o6-+Cv{qVB%JG>fb5<>wV2|SV zDvU{o?;BSxlxcN3+#{rk8&00=dcJhu>z>VD4AOvaA=#TWsmegoyw;l-n^-zV`a~(P%Ta< zTn3vjWWQ$JZ7FRGEwQvY2!ID<@_2TP zcv{@#cq2b}cQs65eY>8ZQmolw5bm{WjqP-vxJna%I|i%Osc}!u4HZC}LJXBzB_lLko@DA4C{%g@r5spL51J6s# zfKecvx;K8--rB*|jIFHh#NNk$&wlmdhV%axLO#|uh=XkgY6E_H#z>icK((B(ALlRd zsK+Vida?BIIVAJ?D)5O1hk^a>lg909XF8Z<%@+(FF=kcG@zpnk%U4L%ePf~d*Nl=k zZIAER;C!l>97nrhqIE%YMGpMu^dI$Zyly_2ukZVdR@Wc*7J`s)eMdqIE*2gaXsr8X zcsM;h9k`i~aB(+z)SLZpu=U#oFRwg<>BJsppv!X?^+_{1Sy_4P*jN`6tJRi@&iNdy zXWYKTOfiB?3M3u*esl&2IUwESkYGa=H^Y6^kr+F1Lh9Q7o7NGimokRtRUOSz7gVxw zlb6@zHuiLMG&H1Era_uJV=XN$xt-T-G!B!KlYM+{vDScm&E}Odgge}Yeegq_^Hr4{ zjN#1?AQqCWg&J_}Ri~{GHdQ$!L?tT>yW-}5Kf2RkU@t?^-OVvNX|=Prmz$R*CNAE7 zRlMK1?mL$$mrCS)X6re_4dOe{`#7foG`MN%=n(%6{7;L~5;13cR|c;$7gm3uqEhX_ z@L*cPeh9&t^1eo?l#avd*}BZK}pa>IqSeLGoaGYb!-gZXCb$_eyHzi@yHE zxVX{5!O@>TNfuy?sdJ~w91)eeOw6Kv1*%1_u)Djt)^ZCA87AoVSqZCot~&Fc9q$e> zTs1=mtuJFR0&m~o!ZirjZ`?PIAd^vd-E_Uzi$1@wI2aw%qf@9mskTdPZZ3b|vBLSv zOPiK9@6L|Z?A)BvRZfGk0G4=oO-)T?o;&_e?&eNwH&YRHI%uG<`zBO6OyfOW@L8O;lI(CLt z|9w({j*?XA`s1jG2xbxt`u|4O&_!Q~Jy!}BA@+1gF6N}~0qX|1jBL9ryh+{{u8!5f z%arH9S9LA^=Q%#Dc!lY;J(rTPPTCkNlM<8u7)+q1sHrKhtXyhsEh=gvYV%pfz`#md z+RN)gAh6X;iV})DWI75-1W*}BgiTFN_4W0IlxctjBr&nJ7GiHG(41PQWDfj>WNZ<3 z1afaqS91#1@vK1u-+||cUG44aU^YR0b9{V!+Ae6Sna>T-)hJN@Z1)9F;rR4b%U@0V z(zAp{h|EDk?@44%bJjhQP`JnOj_q8t-~0EG(b0(xh&&OMa$hqBh)8k{ij7I3BJ}T!Z=gC`3ls=srx9{O4=dQ-r`1hE-WnaT#>QX~{ye2bnH(s)Yif%8`apgj1&$nQ{q|p0xY#uq05fger!N zUkf?K^dVH$4kZs&gUoN`BCsNkSJ$G8#ScOAWfKbv#a*~zJqG{THnxgp$|mb{Vl5v6 z;Wb-a&wH0=!cbMd;|q)9M;+big&1wNXPn2|DSNy+TeP&)Kv4nMo2=|ypeF?cy{PG_ zi9g@YX_EzAg!qrXV<^6&d_4j=*xxTT{}mw5r%~;c$G0v-LafxU#OzpE^0Y%HWXWNJ z1L*t&5(UsYw&mnktpY(Ez5(B-IYt?)ededQ6Ix1LiqhZN^W!3aiOb0(*kv0R$OzxN zX8CQ1Z}-Pi^u$9J%vPjp)r_Hof+n+MJ>{ zUqiaT`QMOU`)Dn|=IWw%&Q$)b1;7b}0O@kjL0p}bkU$HG`Ts-r9;N<&pnHNiJnhB; z5ZfHH8qh&-uajfWXP>lKQl1StVxag$18t%@Av+Dj`EsX&9s0w?M9>}2eg&-eZDe3rRd29~(V_B#<3M^q0lVX+*TIOfQU~Y;mxi7;>pbZya^H-K z?ZR<}!@6Pyi5Dx2s}?jTwxbXRvPR)34p<%U6ta-o^KGi)(LrLQVePj`HAyGp2mk=) zzIf~F9K)KzH5MVm=L+-(uJl8CpKElqm7VXf4FqulY;T}zB+-rGx|1@!h(JdN1!5nq z=;xq;!jxCMy0*Huvg$(|MkZ$Zt>s@15m{PfuGl!(oI0 zt+da`WvKzp!i9u{AoAfJ1Oi;GaeM<^6`MVquSC$-*4C87q!$HNF5Gykn!@V+<|55v zh*J7f=xX=mIUnQ3N@k2f4m}C+?^K^3{Tm>3D)Mz6@?#!pmS$2^Qp)0yuZ$4DP@3Z& z=-b5P5dO>2{r8FCjALUvWAQt@35fF1ak$Fkyc}d@OaGSU_ugMcIeKVt@XOff+UhFQ zm^_Cbi0kFl!z+A`SxR6NXwCIb5Ok=}44LQhQI&6mYb% z3wVJvo9A$|b_U*ded%1J{#W&CDp>iR6~w8B;8yt`fHdb>P zq{Sl@%qsrZQ|bgYry%E$pl3@_rnWXN$asCY2+%n89=dzimc!fcPYSIZ`MZatnc6M~PhgE{6*r@mScJSo1lr}&a_OGAZdSV1uXrwM6xj>bOuW1^4SxkJsb}b;v zMmIMB&IX7wywF_xNP1Je794zh_sjFcju?U9;5+!-bDLn^>!gk=mcG9JgoN|n;+kP$ zC`9n(ougr+JAh(SOB(fs?FqT6#U7JF-U=?izGPQ$EIYx=hN6Rl9!!wa(OH2C7c=xY4~=Qi z!8=L;uslF@=llmMeda*i4yF$%Kv3b69~m4Z>-%{EyAAc4@4MGsQLVu1ygvMl*i;FF z^s;JxDyn~Fo_xyzR48S5t9D;={OhMtAFKw!3bzYMC1ToD(3qJ+7K{=f z&9h#m)Sp0FcX(q7`V9soPY@9iMHfWRgZ!8|2S(OMmeBGHpRiHBUI|-<+9?bykJ^F) ztSiACHavmY_8hW2he>}u zSv}Z%yJ}FA#W;BGE?Ek6cp@Vs0qZeGT9wh!LJ3<1CrdsNf7nQWzu_U|7O%y5>-htM z%IaTIR>sbm0pAdeUGS2A$H31PmXf@+Ra7#zsEvb*ikPos?iI>cNSWTxHxJpV=$M{= z{hFIwoSmItr}uMnED66&7zS!qVxprrM@w_~U7?m-Ukqggn7ABGW5?0d{VLXa9mqO>)Nn8!BaD`wJ;G5K=AA z-id1(pt8&v;V$^fn>u``nsPX$aA&98{o-DqdAIgGvFpy3K>Y-wTfT3_7{xsgo=_bn zyZvyasDq52*WQVn?9=5>GvCjBjf;`7QjZ*eIz8t~(qnF1r6ZnR+KNp$hy|hkkg((5 z#%ScZ8R3pf9%42aAb7EO+_rc)h&^$n-=8scn&Y%$EjotvL@zFBoGN4UQf^^4$&as$ zR#7J(LBwuU>&LU}12TPq&`@HtctQW>4F_4V z$-1;*Rn|US!_|=vIEC8Dnp{SlY`U9xd3<*Pm-m~wb`gWU((}%&-G?^>ikoEhEw{%v zf>m2!c4iITr`3vGdjcww1!Fr&q;{&BE47wz_=U`%)+!%2yu8%=i&?A;IetDZbl7Bl z`=mSBZOu+eVwd)b;xde@m1d`#cHgXAN{yMcg)J{up@3_THbYwa24uVfR=*u*>vX;o z7bX~ucKYPyh`68%ZGJ5Cpt@W;&B5e}RPt}XE@=~W-fBIkSN0~!D?i&XPnl}VJuvmx zll4a!H%6QGcf;{=%xf>prVcj>e5((C(bg^!a2FpB#M7iP9%Dzk^H=g7C3p&A>A*@( zW~iw|f*5EMdJ9cF=2TkFtz2odQ)3o-+}C!Nf=c;@{tome{vGJGs2nz|`a9GM>!0AO z%5br(QCdmq=-@wM6Tmx-?u)K1U(U4+&M_L0`D7gu%78sol0b3bIhXX^)U|A5Sn-`U zFJy>qB{psY|IuWzlb)qq+95Ns-=a!z#oFx0W3jH-CNG%_>z`o=Nt6B!uGhBlQ*DHX z92=*eII59>j!iTjmTJKZg6?$l-l7`y z!?(B6io=WMhKeoB&f87PJRA2GsBB&?8JN@h5gmIbaqI7I%_`D(rx^|PuOIh2E?`~S zSS5gp?<{R!Y=ykO#&1g!+_VsmW6$^v6?F*SNRfGLXs8&KY;yr(Cg19opNz2a<@b|k z?^++iXkK*D?yee38(eJuUQCM0i!*4D`M{JAr3iPDJHPZ;@!rxXv(qa`+-+u^tZSEN ziFCD3*veEQ+fy2J7Y;ffoD|3c-YjdvNAh;LMu8?b!=478B=40v4}>=Ds}a%#Wp%Gd{v)_xaRF5K74pv z15Ka9rlyX1yFf?df;#(YN|LjVe~eiq+}g`jD}!<%XTX0&y1Mrczm?gx~zKEWfEJ98V*JF-)sxq+9iC(DN~SfagnQ0XRP2xsXVUt)Tk|(-(@B zq~eTdJwoV`o7{mYc8@o>+{M!Pv&BfdM&boSZg#g2Azgw=d{_qebt_VDgHwo&>F@i) znjcvu^!P}LRE55XuE*nG?n6)C#t_fNsz}+fhLJ`-_!n3g8Cua3U6W@$#S01+8>_j#oaBw_*($~P+lQCtl+g3v8ELB_RANb& zt1qSUwCoi7+jy9$n=%IOkt?W%?p}cnTrmP{?D2{Nl6c;`+8D(5Y#59!GSe6o zCv;;`92+>5%-W3AN|#9C!D2PEGktf;qM~|JF!*7W9TM#28X1~mRK)aScHNt?@o0U& zJZjPIktrnEJHbDd2nVP~bj))A7fpJDZ}zf1B!qTE(s(kH^~Zv*V_cON65_+XbqU0PNzCkT!QSkT zkY!q05LSoF3E+QPQ{P$o)wCmx5mp~M{DhtQ@s_!)+G&Mmm|lOT8FHJdS8dyUg}g;{ zD0h#YvnCpGKZ=lltZ6s1gmu32sP2cYuPTI(eutXjsYtds85~Cqx{VZz4f?&8OR?nj zD(GX|QxH~iEOX}N{?4Q#eQrcLe8Ad4Th1%JO_fg+7OAKTU<|~*6VH+KDKKrP7~53I zF&c@sBI<-ix~y`W%i3a=-S2OLxgQCq`f_%d)0T&z!DuoiJ7C=&r=U+eM51)LFj{IT z@=%JOcBuG3;XGf}!R!UQ9xq#j64h z?IUONyw$k0fk(5srygRzMJ)}TifinZGTQb|=*0(=;FVtkcA|Ybcd2Mle9vh8U_(y+ znLjj5bWfA4sV5I*zxPs>nd-Q`4?&FQEA}jyu3A7FqAyVUGQK@@N!L&P7|y~|EPWJ_ zwjZBQeY~S`tU_C+^x$&)@Zms;H79*+pUXiB(*D#pxiYiVx|Qz)8o^sV<q{YUf&{D!Vv&vpdbnI8{Wy$S0 z?2vZl#Pnys4nvXaQj=L~{UM;#Dc^H3hLPKpy2OX(y2@ovxdb)cZ%OP7t1Wk6ZAV_v z?S64r8-_(|KTcF#>~NkWa&eZH$v>g^)z}^PQKB4;1WB4Ehtapv?ZbHQoWkm}tZut6 zMV?*b>T@ZLrD%ygUS{X{V2Vab*S#vNBfyU?l$bD8vi-}!uvg~HU@itYTYi9+iuQ#|b_x`CcBs63mSxlHn248nMT^FnB# z1#Rx0mxadiDF2(wrJS%!j(K2(e@=NmJm{`V?#>;&ERVIEVl-iGtQz|p0~yyhWq}qk zqEVGL(GQu)=J~)g5wdm1$_p|N!Jji^sLDV@Uu4nN59;C#R^Z~<7296GHweNObBwA9 z;on00iA(UCWm_ZPoKeF(b%RVocaw)@jVi1A24A{C<6mK`3o6In-jcNCQ{3JIspx{y z$M6<&!=(#iNt1S}eJ8`!XhRN9X|)~7h@p9M$6ApKoRi;g1t>GyQY>1^yrc$l-#6P6 z!)PcscCAOg`B(fLOk{ zd3lGF38cCbHXYaw5cpP(k{G1b)_=XV62*keQ>wXLb*Su|jQyxCl%}RH#x%cMn z4Q%N2|MFkA?LzhTcs_pq`4iARO^wZLtgH)*^U&7Tl=z%(+FtcMxtUu< zQupz={_^0__DC3>v#^u|7^$#dv8eGEYdC-gTg?`aeY~W{RLa6G@>=Bd_!wdgsdRJj zgkRpl;IWZzp{Jl&9xgKQlxd8*>8jE=HZ5s!D1j(3xoQzSUi!K&7Mq|16<1_zOe!%k zv6Ph+KsqBMBWkg+=Y}9duk%GH&({bK0E%6;3gKI~zhX%pHvnu>O)e%aoyck)Z5DHX z`e0+M`Y`1>KMJzDq!7o8Y{&-Ef`WpI+p~{%aiG=u3;a?WSy@?@mU#femgmD~=Bm5& zgQ3z@2rPQ6I5T)(cn}_P0#>xP8wQ41tJ-Ow6Z^?EL=22kg=YOmT{frb&bO$gM9|{G zb-UV{|8jn-1)UJ;Jb2bP|81wZH$A<1aS`;I8NA5pO5`2;(l|84&c`=7{OUTEgG|EE zdH0`GCm7^(LZ0nr`~vHV6Kzk&grtI`PL7@Pa(mVe%B79mYyE}0LhNz5`0SG zgM-TS^r-Jx06VkB1(Ou0o)4Gkp8+a3hIyGEuLw(Q0v;D2IWd9tKNKZaD~{1>1 z)dIMWcS~AbX)J-%%61m65yLJQ=LC`NL_oj~6iod0~Vj?528kC$+#cGg;8pWt3k^Y;p z_-_-z5#{4JJCG%fps zX6C-CinsV3u4Lb6K$Ug3Sk@vdp+`(5> z6R(q=OIyR#n^OD&==k8~xzm!pkWv+2#DA^?x3HroB4!lIJ3=Zx3N2AHY< zPCcIoe7Zb9L`QC_2hC`x;8bq$33yI@&W@%#-hd#g35E4;##sKzMoy47;SMZ|&IjjX zGGSCK!BXp3oJ+Ge-!ItgeBM@|Rr2UD^T9|-NKA}(l7P)I=lahKI+?pP2i?XN`@erP zv$IlsgD2RrYa^b2IhX4YrU4U^vL$eT1Ge8|u^xGeaz1&%%QbDL7OY`GLH(hin+ybQ z@ZjV7)?1uYs$aba!9LG4yXL-@ma2=xN^q4sep1DFoT>KzqTZ8JQRxkj#799%2q_G- zwGDK2jchFAnnUU&z9qPjN&3`QKOcHrq+6l<3y?`t=8m^}&gP<3b~3hs?CkvpD*I(F zg$YUO&BVmSkjXG=QAR`RmmFL7dVqXr%uSrU@RC{9LLa-JXCEwceLMHMQ+qSDIB z%!20{CK?*UZtkA*^QM3tv|@o@Z_LPt7<<*T62*!JekyCV#u8&c?|19y>aN>Zi&1gE z{U8$K9M`fpHm2k420sJ=ASTrW7a0r>{G`&Z>6NQH{+9uni2WlvUSxKewgld58&?gq zVu(hOp1Vih4I)M-OnNzS^d3lP+AvG$%Um@9^P-mH7KUVyoz$XsvB?Kj$rZMriQh+; zKJ;xbq?*|9lFls{1C9omz&&{Ul1A~SbQ!;Lf+cJ)S zS@gUI#@G4X{_uf!XGFxGHApijE#P5>_4M>qNfpyJ6!qM*qV8aN;;e|X{P~H;$(;P+ zA6$I-r|zTLssf_gdW3)8Uz+F7tcH)tvGJAZfC#4`z&EkwId%aH^C;PKql%D}gk*)} z@WVV{F3t67RrH%Vzf@JtoCP|meKU_ld)Kp?jcSGLx?e$TJ0ZN<%jRoeFu0l-aD{jQ zb*#xGQ5rPc`o51f!kaLP^t}z*$-+;RU zM1wBTKd-x!P29bJ5dBG}fft}7M5%!g!*vI~MUapUW+y(=32MYebH9D=|Jk(Sy!{nd z6&ZFDkRsKCd~m(iBoBIpuO5>)Kh^IGsLZKiGjSB{pxy`e9|8pif&{_13iDjR*q6y( z3dHf+;{sq5a3_Dbs|i<)D8%}6{#~o@XPXWo~YX z7L;NG+v2oS6o>j@#T#F3AoKje`RF$nXH5(1{J5td4}gR){KJQ8aUlP|j%>|Qeytr2eFei{Bq$GzSZ^ckiIF)?GqU0@aE8W~l zmj7;UrDP04Utp#d9<^MD$AZvhOn(?96Tq2j);joJlvq!ePgx1r}n{&N7k+$gndx4CxRTvMDkxYm+V{Mm6Q4b6}O-TSdHQV)fv z!Y*PtyKhf%{Zc7wD~fnU zZup*TLvK~UuGYHBlvK}cAt^Sz6+V_XtWMvZcI;FMlRTf)czqGs?46&d^`d-W55N%w z(Z3T2&-dipnU@s!JzEU8%M8-o%*`T#8oKt_3K0TF2l1v%e9ICpjbPNV3T^vyJ6^V< zy4z=A@Wzdc2;JqY*Pr-(*Y0VX@gG9HbHM&%pdiFBK+-Bxy6a^xV`)(yE|Elqeq?{< zxbop5w+DQcZXih+LfS>7IUgba3E`jp3&QUJd?rE87Q_vmGe?(&*)v>=OZl8r&%628 zy`eo=5p7RFF0zY`lGrps#szLD=WKQ}nuWWc#}{zgRh+rTaBVZ!^}t1NWtlpXK63P2 z+~-kZ{0B;{o%ml+>RUK4q)T|pgiET#4*lYv-j3~cC&o9Zm}hR-9c-4{?n1Ix{UI<9ijw|M2*8Oj0N?_N-fb2UHt>6A^& zG-1=0RRBk#I+fq`&!)z{W=o!jj=OLVP&<8n_ckDmSD}u6!&f;a0>{Wk>f0z@`BnrH z!&kbMGml-lY*_MDr#bS8^=G<51%8vs`KjB!ldYU?zgBp}A%!KQvj85=GnI54n|%N5 zKQ{~iairzk)G~d#xyt!<`O8m;cov8|0gZe(|vt` zyoa2n&OP>LwOf~UCssm|pZyh+f#WH#;RHq&U50-);S!YDg?{_34_~IR-3Y>UU!R|! z6_KRPk8v&!O>lVq^l%i!@k9In|L0l3!)o@2;y+z0wl^kgfXI0*q$YysVllAv>VLz= zU)q%W^n4ZoN$D-1l|=y4g@@dxq<49knVCV?edmFIz>p1n0~TF8NBc>C76i4u8^%R( z=oS3mJ6f!p??Q}PLfq#fWp-u&QEGosO=Y=B0w3`3HHU!$z1A~oZf;H+X`1IEDJcmI zPCirF0+ZncaZi{1(=AhAcTiI?fMWrH7Dkk$JF7Y-GV+y%Hox!Gdq>TJ}f62r@(L^Q{%&o3c($e|@Yu{5d#->X*=jP{8 zi5jtXfR5kN3A#jD@0~~s?P{mIlG_$*xRfzF+TZGKn)&xKTLZ`scO$ z2AyKQ8lX94*}1SXTs$b!d+;_OLeVc0Q>P@xE3A{ElJ8RrBXTP%vkD35 zNNZ`Cs7*dTK9-OythNJbl!!UC=EA~40|Sz)=6odG#&}~4aeA59wNa$ZP!Rk8mSm&a z*cgC6FB<;e0ahj*g)|ks(YnB_+7y^ccXf3kP>GuxBH_v6z_QoGOb~Eq-G2k8=Q@z! zi7mKG-vg3$=U+;s{{9=V>H(%9z{o>Bc#yopYP7$?y1}$Fz63Wlf2DqFaBGb)CnqPI zN?3J6OJAR3pOu;U;IPM+(+H|C1%&cVfdu)dTdu(B7Gyn#goWL`dlxzy5E~l{Jhy3q znnXt@af8mk^Fg#Or7k^5W^p~Xy(kjL5dj3QHtIr2BGwkF4yv!@w2iEle3Uh$r0k^Z zWUZ~e9o3#0eQ`B@UKw7j;<9&1Q81b?9M9U;7B~X?sXNZu4d%X*o?jlw>5zB_e-Wes zw-Ye$r=JvZS<`|D)vO^pyu7?ZhULYwXLBgnSXrxq37=6UP{PAUA*-Qm@IW1AGQM1525J-)`e{izz@s5$wN zl~q2~9Jut_x*ligUyW%2E{nzWHZ0jvhgRvaY(YUc2UG_D_mCRpf|amfh3-U>t9abvNC+^k z*c@Gs-q|kjI)0_urOs;3O#%mI?+?MmeOg%qDFOUMBO@cLn>inAbgd~1`yBirQX#|t z!gW9UpS=Dd4#He`f<sj47R>(al+is`?+3qRI6yZvLf;QuUs5sH*9VA7JClJ^{>1 zWXEs7i6>Kj*;lU_Uw_B)979mdNxqRKXP)xo6P{T~tXr}ewGRl4d+hVB$mLZe= zI4UVJxhLy}^-ihKT~2bNCwY1sELm*=#0NHHvzsy~w;D z1yA^)sy#rx_8tl)(dNo?C5fJFHNKatpEf{yZr@SeG*qYyK2S;63z)tN0t1hMU-Z!I zJk{CgvE&WLk6$f|>-Km(8E53LFeX)^f;5f1m1vau;UchO-rmuy z#Jrn{h|P(=ZA5T%2>y-t0r$OA^1_^1Ha4cZ(oO*!fm=E=1rkK)4Mq^<869X*VOe=mCO=xBuqc5>8v}(2i&X znZ$BbBqT7*qoWC5@DyQt-Tl2h5S|YDV*LZfeY;3jt_p?x-#{CbfluBPWqoQv(FCh;lt98CLcsh1~H1Wyu=cR8^bk zDog&dL&oGVp>i4&d9gJEg6sd;MkEEoPXq*MnyEDEwn4UQus9-V85zp)6jFsc#l3sc z$1aAMe4I0#D3pEwrL3%M8tsL!<+}d04ThT7(X!;zmmHrU-v4kOdHL$q!@zUz5wDlK zJHvY(8a+1AsbQKs9!d%q8L(svcttG9p~__9wj0_D0*+5?l$A{vP`{%5zDcNgzyN-zH94kilxLsDv@y4Q_QS#Hc<@Gh}HE7GW`*hGnA{)v{} zI}bDeeCyUN=U}hz4&bbGcvqmij1=ijnpfxm3brF&aV5=mdNeSg&$h8|Ce~acH$$}b zjmU(*k$Mk;M`C42UbV;Zg$e_6WK6@E&!K5j-eP$KMie-rfsAj#Q2~Y7{(9P?G5N*){TiBFV%QBv@YBtA zRKpOH8Jm=3S!;IzXH}gzoTWX>C4Ef6#n%FyPq2^wr7XZdR~DdisBWA~MBO&u^6Mnr z*#|SPmFA?CE#S*C9VzC$x(%Yf8-V=Bq73GBRceFNGrz2?48_NH#|@TXX<@O$UJLY& zo*=VURU(PoNP1uF+%V4IRX(s@u>pF?!E2(250?KPti)F5conEox9ih4oU0N}!Lf&) zyl86zcuRz2gXCs!X5J`3Ie}lDi78b_m)JuH(l6bwF)#5(5NE5bRmF>8Q14hbvPixt?;f}=cBiy-9ibTVv5eeX41OsssU+xz`k1xdjAD>n|5vP=tLnlD#Z74S9$!lXN50D-ZLezJZGM?LJ4}xkkc$8ANtr zpH5DRFHJ4}OXgrEW)f1vgbP#=s`Cp>eeI0(x#A%3Z{V@toRbUTXp-TOoBZe2O1FVg z!LkltpmmdZ{v5XjiN_cY0wo^|hfV>H>Q^SDInOe8~x_ zsSM|yckcVL7WfdCfdm-4F#PTNV$nNyQ4|G^900=r-xm%=pNq%OCI5#kK%gL7FK|5+ zM-Ttg>fHB*gb~-rev7ydP-J>T$^hwqKQ2I5Y*!9YWV2h*v==*Msn@aq)uxOp4t;{7 zy!%5)_glxPAX)jLpq`EdPo)x#WbyYSSK1GEbn$7ZF1{OCCSFs8oxsB)xjLlLwfb&1 zcS&uH#l->61WU@qWKAIjcjlboM%z)Mt--+Z_DLg6Xizcl4)vdI-WF8f^Z3HFy4;)J^&&cR-wLN80C;&0Ugd^g)zCs?oV4ackU z_aiK}@l-}bi~lr|@g|$IO--}%vDNPj<&yTs)-_nfoqj6iu)ha8L=`%$oYF!h&a{_| z#-Hw<6VP*Tn+I-iol^xj&fXe-FnXk0F_mhY`zAp{QE<}b6?zf>iZAx5F)hu^x^7S? zgg500EVb@9I4Zk=#uu58-#c18GoH-eKyG{L9tGw>51kM*W8XiAw%jeo+=f?h zYL@X$J3RR)ksknjB_>phUB+Yh)f}t_5`}l+&!!z#=5V08exkQ-7n7R-dLlWw@#t6I zCsBp>ozTA$g^db{vpe5n3a7797>=xcfT59;0B#Pvo_IHfs)TF6vxD?u%UxC|^+1un zo+MXZN%hc??UDENsYsNN!-M!NJd| zA2y8AFS4UPA^oiFr|mSBHb>KrwBz6j8+0bH@D0wOwfHK=(0fm;Kfx2q;?%tcnfP}h z=h}`Ruap!Rb-@85(vEHjj(hMBF+VI>G=lATKYaS7AP-!!4);Xi;{yVUQN_rgmnJ71EsmqrxqR;{`oX6wt*bS7XV|j&hRmRQSoeJsw>;^?qlLI3=S0;y z9qagwQa16Ij3UcQKeD>FYAoUEpT;?J1vHE$M9E^HvxU)=SMVKA_pc4{$8vewB;0U0 z-T6elPkOwToLDuhW9*7F^VNVmNMF-6RS-VCwT0ZXUDcst%PW~DBO2XJUJqetXGVw* zSCVzaRD*GW2mWfG$@WSJEq5Esrn|GuZ|J0d>&nNyo_53nH6MRK% zaHjurIk|iFm5X$Q+h&(_@4XRXKHdwk+l~KQGDf(%)oCUfb|5zC(=}V{W1Qqm4@ojS zLp#i<`Pv??_~YdzqEtxsQC7S+j8R$hm9rHyTr<97CZm&UU1#jN63s(J-6HXhPYbd= z7*=oko;5(fkJ9?;z&CQEb`Fb``v=DuWL~6n(jiqtZX!GBMA5}rV;a_q|8!TP!IYf_ z4#mP9_H0>vDo$8*Ty+KV-n>nACNBs`#p>LkaT9!0qnX(~@*iFR1uOovx0C!L$m(070hkzle~Hq;9W@if>1l)7<33Gvsu+AP%A-@HjR zwN8#T&h4>TTbl@u#kJI`(Z|$X!{c_Zd3J@(_G@GnoO1cA6vKFdYISgf?zDJqX(X!4 z={iPs@`X}aJ{$=>qe$W)(4Bl;NR5w8anKcU7WTb>*1xX2;gpwgyCP7sYg_ud_M!pA zHAS#oa$G>hR^BVxxEEQp#b!-}0M2-TBOf5jYIH3YYAe%CW}QOA$RNDSkMf*CC_1h- zsldMGrJawm?5S34+5CysM_jm9eS+g(j_Z}Jz3o7BfrrZ{F0#?uW7$$U&)WXoe(GJ1 zG5vP}y0<>AQ!8ldqR$jzm(qB3u@-UAi|F6MFcBEpZHw-16om7ak1!g`4YRIhN_RlO zbaj^rZ|-Y$p@K?H;g76<0Aa{zZoya-2j`$p!?@#wPCsiQdEdyyymWt8q@jNFuKucg zS~Y7X@;P%L6Pxlr=Ap!(hE6+kNl4C_a80-v>xf2MzSY;s5>FL;@fyPsqu?CQ;a#^x z>Hkz1{9~?3=7X2R7IRzj&N$I()XNCpxG|;V3^%9Dw)}!2fe!Yz3I*|wA_;~(>driv zeY2C5Ak@&jFpeY1SYMWmcx-5PU&Q*Eo5xBO8RQ-q?YK?n8ITfO2lfL%@ zZBl)oS#2teREOl%9>-$zF!Xqtbm%OEp|-nkRQ5~L7?ZQlO{p}re?V%r83&x-RcKPZJmbY>L@PXSYPy8pmHPdC3r=Rg>FZk^-OuUYHO$5 zplVP{kZ`3Kc>O73f2!jV1I5)l0*@)!b18?JrN2lIzaC_Mx0Zi>5K_WkV)Q(d@Wmgw zd{3?$FR3L=d8T=Pa$KB<6J1xPjh{Z53s@A#Y^OR-VMLEwCDPPdV!LTxWu6MscP3g7 zrqIZLT{xI(pfh@z%OFVpw#W_RnrC~Q(>$cCGRc1J!UHIk{sM0(OC^{_bT}X!rlrRF zg^qRabiQ;fie047eG~a+%f%sTp*V*WXe{nMnYZs@0ve0hPF2k5a1RIS3%}u!SWRbC zd)4dbo0~aA#u$#2P@bowqYHia7r7(L949omy1ag#eA7J@Tw2%V-Lc{_3gBSvAe5CO z-Mdpte|qWw3G15e8Om-7*$r+XrQpie)B1I=H4Js+&>e;;1?+NR3~0Z4n;>|0w&7T; zKOc$)_;u&@Y_31-_~kx=g@QzYiAxhB~;uj+i;j9VfCJ2 zeN9-^iDScJsAT}n;g9|7E(tCl6LP;Y%z}K!nV=LGd)a4i$Nc>%ElZxhg`)Zi(p4T? z=dblKPshjk%3V^xaMAeAJxp-=tF^GKkJ=Z^eJM~6~HElHM|IvQPeF0n`z zV6fhqB1k3Vx>3osp|nByG9hsl;qe6%73Xm_oOD_DZcRf8dOxqHi*|hzZi(KShFh!( zUyuESxGM^su$FUdo~ zV&11%Q_yll^C>BEuGSuKVc1e{37FEO)wYDErsp$szqSs1Gd$9JQN|#sV+7|=AJ*4c zWzVxo!Mi{L+p)SF_}5>5rE-Y3n{Y)9rsc zVBH?2l2FSiiCPsuC7ABQ7iY*|j6+b5UkTo7c^=cPt6!5p+ia4Ut@HDZ;b_A>K3wAMu0Aq@ig&|yxKjRv2(V^$b~WEmTXtY>+^vG9 z-R_;7j^4z{v`=Kp(^x!uB#l2iA-SdyH>PSy7+#-wKuB)=i&PamqcDQ&p)q#GF z`()BhUw&`yhJq>2-5V@yYzm69Le5*pP4g%zDm3|d+`=LvBqaBDFw>F}5)zyOwxoPJIeCa@xqQfe*xGqI$d!dtB==DqcSM~-rHXvBn%4MiR#Z9+f z=H0v8&If9e$k7QX%#8%cZ}n4*WXXlM`_pY|9@nYkfIj?aLZVwpB$HCA*qdKj6W`z0 zNqS+H=p`3}g4&f&X@EWi7_UQ8Hh_tDv}ca!#VzHMKj*zAgU`GwDm_3a0@$2Nz%;3K z&$=)0E{!k+uiFT-852{5fsOmM!@G=XPoF+zQUIC2g*s*MXwht(?^i^8{(jn7%S*qi z&1YNQT)_rjy$Z|DF*7!qUmu;Hon4(>p9kaE_?U>~g-Y5627}qy;M8ASSOA#5?PN7S zut{eeNu9E$nIXJ*!K(y}^wsRwDwr0x_KVN8R5!SdMHl&oNRAz-K9MgmgE{(%2a*!!19Jou=wZ)5d==fbJ;px5zg zwND-_FtD{io7Y5z)7R1GYnuCT7`2Q_%k`bRdj!9^xLAbUe)@eus%KiAW0g`w}cI`QzeD~yNf7k>P;S_J&m34fw zKfS8!fak}`#K^cJFKi*TCwBz62J?!3*5l=JCy{hAJCj4ZMYK8Rtj>S4J=x*&=TuHs zN|N9xP)Um!$f>KV3zk>dmzDv#qxl6>@Uy9FqT7}uCeJ)&pUOuWS|kH+AEnzPU0q7k zvD95oqgs!QKx9U+m&Cmbu z9}iRv1oxKO#k-}$D9Fi)V}XBrbnL@?9!CU%jg>8$aCUpk;nvozp3emd$FXE)4yd)S z0;iK?1G;dQ*&)+A0-Q;S=;@D2%9IhaLc_&|(?97#Aw!tD64{jteeWgzZG-d<)8so8 zJntqBHr<7*$XQVKB{|ADCI<&tb%>_MusShu>J_4{9m7xd!daV_l&I5hAtKbav>jNO zu8^hmUsjFa=nsi=fnusxITM`z9v!1nPft%hBogVr+W=wNsI=19a^=)I75$rwSNg4r zp_l(NQsSOBV@R5oJ|rb7KH^VGPZ9B^rUA8|AV8ifbU#{(1;#B6+Y4K#&KzG&n+{75U85Hcm7B-o?`-UH67lqiWYwV;%5| zdz1jnI;gywV9BV>%cWvwmUCQttlXW5ii}fOJz-Qz9PH_FPN>#0$8%6v|$hsDhIk1el-5o(4a!oqnD_`5}- znK&M@WHY=JU?WD)H}_uHQ4tOM!W|g>>uoeILaeSf=yt2T3k>svS2BraKDk}obMHK7 z1kkl06+7)RRaD|0rOLLbH*x19H+6ZJHSl0-zHyj3-v?QMibAz~C9Vc+J8J8)ognxJ zu3_2!@Dd;yl_ci?n|_9YUiGY-mdgzwpcbLL4LBSfU`rSR$umxLAeVu9tY+h{ixutz zyVM&_D+wAu7)kHU$xpl0(cSF>EIgg!`Pj@pCw47hBSl(H-|vu-kT5Qq%M&UUQpTFizrHNj zlP4`w>Uz{FM}J{qKCmnL!^z@T0Z5)HDk?h9PcO+)sPeOZ2AXRpl`dyn|R z(Y_!xqiZNP;_{hMxVXj{{mTTka+3~{$(T-!=x2|S2!vB8XH0DDa`fep06wVm*OFDh zUu(N6=&eASMM|y;PXD43q${<`WgI633h!=Un(BJ}eUr|R zBcO34hM=@kM4aUrzwir$fMny_G-6s%3t*kh$iP4@C~vtI$+!YCq3P)80^YwjK279f zHoMl=p!B1{7Ng|!gX7{u`;&@zY4FFWu*HwB7Z)&4%cV=@aH7}z>uYhG5Psi;S*3oh zQJvV`ro4D9Qt3w5K=E9_Rfua!mHY*dzPr1RpcUuGifDk6y%pOpa`9LCfBB)`s*I8_ zriB=9zKqd(g=dY6qgwZ^^hAB*dAj9xFA!s7-)i7o{KYoXejdlx4_5X)U`rOJTLgs z^}(W5E2E_9CpU3@`;-S#zY5+MOR97j^HtT&f1Rhg#DWPegEpPyQ}`SxuKT-bdb>)! z{1`Jn1+$63u^;+L$=r$%veX*s=t7)mqeoFCA$XQv(|$;dHf9j23`1{N!hBvemL;W^ z)pb?x9dO}TCsKjuZxKI&La7?M?9C(yzZh~iezP#bKJ@^Y1b21%#3Th^t`}JE#?x!9*LsQ`zIvaM6%3ShHDaT8f-z!|)Z!h`ZCC*K`(Og{r z?UtcC7nx?(N?aGKFjU8mZ}hOZq1z?5gU`pe)W2ZV*7Uxic-d=J^%o#rBLI1J*e_Ey zP%W?;9*P6fyX3EY4$3@sP()b1g*i@F9}gQAwU>PMEa#*)EimM(?{#CD2b))1!yY8I z&~gCwgcH|xFCvp}g9lmMaZ%ny9Q$4gDojdB;olLg@BmM5(Y)Ad>dafif{t2r*yR#4|xjDek&)899 z2A6iQE-~lS_1&vn5B=7WdP}LRa1zKc)~wW8)o>67{#;`H8x1R3Iigx|U5JQ!Io(dH zT*+ioG5%{P?A+HshY>C@iBQ^A zDo|!sFCN{d7O>iiVVQ}H4~LgqPkJbO1rW1o9DrE2m%KbYr+XC*DMUu55xA~R zCtZ}W`_UshPVLfn-@Y}b`aJxc6ZRubOhe7c!O4l8oq1`x!54J4dR7HK{v^byz^@z# z!*|<0@k&C%LPCx^3{NxL!-2OkYEO$u#Bo89R`XE~SG=G)l z-#WCv|GJ~)Zxbg($>Y>E;lAzY;6QLvdN%Is?SA|_;|3Aai@Qr{DY4ob8o=ck^bzCp zmI+-80KF(xP~*cP@pxc&dc&#sM?y}{A_%X-d;cB;U@j~Sv0-}~fq}PW(d7ve<>G}@AjXx9>RC?Ol z+sBa|t*yhY;~izCeB3M#g@vo?>KlPLJJH$#m}Vf&dZ2aaiOI?ARiGO11qq_NX%u|# zde04s?^0>$=^amk)*QQ>vuorOx+7{i1ad2xL84=4XD28>ttTqE#l`jUOLOg33oGCU z0r&(h&CRIC#+^L;7?5=40shr0kwVaB0vPTC@NFIZnVXAAN@6o3wVJ90K%&lzcK_?= z>7fpaii)pa{{-Qg5ou|FPmKl6y1F)1FQ|;a0ju+F&_joCRA4B{bzwNnPn=@?o;`p5 zTyxiY0Q37^Q)@VF8Z=f-N9#2l{`>duz2AGNHre8$qMfb18w9twnA^q?CJHVZ(4v?0EVFSq-AVk$yaZSBaoq-ZFV z!uvrrhc+)=X_o(Bc4rUI5M>8Y)x0|?NVwYOp(>oh3#3xlj*gDT0jA+|@O!4^D%55V z#gtZ%#vfhdV46!mOv0&`OQ-v4X}qFXDM!_4tq6d3q5N#T3s83Lx3&35Q&pC(m4XDl z_IF%0Ydpjg8Mek$1UP0l>CxA!U;OG^GfNdSQFU|saa^_C8bT#uvlCx`f?ZskrVFs1DIz!T>2!vxd`P6X~VbXG-5d+w_CLdvn ze-88*0GzR!{Tdnr>_^UtkCMQ_yvAj{-!-%~1l|tdNrNGW6+gh-lxLzc;m;j({Z6?& zg=?osVej4bOa`E6XCl8EA>Zl3@oUNLB5KjF)Q~$%)N8aq4GmNset)|xW0o^FuwGuA zuoc_<2`r5i;3T8hu3lWITQOD%c>i71(tGUDRMC3vBCTzunB;%0)8x89B>i90-?eKwWh4Kl@(TZ&QW{Cz_QYF04*|Rzu#Tl zNatm_STrQJMK8WK@wU_+e{|T~vk@mIRN1+jAc(Cf!b6Uteyg30Fc0<>6=thCdc)S3 zmmWuL;IB-y^y^1LO<*hFOal~QA0ru&l8_Rc_;!yVL`h!6g&i4EaR&qW zrFdGHCIpz){U>nngut@1Q6CTh_{-CcdOB9;SpjS$s$<*@q6F1UP|^TWmyg|TKn&M& zD$twZ7Gv+@5`6iDH4Gqc5sqQ}5 zWhG#~Hd`xP6*G}}oD>(wbk<&+nfde-{S4COvO}4&oZx%$c=j*42d-$eba~)Ac1KRw zTj#DjJ1fT|CH4C3YFtv1zLwTYeF)w7Z`b4?sz?@mdHMH>4pJ5~86{le;ED=5wYZX& zR(~XPvPAz#P!>ZiM~n0?^vXes)vO%M#WvH?`Th{Jhu2W{= z8VgYQb0*mfylYFhpKV>7pEJ#(Z*5K$NrBGHuBt)wwe{5?>LdO{T_FXCzWB8n2DO$! zM#C1}D6VMg)~uEVdihzx?hhY6080Bwj8azWXV?|`SJ|u#n&_V~e4k^)+nl_PNJ2b| zP*ycSg|IL;Crb(fGBT;m$ExeA_d<09O;a!ED=uGMyT6q9Lp$v+38EI2f+D!GoTBVs zq2ej2Gc(I9bWkTqj!D=3-X6&_F^j=mtQMjou00Z!_yagft%$`X)8z%IBnxG<6bx}- z4-S@e5#jNitMAvIEX>bmbJ7BLCjDvQYq9w1-f{>Gdnf@}{!TvtN@QV;{ zsciZ!sKwsh4RQCa`*H#d&8-X|*A$iL?k*xKI=?vY>M*33C2{aG;Ch`COmPDM@^!2W z?QF$^yxqq7SwY-1s)s=6mD>iwQP8#moSe##b`cq2xdF020Zf=9d9wT^T!KfV+;+5* zeqdWMQFY7^_(^p=uOe|C1K%k#gAm7wS*o6nG)o5I7J84(!t%zP_!jI`^{gDEp*eAy zkuzE-XuTBWtVv6Pl`f3w{qj&M*jUfggTxz*A1;D0q5@J|cs!UxDH5O4`T>X!0kfvB z#=nexORra4@;p6U1o8BcG99(Mmm>tSEl0_fJSu!0xy8RjNp9Y}xszOZezpP;X_SPe zU3tn0hwD1!sHF0vi#>?H#vlJe0v(i%)=;ybOLFKf7iQ-BK5FyMmjQ(R`pn#Id2s~= z!Z$71VPN!e?&0FGvfU#om}>NZSo$kP z^ZGF5l(CkAgwmlh+bqLC9PM}SJ-n1eq1EYzhAgY7U%!4Csbm|Qb{yR&C2{?s%RdC` zHd_vfe}3+E)}lat9%MiIxzjBKc2!|+*wEK|+`59iCgNj)N5|v5I7l+$bG$^@z(^%~ zOU%c#7CI2?4Ge|~g~&nH&=@z=8CmU$A}BI!m|B?YijR*6huF$%^G4XcB!$UD&e9{w z<;Isd%YeTzqygza{|zWKKPj*KGKw?<$GVJ+4DfzJlnlKO2mtX&QNTkc{{dw%_fR+) z_fx1#yQ)$`1EUH`F0Q49S`+%&^xWvIvvZ=}+w*9zA7VRLZ~MgZVr}n72=GGkrHe0s zb&$-4mr||1t@q?jGS1f{gl27VaNVUY`CmV8^ZlL@a2c?q;!`Sl;tHj|VG00aC)L#_fN9JO6DxfI_A0`^R;$SI=f1`)3RlBy-(Y=+IJ|kPKMfSTbD~zvtXgb@Z?cj>i>&*rKPug5$sbyof z&c=tI+2O^H%CozMb&VBpPEE#OLDCS8jdW#mTvPb;Y&>!MaAXG)$=)sa{X95pE2+Ry z$Zf6$H@&`sjBHg$=020I;rbieL+dRq(lPpC<;GUetBP}$f1Bq3BjeSEZS$AzGb6u( zTcMwh;;@y%CZv$;`KooH1%&VzU4AbjZIsDV{0!q+JZBZ`?vgPuX6xO$m#_D@NS0rS z1wNOuK6OXHMrHm-ZvQo-Aej$wfk#RGx8Taz`yPwaQ+;xEgUDx3J4`;nYu^+HMn^Xl z=a6(#sV2m%|F%{vc6HS`BF_C{p;w9D`6`>mGNu#u8U6f~;;~-_7XV>R8K)rnn zCTU^5ZVczA)g(0^b8dHU6zYK3R|OQ=n!i~O)fTzT)FXX0fpL$^fT!#LGhH)%W)LxW z{PsC2<<=GiX&Sz=YDz4UoM6Mu#gJ6Mk@_-sdhAs82!FIiz&0(-6_f2=T_agLTihNs zd$hBm9$u}&&4}UEPWc&Q;t>8vTHJ}rVei!$ZX_h45o5AJWcq)4$i~I;Jckc@EG8$SdsyLAxo6Yt(oZDX(v4mO7tuBGi ziS8keJ>%WebpHZ*qQ1rX!bFRK&HIZ=M-%(a)w0?r*8^iwSf!KtaU(I46^%EaKPv3e zd9F~bUS&>L%6g>GL2b-4SPRJ*uBY1hPAYLYblpk8jChW|i@b?F(7YXq!IaJgbl+5| zsUbYfi+qka;JSp)0fY@FC&Q`!M)9%-ntcI+5r+%+d?n{{=NlWc9)utq--YcemI zhkD7Rs_#PO?7MdhS-?I{^pb9k@ZONxF+t%my+Nps}2qj4$-dSC_Hj{gpLOAPem*lT@tP- z8&c(VQQf&+&RDBHq{uqps9!H^oN`~l`L*>g#ylIOFH0c4293AKX7lQRF)L^-dqyhZ zeP=%Iwn0hxCc33ud!FSs)!^_RA4a@Wzq`a|+BFBI$4rf^T3 zEq_K9a+@iA?GL$Z0KFg8<QmDzfdqUb%1)X54!&NKLs*9_zc+iy9=)e+ z*F`P9BAl%a#D)^v)w{5jx|aZNk*8S&LZh(3aN{`+`!cEVYaSlI*zbl5+sh3_mB6IsY_s70`BI}j;tt9-YXD1w=g-5m4;iLhp zts~k*bJksi^H8mpfi>idPZi9?rS<8f1J!Hl{BM1Yktr*FLuJBd#*qbL=up`wX1CdT zd~6BLq!})fZF(*IQ&WX3Zx`iuKAMFH7RtT&gw=`W%jsW1STYU(dS#D3F>6gmimd$* z)9p4op29WP?ZVbSWJ9SMg&z+_rHTBB@fdZ?2n}sa#l{__z%Q8Wypbc3|K#q_nsqt-Ba;r{(SlGM z)@{8m=LG{LY);3Ro`tv5&UF4g_fRws0Yge`hH%2lqneB^UFsps{=KLt1MA8wwka)T zrwu$i_mcZ=aK=dxWj5*PM{M62EUu`6eMbHfvfe}aYCi;3Y8T>6p&2z3p+s!!n^kfG z>)5NP+RqwK8uyy7R79s!z5V?|b=Cf6!nL6)2h!oX<`-WIX>*s~*j-FZ`173(s7;zA z5QX*in--HACc~X=wCaM|1*H>DY>&@;D@;!yuz#)Crs^rM}&Z_OPe(z zb`M1pZi2iSa+XA9BF?C~KV>!Z^1X93Vjt5+cHcrS=wm$F)RF!Q<=N;r2}{6M7VIuc z!DkAlH4FdB*uB>}#wk=Li5RtC@q?Bh);OOcf)lVO9@3j_b{)-e_yzdZwQ%kU0 zTN<1amOg14F}O-+)yu1Io1hZzKCK-SC59?o>Ny7TnM@mpSG8-G=WX<74u*TYOTU#q zY~~Flm9%#r+EgDNamsnXHBfo_$x3}v`55_0YtbEbsz+e>Ch1q?v+G6LV9wTG$EQ*0 z>HTdl7G=@IC0PtFrj?Breg~XREPhYZAoRWS#v-Q}TInfEmJQ#+koGeg$&;)~ZrOc%4F)_ZRCMj#ekz z={Za~6Hk(tcCZ?&Q@ZdQ+Jh_|k4aVj4`**37UlYPeX9rvD5$8221N(@_P+Q1-ap`Z-sgSxANx2s)M4hDE6($~ z*7_{Aa7#0FZ7D=tnO&6&);uk-^ta5jn03DRgWyYYD{R*0X#SX9FL0}I-2SA})^Jm+ zOseRpIHb2EwXJk)&wNsEkZdcr()vMd<<8Q=gFTw;Ti6>)tuzbBQ&t=GzWCKfZvH20 z%0s_{S&yHQcjqeLX2y(4>s{u_LCHCZtLc72VeYdb4bBaI(YMP8<-nS zE=p+RXN%+(cy80=xvv_I>WEV%Sc<)BV|?Z37b|<%NQeF9HCf_f70(!N=f&`+WmfP> z-%7?OWTscS@;o0R=OUF`bvIPVedb9F$6y_Kh2c)W5%xSM(-0G9<6QE-1hAcNp#OJp%D6jjk=T0#`h znd|&{7BgBzGPwBBj7Og9r@Ra0U7L4T; zhx+N8W+yGjLVGCJzlKyg5u6Zy^zL;&f0hvtl7Ra?cDpR;dgs6pvzb^64#I4G74@l! zJTLZq(B~ziy%EX<6YLgU z;kq0DUDwC`q+VKY0Pag$3NFeC3GY~|_J^?jTQ@t#&?JR?pMAdRiMA&;ip_K9l~+tB zDLUTruF^_QD&2&>;?X?Ca~nc(p9#f-$j^4Oz;MCIUE)1lj-FQGgr$b3YWFqQ*UyV3 zhti$ccmLAAGMnWgJ=47JR_QhU?L?ZbN?VuUedr*zy;dWt;qkE>R1cr<|$jM7t$)1XEXWQZ*b^;-auMUP+l!A z<{eH*q`iH+nVn50gbt>qRcgD?r@V8YLSo~CvsL#`K%#%9@oh?k?LL5h16Ale5m9Aj zA6?;x@bK00y2HGo+Lrg%*#VEL5+_{6d57S*oR{KqZiL6-#uaJ@OzIN?BJ!;bGI?&4@j~Fc}^m#<$9XK@llA zIUOKb@H~wMEzt3CaZl@#kWO;-V`Df_^X%;ACKOr$I=97G+RfV&<`(t${c=XU6J*p+ zJl_+D|4*&lLnAnV;~jJERsvQS4Xlqdzrikp~HYAT>0*2`2X~t)~;vXxJ^`X zWF(Zky!xd#)`jEl-H)8~_P^@=!R!cP90c&~)tC==AN|F^;L=i1z4o3B;D6)3Bg{o8 zNbT(G<~iBe*?}c(bp2O|`^n!td&hq{8V@cD<;n*b@7sbYesa=AdY+y#+S;Q@FiFW; z$x(y+jEr~kBmmxT`{^?L{n!bc9U}I*MDSKb_>m?Zgy8zc`azun9s1cHL<>ljB z2j*-M$H}*!rqt48Kq)HtUYZ*lWzQ)mik1S-GN445KoncnZs3JSx*r-x;sAEeLDP%n zPaT8V-pE{@SHL9T$;*Oa{9f7g<&7G8U`}~e(4zCsE`P*tPA;w^01uG_?s#UIt}97O z&W$HbY@Shni-AHOzkf5l38R;i4bcf&ySLphkL zE}|F9F75zIa$lpFBoKZg;w&l!-i337y{`bcHX8BU_;y#vBh+`o zvJHvdZTzTmGmDKO=qtDx=}B2LhqWNbSd!fTx^t)g zD0A>C7L7`rh?0LRsLMy)3&H}nk} z`;!%#H+NI3P^xSCff%Dt6IgwzNPEIznHeQuZYP|A;xys`~Wf=QN6B?AquLXMr>>T4kD$ zY&JtPr_2O%$M=Qo&?sFGCZj(loX;?}k zSTmuj)Lbr>;CwJbR5AqsB8`hKfL;+I{4=<;iXA;)R7UwR6_)`F66@Pw@<_!AOO)v6 zcMnxnKhy$Svm+uVhMBVT4cL&{$*F&pDKTDdkdqgRpy zVb9;4Sf0QVgyRK$^qwY5vZ7R4jH8}pWO${e`FI~XIu!%0J15u5G-!M4@L|L2sEq-G zkd^~IliZ z;!KGpdX#cmv;394ybx+F81_n1rNi-!!6zfD7yq&VF5F2uZ>3Y>(rf>}S35_F&DW6N zP3)POwa0RmXZ!(oabRCygfm9wIR7Pot3SS~CDWYkmHDDt7gNNnE@_i)cgOu`Oddo$#I!nM^iJvRF z6hWR{{DJe9pP~e`NBGO}W#z{C{{tzs9RwT#AAzB+a7Nuo|f1HMK_Hx@_Az+E2@Y{LCmg{Fa-lA;;U^#Z`u9CSxw&+3-!yzHQX#Sa>Rq3p$Tc(wJb&5aDfeH)XrYnGa!5bamZ zKS@RDSy+_kWdZi-V+%~H&@W+ayFk0_7V1&+sK=%(xH3+$j^ZDFgn*?^yqzTO@t*NQ z#Q4Nj(|m+!TeWy%V&dBRniv>H((i+%%gR?U>pQm(g!m^ zg>}2%U!YVG|43A9gDu)io4?SpSEKss*cC5LK{dNb4Zr*GE|r{P&VQ=7Y9l1UiGO$| ztD9)-tJOMY!!OP0pr3x+FU3L?=BIiTC8lJPD#7iTv4BxZm%ZE+bCm?pk~{M-BY>VP zzh?u8bd^db57b?XF0X;yMx=Mbf$3H4$B$o=zYPiLHQQ&{WLVO&_(_As&Ht^IF@3V)A(hYzt(tC+IJ&RzS?md{tFwgcAm~FuZgu z&;uZAEfu*DioHP|AqC)cY}jHwkr8t8NFDc3j6A&zU6~HymR45t;G`W&?Gxo1Xm{`h zQg;I%&v{vc=FcrjbjHLU^IIovLEz2*lO%~4lzSf(6ebZJf#4jW0{Zb0Tn+-M2Fh_- zTAD5Sqo`}a>6rO2S;0Bn){s3@+D9k;t7$E~0ZQcGODw^%yI~-z-KQxA%FCYPOI5^k z01_v_DVAxErO&3ftW0UVW86^Wo0DO0+WodI!%m6HlqZuzli$w2po)u~-FgmlW*!SN zt(Z{D1{3}a1J8rKg#t4Iu@T=_gc5~BD}qoZO=a^6AaSlZwD(9is>=(bMV)XNwKiA3vm}@eNIoSDn=cS)_8@{2(^O*3M;E+ zN0P*rc-PZl2tSSRb0c%}X~3GJ2~yj195e@&QZ_%BG~Sy&i%K|i2Pe4m_AvaCaha* zZuE2U)AZHnzQB7gR#(Sue_FRhrviB0yw?*vr;I)P*P$=K8$R^$I5l6aO$t2yOt-^M z{WN3e+Gn;GTxQD2*7BO0oaWmZO5ir!94)HGWAtu*eyCW9u*=8qDBuQ@KzUAr-C?V9 zyjrnwhFS_@_s&T#bYayQRSK$oJyD$l;)`;+H2NIs(9NiX?F8h z;B={E5m$+Fgk5!_ zl^U4aH9^PM_BPfzuBKmgp`M368i%x;v^n^%OQ*n@+KGr_i4h%pRu86|AAF4F3yim` zPWkmJk#0MmLVUrs%77zY*Lgo+S5V2bLZ^dX>n|L%R&W-;Ed<>Rt0k9!Jky{+EUWQY zb@wocO_a-FdPP^m(9*~v2$h4P-O$qn|&#}!-z=BZUXo#?ce?50MrUa`Yd=5dM4olcbSiv;%{nsZgX?;O}u#>qgXfJ_ojwUS(&^pN$Lgg>VJR%{zKj za3TAK-L?B5V;43Ad|V9mUc|Zt%)tHR1b`H8Wc%gkPb8Vxg3QPd?l;h?VS0Gtw~RHz zt4xh{%feQ91z!37I0LDn2!ZZx=1W=Li#bGF48>CFLQI4m27PnxPp0~cc&3rmyA5b8 z%zodmq*0O3du`u2Q9wiBuWX?E%iKHhU_WziIxJKHPbU5*?=nowF92odPbB-0KspX?1?`89u@ zzGF}Em=@IoncdCzEI{NZ?38*c;qc% zy|LEiHMYrT-p0t$W0Uv@h5A@iw-2%F7$7~(UOseTAUAM%#1OP6Jip}r-; zrbySWf_qd{*8b^dCh84Xu#04@DUvHub*mwd8kMBzzLdGx@TO}0_caWEc2!l_cI9T< z8I#FuXX{GN`bOkezJ?xdSr)xW-TjHYit-EJ5`;IS4#Nd&n$C5=rG#+1CM~`=LATAR zA11bqixYMpy4WYmEF+;z+c`zc*HFo)xgng%&RXBff?h;X5<7IWKR7$86=r})%k;sd z=LB+h{ETeTpEpuqZ`Wf*zz29ZI)@@IR+=kyf+VL3wGAxf-pXBeQSRFsH)|>_HVAxd z4Hocv{z8QA{xevvv^15*aOWr*3Mn1ZxH=!OGE(7K&3(wTA+xVG2%Utgd z9Ohf2oha6iC`#}JEUXFVx=k`CnHz1l$Bo6irB!5ddt}3sJRn!$R&&;eGFiu0R6v&j z5rmm`VZ}C=h~Drb|C*yS{cUWWQ>nZ`!8#+FtS;<5{m31WXzf@SA0no@$7?x96?UbMQUmmbM~(5RQtmNH0?eO`5~mato^YDY=D0E z8;OoQbL~Ot%FMn5vK=W;y7)WHXOkUW@f+POzF9%)SZHovJmq5QC5(M}s`4*E2tsKP z9}291-wJEX1{Y#)V?Zm$Sw$iLiOf}rZ(q@56jZ^VlA=6j7bBU>{P;oN^nY6c#=O-1 z7G4)@;-Wu>{R&ooUa^6=Olz+3RqQBc$16X<_y^x(pBDF=a-W1Tb#_z2$B$xF z(2?!=2s?}rbu4wQUbz-lfNzbsSLsG1gYaep4(Db)UBH|WO`x}JzfiWFuN?Ev2(0?z zcv`z^TNUrw4;3bL zNd{SEQjz=`!|NnP?%gdTl{eN3lJ{rb5Q6FM(|^WU0Gcvs{#N|*wMnyE{bL`>bB2oj z`Yta7-^Z>m{ARc5mT_#V7qI4#&$lP9N^WU;cQOwTgrE%dKU9x zW4M@CEMm{Yvbf`iN^g5=SKX4V`1`y_jB}|xIqB0qsT#gDj;iS1fyofGe~h|Po30NN z5WSuALiUF@$7QdxwAqMt)iV~!3hp%bh>YZvI)5|HEvs>Tn-ipMOyN?u}=wtne$)oElCe<@0V2>Cn{`;w?v}IPVULQWstiS-)`7_T0G)Y|n#< zQA9M?XKnKQbh;TU7+>r8*I5sML-JGv3G{)M#SW1o$JDsj&s-z#Vsd}8Hl@z{hP zNj2zo@Xw}gLC?rgo{DLW$oL;E0IZjduKu|RYE zIzG4tVsLREp3hHW-Wd3cp7MHU&kq`=>~rL@)2B<-3Qk(a#>Oh*tFJ@%W`Sn5zsTpZ3+iNq#h~}_WPdy`DNq0kGI=X;JSLiP zAl&fvyKeELUhvA~np1!^GOIv3Q}aS%%xAJGyd{Pc4E&v4T(s^Ksd|E+K<;bMW91v! z@h`-P0S|zS2o&{LGu5^mO(%(*X+!MWYqSBp8%Pj=`T<5CJg9BqDx8-_aoTilJDCq2 zs*s=raQs&dDh<}GE4>YF(7FHemycx5)&cpEnKJt^UxQj^ZZig>4mVtzy)WJaFeE;Z zt5ZNocB2WWHR`*+Bv}6W`0>I|ZCu|K-+dI=nka-b+W38!a5PfAJxZEj>2NRfiJgP}`9sT8#0j{N3-3f0<`mF;SV zfn|&qk_oa)uDchD1f9Udl$e6s zHmuc;vCR=e-Zwt?uGr~tg7;XJfd7rZeFz-HPRkwzasn zy1Kc#<;cmY1W}L!@8lR}NyA0U>-E-#trw z<3)3ZV(i}Tu6)~zvjonE+!O&%26%UZW5BsE62&#JPW22P&$+iO8%B3M2DBP$hE0N@`%mms&>RgrLEiCC zy7TMul`B7$MxA!v{syOjN=q{LvHv)t_`dZBiEsrih5+y)xYaPfsIN!?YmmRus&1@!@2}LwBEt5rRIpe4 z5L>C%C`~!CEpsD@giPTx&Epw_@~HX9d+9~K@mmK017qeibyWvrU!zzxdVWcP_lCFi zba{cTuWqTs1FHsvfq=sATbjWKdScTb3;_HC0JW-XkO0-4dyY52uOxet&-gx0Hc+*3EY@EeFx1XIcLwF z6;&r~xE7b5@7xDwo;b5unEAz+H4r)u36l$9lwSe(IoiI|(O!+NmjLiL$bTeXGR~cj z72JFQ)%$?861CQT`c$qDo$=!Pv9)``!vAmHUny0&!LpEP(`8GIzGcj{^u3Ul+e{*3 z8q9;@!1{uxYyz)>b1S~4u%+Q^0C)xf-F+Sjgf}I7G68(v`Excj$4vK@4p+(&kl7wLS2PtfO|x?e)8>RDzvf;X*tv{jSx(oEH5^M1bss70UCibpMLO z^zYw1)_o9p_)h%#tHahR*F|AZUcnT%LcbS&9`cwk1jM%!6C+g0hd}pml>({F(ZTK> zO$(QarxY)YHC}~Q_<4OCJba@K*ctL&Nh6IH^G+dORdcw@%ymuqZihI z*gopB4XcPEGRr_gZbcMvWJKM5zj}ps?D6j)J}Ht9v|s4F|9olq%g}e%%tev+P9(FE zx*3)Xa+N(q;+cvMdlb^PPdHvh(x0QUCoBsjET-Co#?T8>-E!s{TvL=y@d|yAW;XU5 zlk__zs`A#&QPQl6>X7MDOuuHueJp+3O;$7c3qWfTaeUCsi&bdLi`;!yM1o|bhJwTA z2MXENWSP3L&IT$S!Pc9Ga+J1Z%T+Cv(_;tILRR$=0$#Hp1C^5{^SE}8o5%f=82(`% zQeZ!hb+>@_Bmyh~tDDVgj;kL?Pd90N#^`XDY)ZW&opbQeOKv(fJ^k^Ff@x+~My!EV zcMIMHG2i`!3dU$nUDhV6)O&`I_Fxo<*;@Cs9S4aXi+{6d)??n?pE(=8qPL^u#z}$hSSah2-CBX=-M< zTPl$Ppy9lFueJAKW6E-KT~TCWGg5vR+1x8Y?0o_cCO?$d_&U3_N z;pidKPGh?(_3Mfs&g+nhi>4$yl2Whd+zCY<*cAWM6!9tgR8vGKLrg%3GYu;J!4X6&)axrsJf`c3rLCdX2y8>GoW|>McN+4psoqzH=@n_P}AHzGfFIV+ir*IS!7htg%hggEXg@or0@de zPx#lJcfDG@tnWxjK7B%U^NF{&j)&v8Ybd9Y*mc-uFbzqJDIzJ_9Fo~%FH4>s1)DS@ zoCS21$$UoVWdOAW&bEh7nh#iOymTn5cKYqhe5@J8(r7kTSAR}vU(-YN*vPKIQ*J1e z#v0wyuxx;v-9-h>9gaLi9*9)IBXT=pPcvNI2_6AGxALhH*S1W9?&`a;5MPY zUcG~DiB=|Uso!3|>rzY^Jt36%NrPSNC#@ctA-aY2hvC6El@*$)-1TB5@Fe51aiU&!IpsnN z+}}|vk^n2zrsqd=>DD9@Ron3+c|qJird>E_fzquHt@}XhftTx2tDL-KTp}gi6}3rW z?JkwK0B&I;*ayftWp*Pue-Idkb@SJFznciZM#$z4SS>4Fr}H~lok{X)NB8yIJ)_r? zJ@Og2f}?e&JgWF9?5pQ8%>iak!liF>HygnNY}B>L59bSA?nZS0pE!go zVk@o=ERGjB?MXv4a~7_@55+V?WOtu|GE*ILBv(imP~F>J;bF^Q@uHORQh!a84}NtR zzl7^&uSWOh3@LKg^w4GGpk7-(G;dqon%)T*0Q1k0(nrZ2_|{&)7%xp!Jw8=RfsvG0 zH0U}*HiElV`m^6)_O~-wSXixY+_*9wsK$4A&cJ*1$-bB>hYb5>br^E)3;t>A8stgK z3mmdSS-e6*+rXn-I>L4}9XcqU`$dhke&{ zdD@fbRL8P@!>j+=H8XdxKV5pS*liAsk6v4gpVD{}@0qn`H0a~~$7M&rz$8%B!cGQh z*>iMsT;zn_ZtD5Kwg=@kzSxD(i6|M>AknRwfL8CKEbUNE_4R1*tYne{9ZTlruiJl!`xeewYn9YFm zTehqrzPzgX=hRXr`%G@lL4feSL(I}Zg3n+xk@vQqSUK$pOwgS|!j~W%0JVAJv$r)z zN8`oM!on?8H|y>YR8!8wt)7YnG;x;?<6tdxt2=DJcyJ#=Hh#@b!wx*~-#D3YZ#VcF zbbBixKX)B&u(!3gLKGC#dG%n|;7K0lHa0fTo~1e|J%fcTrR6OIcB0B8b)U%Ukqn&lUchHa$O#VK;A`n1qV~bp7hc(b0&oA~E%cY+;|^Dg znRA?#n#GAwKA)4bn=}4`jMBf*mwY(hyg%lV!vEOmc(?majeB0}ecv*@ce{PI=$9v5V)>7cP4Fq{ z3lRUUXa_;@{1UkHhutyG8M@-+66g$NbmetyMOWXcL_Lf0b4%>crw>|D8(BAR=`5o^ zp5lYJ^Ww#Ii#mV4E5qKdN?nNSA5V$;g1>Wq5OB%3lD(H-Pq?Aym(}MSMef!*FTWlq zSv6Dp{XmSu`9QRyyCqq+vg9=4jr5&A=LcPWp%pDQ58gG79SWlJSN1wzCghqY2}7i9 zWj4qvO|3fZePi5ybk}Ut&g=JUoF<%HIR8Rg43>j1yk;XgddX>RVefs%!M;kWd6{ll zRtm)pGuN>Jqc0`H%_ z;;AT6*NdK$&7ur;XLtCF6^?It0c3lh(gNjQoRgCyR4e-F;d*7UmB?R4n1Fz-#y{hg zb~;kshs!!%?RtGxYo*I-q$QSnF< zfdv7-tO2B+Q^MCK-wZAlhm#iL3wJKxKer_GJX2-o0Fz#9jr$?+yl>9b8=Zdeo#)(i zB>uf zLsJXJw~CSsEjr6Pr>UJJEVE8O_By#-TzS_*nYZ*{Juuvfer^Vxe%eKQ+5OxXFjw{$ z%4JUenV|MV;xG0(`MHC`-^xm(BDBXx!1zmg=Od`fl{&b0kpzDb@wb%!@xPQ!LMv^K zvZJRrPbruJ|Js*9`d6#HBq6~ms`2GNEN9Qbk2VBulKtmi;qTk`i!pG|T#r}zBK<#q z-@m{9K>kHNLdxe-!>MPO(7C(5d=Yv?SE;WHfcem|P zUEK=bk;=?Cca1FvFrq^&15hBCS>|Of4#w63eCOA%Ut1}`K(khSUe-1iByT#FcvHY! zZY-l=s;j>OI4ZpW22a9s3etvzvuw(Lz!&mx%aD9e?T2x$|nM=abZT_gHxAy_9sPjFJdtk@-9H0pm z9E)1`t1A|P)&N2?HqhGD1{yG*4XyD09YFQ)p|UFA)(PRI3R`Xa-%%RM)Kb3HmN#f= zN8bAvdj?w3T%;B4i2}PKFX$Xa09d7}#NGem!}w5HMa8YaURue3v8C2JGsOUk zWP9&<-#G>4gg(xW1d;B85t~0kw?IJ(82%DpylM0@9T^(qTL7!t0z`WIk?d91W8W-} z>Q7@mVqA59d!+-@lFaKdpP*YTMV2#KW(zeld*a~m=_?$yvC>~yk0|;S6>BPm0dsK3 zuf-k>6|MS~KK5Gkmb1D$hbw+kX3f|5N*n3CY(RkJtVmlWv&;TcdDY{#c`JFJGZ*xI zHhV$!$h(%uqHfFHKu}n~bsX&V*SS{wU^;$kE1#_+OJE9?i<6jHTzWUe*VRqt7yQS?Ij|?#%KhXa z5(oH96p}mj{P^`~qQ7#7guB!>&}RnouO;`=!$4%HM|;oj;}?Y^sZwTo<8r%^`FV}I zYXA&a2l!hq0x2gj&p6VAfWSZ%B>yL`j-+ms%GhUPpYhP8s_n&Fl8!cVjiE46Hw?FM zW=%m?R~K@!*z&M{;FC$Y{g@=+s4>qK_KK;APkjuev)VM~cRT|CVdyzyK$09KZm&-E zisgbqa6s8}8*$NLkR8$s6M|%y$_&k~w6(NoNNeX7M%&=Wm{!Mjt8BS|RT>o-30 zA1CVzDY6}%UyvY_s52?7*mJY#?yHH)?WWe|=5`DQ=jmi>s%cvOwlgAPBe(>>NCmHF zXitE*e)uR>^Mp8Y6R7IZ*V0og-@oxAS9u^3Y+ z_@jJNY9HGn6GmstRr+oKO!^l&SI9!t){Zz!%QhUBJ-5JKonK<0Z80IbS=bAF)P#aR zb2O|+sp0ox0g^T+D{B@c-t-8oO&ZBvvM!aCD8|lV57UOh{%M-=HMkdO@fHS;^aM-5j#xZKLRRUG`y~{IcL;;6?0qeVScsT zhR+q{mk^JEY9kO}S_dPPp_-7qRdX4zwGjdOOfmhB+qT|V88zGF6A!QFq&sTAY*R08^2-Tuf*Lb-l3P(MaMkkMw!5VxlT#UEFca-tP? z?+h3@3k3K39hfZCaJMFk=}3Go>CZ-T`4wsOT9nHdnee_G&OBWIZWH97uUkJHp z@{0-ECARfr%kRB3XTQGcK-BKNCj$VpF3g;4qS!h=KidRUZxPs*X>=v{1g+gmq<=zx z2mrHuY3kB_)WYk-sFugo6&sc^o32>{xrtG}QlyuMo~K7tfRYYpfN~QN0|?`vmZ(H? z>uc}&u3Uc4u~4WvvwF>Gy0rrA-xm=%og41Y zZ(7e>qe#qg)KYg4GzZe_>`QkH`m3%)WeG+BCcu_R6og}9u%BOa0=yQ5BV9h zu+&|)QS_@jxO%Z$P(!s#rVWx|l_0f7Oy^!tEl^Bh1uIjoSQ@RV%Km96171tBxi7;> zW9%0->xv^tdt_3Y?bd*FYi8>SHglF%J@+~IPoAF|D5bf6?xRI4JdB>tYW(vm>f&v0 z4k^ExWk0%>j-b$YoSdAyt_yuYyzLVWB+^8hIeXr}d-nlO!gVpuwc2q7RavPQ-v~4& zKRiHp2XGKA*QY^AFdzsUwY0zFb;z%rXM?UEtal74MMasVy^XIh^VEJ5>l82zo*+xF zMyUY0Fl*CcFA|BI|IM11WQn|f?b?93UXmr-=9tSuAJ#LO^pfgYwjV`EO+u9uvP@{| z=3oWBfOfK>&3)D0Zy%~r3mDHf`3S4ltBU(6 z#hu`A&Z+zJbw|tOPM9T*s2{IpsE4I&##+4z2uO5jfGnN6LF0pVgKSKP&}=WNERW{8 z*=!FKjgK!4mAPD)bN?e9xnymA;o3Q|{l#L=Kv(MG{cx;;ZEuO~kl>}(zI*42z__(o zBkqmug6#uEu~O^k8vRet0{9~3sv?F!o7iTIE)qqa>^@GyG&dU)qs}(|%lmuTwyHa> zQOYU>_6g|wNtJq%n>`xSG2?_Fh{0pF#Fz0x4;JRGF?NQ@zH+lDB-TmCzS)b{$Ex{# zf0n+Uo)!Dj0=PQc(T@%_Oa63jnUsn1#VS~L{q2MgRjM}<#xT&_G8@p$nYM8c5%Iuh@z@AnV(}s*L2FUQY zPKuJS!a0vhPhWuGGKKpy|E?y#$_HZ`s)CI=~fbN^z*!9LHysNx~+VE@hrsQBgrnO+B~+iQNmZfJ@lsnLV=1DVZ~81BYe~ z8;{%LXRsG_woHQ^C_Uc=_r}8V#W4=JOwv1Kc1WnS)A;Xqd@Z8om(nTn3$kfDH+n9 z0scBZRLYj?B5e$tu=B3DAsBj-=j%q=cc$%ngkv^88wGclx)?<+LuoF8QVvkcqrPu_%6lk_sR=Wjt?hZ5c|{jp-cOcc}yBF-sGQ^)9(A3V3XG@j*NsFsD+0oA(NAJ zo}&wO)69`;#Pr@N;&%?QwLVo<^{*%-XRiuqXoq)wFG-HI)n6!^+FAw=?NWmd15e%O zM1DS{046?5ikNwh#w>Kr=nU~eoN%GnUqI5H$c*XxrlU*>9rO|V=OPJ9}P8yr- z9%(q3Pk_c()b&hS=8P(jl{lE|S}hgB2D7W8qodn>H@4e7=FG4@GFx)G+7_Oca(u^D zx+Eof4cNlh#*{2d%~Hr%pIIXX$1eZY#ip#L=A8FA^UbMW%_027hA``kn~esQ*Am3o zX~BXXaFwSA+E|jk)rnt#s7I`M>~=Chb!1Kh6GJJi0Cj6bz*69SZ7)(GO>mH{WosH2 z@P^exgd6_-y9D{T8B49;`VoytU5bcw_j*;-R64A_M`pDTl;w2^`fm2>*kb!7H;rl( zMmw6w(@4nP$0FWFx6I|XGbLDBT8fB>Y-Mn9+AAKvL;N%q9mDYBB>i(Gs<=0&X>1n0?n$a+g$};%EODUj%MNm$zz2$Q8OmltN zPud9*`19&_Ux2jU{_j9~LC)w{Q@6sk!k{{@awX`*#nQ(zGJ=`w;3MtI%vX`2PB%loXUw(NqoaHV5YrWCF7 zddAu21*0{9L!0R*2R}_QG5lJ=$am0~lEmh6HC0g*k~g*pmPy46{UxgvG1CZhQ2&;h zV&*9--@R+2uRjdN<+%j(iP3GE+Jy~U;s85iP~(YJGz5#$oNZXUgMmx0)*xU0sO+t= zdhjUIe7r9+#Yj#g*s4EojkiUBea;q;7dR>yw!*ulGG^isG2sF?6M2DN=_RIbX{4n@AJR$=wdR`jN zYK3B1noaj+>KMxKaGwB%8h)=Wo9=qM_zXqb5sPonN#*sy1EVYw)b|ZJf(lA)^iyNU z&XSgW&hp`B_8uA*=@BzJXlQvm^X)n4TQvvK!=DyZ98Xi=H22*)?0aCzwc)8IR`vrf zp_6MYg;O(sOI$~A8(Q1`v_(~3qf}f%5r$ib()_W}~<+2Rif@Xj?(b*d|=J}T9}6jwDPG@lPH5q78RWKLVz;tFEo@ETTjIa7@*S{e)E z8ixCSUltW%6{`ZGZd$*UyTfWz_^e#PJ`n6*5YYDmVjTom(r$^xULOiC*$ZBjyLU|K zK3_eEC9STKtw@@_7jBvtJts)PXuhfg*~*GI5YMzka7Xqo}^bsIB69rLBgZ-r$Ro*u_Fysb#`# zK~TIg6T=AwE`vk@SNrMFXvL6i1uhCt506G#H*Y|}d5;oqG;b;U^-+kzcD{0|TS%|M zajGjrG4TpL-^~DKYb9$(y1CgTJM*N?Qk4#c`EC@oM}0|of)ouLEBJgcU$4} z%F3UtzCgOO5fT-XRi`w#D8&$2#Gu-vky z2+0OkBR&%o6G}?T#DxHu=;BD#c8O*8hS0->G?-nlC$^F=$3^Zqc8y}=O1&;V(!~n@KmfOJL`AZeKK6OL=Ia) zkf=>|RbV|(<=f4F|K`6V$UhvNsa^>lbfj)qF36pw{X7?pv<%fNr2fEXrv4u@129lL zA9sctes=2tB6N&IxV#)dd_K3IcLzh9L%XPp7yf<4|DJ3PpC6cL4S7v^>@oY#k1t<7 z&A}8LfB%2KhQHqV3kkh1{}XzF2Qx2d&~>IQwm~W4*QQjqv3{Q^>n@)1Uj1FUI%|2`-!w*V1(WmQs-}ib zwuammyi?W7{}R&~^gLBySkg}MA#6`b-i@NW{%E2(Q6TDsPKN*Ng?J5s`DJ`ZzPxDh zUnd^je;>*Z())uGty7U5iO&y0wMJlUFfNwwvF(Yf;&*E~*u*Vn{6h^{+&p*J>+16NPtn3RjTt)cd$VXd?n$ok^J$S5dOP4 zdk?R+yt6b8_#xHmqwnpJcen7jkK&9n8Y3`N$bJybU5S+4&}sS|IT^Fj~Q~x zpxnam+!FtDZ7r?M1|1e{3j;T8PTBJu6@{HgHx2arm*(M>V~189x-FhMNv(YGe3_a4 zwx`j7rSBM>AGG`h8C$`ss4TAfO$ARZCp%fJ@IrS3aUncY=xXKU#kYl_qLh!Q4p-wdi$-Th7;PnW}4zURKq${<0iJCXNvWd+7BRM z$fO(+wQrClOCg+Hm+C$fwTmVOhebyv3(M4duX)RUqZ`Q~n0BjweEfR-f0%pAuqdPT zZ&X1H3{*k|0fR#Bk5d|xc7d~ z-oSp(|D5Z5I3Ky@;+bdGv(|dneg6tSC3Nv<-h7e5HCS8zRt(QY$Yo`fnF|pgvc-G@ z)_pTdDfP;I6;Ug9=C9@aIQK+bYyqHeB*(=Cq~kR@nwzRIsbVbQVk)5JEjvu zeJj3I`Xq(v`7=S{ZX{76t11iL1^#ZO{cU@LjwLDX6Eh9(*V7+P1m%y4_?(Z@qB~*K z#N#d$Zq~gQy7Cq_LA3cXTg%I=GFP#4ugtZA{{!aZmN~Hji;;dW3&hpvwTno{$?dYm_ z^%MM}RILC08t5As4sZ=Byy6VeO--Z?rUzq@%d4Rc%(NJplu*RML%YTM`%xh$E?NR5 z{7Xc18P+upK|(UVNxz)nV~(y88%%E$N|iie134{5cE@JYhxXmwll%n=E5$J%>$+(# z-v8el=f6MmYHP3=ZevoP-#NM)<5$)Jfa_agE6*AoJsILRmt`sd4SB9I-#kGGlamEzVuBBSr;+;YAx9F;{R;(%%^y0FYyYA>DR4c!D;%s^2W<%=-xcgHd2Y=2 zNxr`{1IkHL)3lwO^)hMT&GPPDL~%o1UCE_H<8huE5Rde&9C?gwan;n%OYCgx?{hy4 z9wH7t$Jf>x{qFqgl)5;gqeqPc87MWcUjs{)R1hOe$H)h3b=?3^j?41*b8tq0Q4IkN ziaCb}893nIy1qiFt)&$)RUNU(CQ_cAZneHRQw)#i-YW=> zU9XheW%L0rFFsLfzP~6FnmD|)XqjbK&=hzJ0t00O;n_a)R12C^~-@m-Go`YDh`*i#Zm({D62uv>AzYc2? zaC7^;;kUL{GdRc$bP}SDvigSKLpiFZ+f@(}P0g(C(MfJ@VQZ}KsCL%poJXrqZ-#oS ze2s|M2KndVB~hL`Gp%uk&*gIkV4OCi;sdCAB|C}DKorq0tMl{c&vtDU`)yDN47idb zl`3_Lty*sgGz0QXv>4(5)Ub0WLAsU101kN|EbQKyzR{Bh0d9b%c-TA#C)|FYI z2qf$uC{37;G#NFXVLWTzp0xsKy2QSo0N|4iDBI|_D6+&}GFlmLJkvV6bMF}IVl>$c zLDX9KBTF*1ohMT>@HQ8Jwp$=z_s>T~?d9-EOG!O(`gER+S*Go&(5vORF#F8Rh!@1# zD`tx<3@7p!5k z=7;cyQ|#6>9nvbEQCw9(3G?yeN8n1i2cp{2l+)P|tsyYXZ^zca!ISEvQY z_Y_zpOvapfXQ$lX9y{Zo-=Z6p_AUTYv&%GG{1Bnkq}1+4&%pD^y4uUu?d=R?Z^<;E{80g08^@qzX z>2&YBLWKa?fZs-l^YAQ?Le}209d)(u zFZET}_kO4xo3zW-MYJ&m4BipjnX9TDO7nScwe3!qPh_w z=g(d-gWYEq%hCebYZu?$O7e`=)U~Yx_|+`s>O`1HBzBo5`8SmVGS!Nrz?3ZcrRWS7bBnkg8qohR z^B)GS6Tlhf2?ufY{XaiYJZ0JcxtmSdp072M{WD-WBo}tyRCWfaWO7>g$!S!PA=CvL z(u;#71z>;EE}hOQzAXR9LZFVvb5*^+*m0)7K>f5u0E@pnUP^h5JsWcZxSM} zsjZzMx1TUS`C`M0kk~abAz|{-Se4tR74>$;L}`j0*xx~Rr0vr7?@t^Wqb)d#^*?y( z{w6Q(SV`oSLx7^?$KC?~YJWg$*m$5-?uZ##JxEHFb)j`g=R&>?!XB0kMq*-km8RBCC0b-7w|BbPE4Pi z$*)iyE0tLD<;an}dYsU%1A0x@bJY8s{2RXESG7Mz$*2oLT206uyJ)*iInY4z*x-_B zXuPm!P3sPVFf~xx$#NcRct$w0Ba6@b_bilY9*dR`a)8MKVl3R8j7KN`rOc^VlDR1U zW3CoRowyJ}6TR9R7zRmB)3GpMT|7b4h!JpS5=2YeN!0@|?)B@85SSx?Cd@97W#v&L zPrXgJ#Bdu1>A+PlqOza91!#ck-AiTLr3*iHLpQEj6XT(Z-yt>b+7W4*(>A9>jP28- z`fP^RCM_ai9%YK!4^MvwuF*ADH2_nOUdM#CWcOC>lJnEIok?&r=bVB z(;bOE)G@r!vgw3R4(ZmYGa@=-ua=*Km5jH^J)j{QP!B@N5gson;tUB;xA`MQja)|# z_DQJuDx2dV&1F`n4 z0<<1$U)bRvW&sOf!wPlx!jewEXE`&|lpF(%HbC4$ZCp*;!*wt_8`@!m{q2FTrO{Eb zu}c#Vgg0l58BxP6XAOC-FPLh~y^^1eSPi{gY?hp%sAw~saGX8mf6WwA-4~u`boLUZ z10Cy}sUlj#c#@j+{0v#pml$m=buG2twYw0`nJC%FcS+NJPM7WTprS|ulU909d>fy) z$vgiGSC`vJXP->P1OOG<>CIC%SvD1Rf&MLMh&pR{*d5+JXx;Nz_)_D0Z=96NOB!uK zYnMfAUp^`<`a2Kg25N+xNW&Dp9@xBfq$uB0i0dLSslEPQA&Q&%&{TgT{ta`Z%sH-t z`-%5hGg&e+B3aEDc0dl8+rcTA#YR-r?SYmFcNu^d!^^GBgw|3<2W1vUzrXo(gQNTG zw(BxDqv8G}4zG>I`@gW+$aW)>DyH0UVl{HkFSh=ZJ}N(#xqeC^)^#>k* z^p#dEQ!L+9a)GYC{$lwF>@$C||K81qB_Ou>pxF_INbo*bZ)$4FH(szxdC9J4j`c7W zo*94a{{uJuP+_3OCD#kJR+;RPH2fNKS5=OvSso{EY{IKi5smArE;+CTZrs4u+}>lDE@F9+Tp-c-d+>}{{=b&gm9Pe{D1VP9QS&#~VuwNDPZe6Zj{ zLW^!=prcz`7|;wOWsuJexy;Jc*eaT4DfIPh8WPxZOVfHdfDF?Os{s}qE3n^w0ZSq( z0o{KAA94w&k%ca_Oe}-+z~|%Xo_(^i%W*I{@(c!&10dVtll1@ zCj?OqB7sf4m3~YnaOJY)viz)v4bY4`0avOu2b0~)RJ_yAPC*mjGE*m(xUSEFGf+3~ z5;!Q~yVoV5P6*Dag5hEZ(TNgWW##9PAqqC_LdQ9ccWw0n)N|X+97`;+rqHQ1iuIhQ z5eKHxqpyiB;(Rx)ohM&2r)>f?Mjt!xn%%=9UZ}%7V8QeC_kXnlw!ux0u*uu*AR!gC zo=%aC*GSAa8BCEF0m2J!d2-w=_;TxW8ad^#eLN2EBuDVfC{W>+!q2iq%8$CsmRzGHbfz$9AV&U7nA@qyk^Ko%0v3~vVGcoei|Iu zM>`#+Z*9Hed9^v@9BtytVi`aB0Y3J4vod*=xozTxfqMsUdyNeJJ05kM{Lmu4Y0j^x zpzxiN3i)Sd0npHjCDkA8Go78vG85M_!~n#gZ98s-bYVGa9rdg`LtmkL571S(lfHIQ z>!LqrYKs0-G4WNkSo>5a)Lwrnnq+nMU}TVVqxZFm60aQreE*t-O7} zh?MH^7M_hHg!jE=iT3V_pZU^ zC2)vw5@5CiRoKV!UK0!d-+g5<7o7)f8$csH<7b>b1$rJkP!!OWP8VCXH^H&7fL59^ zjW*s4O@U1`h2Xh1_3R22T)CF2AqBK1CE23ziX0-Li&JlkGz6*A=7;MG%4t;4{Qy6j z5O%29NT;6AC8*p8WyXCR?R_yfo8^255QpvUC5+Yi&t%la zEc~M-&Beu4sNcCNS7AL;>-!1I)T za7HuZCrni}sF`vg#q}LxBT+dg)X+RVWg`g7(O$A1iMSGeEFAsna{@L>{)-QVQcmzq zymPf0uTX$^QAbc7<^AE?KVG13aWR*q$>F5F1yTwK2(bK}Cy`>7R zbN^nsKDIva8+t!VT!=Wzc*@z`#Nx(o@(qJ<>!vrZp$b&`FPcI^9#tVK z%HWbmaM`~drMMyD!bFkQHUFi18>^6tDwIKep9hr6<(Hf?Lha)*Phim${DFnYMdx#b9RzR$& zu>1BGgDB5IV>)y6IA&U%>VEXPf!OC^)>0sNY&sY4w&hh^j++S2NqsoazYxJ1=i**$ zuUrZlGO6H`65A}Px>Z%XL63A_J~5)~?ruv*T`MJYv6plDJCVziI_i;~$sbmxOM82Q2Qv2QBigU+(2f+aD8N^X9*uuo>GY#HH-`3q7aQ^I_lSdiDonl@(0`?Ygug>ZMr+ynK**_8(j(h7V~TW1nuaxBf$3Pa0A6H; zoZe1hwkb>Yn-(J3;W4nF*7+&dU#T-NIrenlPx}o6Dy%*GSD|jRV{v>|Lj1-*Ng8aW z98jGpFpJ8Ib4&cukf~=4e3b`=VTDU1&i&s~=MtBs8P^1^K?^t%j#5YP^z?RyGyO*O z5uz<4ynEwUPbEjP>F9m6N;xa(x_^}#f{eM6qD{g7P@^)QEN?WN=A3m=WgyU)<> zuBY{`HmorsA_PouzC1B*SGo#|Nsj5Y@H1~2;f;(7JPa(lApLC|)0=5RVP4F&Iu)Vh znUAevNvyGO+UW^^6;%qxxB2dOh>movuYF;>XRIfYdFW_2Q>ED2eTx8q0b5;7z1p$K zC-u{-+lczj>LV&;U$`o?FRx?7WW-ljBA+-3T+=OEiHM2Z?6yR}Xf)Lp2mieDZSJg? z_lKQ0f#{V`FdKkU*GK+d_RV=f(Wt5LznIT%dZA<{iDxX zb}m&Kv;D$k!D{Tz7UP`w(6AKI37e(Y$OYV6&pj(slwe%c>rwp<#_LVxx>hBJHmN}9 zBCq`U;KrJdT)@Gu77^?$^lXo1Sa*i~?}?LcQ1pD^NHQ|!3!2U+;%pN&RtDKxZ`&~u zs2>u!_6&*Ii=_(G!N9zK#^3j{a(&LjD^erTOG--f#~ zhHab(b!}Av46wgS#mcb3ZRCT#)3)y_cZhShP)hzr3Zq3WfH`QDc|EHe=V%YD!OAe; zbJ&$3zj4y9)Q4Q-EZB`#_m3ug>Vnqa}B2A9^rXX#Q1t zMF#V9U-Mz6rjus_l128!t3CcJjPSoy#N#87V$e4YZF0cD>N`Fc4t{=9QuG+R)1Yx_ zTC0yQBMX{3TX;XZvh9*URKq+0+qATYSV}|*C8ymu&J4SA`KGd-mb#u^GVU8Dk{7i0{ zK=e;N$#CvJ@r0>?>Eq*Oer*}+SFk#TDcftxRK<4M+vk_PeS7BIxv-G1Kx)41{CvCp zQpci}H!LGWKte3?^5|={2%KH=cYpl&@v~>)E^fNIQOyqtRELcNj?LBfS%QO`{GVvABEIi!OTNEC66hxa*!!QRA(p(47@Q@I4pt~iGjqa>6s3kCo7IN00P^zGekmFQ5`Y7o}oxKa*Ub|2*6;&Z(>n7#uYG}0>oDOA-6{OF} zecl{q;4qygc6VZe+`UAK_|k3u_Kmok$p_Obpc{hj#Gke&L6!epI|lUqhtJSg%<$$8 zyyA%c@+H0~L23+WIGpnDEaBpgb{fQ2FZ_>t`l(?lPcavsWp z7c{`6_x>ShU_RyCtz`nX=IYKDoi3}B{**i{e0-X1_&D`e69pIG*=7=DTMrf=NY)Cx zEdX-M3qkP-sA-#_!##dfe2XoRHXMzO_M7yQ`N5J^f4*TGmp#1Fg6HmCo{=F9ma%z2 zv$A(dGUEV-3TYmH+<=k;rNd`T0um->9=|3L+iSnoj*~9I!v$`C;et*cW1&{ymoptK z6V|jaP@I~S)DkOZaHT&>VFk~!N4>!(sjrL$Zv&tN*qAr~ZWAC7NqcnnKYQ~hrA<55 zQKSER4{J`|%+xP;4dYGPcsW9A_Q)~KDU6%h(b_?LfIRI&T;a}bkRHeL>gQ<7d{j`) z>o;c1hK55mrB5g*XgFBe*qLW=BD@TR_NM0MgjkF_GCC*~4{)u1up5c;F2F}H;8hI8 zWNRv;@?WkDJR`}dxRA*#oD_~+9CjLjw-)2aA0I2lBjUD!Z|Rq+e?WCJMZ#y|b4@!E zu!=$$-uBEQ_#xmbrV+B^Ra(#-k=+G;xLlpBW%6$Y3?;wYWQ2)BjF(3dF>)7JE`TQ+ z?^iXlzvw&}nh@&rl$Zcntp((5D7BX6Gp&VRs!+l4yr~6-=^*q@9?9MKM1P+{uT+gw zLFhe*wm;b4jdh((*S=U{*~g`0O)Q98$!nm=ELI9j9pvx`ip7HkzdL;uyBrSA>n*z4 z_uZ}%v>ukDI=W8#3&qcg-KtP^yDsHFf1Sp2=E)5bDz2BCt$GHYMccq1ZRy*$j~`d| z$`d0Zd`OGwCnv|z)n4RDOw7zc{B9MjT01Y-CNOndM7!ey&G z|CqFiy6uIlkT&>>8IO({ZEp)XAFe+0)CbsrnOS48PVwSUS#jf(fu>I^;-I9$5g>Z~ z`Kl4}Af9m+bU_N&(Q)M{0Cr}?#Z`CrF8k+KlilT7@9OI64?=)UvsQ8>a62qia?w&| z2~{n$G+Iv|XZHV&W1=ysb()!((f(s{(7S=GYb;&D`wr@i$P+>4@V;IMJWqQqRZO7x zYe6%FYR?=M)umf#5xMYvGBI81kqrH}J{|3_45ciNU$xrw34tuB{sbL3HuL3=lmHX=QR;s;*d0Cy(;zmYf8Zt__4-f*1= z(FA!iMloFpV$gOcP2TvdZl)LlNo|@m_)wR=Nce45V>UBV(3k4g0}3pshj?W}sLL!! z+zIJ7RG3j=nad@pGae-En};sG1Do`)2Jove4Q4O8x00S3qYB!MPr5A$CsHEv(P9v1 zIXO9aGQ3-!2rii77`D@nMqGY|?Qxaqnl^bpN2P(+Ds+_u9av_yN5H3AOtB9OKXg^r zS-QYDqTlIQl|1pt_-^gFN(Eh-$M$vF_ucDZJv<0R;379(lmVL%Vdpu_-_cps?>}1j zTs?*FoX=5G@B&eX_Zn@3VNuQ3-c;OxT}BExvotcGA1PDeqt|u8iq_%O$O40 z&0=F~;?@T&q&!$CWi3E5=QXrsU7+S6d=)$vk?V6ktP65NKg{%!o;vb->6`p^X6gO# zvbNr4Z_Ac6XcquJmL&c6Frf?av9h%GQW%{0AEEs`Hu(3A^fF$X$$20(nv$^Jo85D% zJeL3H%|K>4QQfz83%k3qgqW^A4X4*oQ_ZL6_6!IT1T4N=a zq(#9(la}dMV=hOTk$ND`M=_7d8}tc04a*PxE_fR3J(a>hALm9$vT$`m z!F7lO$kA3fc?NJKl5ue<`F=~pweU)M;rAO;le&r`Q{f9zM&@xIJJA^7;Aq1uB$#=& zuf@r7LTdKS5p}R`iGFGAImZ zKO-TdG(RnuhZGa_y5H2m4VEs&8I5Q854-+l`2*F1X+mP+0t(Pg(z2AlXho!%c7T0p zLC@sTfVBX}92={CN^}RVWuirP>UwKoVWI1;*-OHyjqM^S!{Bw8fi19Osrz)p!p*Zw zczgV-pmNu+9dqxyC;;x;l}uohp=I5K+#a)-9LgTn5%3bIy8is(f80O5nH?)Wccyix zVKY{E2A9#4AqfQEjg9B>^J_g@8dY!pL?pl@5WvnwVN`wsF#99g;_PoONWs`?rF_lM zlZ9Btf{9umlFTe!#xktN*ZJLS(W2#cKxD41TTpoZe0%q&Z;;G zm9QHT(=q94xh;<|4l|c{kY%krsk}1qreJ1v>K)hg*wF3QJ7*M`40it%Z>%@*HRQC8 zT)j#1pF@9&07KVK45F#l7kM0Kxu0-ysX{x0EmG379>03}w83b*VUNX}!FECl=%Gv6 z-T2p4Kixz8`DBn*(Q0^`*D~B=8Avu#oACU9DLGNcpp=SCiGKQ42iF>D5hnM!7~DwUD@f@frX=GkC^(!ZM>9aHGQI-Pjq3ekHYSF)pnRbe)W@l7=O8et7JQaHk5Eayt zf5)J}I`!XH)8EA<{`}&bukx zHexW2RsktLKZM>hXDvJ{jgc=FM0J*HhRtG2m{j|8GBr?K8031DpagD0T;Bij6(@60 zS|w0>Nu>oBYA3={FyLGTHzLOcM#mKlr`ox?mcEE0z51@kN+>K9VWE2zy9q2T_3hPfVT=P+2|Ls@D zw9qVh2$Canokdb3nc04p6hhNgK`P`H@F|`jGmj$*0Wu$SJw;)0SPmm$xJgfzRw6Yv zs=+ivzhD<6^@V(Yxtmio`Z%q~do$!;0E7LLXpjCCK%gozjDnm=k8uWM{%?UEz&B_c z;A!Z{xOAy>L*P7XUknW>fcUB9Yc4jb?jnZ9@wW>R#ra++$ipKquNdY zk9#PIAtX4Mzpa~lNFQj}f!Y*eT=$+VsU5AQEt<}@4cIh`zq$lvo`Y)OV;?iegZuYu zOD=@@qzaD+{%;n&UJzPXtSiVl#FQ6AX;MQ<4QtP~Ep<^GfZbEg22=71yLx|kM7=4} zb6aryE}-Z)nhuNgcI)sqEI<3 zT-rc}cM|Fj8YcY-;&QZC+BN*}X0U7z92X(U@7xwu3ea5C^(UFWjAn{|TC|;<8`aLM zxT5bMh2g%=)@xb!XW9JdaU7r<-V_vf#7(N+WC$|t*3 zu9NN+eGeE%{U5#*7)J$1h8;be;@5j2Ip{f^*gE(-2IO~ax)TP=FCAG{_&?)N_*NFH z!AIMZXzzt-;!i(SqKXVc+fyxv-;Tk^tl<~tdO5dlq>{JDr~UkS`M^PQ3bgq#DBFFx zHX0qvCIioriDnPID8j0-^1ab3T^WrWSM*ERn_NDf0HSz_SD!D;sqPa<{A4Y37{2|g z!%+RuNy>0JklFeE4iU4eQ^$BsbIf#R*)P3JcmZnwg+fJ6?Edg7BTbcuer3s^+r!}M zh>(*kpU#Af@9Jf2H$#*jW9Dx}b0xi)X)AC{Co9-Xcn%#AO0jz$$TcuIdyDb6Rffy2 z0vnxU-plymxl?_n-+EM@Hb3`UEo-cgG0lRh*z5#WF{@p7-Q_K+e4|A|M-<-cdq>;Y zxSiF&q2L5i7tC=2c|27;BlC5uYg*e-&U(9Si_sHCQ43Sk_P#{KhvaL0waRH6 zX)%XD5rfPEHd>ExKDGKpgf0rNctCq;i_al%GOTFwW1!OQ8&|8VE~K2aZ{6|!?3Agjea(G%MIV3? zCIL)CAsx(|W8;&DR`*EHg@%{zC5+|-osTLxt>S&;)DHeUlOVneN}3!O{v51D;}D)Bl55fcBk zPcL@P_|^F>l(>XM4X`=JECbhwZ!hYItEgEBCGo%W-_VF^+B19HWAl41tL#-P8Mwl= z!KiumyLUk_rSZgsQG3 z?`V}?S^~v}bGq3txwfj(4!S~@;-BF)C#B|`B9DD6fiTkA8pwUrP1$cwFYbo+Xby%^_ zj`ueOmNt7YpI@qF^!^v4-zCX@s&y(BQF)MZ_+LDj4(|Vt8~grK_A)m*#m093()qpX zH|0qd9^HXJR)Gz`Lx>38b?MPFM2x4DR6Wp+ww$j5J?qe0=EcBh$yEi^Pg8BNhk)hW z-Q{&mn5L~+T}5E>>(?(psh%G$m;zR_7>Z;fGA$ZYXOa>UYUZ_4WH+n(KsPw}T4FRBpf=!< z$5!oc3^-Qw?}j?Ak7m(wzWAYK5^ZcwX4P&wg^A})*Ipq|N8ZFpenla9AecrvTS^YLlr-b%C6r)<|< z+}#Ud2A(A}gGCl$PVSmwfTRT_0XWnSAV?<Q28fBfGBr(%jr(|KvA3%p0=Ipg?Sj~Sc}boy%3puoo5(@CmV3ir~omjZ9e=r+N%6M-#n0eXX!%KI5%~ZpDO_;Z;lY^z;mba<$J&9cJ)72m@O{pHqq!?9$Kp4h)`( zdO{?;c`4Jb^|Ot`<#@2P_AYDFDkh^Xk)oJ4`mIBig=QB&QLqUv6k;u7cY?J!@LqGX zcNC{O&JF*JR4hO2!bA)8%=Vq0R#OP8j_~}op_#g|BN85-Powg>H%aDeRF&ZV6`mD* z*XPQ5vx=}9BHnT(dT7hQ=TvVP@-+-@F=$k_L2)dIKwEG0@o)9aKuON9|3^XtnOs$| zrj~piQRd9%l0RCOmRS&Un104NIMeqlwRqxnEb&J~-)OXpvNYepMsZb9wCNjO9Vccc z_mrqRVX|&O$lNCjT~1e;S{^r&WSo`FAl8f!{U;E?mw^FE7xBS@I%6L3-#uKz%Qmey zD<=p^gh#=@oh#zS7s-o&437GvT3Lc{-0?5j!>Nz$x#N*JOI*t(eS2F^SE2i1uepd* z6(V6Qz`@19Wr95H>@lc!RP6r+79lfg*%ZR%F^o9$7)ZrDh5~JZ?wH@XhzS@vxnLAX zXQ84YMH-7>yJlfx%2g7OyqTev64-jTOS?qu00gA$U}N#PrH;PMcOvw>e*2pyArwSc z@n2p519?V1Xn$aISe+_bwe|brle-IJ+WHyg5c~8ZPjJO_rkHe25mt+q5(#@CIhf2= zY{S)v@7uO&HbWGW56Y~D1hJjFq6%(dhhXUBnx*ss&DQT0q~0lkBiVm@T|vSB_xsj| zX)G0AHfJ<}#iLYW7!qmjqhkF?g-s;6s0E#jk%m&lLs*r~B6lwI!Dxs-CLkv&%oAfA zZ8Ci72ajsFRrER0gG=FS`yaj)|g;n{b9tbZMR66{LT#BXCZdbF>yao`1jzeW^SNmSZGguUBje( zFBLwt9^7d!FBO#UO*RR+O9vM%0-jDLgR%p8DBY6IALr_Hdgg%jOi_O4;-eIgrg>fW z1?cIrOyG~zDaX-OMs~fELBqAochO9YL)~2Lm5?9MBwBQ3sF&jI;QgMGxze-5{eE-x zhb@3zgNuz^J%Y>lBeMm^Ln54f-$Bo==)!&UsNo`70ZN`-b>KP>BI}~IWvy{3R3%zjvw-}5cR)%t;Pf2w9 zhdWo1^ZOV$p-#KLH!#;KDpA8(f`d_%k%cYOku%&@syOSp*3$Ry0G!2ovSkzVs+53% z58~2Ip7>~j(`deTW@_D4!wUQ@u!Qu^MXhYaFV=^KG%9foR_0bhe*nAuN9yYhW{3(z zWF1gp`+MK|@}=AD@2qQ2rFlJ9Qwu(uSbJK{>>d{j|LUZ}%-&eOeHD6^?~eHxG*(?* z-IY#EY{VfuJeasilPiqDCM7MZ1cxBk!fPYc+IuY_dgeXu1ND&-MmuW{ovrm3pj7Y) z*g#}j1pB%|NWEz>4fL~$%)5-uzw1}o^!bUQbndQ^v92%Y2oGNgEcj; zGn!_B;Eka{wg1x$G(s1E*r`px8f1g5f9e1TJv);x3(q7ybt~>h%mU@Y#u)T_Nx5P? z1yyA3IRYkW8CRMeTGkt(jR{3EIs#zqZAdvP z;;i*-H{-uQdh-TPem%oJATJ1(sXoO4IcF&kkRFb&^F;1yrrJM@mgF&}+Q_HMW6sJ7 zNuA90jM|xYdcGJqAf6ha+Vw(x^XxIz(5N*5>J~p0#Hq#W(VKvm#?+X`?u?dlBci*} z5&&xf8i-HCk)kgdT!|tryZsVQfitedHcgW>u#94t!484OvI$jKyVoXLbo7>*lN8B9 z{j=FeZh3Q6z+W>?4kv$KjbHK?3)Q4e-^5U*2qR-dX!N`KwVC;b;Dv{S)+IQ8LPPdq zN_Q>ISVv67caD|ixW?0JgkL|I=m-`p$fFa(R@jy^u}VJ!uocg%()~k`yzB@eU7Esy zgggoClVhysDss~zaH#t4mQIr&kuy{+F(L!2VGpT#g%VkKOX`KEgOtZSxJyE31{)z|tHh6UsFeKKw^W_dnZ zi`RJjnlORs>m`D_grBco=aQJ*8!ojmwhg*{h3+n66qmE2eSlcTd~1#k@L^}F{Sm5`H2W(x`$ircrvoR*vP zxBLL0gE86kG)2@!vP5wjy>A$2!2W1J@I8qIXH-t59u~3aq?rIZcJ@V(uhCf&VHN*- ze%?~Y4xIU&=ejZa$WgkTwdr^j_95F@Qx(1vvz_7yEN4|D%XBTH10pt^TY*~=@Ce!`Pb3LG!F375Uv;p8%bs=i@mWi#%@7B(i z;0&(?ohnT4*L)5k#s|XXTMeW)Bh{p-@&=M$0`9_Mfkuu#%ILJbjGbM6KnGB#_Tg1_ zvS%;dTn2TAMJh{K(bs|QO{7&O=|?=Irt3PByvU+5p&*};oSWO;T8~${cIO!6tl_I0 z#WX}i$hZW43Lk-y&ySZw!!Ruy@HPEoMh{cGr?o2SQw3fO1z3 zdJ+am<#YepkvQc&NzM;cJ_)6d6~g&dQaMuQci2UYi}PXezv5FFEEtR>Ag z!^!ZuyL&kcU=ax|X74q*GR-`n`!>=728eaUDEYZs9|k$I0z|ExBErBv7R@^Gf_o_4 zTMM$@P3AESRm1iYt{-E?TU?{t`hb+4r{41 zk2&&R{dp1iwhpLhLoj(twyPeCxp1Pu>ITsvtFAW<$sV6Cuiev5o3^sFj@8lDp8e9q zU2FxC3xOr@3aD+YrqGgI0`a0l?>9R9uMYxuY+A%#9v5oy{@^PhZR+pC+$TvR2A+Fj zJoj4yzDv76M;fXGoo{YDqVY~2yH}Qnns-WOHac84I4m;5ro4Vlpb!k5-3BcMH2JKh z)$Sk99*z6|)`0rkkBaLfBEX!negnF&`KJU4qJB<~J*gQs%aPFiy;6_2Gy^REuXbLFC$#CEr0^eoJus|$8eX?d4z|n+ zx5KDIsRkqn&LB0P0|g$aa}~kOI1WlH15&yyh(&b>uLtsVyrUc6QtvClqZ8Gi9s~ya z)60k*y%+qs7A5PIj6}`auW+68sXx8=@2ot!nWJm`FQTM=;WNL5dhFM*lMGc%ADq7a zfB4e4%h4GnuKKXl4dcnV{XN9*joX)OtH!@pwaP5&Sjy74^6eD0)ee;%8$bL#!xiE# zWB3PxX~?L^pC6P=brNjKF|IQSA=L6px_It+Wkr0FJj!tez1KnoZ{A@3vR%~lY(}EN zcGg`VH!00trGqKCRm;7mR6|~dqw^X+xlIcQ;7qom(X@pQ9@4wXQ7_EoPDT?X$VCM~Sz@wbV&gWzGdjD9xGKf`anlOEs-oCN4kni)XF zgN8-T7!9rP8~M97%jh*cT9pFijse?#L*|FiF(4!`VU?@A9|Cp||*G|0!Av-PxH z$AEh1GJIxsjb(ZvOZ&6|RueG>eH-N6Ixp62>g@Dn!dMV#jy3bw;=<8=pnPU8ivRc+}a2W?*T zd<$}moBOs=zoIh=)B9GeCESEk?I+33uxV}XvzrM)26Fm_&3?J5$cO|?;^yC+_*k^x zit9w#rjV@uo;A91y4|6GsM$OvGF_s|YQ&_WC8zM7O?R)vK4iBgq5St}+E0Y?st*7r zw%wa)QMXZ*bhr?v1wBWrH&)_-Q1BS|d;|#i`zIJT^B~a!v2Ll`zxMbNr{q~Wt&Ar( z$E6$Q*K%rp<|3mHiW0S=0~Kd&9T0^|XeT89v}sC~(bM&JMzS2YzoH;#MEh?aEVW7X z^o2^CFlML4ZkQ%QTG!NhQ+ntw8yL8?oZ+Ue(t6yG*jU6G`8}to!Tc|ZjigOzmp}gdbZJ*XCRqpPUw%#3BS{u^r~r@98bl4kBIB$ET)U$ zik%Lu4NpQi%DJ33Yt7KhhuK2>_VRfZYRffMHS@+#l@~6+HyBRZ2Y`g<;aJupiTxCn z%G4DO-b|jayXx~UbPM91%38+HEgvVN4>wIAqBF}$-+gGmJ(wzM`5a96DDT(l#Or}E z%y{Q9wx$#y{Z0<0jX#hm-a&y;WHu4P_9 zPtL;QedHF@72?nZhp9SFp2`Z>t{r{X;5WXD*UtL|23p^hgtr=ASy1OqQi=%ZZ{a74 z3Z*LNC=RgHUYh>+wznzfi!l(Jr&3#1L0I`AflrW_?XFk6$1m7^6}(9Q34TDJ8vrXc;keo;&e>N$=Qp&x$g0y!{t2_iv4!_L~HBt(1~qL{GY` zcJwLV0*y@>m%As;o%*Zit^5>`8G#>u{;c%abqf5%3UafRp;N6Z`uxQf?Vn8{*eY_W8CT8%bL;8SAw7!FjC@3fhpLtea35+>FqIglu z=5yS!JsQvJ795)|pTU|K*czK_yILtaHH?l{S6An+tQgk%XliI=YnS9Vs?Q>-fq`j&9c+Dmqz7Y2;L{;Zz1cm)uo`1p8O6bOl- zA>1hDo9!=}11OEi*~a6OG>Y;xLO!aF5%_)?NmU&X)|CE8UK$Q9wUBmn6fbjH_(*&a z_wdl*oARWrfGe%iLY3@4p{um{9A5?`T1N+zK{_MSC^>R5lR8O z@ekMTx7-QgvAE_7SxP!smXh?j0yH;P5)u+mpMJQ73T4T8miIftB<7FktHooS7x6LT zEu-J^CEwvFmu;?7NOtY5M1P?60XtbKf$6r#B z-f8zEzy~jk2gwPa1tE4mpmtF@)C1YLRe!!6PhUCD9qlzj-x_q5K_NmAj;&X?H8b<1 zq@)p)(E|4ca?+NY+eG0vk_>EIT%OblaOeG8cDue)-u!BM+*`)~3 z$F~QBoPbeI<=yr9KIlcG5tpgx9Tw$)W3$(vb=1JOAU8J`pjUN2>H$FJiJ4WW; zT2c2c5YOWRY*Xjl3YU21=Hi{ULDVV0WjleK1|!j_D?|@OR19r=_uxGum`z2p`q(8{nDpb1xO#ha7t%o`W(}FtGE-V%58c zAdPchXH2bg3ROI8w}jmKrsNzsohTp0{|B&jKl%CLlpzoZh?L1lEdycZuD~DSI`!>% zz3TUuZrK4r5#A7izA2Agznou0L@#gW79h(GDCcdU@y>E0#6xlh!%v44V}whrM=Gyf zyVm~`0dyR|_gV-90}KSdplv9@BVD_jWe77Rk@aBAn&W(LN21ON7B({gn6u>tx}6`M zzFK_(^iSUHc5b|V?{sD1wu+j=x2!e5o!kwdX1_}Wknotga zPLI_$ZnflW&y}yS_-b^q*WINQg;=WCMDB$#cNnI~ex4yU^_T$89F|4+jFl++jO+CC z_#_QCxmDtIEo)#c77~Rx*ajeKezANUl&6BO)!ii#*!*|^p%z-F;#*9@{!jhGUnb4u zTl|XD1fyuxEZrnFv*)e24awttkIM76qhC$Pbupk4wG?IEoO8T%u?!@kC@u9^4;1T& z?Y>y}9u>7{YfDZ(vF+jmwjDmJ-tfq;1IvcJ4t@+eeGA##=P*NC^0(;uEMPPl?_sV; zp|c|vrKkWZi-Dq@S*Cah&`0bnx-ui?^BM-TBEpc2wje^KmoCvPo9I1$g~2r$*BlfI z@?#q}o)ch1SDEs{th!q$VjOG+`CNhP;ZRnD$LE7k_Oki>8Eopn^}y;)+g5;w0t1p1 z7ZsHbK!yL^L4G{2uHAvalXL7rh8(Wfwz0ysP6_$&ZoG5O%I^g0%D&u#x%CmNfzG_z zpK0tJ=kmF#^sDscdMSx&6qWly#;qH8CQFA0ODQ^-$Jl-mQj49C$g`aUf^0uBDUj3^vV?J}%0Nru-a;lc}Kr$YjDzm}tR+|Eifhjm~66KFQ~&^*XT znelZ}H`!lVS%D9r&CK>u}O};!lKU8yVV-tN}O9ZctfX88b(f zs$=jK7t9Z#-+2j`y*_SXH;4d;fiZ_WYP@u4`uETF+YRDR=#Lb7NV| z&0J(6L#EIn$G7-QbVNi9I<-gU6BQKBE?fSg9(__~@m>C{!k&ZWor^YOTUso+w!vuz z4iI?$GKe}v<|N`(iMSd%>=i;sOB9^MuNn;&Jgp+YEHg_yN-9IR1PI?mnp=yVL4Y~+ z_N`lOp%Qj${l;5fB7{4(r*Tl+ROJe?Fi7ZImTtD_oU*Mf zTD6VCP2!0WQG~9C_^5mlCCQa;#S4<5xN<-!K;yyYXF4|FP}yZY9FnVssF-7l)7u!1 zle8Z7L#PDS_?DWg8|mr}TjSgGY-P9XBCU|A9BM}h@e-5i*hpqhl z{NGlhbwMKy+j_9OfKMJSf4fjrv4!5MtLrMA8TPol8y$dhH#Y=f<`}D2Cdr7M-ZDvv z{Nl8s`d}80%Q$K*7!#A8uHMAODg}R6=+JdvJJ}YH-=AV&zdot$w~R^j1>%uXEKe4| z%MeA4LxD38xLo-`q%#+z5Tu}2Lq(!YC&O1|p?>o14g4X(1=Knj7*dU1jSpVQA^DPk z!SoEv@j9-?$$;;z*-H5K`;GmM?kFwa^usM%m4KF{}_U0{oRCyO3 zKBxj=pZIGfIHWr?&cu~(Ls$*dp^G+1rnH{^15ms8i1!c@UQMJZeGFxmk=)TRTi*6X zXnD-w>q1_=&B)2h$japxwA&1_u66^?mtJSQ$Bd)dk3lyTsfvchK?HQBX{p$LG%(W# z=%K*!PB^^wdIzW;N?3Xk*!kgkzyauuo-=!#+?dnmmE_?VttH)Q;u_qM;_YV9*E#Jq zqxsD&OPmE4z6#QPqBiE;JdF~g4~W7Oq30g^bEFH?h2+Oh$B^fMhGJ!Y$O8V#!-dXv zcg!!{8JiE4hBK?ZmI{fQx`qXEAQG6P(-QZr8Jwwqpu`ePZ3s9 zh6=ni?}B>WlFb#=9Tpd&-Sjt_!e;Oh)jA)L>b?hwp|+nKD!n5T`2d_zx0zXMA>;v^ui~*oRvWs*|ZYDM8pdJ z9c&|?9h*On6t(9%E@i4x&z9%vN8;#Hh9*eren!Mo1tRyS8-Y*;%s$|A2p>E=4JU!RRBR#iRkJt*~*AA4rX`6y7cHkA(`2~<{I9~DqCp%COWg1KV zbou&Ze_=?-#cQ8K)%C5Q`4~K;yU}`aU|;|U0E_Q`17Dreff*+(tch*G4Nn4*8`Jkh z8*$U6_Tb>+_$#Pd*=GEx=GOZ16e0zl8M=GReECrpEWT>#mDI!}=0Fxrq0^R_rFvcY zWc;VuS&Pw&-xa*FC8b)_%skAmt-Mpz1zYrjkVDtdq6Nw|HiE{5lVEo&#;JUOazc4H za`L-Ekw0}u@TDd&Fwg@9I^4*Gep}w@O+B<4y>XqM`aI{+gfHV++4=sfw%>IC2ZDB3 z`R)mO%%i&kl1zzKL4_^}-#~qPJzs9|_l7nRrU+eZ+1jcbM8{(?Op)z62r8Qfo8Gp+ zL`{)RMc^O5KC6%7dRsN}%9f2n)xLZQQ&^?)NA1Xe1eJZTA)Qvw zT5f7cEn+Oi)+!2QnSQpYqAf_@t=t!V{go%d`D{C<-S^5MQopQKrzeF67YR8|cTxso zDDr^V7Gx1R>=Y;NREXP-Gie2@(clNQB%N0bf`uU}GYDu=DKF zgGWYX6jvBU8p_$?@IE^wDI+m zLsK?FUeEO|m>1YmINP(W1dAF&6$49;-02#%OOyy5%IU_SM^qj$u#=)4GynAT@1v<< zI_h?Ag0;xw0N>&mk%LQeT|-UH%+GJ`7YE(sRGTPZ4K|9M2mg*O+hFv~qm;3)aG zX8O#3$CerQzB6Dc;}JQ}!jgR^xln{KB7Dvq-O*uN+F$JSkPVH^IjaxC&8{tV4mc7z+$>XJyPt{{ z^{LpmiYL47`ghc=3A1K@gkZZvr89wP4*+K$4U`wq6G~o`zjkf(fZ-+m7@#LI%|o33 zTwbV00?|x>;BXD6@Ac;fL{Wb>-S0;ApRQHvw9%XffFWc=bmOj77hJGW7Wmny_2Kj4 zdt5I_atBwWWhS|+iUeG~O(xAZ0r!4x+3EHLVW|Qkktx4zIcEg@i(+5twTbwl@+#C& zvS+IKhICJv%I@t8xUPZ2tk2I6>eIg`3s6namJ<`G(V9g5__;I z^4(`_ZU1v{^g=g)p6$ot{{8 z@7@L<#+6_J7V)IY%E-w5o?qB3Cr;=1my|NJo; z%1>c3WoWs6wWwH_uVN6%IwjY29;vOPXx06iiZTDWwf!o0h-PqbaLe@}R5UA4f5c2O z_ov%-sL=QAb;luY{~nkigv>uTVkyc79Io?0FJ%-`>=ydodV4{i8<$V3Q^+YrPAA9=- z>uN07eT7nzy7YGK{;9)e^MD5K2r{~wrt;j&9DIDk_QecM*TjVMUQ@h#x-o0<;eW3_u3ptf=w)|XV+n|ja zUiQ^qk0t5uQEb%(*!nf0T-lLR`=H{+pK`2AV|f=RmVG@MHkJ8kV8H@ya+oImIzIZf z&k|p+R0+G-zYi@d)pOWUS?}|Ug}BeQKt6P@bhZ`I(f(h?jf*n4V+pT3-RLjk-I#WH zO3&I)-OsH-ZHM>miEJXpTngE~HkQVwxT3i6(Eel4vk>b#$rn225~#)R*NKw1`&041 zcD5bd65u>{_PB{z*8nj|;NQ2h^oF+1E)~?M$}h~t-F1^jn&1X%y9%W2KyU*-GExe5 zr=|K3MRr*Mvitqqx4(iRLy2vz{gc|<{VY2f^@XYiAJK#pv%gTK1iS3Q&M~}qj&Vit zdZ&JBT`Ie#_`J+^~z_0N}{da<)o0m!z{K037FkqGVcT>|4{ z&xP5eji>7zc53|HXpc6_?f3sO)STDEE9&$v-T-52gehk{xz`*eu|J>?r$dlxjpj*4 zJsk<5T!9w3nCPs1=X3Rxi?=?$GgJCZq~=Vw$|0dmz6P@w2ire1TRSoAH4m(2?h|Po z-@fKqe%gI{)&gTBQes~9L9vy7=t!jQ;c5jPyAA(PvB7Y9b!MN{fO?nm`V&ewPMu+4 zyT&^=X1G6V&D|Rjy1q;MMV)6ru2~SK6y%y|Hk+!XoNbWx{(u@uaG%jK^lWEWxh-|@ z?Y*lkVY7ovCwGj&XYqZ!vF42P9!{r=%?t-g(^~ktEM$-+lbS;XX+Zrls<+Q_bX(Hp z&7rFODi!1R?Q?t2dKb5uwI8&T+VC&68a>i}=JX$k=M-)u|1ZMaPQL@kBn-g||fykOW-?(0tawk(BtDzadZMvONPhV8L}(VYh5 z#VHxmE@T^w0M>~5oG|TvT4sA%L9ZXY7Y})H*>|r8gOvnq3wkNC9pDH zKSMdN#{`?yPSpdrCq|t6Q<408UO5raUpXNL;RMP~;*I~)vR$MkRAa<|fTcaKC>qqjB}nAm-Xga$4Df(pHhh!Az^m0pO4 z*mv+7VKXR+wT!!GgMifk6)SR~qW2%12;D^~sSS`SH7m>jxCcsQlT$G04gqHv>vy2j z705AEd=Gq(^Dmc8sUcI*n$*fcVQFb;QPH+D)m2qqJu=Dlph=^%;$|~%T2LE(=C4f|YE8;YW$X;3Ou7+VHOOD8e0AFT zT^+JLT4Dmo_3b+R&iMu|E-sRWgUwp=%;lsSLs+H6R0bRXDhJFa(0lie($ZcR$~g2B z80;T|946*1U&^Un&x!f&S9V5No%1BAfR9^9&a0s-6Q;hVFTVt=QlK6M_{LHe4HJ9I zm_JBJ0V+i_uJ#xgH+Of;z5s=DF+dc{8ErDq0tW^fkf$KMRj~7aV^UV1{qLESU(#Ii zJb^9Q`gtHwLF^06J44`IWaJWXxW&x}F>;sk)RQ8~??F!;I!Baqq66*fRFG2)?s z7}oT`XnGx7OPhXx%dTnKMv%&GfKy#Cn+z|Pn8)VooV{Kiso0B9IAwg~1oPRy&a{2L zU9U*IuyJ4(n{EW_NwM71;Lz>$2ABG8Er z2H)A(Uu+<4801g_!hw|Me2cSA+otxTt(K2x!7ml(Rq7n9<*&hV};W}FAOp-t;9naHwL21WLNJ4F;@W}d(lInFQwLjWTF;> z5265d_jtCSYOL1z~U^-vDpvUY(A1I&i5W{)YBW zheRYBP-+%Uq8X2g^1(s<3L8}PCkPhnNo_Xy0KO*>MgA%zMDJEsaj}8MWzc_UrKYBq zu(b4aJqLuRbSk)y7cP71^U>W0wJ-oh26x@8unnjSGoZZ$^{Ud6I&$C*&`SGqx*?&CCA-&m|5LN6mBju_&lop2t*w9y zifLMK#RH!c@jJ*-LwgLUTH=614VuWD^j3QmJ-Vge)QUfHHz-WhL8ut1gw%bUdcrsj2#z8Kn@+UB*WzMburax6M8gx+9wO#4RW;bp@4^?hDvUf*X+ z#ng91o?8Gi@Bze&L!t*4Qd!in7J48y-J=l2vP#uTtK`r+OPVf%rD(O@e0v_0B)dP=UL`EY^&m zkpx?w>=1~C3GS(~s1h_t#8u@-`Cy3Dc#gszix*CQL8!g0wFCeJw)6UKIyYAYHSIfd zh~<2oDC3o}n6Z3N7z*!d7L>5*>wQ7B9u=@h1s9x*9(ezr0aF`+%ZrMdA=>3_%@T%z zwKVNe+`sWFPJi$#%?@iy2kR&{w8@3N`o>UCVNAE^NtMjoa5@hL)~ulQwoPG7dMB7k znHd;TZY_B&6JdZ_so`$>m>ZB%t4uQ0#kIT7= z0HGH@s+X8{=FXq4P)96z06CUv+)Z`T)Exyj@#h71QW#5Y?oq zavTFjqB0bGK;;vFvCzkKkV2plDzy36K0B)>(MPZ!YprpLtW)oSn}D}-dB-CwA@23O zjZ2RTJkcrNIxDl*nPk`}dL1#!UbLp9^C?u@82&4dTmz=jl*+_09ScSSHW|Ju>(;Qk zJYr>Rp^Hd+#8mzggl8t@jbLj!wjilBikpjz)J13JP2pTgmefk}@SFP0xp>t5C|x4w zzS@PC0Pi~ThO?O8_tg(&h?zc|{t?Bq(Gfl+&X#u`Mgy-9u=-}z*$HIYyKz9*0Oj(c zjY_#l@bcEl4#VU&h+w|TP>D;Sy81jPR9(Rr1DJ-S3ozk1Ep4e+te%{fzIgHrqd+@G z7+cNhw$3k&^MGeD7Q7lKVSg{N@W(n0UI^p54}yb!%pd@9A)sxDI52K*Z zvO+vWvrV-*m(tHgKFz_D8{06t)`{dA7d4jc!5?jNHOC|3=~%@?lb!mWfrO$usvGF` zjgny|rVEtJwKcE6LwBKJ5N(E$nidlv7%D3@_<>_0I+FYu>^C9ocf&mrAxQ;j3pI z4_E#{w!k$1Nw!FV*t&s=ttlr-zqZtQB@>dDy4{3YF=6~xXzwJL=R5F&Q8npm=L$H@ z*4;!xm#mT;08u91=YuI0{4#qh!7J-}v1?6k$p|w#cPX9GSn-EQUd~@u35+LnwGmCk zb#7Lh+t_eNmEGl$5)c}ExWoi&AEIGQB#SqD`6GZR(LIAkGon^7CeygdGCVKEHw4^|b=5uct2EP`*yrRQs-iWZc!UbRE@bKI zET~{7EtYrYkPFKhJe5$U;}VwDCqgMsOAtB75{5vkhdqn(P)Qt@hF{VhLzM#AhWGMh z=64`{@}AN21x&HFyIaK2ll=!AtOy^=8X6l5=fLtuK}|W7%mgfVcAh@w=*t=isGFc; z%dOG(K?XDmX`M?21(ZM@9O&98cv#C&G<(OAbLnBOIpE^du>woGW`X`Q$Ny=tk=&Sk z@`uBw>qh=3O0W5b8PWG!&w&d|mB2qgVX$w(28wRIjs)Tv9I!A!gIeV!KWiGE$DL?q zO`Cy`^?C=tf4?O~0B#ybV^BoW3Y(4)oWc8+Y`ihw8~_&70>10*cP_|dBw9>UGIYpb zH(-74n)l3FG-wwAX6Fai^=^$D%2LkiGZ{tNQ5teG79BZ;Ssp+%)6G;M2m%m( zz+08cW+2itD`zph!|Jk5Qbr2dU;5_k8GY+NJjZl93?6B7m$o}6!AV773|Hypak9q z1;t8xxqw1>=MsnT7e`2?Y9)@-0+uPoI zNNBPAzZn=qQM3aV2)59ZhrC#K%|r4@&frzl!dJ6OmhFXYT?D!#z=fT z5;&s$my`J~Cj(yY|8g?_k6m}<}g5!i+32$6n!$EMFtAdM}<}U!zlLYTo^v}<~esLT0owQEf*?C!^ zpJxUtFx`&_#hG5@;25kIsu2BQP~>Qe34OWWAOPHEcNfPP5i<(1jC#FBSwmfR85L}t zsT2i>dt#CC)=_nsT%8;2%rPr)UO>USi|Egb@=ILJuzVS^7I-LN|9)FrTRQz|(CVwm z4QvV<8+|*|nm?@;jy<%pBKz-b;iV3Ln7(^)FE2`_v~|OI2AEk-@gE}0W-Smi=Zv~* zHbr{LZ(iu2QBheOlWTZ{{vn8&%QI#58#a6F}}Y~RW5e6LPWx_dW} zh*1p$8)DF7R65eQIMcTS&U=6#sRgzJ)4o*SJVW!71@(%cImW6k!jW8R>k&Fa;!#Rw zqy@6BXTdDu9l4W;+LF-^QV+gA2WcCeQm@~jQbO~ z#2(!*rwlqkg(W_lTj+VHDQW&H$I2vwC^#v_Gfb?4d@@>Et+HIDD)(N#Yim=8aYSK5 z*2F*!NSqj4%TGDl$b4k(8|r^;Lh)9+AvFA9d-kPVagk4`xzF5PPgn8uCO5UGTD<2> z9(|*lP>K@&=?S@`PGvkiK6!7wOcc<6G*@*lE?j|$ufVfiSD%PO61lrTDxFeXUFyMeq)!a2AtzV)V|pD-W;QlEcpNT#0QJ4PTa$m zhkUresF9=+mPDS^A!~fY?e=C>b=Ml;&ns$owxqHitm#dEvmQdjAfPfP4zi%N0JNcQ z80$h*#J^cc@W_&)2n~^F(sI3P(oGf@2HQ?1c zW7gN115LgV2&g`hVdVYQI=;NN+}pd!>ecx#GNex?ZJdrs2?a& zfO3Pi$;dqOZ5-PA8Sv!*Z2|)1pQ6&h_*N?#S9PcR)YjIb)XDjAcsMb?$|J=ArDS6_ znoqTvM0L{l#Ci^tf}R)$R?Kj0iNjA8BE8Jhr~%?T&%7D?(ley}j{t6ny7RZgL=rvm zXAVPi${~RHckqZV0*eg&@flF$%;Iu#WaQy==<8|Z`!E1>c074vhhM8}sIxOMpE_+V zC7Q{;wc`^`j}d9n`8MsCYw~2?8Wr?j(PP84JLot0_f$7q&sH+B)yK#wLlLyf7v$S= zd5Xmgm1Twy31poP>m5?2Y6))wZPJmo1JzHX~5N*}1VIA`h>MkAxCGV9=FVUZF{ z?x)6_;#$LK4jXcxyh?kXi7CBq`JT3~cX!9by2H~`9eE~e)ApnI@ZLkbw|i95wcMVmFuZiKi`M(oY_LGjQ9Tpte23uSCCaYiznro0oowaQ>q z9jp4KP4(VAiD_kp&=FuKf;HG;#1bB4_0fs`*({Y`$8EFYBaT_%*VWQS5 zt+WOgB=i7eNymZ>O>5!dB#d`30zj!TG1`FVQe1v*Q`1Uo+9ju<^zO62z{6dchX}lZ zHc*;%6RPjm?^4;>fcTe^8e;Q<+l=eWGLQSeCdWIV>!c&Xjm=iMNG{3jZ1hR(W12c{MKIGq*&;5Iu*RF38wZ0hUUb6$gVZ_sK2(P zu@Uoh&?6g)xBG23IUNP;CbEvMMNi{Goa-T&hB7xx&l!J_&IYwP3@)x@DU_u3pz|0 zkAL`45-Bt?$Owm^;X1;i{QRn%U?y@89TCNBIzZVEcsfk)M;641x3ExdZqE?iW~P7T z*gj+9+@*qRZaoAnhaFPoD={rF9bLUCb#)aLB_iUY)Z$B@*V`4I1S|YvCa6famy1ED zrlDjDochd)u$1zV>$Wh#;K~RascYSpG6rAIuA33WZaChD&1In8TXET=x)Lnid(_6W zlMcNAJ!GFsva7O??l23)dz7^kvFt|=XZ(`;7^0*VZmpK+;<0=}+sdOs*1mkj(%#62 z&R~?KI8)SE@g|`xOmfAwiObisY}>U-2F4}#;f`SYmclN1@@lfY2!H!zM_G5*=fQ}m zx_jhsREc#RGVtZ0BS)Bq&WYM~sIGgIMn%b(jc#HU%eTZp+nnws8*J_Cfs-*fAm}M* zcK}Oe_fT;F?g~M*MJpVLw;rqdOF7E1F=0J%QcWtJ?lvg2Wg~m@FfdrECXb{70>k*` z&3|JsnpX^9_M|!wJyT`n*8-jxaIm^0abx=f0zQI_q0TTJfVk#Po{fs$vxN=x3jVOV2h zcRLpl*`$aQ=da1bGx=H66O@lgC8%voZNeG%J8eE zfRfO++L5hAh!5e>Y?s>51Jn<2<^yoxq&@ys^eDJjYj0QugTM@3mmWhgl_kJ-vei%P0T5<&+ z?4r)Caanp%Z z-^EInl$20==+JrRI+YGdBCsGhjPMIE2k@q2ATkStVL1lr)$_t&eq0>ZGus9|jgHoN z2gksQXwP@GnWdc#7G55fh!CUTaPzy~Oswo4eiG${N1C@!-d@}ar?Q25xn-GpdU{bM z*;p0OP-r30fQ@@Y(aPk6i=$|vC?pQqx`ISaIq#rih_7M2+^7TYCgqFHqQg?@!p*#VC?m(m%D2AD5mtDG0S#OcyT-p%-oL zC-Z;w!dlmsFea&u1&_0QQS^E<+ZLlfMm9ALU0L$;V(@?0D>WqeCvkxnJT)fRVL#sT zr)>nfRjfd%0LQ?81&9H(w0U)~Bgv=&tdeNk?45+6R{T~ft97ISb^A2;m>mmm68g+2vn@6Pf=)gX&HfS zWQnR`_3eug--{WrIS76?_{qIJLsZb}AZ%n}1NCLkR1}V*;CBz+DFvj&pNPaM8(+X- z81;z{2k%y_0vF89i^ZqcZEl!;ncW#aF=gsdz0r(o$@67%9C)5<<5lI(J-8^RCYLG2_E()aO~|uh$qE z9>T_zBzXXF$V6DI-*YF*lgLP}=?=#<7 z^APV)kQ=strZ0+#vGD>;)bqW@FOUW<>RfnT06X?`Wky!I{7d7Rt|uSTM??F+r_ zyZ914grRLfiPE3UH;ykZ_%6q2M!UyzMo@o8Pgl2K=uIl0Xx@$N5DuD=CjNZ?6HR%O z(xbI8-R8kEh?^^Q?4z+zRwM0i9ar{zI1uXZpk`LuY7|#iD=fbMA|+z{SA>mMfujHV zT)>xQb~t^}Fl<@q^Yy(liRAehZE!&t-;!^AQ^42oT<}+9?N;bxpU#+B7i}#KjM>7* z)1^#E4bO>j-SL*)#Z})5N z$Tr6J?HAh9D08V9#R#Lm!pr<`LeYjXwohKGgw{Rxl;o1?;K(0w@$3jCLQd-Jf|RJE zVN@<3rxs6HC@V^~ZW3OxpKg-kWh7m?uhE3WlDs(Vq8uF?k2=Sl+VdUY3Ml*_ftdeM z$_TSB^vq9Oqu9GZeX1&-5)e8u#cBMHHvAZ1XM^^73E(tv-_O5B$}Sz5r@`HA=l?2d zZoqA8CYzjL`EzC1=x51jn5aPSi5VTMiXHz7*F_CA<6C<%oz2LDr1iHVzV+v}bv=(w z7V4*D`>RGADm?xOV{P2}?1SkAB66Gl@wr{o1i1N=0fmtg8`n>s)zCFv7zo`FY32Hv zrful8cpksAqT5w+vf5S_se(d=`kr#$zFpRHYu71+`s_NmPn~CH?_2N9YU#5X@8>Y( z;H@AL9>AtazZdzhPQa?LhW~i~;=lbL|N52fEAj&kiRFha_X;4KWeK=n zaY2doK+tZ(LAz$q<-JDtAX1*1!c%6mbN`ox4m5#$y~I&(4_CP zsLA05JtuJIA`g#k?-wuYPay5X5No4({DQ=fKgCsGs4w<^6ai%pvcAhq`Y2TT=*UCQ z6ZG^aPVn;yv5WaUwz3+|isXwsy$$N4CqWOx;dcoMTOfP%@da?UEpuzFb_#s?^5u&c z%+Em=i&*Zjro6ra`_5-aPOdK;y}&`iF2tnM& znnCggNV0$a{CSLi$NO<6K0UA-6M^4(()q_A*eua($4Ib%Mh*b313g4|&D#X;n zI!;}mlJoNifY)0&afw3C{uP9AZM>m~iJk0(0%_Ito8iZL0LY@Z0d!QraP1y08`2ne z?>;~nqD@?a6h~Pl-6UqdEG+iTP#bMSjdve}7!GX;Is;tJwyw=KPRz0Hp1M#S9?B-= z(Qu*G>u#XA-?A<4;?~ppdOl`)8JD4ZMT}eQ+y4{4TYOYyu+I4Ub0?Jf-V)iN=$vK%x2oKR>?%=#{ws`7@}aGsk$hSL5Rf;eC?# zn?Lm@C55m`j+{Gt@bJO3^mK?xiDD=lTY_qw*wl>w4o>k>G@cI_7TiJkjrh#@$ED{2 zzI^$z(&xVe&H&?WnFJ6kjJAqH&4U7*d+}b*gJ=KqMUYoHJ)2h^eJ9%a*vQTcYa|Tl?Q-@l70;rHj zN~Ow_fa3PeTJFRzpk8H3hO~lQTGGJzv}I^&qf{v!=s4>Yo7{x=XC%WwrH^b^v2&{N z8dc~Y4Pagp1{Qi)8hFv+-%!Ebb`@dW%?N5L1UF5*g!2H%sy=(+f}x2C(9@N;QCdMs zOWZLGtV!%8@cwl+iLDj+Zxmg+{UW9wSX74VqvH&=POykI=!pcFje_d&m8+uB-hGK6 z{gt$%Mq%0V@&O@Hz>zbTLA;~vUH3o8yNsz&Zd2MxEU0UYkN+$5`dB)b`iCB%{D1Z8 zC_J6Ix3#K|Vg(@#smSvCz#*-hk$Mel9`mYEav}$$nq}WH90X0V=a`sk3D|Y&x8f3l z3=Rrfs}k~i;0S1gEzlS$_IaCZpxzm+LEeeX(M_;9+{IE(_R8}U{-0`HPoO+KW9VOr+UR-0(DJ?as z<+6I^mbqlbX6_8$0%{#7{i5h_-6|-nzrg0+0ML^O2Q%0&5Sc|RLwK&}fg+Gr*SeOg z`tvX4Hox_>W?;?Zf{xHJr^UK)oy=f>?tu2+MW{G=$Ya2g`ed8{B%4<|8N)FAGh+R8 zbcep6!6*4ZYD_lyR&QbJlO>U8KsMzEQM=#!qPpuObuo>VM38Ra0o*|(yE+j&*6D^= zkr~jmfLN7h1%3!Nc6nQ$LBiuBDmy6 z2_1VDbk4@*9q<^qHd8$Y`+>(`B-ze}pyhEMfNfA8TI`gOZ+nDn9K>F43a3nbd_tYm zF(2g-zOJk`MnT#=RFaWwn-mFsUtP9INZbZ!y~C){!UljMY}O+MKHucv1^rQ$Am~Xp z#e>?R+_83PQQwnj6%9?4E%RX19r7|QlIn~WVaJx7 z&~WT9STU~;Q=JK)JgBxk&`N47$OnByVAj=6iEjflAOg`z$E;G@sC8x)BpW{h4xw=o zTLHMOZRUmq=flVeQBDP2*NGk`B!GC_ClHl(msJJ4+cjxlLvm(h_s8~oU&?payF?Q#ux4r4gOfpy{R4bs1?3qy`A zR=fbU_ZU-2nyM9Z=(>2;*pN08mgw8@aO=5sJ-HvO_&SUNqu3j%k}%T}==fV-@T^y$ z2Rdk!x|50X4JNYNtAkt`dYm_I5GzSRs?dv|<|AJnC|Y#~holDkDp*H`>lVCN)E&m3wWk{4;ba+jIfG*#S5K;1w!u`{?tV z5-_UF+C&LE0uKY|Y@tTIfwZpJ_h7X~R*1vPoT3%#2#cAlVXBz@=Zhbm`sD z4k1{*(CNK6_d?uITzeH64COL$)K$%dugQ107bGB{4jJ8e)FC3dUOX7`CTMD@mOFdi zV`$hKu5xcO92r~k;74gjhVrnFl@&}Jo%d9^Bl)=Q*o@CPdW@9|HugK5hB zmjeEd2?w2QqYv`%o0jU-njBlOElhPx#_xBF47|JPATa^`#d6MOfec+8qi@|?r}ZPO7cPpBP1;mtY&g`?kB}H_kry);#VbZpS}yiOxDN$g6?(kd zIm%wHDcb3Qr8;`p`ol@ji$O7;=}Yft%03wHDTn)36|*3=Wy91~W&cWx-RS0#m}>yExuDz5>Mu;c>h-tCunjov5oyo#1*uFJxj07>_iFw{(EraXMlf zef{dGFX>B+X-V-yvCnNY3wCZ>3)@Bi7@rcz(A?6AK|b-+*Qj0>x_b2};el&>J{I>b zGYpwx6Ce_J=Qa%tnvu3CTrb}??m}YJlcQGbT=w)!i4W8ZOk%>@rOhsMZXTYg*eUlP zi!PAvo2y~ZWA?O9-ykZx)@d7;xTM?nsCpKK8QfQkdv2GN)2>ZD3I2^Q{QXZ!tVgjU z%&8-tdTXa3kI)O8&*eZ5*xM4dYa@lAqn4tZR z2Bd?FcDo~9(7x5ZRn;?3_WQe8tEJtoIn5&njkq6)Nm$MP3J=M+n%5N-_TdA_0z{}S ziu>rJFHKn>3|de{m5^|Bu@9U z{BINmnD|{m>C@JUJV`0rN6);;WH$3R3AT4PNi?^`&dXUf6%`!*b{zTFxWz+n?QL{H zXqtOUur|6!^$@h{3z+RpMv2UbrXOhHZxaJA!Mi*I5+ZcbQ|^pCCBt+Pl+o!mg#8`R%M)jRa@9pIZQBC z1g3V+PB&poH0Ng7bnbHr+#BIRexr!^cxnG_Q29ARG}QlDTl*PFtuh3AX8H-^*=KG@ z2t`m1aKi$Fsu-YJjx6Be*JLL-pi93_2m&0uOv|8#*L zc{J8G)7aI;(!%mh+0>!9CLKO?V(ItjxxaiRsrNR2`6-!bA-j zkVbVk3CXF{u-=~;5s6k161@xPITSnswO_V3^i3$8uj7L&pij#BZ9YDJjmN+XIQICO z>`7SLX@$BA)H**mdpXl-K=T*om_!YiKrvQs=c?_lDfszu ztWCAyt(oT(MOIzI3z4OB^>5ptuaS3a6pB>aRP(-lzs~zom5sv08|;k0-6&M3lVH%&&Go3;2@JqOfXe;%KMn1bK@^^Uvnpq%B$?H*f&n z?PKtVsC2j*84FkZAnJLpphxd5)jqs3Dnv8Pi@{(_Z~l4QGgkx-7Ftxj2HsKsuVQL^&o87EXui9b{UY$rfZH-iM9>*QF7@~Q6f!Je&N!ojTATK5*MWExD)4tsYv0o4Atn)`?pe}AdYaNk7vG$`mpUoc%UH%_KxbM0Ne{Iu%B||?igE7;7w_^|Q;i+();{57Ml3^aDA*6>nU#?e=}0}| zx;sV^>S1~UIjDEptvzm@TP!2x$NKHOQ&DzVvE_XJVa3<U&P zVAMWVaX@e{(CnzFS<>B)c4B_Ti+h2SPvq;VMe!G4(|h5z&DGS>`_Jd9AN@HSP**P_ z1yFilFX6fuav1>HHTrXc%dWk6^V_!ZpMPr>rU9k*)v>rgZ-#n_Sb$-};FE#ZP5xuS z|9kxph&l~Q?}ZzC_JR+Sf@$4sEeGK}j}kZiO9l_0!^uwjLgt7kElj=cCFY;Yt#ui8 zWoP?zJ==b8`bYa-!v!}>vb2g1R_!H-U#i=h8D~5;HMKNeUZM4IpfuW8W>Q zDfXELwrwx_sj2*QEnP>e>{FG8(_c8_J`$0UxN~vm%gYV_5;Ov?uem!N5$vt$4@!>d;GYhtO%I!1 z&rT{VTKySX!3e=v`wpaTJKy%u;zt}kPrJu(B(WZIYyL_cUmQz$pO@(CQ`gIU`##5! z=~$W1yqylj(wMt5OK#C)S&a#)(`88=uZ*QORUcp3{iKryX~FLp-o0D3u+uAddm-P_ zzUy*-6yf!x<>P?_vvV@<-3ABBYw#21+wc#>9A{m+9L_y1XJ3E^NAt}CFmHeV_0es} zwopttZhhjfmWl>mrwwB#{oW6KOXz~ndj3PNwD@*yGJmi0FdA0zM}?5Q`snWRUY2A} zhqa;8oR?-GJRW)3JUPg`HTSAIylywoTQ)5B5bvIFIw_d?>?us!Yu#xWm5OuB5)^V zd0-%$Ufjx`#q{{i;oVs+fZv=t?l$%{)~wGyJFA0#p>L#cb4$2|oT_j#=U8@vn?ZXU zz95#osj^pN{ZTA;KnR-zVkj7S09N0*g6-TKv+~OI`KB3ow9PZ z+#7+9VwtPCg_|Xp+zLndee|Q%WxPga=}<$Cstb*`Oig%0hg5NLrs3k22)(Y29diAK z_%N1v&u?N%DJc~ePcfBU%R}D2FV3%=vni(0L3wgj&TiRIVYH?<$Vt6#f74#m*Qv|Y z53{fOTM934Hrr;h_@ID1SHk@KR=3UeOwD!f-tZhB(L_}Nb{`qX<+5j+%6opeQ|d|D z%F4QgYoLp${4c5Ir!aGU(0x(B?cuwrW2?ECXP?j}+;kLo~ zy{Ni*&{_Xy^dUq{%#Y;_nzn<1tL&z^_awSg6S5-DU}?gRF2 z0Yd4!^CT`d7aqC{`t8#Iq`C6+xcEod(D2COSZg}a`B))V*d+aYyu8+0J$r5M&fDjf zpgd=KndQ~g8h@OW`^);uH{%zSw08BX>S_f=Mcjic+}uU$k1xaa74^8hk*$9>*8}oR zEP|TQ`B>KTn?f z0>mzz3JSnPT;ll%&`+PrpE13)7vjphzBq#_iMIVm{?fqOcY;DcP%|7Kg(ThU0nxa# zz^#i_lLgjbkj35oAm%%e(U-cdF{5*G_IWfFGJ*!7^n^h1P%QK;WTjm zb8J9r0sP)+XRXP9`OvOUyV>K=VE$FMk209erSnPuk*GcmfrC)N=P+g4amw zB{Ika-AW5rYn_<^Susp5uXnljNh$J`hZ+@Fh3!UisOEt1*f7nAXmPK)h##Rb@#a|j zs*M@eWK+gV}iLd9jFF>-UCMnFD5=0_# zXSGJIXIPQdJ%ar?9Yy4E{k!8Fo1cK8p&`M})Gvx|8%Y@WWRWuFKHRum?0SJH{_oOSn6ap?-elG_OFyyECxM3zaQuLA%`! zbXdR-HeTK&Uzh&R>j}6>6UHP#xRQ6E)B|Bv`@ZGJOHS^k+FsBGD_+!}dU6mT0p3*} zd;<8Ns(q#I_V11yCn)&;pT@pC9O~_l|0Y_97NJN|$(D2zLY72}eV4HnF_`Qc`^=?K zBxK9j_uXV)$B>dR*0HbI8Cw|pjNh5={XV~&>-Rjr{+p-AXXbN0=X1_^zh7GytT7$- z$#z7l)I5qW`)CUTaBP}vv5@}+zpnIGxMC6hAjmiZJK7MePaiSFP&6SfQ)sY2V>o@-FY&GcReL_%xMm2WU4hgoOG?5o`4|8 zTc2)^N-UO*gXOCPVFRf1pbgQR$U1Wa!bB*yMdTRK1a|vuY3cON01K#+LfWwzGtxX% zx)3!=6ZlPjWRR=E=d+_*F3Lw7*y!o@O{~=VO_$;;r9ko~drrdb`6bUKcS>KVICJUF ztGksiZG3=H()>iIYDpb%4(kXnKK_?>h4&atr}I;9o}tR2{fp$W)4lO7U31Cm&1U$I z?UE)YE#jniul!E#jjg_1+S{pPFE6L;G7AIx!B`;)2^cY}%eCA!kR!`SB}~ec&V~0V z&Uo|spMSOop~|D@WFzCIf;e3i_p-#BAn@E05!%cc03H{|T5q`p2+Vb_{G1k0(B`}; znnH2q3qtkX>6!v=KdZ??@J6QH484X-H+DX*MkCJ#pGK)d)UlABBMeeGzUgm+DQX&4 zk(R$&ZDK1w1MSTuHu4(>(xA_k(|Rz`;Uox7nQN4n2f0fES^4L~_n+E}1iaof+)CRMWUqhK+saT;n|#&iXS-`rW7iDcd_N{8W0>I}m9zSmj!HLP|ZgCv@7!hvt2I9t1`UKy&eo46 z{v5qSAkK?CN@X+x4pi`r%}^M_G^knk95hdO8eYOZE7eJ!irh8p}q*fo|caIigXAR=!P4ep@&lfN^JF9pq*m2gBWEnQ-Aitq|5+U@MlBuo+_h zS3krOqKXqOHUB|}cpvu^B%#1zOA&Vq>#jwX#u2pD)ReZ&YB<2aX9VZ~F7+eX66OW5#b<;br*$Fmh^_&r3}*2L~Lw%1#v9zWT?jFYDVAq1vtzD-MMvTvyj0_qvR|kn>wA$&%gjmuIR{4bP-}a+=lPqUCK)*Lz*zBXYD&yCmH!o}MM8 z)ZAKAT|JRZM@u_scy?Oj-YRi0kuHX}f0BWSz6_(t>S*0)VQKdlxSv|@$~G_@R*=jV zcr$Lyq)~D_g*BH$SW`&;D$#V|ik#7R-;zV0DP~XXOoPXU;*Rqj<$x|jMX7hPv{&(( zsy>IX;I&zRX+7^7i|%IHch85Y`}1V@kG7;K$BWo4k6P=OSgbs?x19Cw${rtcpPrru zi+L6g8lUE;d?TCsd{6oHDp-gu@?W>|V9n!n5fWp$ffV{hB*T&{)A_%XvdJ)$OnG!Vo_w=SL+&{}r7 z<*x4guN!uRpu`_~qs=Anj@@Z-lXMTf_VA)>3fA5H5gXlGzK(QBX4w{p{Xx_+(aaV& z+#%q>Vbjo-C;>bjqoR}bq9hzw*B1vOqw>oWE+KWFsXNNy&N|s0S962WZ%%&dHd|O3zL~QfnkFp~Xf&)k{8SuBwv5 zV3lov?*+mP)5tv7t_=(o862%A8g|NEP|7b%-@kpUF1C5+m2~CM<&>L%HiI*#&n&t> zkQII&IQ8vY_!EYJA8mbKZ8AgL9ZQYcmfaX@{Z0*0>+daZ1A_R`y}IgpMh5t`x8{pJ zxEL{^-DpR;-klIsuq3kpwwVZyO`AKuF+^RBfr^&|P%q?so$s3RI(pHfw_}r&RJxl; zg?z7)k7Z@txP4VXvRmo!>e7sDf*uJ@AG~3jS^Ske80cN9<-X8uRks>?Sy)q>So`h# zZr=i&&mse4=6(jLR`+#X0pVb)P>&R$1J`s~2&US97+8==cu56)rFn!yYW9u)ioZ2T zam&oqFPWA@hCWQjVxk4D(n=?770N)`pF0vV)Qsc7C+#%0slSlDVlUjU)QQ?+qkCeu z907kEOVc!_u1EtA7bP=k_ly=5E7+)??QVK@u4gEozqLuHpSEB?CUg+L^u;LD*S>+% zZ}Z1htlr@XQhEGQaP9%NO|#B3k*`Ye+GHIjvU7BJcxoY$6lAEPpK2hzgM&j3VtpQ{p@@ZbQ~ZGFRNf-&s3~E&EvlfRQazg%U4%_H?wc^< zTGWeg9Cgg}$!Z^(ZjF})2N36yLo3zkCCpv^PvObIvda+_YPEwDb1fQc&aCery1M}S zo92M2Kfm0!z^v0|p4NY%j-Ag%6h8k%!i+{4-Yus>I>9cE=i}YqQf!l=hKP?}ca>Sm z|HjUuy$`s+4teG4DFZf^HNm?N;j{Q2K;E4tf8^bDU3qSuTnwCc%6R^I<{IG zH?c+%XoqiYb^>36i84nV3QFQJC zn!jW~x~Vafs$k8pG$?lq6dEnuxnB&O;?CgLq>mP_yEqsd@PGm1j<_&Z)+UaJHbFRX;uXMWm( zCv1D+M{Q?~nW`yy>Q4?UH)@{I)Rf2J7k~zt=J>vt=u)FMWdUHB-KO}Yk6*d ztul}%WB)-TSYKujoh)+FZK5nyJ_?jj5VpT)X&-50-49Rnpp7{SFqv^Ga$OQ9hc)UP zIikVFk$S!x7IP?m=v)2@#c9_#z^ISn>6Om&pP8^o1G#Mns2MkXyl!=Nh@{)}mt0XT zs|@&TZQon8O_md)36d2Dp_p)Ce`g@+kTX+mF8cb_DMJhfu~D*A$cxhOH%K%RSop9^ zLvIVDKq87Q!bYVwv6ltm&jQu&O0ZSi0lP4eLz$G4@@45uTm$Vhar^Vyh{IU^E`4qt zwUU02@uG;7psDl#Q8K8G`JXtCF#U_OAklc>Z5_ z1uQ6R=Rkscfy}qYJ8V%^>9(?AJ0o4(XHlN$#U1{ae0lEW|7A^38rn0TsMz`Krm$0o zcjnnbs(R3g`ytF(;= z%yz&<*fp^6vuv^x#upMH+CRsFm#Oa?2UfJW0l1#*W44m3iC$lzbR}i zjy$NrtWcq!#T$h$Oi7I1JE+ktOD*m+IuAg%A(R=fXZAI7@q{tS9WxVm1h=@zrRq65 z&Gpju;!|1&BPG=`ehe|QL`+GR74FuawN2BAAmfmv)mlx~r~b!&+R8%)(S11V>;J58 zU{=VupP8BQDttJcA!b+N;i>A53o?qBZe+Qj?XvurXPyD1+ma+g1@)ENcVzvA^4L zn5*S*6B?#^-oYz4f(@M7LtJnillQWrM73>d_GPGoL9rUUB#N+6=E|Is@yil!B_H zf&$r0dk(~M?SL(&i`uZ0hU%Eyry7tvOmS5gtpRj&!6%`BF87f>CmW4^2!= z+}&NSd-mW=mDxuX@0bb@u4q^YL={zl$#U<8<)Vnd-aLpiKv29)cFJe4X4EF8rpd|4 zLzoYtq54y43!67WM*Bb-1iJ*h$n^O|`hWkR{%o16M_M#|Q(|sGTb55>F?HjHzSuTd zt)~wUS3i2ePNqH25E#-7RJl4rtgNn#d;ijt1z0dNh!P)urnLDs7D4JY_2sBEPbeEN-@)F`m z519lg&el=sO)qbD(2Lg94G$0B+S&rb;(ov3QGUVRjB{&zYSUFW`1$4-uq@XXOQNNijaa|< z2hg}|<#Hm;ke0`<{ql#!L*Xl#a!o?5cRPPU1iQxZbH@%JWymq=^A}!N+TdAcx|;(K!gPh(T`U9-j?50zR3 z`-{g&8w@i!@i%}r0d{xt^>M~sm9^=?gnO@m8~2#5#)E{zw7cXDtgaE1Amw6ip61X! zcuorBy>_!JNtC%~yR6T3Ws8V^)t+vST0IEpxa2^6ncpr=DdKVHwQIx$3DA9?Y>LP; zs+DBJ#<>Ql-#QgL)eB{Kj*@?~Zpgmwje@5dwSeX=L3ioz1 zqONsY{wxE+Aghozz5P6Jx2gP^xfDXOZIz_~T1M(?9;J@3EQjyD&)8farIXaCf1mkL z_aSuqx$Q_?Xte%vyPv)NPkW3>Wq5@7^EBI`isBHD?Pz69DMRj^^#w;*L}r28=scj? z>zKbzIu1G+2=Ht{C;+wxP8bz{5o*zt0L&p~YJY_%nC=)>33!e~b3;Rhy_nD>&awtb zcY4mefRyEKGtRC6NBT8zoV_USWC3(55d@u2rXXGt#7LB~b(N~2p*_9t#iq{5L)ZL@ zj3%e!k&EVgT`roKu;lmRa|y2){DXo7Z`^2UY;>DVjqJ`d)HgNFzPnJ=dHrSi~f?cRaV(zI>5$ z^?%fwt=0qVSwf?u+3cPo3MrZx_!BKHC$LluBo2QCDe=<`ObR&JLVk6y=?a}uVi*|s@-A9~ao_w5H@PL~>qn<}} z-R3gWcZ=)KN_F}krzKI^_(0kA_+u>|uJA)kBK4+UxVBnHFk%;VO%QBn`o^Y@O8ehj zx@wm;BA2T^gUZAVKe8V2@I(etAvpabX9GYNBAe}1^-=jGA_t>83wdng(8vyOpiX)k zvp2szr1c1*-VXF^D-;oqgf^O+c4pR%VWo>EQa8Szx(0b6oEU8*i~z|J`?@Blc|J-1 z%<6iWmJ+UR`e5VDTQS0#5W_{O-GJ5}%-+&T=ZUFxRh8jVTibi&mihS{FnZIIQ^JT0 z=J)CBIqM!?5oapu;-|wQTo@-Ty#bV0Dhdh(tW0N%^Lr+GvUBDOgIOi+5^@T6(_Mh=S$N`9 zi^yglDI;nqBgE$>Wo$u^x`0M!!_TrNCjO$E`L~$EP5Q15iNLsDB35gcF7DEm1Ap-A zR#V$($5QH^>&@=Ym66?dAU>^OLptM`X;~-8U485XezZY3$m6MK3U4m6XunMG|GhhS z>O0lx)BnPI-p9M{J{zxBx`6EUI!e!foo5q_5iQ*cqZ{{PpXN5ed)P!?Se#K%yrvP+ z2}5JdJt5anR$-q^?@_Z?SU&9T5TyRqFUc7a627l2O`*d^pf1kv5z$j)dKlxj=aQ3c zps09~IyuF2Jp)@~h$%2Fvdwhp-aStd!xU#zF?&l_GJj_kwTXF|UCD2+)P7z!xnW2U z@smy>do;4cdR}ezCGFTQ01tImBDHk@ngRNtve~-bK>|tm1}ICUO)hT|HuaRNKSy^2M zvYZu1TcMG0Ed67jn=1&R@Nk~=ny74ibVo!2C;k3CR40L$Ze`{Dqy1rP8^_$+<31#J zZjUmLt?j_f$E0oUYg`fGVL5umbAR24Ew!*%IaRzK8A2HDJ)9r>l-7XZ{EvD!dt`?WHQ%)N_9kNH7MgT z%>j0Tc1CXNsKR1+d9>9bsmLekp8{SG=TVAJ&_B!SLDvl)&XHf-ICX=^e}SqGz)Ia} z*{f-kThppzWQ}4;9SYt>dd!%@N*m%PwufqP}O7Zpp z&7{=N+o-oWL3+`LGdjM8X)hNV53xrtkBl0}B0EP{dW_t21C95ve!iYDqr# z6vWQ5GoAjzU6+9ff&NE%WkpV3=eq2FVpdmI!RDwPrfW6!EL5L|R7=c!tNu&AbNu*m zcqEX~?EnxG41hZ%h1xW zsNlD+A)A9#P+DU?yR=h48JUofP`~4g#w%EnjSyCYAEAJRzX7X?m11Lq2GVO;M!Wmo z{xvh_)V9nb_A-hWimv1$!W=T5JYRMaKt4s>RKW(3Gv5gK?M=NpDY407@>~6T z9tqsWzYxYkrAKgPyM6I}R%toRSo@k4pi~e}7J6z5(-|n7o|=M0r}5#tp>|w>asepq zpcEc>vdjcf`>@@_193%VV{3Ln9p|8!4q}fjoFe zW<~$`QpL25PqFr)1{$hc)l4E?7@JjPR8&>%86xHT^vMW4k8!JD0Wduf3@2t|K}7lP z`B-K0d_}+mww3Fg_d60r7&DB{r(G-iK$rkcY0Zwl%=EY{_D98anO~jGj+M_BG~JH6 z-HgeK@A#sTjTZ@->${beQ;lH;TY*2cTu_hkCDWT8C(|ek&Cz=5lIxCYhO+{L9;>+i zQ}-u9)hQz>TI%YFtvC|Iebr)k6jAnjKg!~ zoiX`ax3LZmECYKG`6fFOJy$qkqC2}Ihs*4)B|CrMm#)oBQF1+1w<-mPTlOZ$mDZCV z<=k?)*QZ|se^QsWqK(yEhW4Z=vRnzxipVRS`3M&(vMK(a$**6^`e~#Wq9bU5`jI3b zfbU&cP6&=*W~l^pD#NBJ7dTCB*2&}$VWNh^hQ=r*zs6aZ6j>5nAP`Z{F@pr-XFUc2a_GH7ZSjs`-?SGDab$h_Xx|$LZnyPa4Z&}lP zQ!ts}krcfCjDc;r%V#!sJCjl~$ukj{BGJPqg@5a8$YlQ;%{vr!5SkZ?PPOH+o=6`K z($N+rfpc@_ysa(tXC$BtLWKB#$sPqkJL1Xs|5X)zdh61t*r9?VPXcpD(IKZ$_`(|h zt1tin%Qxb4r_NQhv`X!~Xu8wcEC?G66SbDsCal$OGQNJhHW}dW1($oL{B-`TL)cg4qWfLoRfr?zPfzpinItg zA$`|ru~ZtNGs>GDGnNJF4hxc;Y+}nu@~CkGU=moVrkvaaWR0GP5NM3OueM0SsOopE zym-Ph;1uypgB6V4XkA8+E=!d@Ec0nznhN2eahUeLW-DO+DMDkoPCk;-={wJ)PU!KB zi;Aca<`%ssQql|T=e9mlvP#s8KN}+yRt;_JY50j^8@}e z-t49)b6tt7N0D$ddF5yk+|Z*f&x*>9#$CDSNF%rJi+M929}tR)uMJ6V3?|o$J4FKT zj9M@utALKzrcN!k;)gFA!1_2c+b*;kk-7uXnUNnppF)i}gCdaMH;DuD4XB#f?gJ`N z_$!v8((xeVu4$7s-q`^s+|xT*G915{{YO-neyzqW;(MvB3C8S`8fxCrxRiBdJD>&G zavIWDQR;?E7@wld)eW9amK9J@^L?B_1g)WQ3=HL_7zXEsezU1<3*9_}%;l)2*qq#W z@pzsxD5koizn(G8XpiIs6;9j)A}NN>51PNvT58(=tB^_+F5ZVQz8xlC*A;u-(FRz4 z)^ni&Qat3bC6$EWK=Q{@5pn=Uv&r{V&+7zo%fm1g+eI{G`$04R5Ol;s zVtI-03p>0L2~X%NwoNeWo>@fTuk-U0qM&j4Q1vIPfO=JYpD8TxeiqXpZPZ>FKR=Rq7M4CnDyaOh3&Mbs2lhouh$e>1P)4z$*oUx#{NG zy^&qmzJESqWCD(~fC$wzX*!{QW0R}})+Tks{>p=$liP(tDU78JrF={Y=WjiKLyP)o z89+a)hCBz`;!Kq)rz2rwUX?oabQ6pP42u7jNlCweI&bik3Wh#IvK~Z9p#GQ#t(dzUhOAs{tGCh$Ol237d=>!xh(Q`Y%R1wr2+61BiCu{| zw5KO5yk=BUvs3dUy1_Yc6;{tVpT^gQ7hR3<3?%oiA>^SWg-E_fdg_X)v$;kX@vCQ2 zeu8$uFmV*t(+jQfBckaY-onO5h6MF(h2c!(jYmC4_GH&+$kRyjG)fpoOGn4_T&vg6 z@%2I)=ludVHY1`p*)b(h?S4&9u0C|M;%bV1*K1_brHx{dLs)U-2}EC9gLn}uR&AUM zark#enG7|p(@MIt@W$qm6BmNRK9&iIieeKIT$~>}j^sVw?x}YLcxTu88(iW{ z3xHsv^3ME^rLK>K_ri)^#E(@$_*4!VV-#HHM(PLgSRL4$W$~@a8?$sFbGc6Epj_2EV>GPw|LrLfTZ637`f1IY~AgJRD7SXwn>6_+FlvE0 z2G#wwPfzyw*r$5Ea~D(&!fl-l4y9Sa2c26(e?Ke#y{5bddNAfAe!s6U|G<>&x&VCr z=DBfq->v=nZyBJ!fIhRkbC9&5&7P*hDdwRu+)<}B&ur1Pm2B$J|K5gND7`X1`2Bu> zAr6DSCbe@f2N`i75cQC8M&>*ec1wIi`HjO~B`HUCPdSKHO~l(Eanj zKc8R7>_;kg9y>T8;B7e5&d5r>sq;ytK`43`+tOINlC)uxqjUgrC6iD`>y%KVr*dyP zQfK{>sOPFBP2Sxi+dh0qYMz17MIvGPLk|6cP$3Ymd3E3El&B`zK2BHZ@0g9Y`0?0} zX=670ld10Xp16A?hMXShcf(o)u^h+99j0{G&KCO`!&X?C_jqZ2{$ajX z+U~vITGAaK!B}TYXjSxmB2*{aZ zH`}&7s)J5H^55ZM}KPInoJUfBNg;v5kHvtbnnST!8#4dli-XB0GePH+Alx!BdEt1t7-qe_c*xAUc>HET&$}HR&LDeK3L>^N7Y5XD+a(UssBOK!AN8dN{*itV& zUOM&;A@2~26n^6*`YRK&KI892&p(scS}CE&02F4$a_yDG;pO+O9_*~Aa*IE6j)zYerU-@bvg@PY( zF;&JrD^4Y3ueG>-8d;veIHt3(OJ+TH+4C&<3w5gpkS4tShId=;wplqRA7ndvX^c8c zR{FGPkq*1sVx9`=%sO`%O^i+XpVS<4exllf2j z({snI;U9kQYW_{`kabRJmY0Zw^zrSS`3fUR$7vZEBPt2J-i;>~Z!e zu@$@5e;jg-kK8fSDa9|u?$kd}zEFZh|53bqH5vBE{Xk&+j%P(gX3UALH^MQ%WPb8tYOD$#S2_ECradw{YY^2{knm;VUu+-G(wJphfYXojv@&xA$@o1*sqTk&VU!tKg2)jb Date: Mon, 2 Sep 2024 23:49:42 +0200 Subject: [PATCH 06/67] add github ci for publishing to pypi --- .github/workflows/publish.yml | 45 +++++++++++++++++++++++++++++++++++ 1 file changed, 45 insertions(+) create mode 100644 .github/workflows/publish.yml diff --git a/.github/workflows/publish.yml b/.github/workflows/publish.yml new file mode 100644 index 0000000..4d41f2c --- /dev/null +++ b/.github/workflows/publish.yml @@ -0,0 +1,45 @@ +name: Publish to PyPI + +on: + push: + branches: + - main + tags: + - '*' + pull_request: + branches: + - main + +jobs: + publish: + name: Publish ${{ matrix.package }} + runs-on: ubuntu-latest + strategy: + matrix: + package: [ros2-pkg-create] + steps: + - name: Checkout repository + uses: actions/checkout@v3 + - name: Set up Python + uses: actions/setup-python@v4 + with: + python-version: "3.x" + - name: Install pypa/build + run: python3 -m pip install --user build + - name: Build wheel and tarball + run: python3 -m build --sdist --wheel --outdir dist/ ${{ matrix.package }} + - name: Publish to TestPyPI + uses: pypa/gh-action-pypi-publish@v1.8.6 + with: + password: ${{ secrets.TEST_PYPI_API_TOKEN }} + repository-url: https://test.pypi.org/legacy/ + skip-existing: true + - name: Publish to PyPI + if: startsWith(github.ref, 'refs/tags') + uses: pypa/gh-action-pypi-publish@v1.8.6 + with: + password: ${{ secrets.PYPI_API_TOKEN }} + skip-existing: true + # `continue-on-error` needed cause `skip-existing: true` is not honored + # https://github.com/pypa/gh-action-pypi-publish/issues/201 + continue-on-error: true \ No newline at end of file From b935f70e7056a67ebfdefce55c1ea5f2e0e3cce6 Mon Sep 17 00:00:00 2001 From: Jean-Pierre Busch Date: Wed, 4 Sep 2024 14:43:52 +0200 Subject: [PATCH 07/67] add github workflow for generating and testing the packages --- .github/workflows/generate-and-test.yml | 92 +++++++++++++++++++++++++ 1 file changed, 92 insertions(+) create mode 100644 .github/workflows/generate-and-test.yml diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml new file mode 100644 index 0000000..47fc298 --- /dev/null +++ b/.github/workflows/generate-and-test.yml @@ -0,0 +1,92 @@ +name: Generate and test packages + +on: + push: + branches: + - main + pull_request: + branches: + - main + +jobs: + generate: + runs-on: ubuntu-latest + steps: + - name: Checkout code + uses: actions/checkout@v4 + + - name: Set up Python + uses: actions/setup-python@v5 + with: + python-version: 3.10 + + - name: Install dependencies + run: | + pip install "copier~=9.2.0" "jinja2-strcase~=0.0.2" + + - name: Generate packages + run: | + copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_default . packages + copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_component -d is_component=true . packages + copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_lifecycle -d is_lifecycle=true . packages + copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_service -d has_service_server=true . packages + copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_action -d has_action_server=true . packages + copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_timer -d has_timer=true . packages + copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_no_params -d has_params=false . packages + copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_no_launch_file -d has_launch_file=false . packages + copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_all -d is_component=true -d is_lifecycle=true -d has_service_server=true -d has_action_server=true -d has_timer=true . packages + copier copy --trust --defaults -d template=ros2_interfaces_pkg -d package_name=pkg_interfaces . packages + + - name: Upload artifact + uses: actions/upload-artifact@v4 + with: + name: packages + path: packages/ + + build-and-test: + runs-on: ubuntu-latest + container: + image: rwthika/ros2:latest + options: --rm + needs: generate + strategy: + matrix: + include: + - package: pkg_default + command: ros2 launch pkg_default pkg_default_launch.py + - package: pkg_component + command: ros2 launch pkg_component pkg_component_launch.py + - package: pkg_lifecycle + command: ros2 launch pkg_lifecycle pkg_lifecycle_launch.py + - package: pkg_service + command: ros2 launch pkg_service pkg_service_launch.py + - package: pkg_action + command: ros2 launch pkg_action pkg_action_launch.py + - package: pkg_timer + command: ros2 launch pkg_timer pkg_timer_launch.py + - package: pkg_no_params + command: ros2 launch pkg_no_params pkg_no_params_launch.py + - package: pkg_no_launch_file + command: ros2 run pkg_no_launch_file pkg_no_launch_file --ros-args -p param:=1.0 + - package: pkg_all + command: ros2 launch pkg_all pkg_all_launch.py + - package: pkg_interfaces + command: | + ros2 interface show pkg_interfaces/msg/Message && \ + ros2 interface show pkg_interfaces/srv/Service && \ + ros2 interface show pkg_interfaces/action/Action + steps: + - name: Checkout code + uses: actions/checkout@v4 + + - name: Download packages + uses: actions/download-artifact@v4 + with: + name: packages + + - name: Build and test package ${{ matrix.package }} + run: | + set -e + colcon build --packages-up-to ${{ matrix.package }} + source install/setup.bash + ${{ matrix.command }} From 1657eada3c500be687420d45df80c579496fd82a Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 19:58:36 +0000 Subject: [PATCH 08/67] enable github ci for non-main branches --- .github/workflows/generate-and-test.yml | 17 +++++------------ 1 file changed, 5 insertions(+), 12 deletions(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 47fc298..60152fa 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -1,29 +1,23 @@ name: Generate and test packages -on: - push: - branches: - - main - pull_request: - branches: - - main +# avoiding duplicate jobs on push with open pull_request: https://github.com/orgs/community/discussions/26940#discussioncomment-6656489 +on: [push, pull_request] jobs: + generate: + if: (github.event_name != 'pull_request' && ! github.event.pull_request.head.repo.fork) || (github.event_name == 'pull_request' && github.event.pull_request.head.repo.fork) runs-on: ubuntu-latest steps: - name: Checkout code uses: actions/checkout@v4 - - name: Set up Python uses: actions/setup-python@v5 with: python-version: 3.10 - - name: Install dependencies run: | pip install "copier~=9.2.0" "jinja2-strcase~=0.0.2" - - name: Generate packages run: | copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_default . packages @@ -44,6 +38,7 @@ jobs: path: packages/ build-and-test: + if: (github.event_name != 'pull_request' && ! github.event.pull_request.head.repo.fork) || (github.event_name == 'pull_request' && github.event.pull_request.head.repo.fork) runs-on: ubuntu-latest container: image: rwthika/ros2:latest @@ -78,12 +73,10 @@ jobs: steps: - name: Checkout code uses: actions/checkout@v4 - - name: Download packages uses: actions/download-artifact@v4 with: name: packages - - name: Build and test package ${{ matrix.package }} run: | set -e From 0a87163e4201f3953b4bd2d02c56c0baa1a8f329 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 19:59:26 +0000 Subject: [PATCH 09/67] fix github ci --- .github/workflows/generate-and-test.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 60152fa..78148b6 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -14,7 +14,7 @@ jobs: - name: Set up Python uses: actions/setup-python@v5 with: - python-version: 3.10 + python-version: "3.10" - name: Install dependencies run: | pip install "copier~=9.2.0" "jinja2-strcase~=0.0.2" From fc3560e04741f26159db58b4120d5a45ef26a0fc Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 20:04:37 +0000 Subject: [PATCH 10/67] fix copier git call in github ci --- .github/workflows/generate-and-test.yml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 78148b6..dd7b8d5 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -18,6 +18,10 @@ jobs: - name: Install dependencies run: | pip install "copier~=9.2.0" "jinja2-strcase~=0.0.2" + - name: Configure git to run copier + run: | + git config --global user.name "dummy" + git config --global user.email "dummy@dummy.com" - name: Generate packages run: | copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_default . packages From 05fb958c698b08930f21363555b78332ac61326c Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 20:11:12 +0000 Subject: [PATCH 11/67] simplify github build job --- .github/workflows/generate-and-test.yml | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index dd7b8d5..4b21deb 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -34,19 +34,17 @@ jobs: copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_no_launch_file -d has_launch_file=false . packages copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_all -d is_component=true -d is_lifecycle=true -d has_service_server=true -d has_action_server=true -d has_timer=true . packages copier copy --trust --defaults -d template=ros2_interfaces_pkg -d package_name=pkg_interfaces . packages - - - name: Upload artifact + - name: Upload artifacts uses: actions/upload-artifact@v4 with: name: packages path: packages/ - build-and-test: + build: if: (github.event_name != 'pull_request' && ! github.event.pull_request.head.repo.fork) || (github.event_name == 'pull_request' && github.event.pull_request.head.repo.fork) runs-on: ubuntu-latest container: image: rwthika/ros2:latest - options: --rm needs: generate strategy: matrix: @@ -77,13 +75,14 @@ jobs: steps: - name: Checkout code uses: actions/checkout@v4 - - name: Download packages + - name: Download artifacts uses: actions/download-artifact@v4 with: name: packages - - name: Build and test package ${{ matrix.package }} + - name: Build run: | - set -e - colcon build --packages-up-to ${{ matrix.package }} source install/setup.bash + colcon build --packages-up-to ${{ matrix.package }} + - name: Run + run: | ${{ matrix.command }} From e61345ae544f2ac7ee224b421e781008892db20f Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 20:15:35 +0000 Subject: [PATCH 12/67] source ros in github ci --- .github/workflows/generate-and-test.yml | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 4b21deb..f5102a8 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -44,7 +44,7 @@ jobs: if: (github.event_name != 'pull_request' && ! github.event.pull_request.head.repo.fork) || (github.event_name == 'pull_request' && github.event.pull_request.head.repo.fork) runs-on: ubuntu-latest container: - image: rwthika/ros2:latest + image: rwthika/ros2:jazzy needs: generate strategy: matrix: @@ -80,9 +80,12 @@ jobs: with: name: packages - name: Build + shell: bash run: | - source install/setup.bash + source /opt/ros/$ROS_DISTRO/setup.bash colcon build --packages-up-to ${{ matrix.package }} - name: Run + shell: bash run: | + source install/setup.bash ${{ matrix.command }} From 8aa5e7e6c5040942ef6aaa00c2273bd67a6c3730 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 20:28:04 +0000 Subject: [PATCH 13/67] split generate job in matrix in github ci --- .github/workflows/generate-and-test.yml | 67 +++++++++++++++++++++---- 1 file changed, 56 insertions(+), 11 deletions(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index f5102a8..955d458 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -8,6 +8,50 @@ jobs: generate: if: (github.event_name != 'pull_request' && ! github.event.pull_request.head.repo.fork) || (github.event_name == 'pull_request' && github.event.pull_request.head.repo.fork) runs-on: ubuntu-latest + strategy: + matrix: + include: + - package_name: pkg_default + template: ros2_cpp_pkg + auto_shutdown: true + - package_name: pkg_component + template: ros2_cpp_pkg + is_component: true + auto_shutdown: true + - package_name: pkg_lifecycle + template: ros2_cpp_pkg + is_lifecycle: true + auto_shutdown: true + - package_name: pkg_service + template: ros2_cpp_pkg + has_service_server: true + auto_shutdown: true + - package_name: pkg_action + template: ros2_cpp_pkg + has_action_server: true + auto_shutdown: true + - package_name: pkg_timer + template: ros2_cpp_pkg + has_timer: true + auto_shutdown: true + - package_name: pkg_no_params + template: ros2_cpp_pkg + has_params: false + auto_shutdown: true + - package_name: pkg_no_launch_file + template: ros2_cpp_pkg + has_launch_file: false + auto_shutdown: true + - package_name: pkg_all + template: ros2_cpp_pkg + is_component: true + is_lifecycle: true + has_service_server: true + has_action_server: true + has_timer: true + auto_shutdown: true + - package_name: pkg_interfaces + template: ros2_interfaces_pkg steps: - name: Checkout code uses: actions/checkout@v4 @@ -23,17 +67,18 @@ jobs: git config --global user.name "dummy" git config --global user.email "dummy@dummy.com" - name: Generate packages - run: | - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_default . packages - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_component -d is_component=true . packages - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_lifecycle -d is_lifecycle=true . packages - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_service -d has_service_server=true . packages - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_action -d has_action_server=true . packages - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_timer -d has_timer=true . packages - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_no_params -d has_params=false . packages - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_no_launch_file -d has_launch_file=false . packages - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_all -d is_component=true -d is_lifecycle=true -d has_service_server=true -d has_action_server=true -d has_timer=true . packages - copier copy --trust --defaults -d template=ros2_interfaces_pkg -d package_name=pkg_interfaces . packages + run: > + copier copy --trust --defaults -d template={{ matrix.template }} + -d auto_shutdown={{ matrix.auto_shutdown }} + -d package_name={{ matrix.package_name }} + {% if matrix.is_component %} -d is_component=true{% endif %} + {% if matrix.is_lifecycle %} -d is_lifecycle=true{% endif %} + {% if matrix.has_service_server %} -d has_service_server=true{% endif %} + {% if matrix.has_action_server %} -d has_action_server=true{% endif %} + {% if matrix.has_timer %} -d has_timer=true{% endif %} + {% if matrix.has_params %} -d has_params=true{% endif %} + {% if matrix.has_launch_file %} -d has_launch_file=true{% endif %} + . packages - name: Upload artifacts uses: actions/upload-artifact@v4 with: From 298fb72de36d17f25d8a8e28fdc9867d371420d8 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 20:35:00 +0000 Subject: [PATCH 14/67] test github ci --- .github/workflows/generate-and-test.yml | 13 +------------ 1 file changed, 1 insertion(+), 12 deletions(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 955d458..52b3726 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -67,18 +67,7 @@ jobs: git config --global user.name "dummy" git config --global user.email "dummy@dummy.com" - name: Generate packages - run: > - copier copy --trust --defaults -d template={{ matrix.template }} - -d auto_shutdown={{ matrix.auto_shutdown }} - -d package_name={{ matrix.package_name }} - {% if matrix.is_component %} -d is_component=true{% endif %} - {% if matrix.is_lifecycle %} -d is_lifecycle=true{% endif %} - {% if matrix.has_service_server %} -d has_service_server=true{% endif %} - {% if matrix.has_action_server %} -d has_action_server=true{% endif %} - {% if matrix.has_timer %} -d has_timer=true{% endif %} - {% if matrix.has_params %} -d has_params=true{% endif %} - {% if matrix.has_launch_file %} -d has_launch_file=true{% endif %} - . packages + run: copier copy --trust --defaults -d template={{ matrix.template }} . packages - name: Upload artifacts uses: actions/upload-artifact@v4 with: From 190fd582671c6e5aa38cb72898b232b632019edd Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 20:42:36 +0000 Subject: [PATCH 15/67] try to fix conditional github ci syntax --- .github/workflows/generate-and-test.yml | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 52b3726..2b89d5e 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -67,7 +67,19 @@ jobs: git config --global user.name "dummy" git config --global user.email "dummy@dummy.com" - name: Generate packages - run: copier copy --trust --defaults -d template={{ matrix.template }} . packages + run: > + copier copy --trust --defaults + -d template=${{ matrix.template }} + -d auto_shutdown=${{ matrix.auto_shutdown }} + -d package_name=${{ matrix.package_name }} + $( [ "${{ matrix.is_component }}" = "true" ] && echo "-d is_component=true" ) + $( [ "${{ matrix.is_lifecycle }}" = "true" ] && echo "-d is_lifecycle=true" ) + $( [ "${{ matrix.has_service_server }}" = "true" ] && echo "-d has_service_server=true" ) + $( [ "${{ matrix.has_action_server }}" = "true" ] && echo "-d has_action_server=true" ) + $( [ "${{ matrix.has_timer }}" = "true" ] && echo "-d has_timer=true" ) + $( [ "${{ matrix.has_params }}" = "false" ] && echo "-d has_params=false" ) + $( [ "${{ matrix.has_launch_file }}" = "false" ] && echo "-d has_launch_file=false" ) + . packages - name: Upload artifacts uses: actions/upload-artifact@v4 with: From b3598e299c416caeb68f5a3da571198cb1ef7bc9 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 20:43:34 +0000 Subject: [PATCH 16/67] fix yml breaking syntax --- .github/workflows/generate-and-test.yml | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 2b89d5e..551d04d 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -67,18 +67,18 @@ jobs: git config --global user.name "dummy" git config --global user.email "dummy@dummy.com" - name: Generate packages - run: > - copier copy --trust --defaults - -d template=${{ matrix.template }} - -d auto_shutdown=${{ matrix.auto_shutdown }} - -d package_name=${{ matrix.package_name }} - $( [ "${{ matrix.is_component }}" = "true" ] && echo "-d is_component=true" ) - $( [ "${{ matrix.is_lifecycle }}" = "true" ] && echo "-d is_lifecycle=true" ) - $( [ "${{ matrix.has_service_server }}" = "true" ] && echo "-d has_service_server=true" ) - $( [ "${{ matrix.has_action_server }}" = "true" ] && echo "-d has_action_server=true" ) - $( [ "${{ matrix.has_timer }}" = "true" ] && echo "-d has_timer=true" ) - $( [ "${{ matrix.has_params }}" = "false" ] && echo "-d has_params=false" ) - $( [ "${{ matrix.has_launch_file }}" = "false" ] && echo "-d has_launch_file=false" ) + run: | + copier copy --trust --defaults \ + -d template=${{ matrix.template }} \ + -d auto_shutdown=${{ matrix.auto_shutdown }} \ + -d package_name=${{ matrix.package_name }} \ + $( [ "${{ matrix.is_component }}" = "true" ] && echo "-d is_component=true" ) \ + $( [ "${{ matrix.is_lifecycle }}" = "true" ] && echo "-d is_lifecycle=true" ) \ + $( [ "${{ matrix.has_service_server }}" = "true" ] && echo "-d has_service_server=true" ) \ + $( [ "${{ matrix.has_action_server }}" = "true" ] && echo "-d has_action_server=true" ) \ + $( [ "${{ matrix.has_timer }}" = "true" ] && echo "-d has_timer=true" ) \ + $( [ "${{ matrix.has_params }}" = "false" ] && echo "-d has_params=false" ) \ + $( [ "${{ matrix.has_launch_file }}" = "false" ] && echo "-d has_launch_file=false" ) \ . packages - name: Upload artifacts uses: actions/upload-artifact@v4 From f1e04eb54f8639f1e1c869356948028b31943407 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 20:46:47 +0000 Subject: [PATCH 17/67] fix artifact passing with two matrix jobs --- .github/workflows/generate-and-test.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 551d04d..6996d53 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -83,8 +83,8 @@ jobs: - name: Upload artifacts uses: actions/upload-artifact@v4 with: - name: packages - path: packages/ + name: ${{ matrix.package_name }} + path: packages/${{ matrix.package_name }} build: if: (github.event_name != 'pull_request' && ! github.event.pull_request.head.repo.fork) || (github.event_name == 'pull_request' && github.event.pull_request.head.repo.fork) @@ -124,7 +124,7 @@ jobs: - name: Download artifacts uses: actions/download-artifact@v4 with: - name: packages + name: ${{ matrix.package }} - name: Build shell: bash run: | From a7ec46b7f766cd544d64d4e3dc5beee3fab934fc Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 21:04:07 +0000 Subject: [PATCH 18/67] use local templates in github ci --- .github/workflows/generate-and-test.yml | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 6996d53..9499ee9 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -62,13 +62,9 @@ jobs: - name: Install dependencies run: | pip install "copier~=9.2.0" "jinja2-strcase~=0.0.2" - - name: Configure git to run copier - run: | - git config --global user.name "dummy" - git config --global user.email "dummy@dummy.com" - name: Generate packages run: | - copier copy --trust --defaults \ + copier copy --trust --use-local-templates --defaults \ -d template=${{ matrix.template }} \ -d auto_shutdown=${{ matrix.auto_shutdown }} \ -d package_name=${{ matrix.package_name }} \ From 6a30e8197fd8dc1b7b3e5a2f92aa8a59cca2a96b Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 21:04:27 +0000 Subject: [PATCH 19/67] add job to check samples for changes --- .github/workflows/check-samples.yml | 84 +++++++++++++++++++++++++++++ 1 file changed, 84 insertions(+) create mode 100644 .github/workflows/check-samples.yml diff --git a/.github/workflows/check-samples.yml b/.github/workflows/check-samples.yml new file mode 100644 index 0000000..c8472dc --- /dev/null +++ b/.github/workflows/check-samples.yml @@ -0,0 +1,84 @@ +name: Check samples + +# avoiding duplicate jobs on push with open pull_request: https://github.com/orgs/community/discussions/26940#discussioncomment-6656489 +on: [push, pull_request] + +jobs: + + check: + if: (github.event_name != 'pull_request' && ! github.event.pull_request.head.repo.fork) || (github.event_name == 'pull_request' && github.event.pull_request.head.repo.fork) + runs-on: ubuntu-latest + strategy: + matrix: + include: + - package_name: ros2_cpp_pkg + template: ros2_cpp_pkg + is_component: false + is_lifecycle: false + has_launch_file: true + has_params: true + has_subscriber: true + has_publisher: true + has_service_server: false + has_action_server: false + has_timer: false + - package_name: ros2_cpp_component_pkg + template: ros2_cpp_pkg + is_component: true + is_lifecycle: false + has_launch_file: true + has_params: true + has_subscriber: true + has_publisher: true + has_service_server: false + has_action_server: false + has_timer: false + - package_name: ros2_cpp_lifecycle_pkg + template: ros2_cpp_pkg + is_component: false + is_lifecycle: true + has_launch_file: true + has_params: true + has_subscriber: true + has_publisher: true + has_service_server: false + has_action_server: false + has_timer: false + - package_name: ros2_interfaces_pkg + template: ros2_interfaces_pkg + interface_types: Message,Service,Action + steps: + - name: Checkout code + uses: actions/checkout@v4 + - name: Set up Python + uses: actions/setup-python@v5 + with: + python-version: "3.10" + - name: Install dependencies + run: | + pip install "copier~=9.2.0" "jinja2-strcase~=0.0.2" + - name: Generate packages + run: | + copier copy --trust --use-local-templates --defaults \ + -d template=${{ matrix.template }} \ + -d package_name=${{ matrix.package_name }} \ + -d is_component=${{ matrix.is_component }} \ + -d is_lifecycle=${{ matrix.is_lifecycle }} \ + -d has_launch_file=${{ matrix.has_launch_file }} \ + -d has_params=${{ matrix.has_params }} \ + -d has_subscriber=${{ matrix.has_subscriber }} \ + -d has_publisher=${{ matrix.has_publisher }} \ + -d has_service_server=${{ matrix.has_service_server }} \ + -d has_action_server=${{ matrix.has_action_server }} \ + -d has_timer=${{ matrix.has_timer }} \ + -d interface_types=${{ matrix.interface_types }} \ + . packages + - name: Check for repository changes + run: | + rm -rf samples + mv packages samples + if [[ ! -z "$(git status --porcelain)" ]]; then + echo "Sample generation resulted in changes to the repository" + git diff + exit 1 + fi From 9bf569e25a533e83467fbafbc9f869fa86b1ea7e Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 5 Sep 2024 21:06:34 +0000 Subject: [PATCH 20/67] revert use-local-templates, not a copier arg --- .github/workflows/check-samples.yml | 6 +++++- .github/workflows/generate-and-test.yml | 6 +++++- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/.github/workflows/check-samples.yml b/.github/workflows/check-samples.yml index c8472dc..743a89d 100644 --- a/.github/workflows/check-samples.yml +++ b/.github/workflows/check-samples.yml @@ -57,9 +57,13 @@ jobs: - name: Install dependencies run: | pip install "copier~=9.2.0" "jinja2-strcase~=0.0.2" + - name: Configure git to run copier + run: | + git config --global user.name "dummy" + git config --global user.email "dummy@dummy.com" - name: Generate packages run: | - copier copy --trust --use-local-templates --defaults \ + copier copy --trust --defaults \ -d template=${{ matrix.template }} \ -d package_name=${{ matrix.package_name }} \ -d is_component=${{ matrix.is_component }} \ diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 9499ee9..6996d53 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -62,9 +62,13 @@ jobs: - name: Install dependencies run: | pip install "copier~=9.2.0" "jinja2-strcase~=0.0.2" + - name: Configure git to run copier + run: | + git config --global user.name "dummy" + git config --global user.email "dummy@dummy.com" - name: Generate packages run: | - copier copy --trust --use-local-templates --defaults \ + copier copy --trust --defaults \ -d template=${{ matrix.template }} \ -d auto_shutdown=${{ matrix.auto_shutdown }} \ -d package_name=${{ matrix.package_name }} \ From a361d33bad555a05a217f0294d7194c35f7b96ba Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 9 Sep 2024 12:26:57 +0200 Subject: [PATCH 21/67] fix warning box in readme --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index b98dcca..aeda448 100644 --- a/README.md +++ b/README.md @@ -79,7 +79,7 @@ activate-global-python-argcomplete eval "$(register-python-argcomplete ros2-pkg-create)" ``` -> **Warning** +> [!WARNING] > Outside of a virtual environment, *pip* may default to a user-site installation of executables to `~/.local/bin`, which may not be present in your shell's `PATH`. If running `ros2-pkg-create` errors with `ros2-pkg-create: command not found`, add the directory to your path. [*(More information)*](https://packaging.python.org/en/latest/tutorials/installing-packages/#installing-to-the-user-site) > ```bash > echo "export PATH=\$HOME/.local/bin:\$PATH" >> ~/.bashrc From 2ea7312c49425eb2f6277108b54e6af7120ae898 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 9 Sep 2024 16:10:33 +0000 Subject: [PATCH 22/67] download all artifacts in github ci to fix pkg_action --- .github/workflows/generate-and-test.yml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 6996d53..3180d77 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -123,8 +123,6 @@ jobs: uses: actions/checkout@v4 - name: Download artifacts uses: actions/download-artifact@v4 - with: - name: ${{ matrix.package }} - name: Build shell: bash run: | From dd093bc84e77d601d1d492d4da4eaf005faf0cb1 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 9 Sep 2024 16:13:56 +0000 Subject: [PATCH 23/67] use wildcard in artifact upload to fix pkg_action --- .github/workflows/generate-and-test.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 3180d77..b90c938 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -84,7 +84,7 @@ jobs: uses: actions/upload-artifact@v4 with: name: ${{ matrix.package_name }} - path: packages/${{ matrix.package_name }} + path: "packages/${{ matrix.package_name }}*" build: if: (github.event_name != 'pull_request' && ! github.event.pull_request.head.repo.fork) || (github.event_name == 'pull_request' && github.event.pull_request.head.repo.fork) From 2890303f72adcb3374a18826d5a52087c974acc6 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 9 Sep 2024 16:17:48 +0000 Subject: [PATCH 24/67] fix name of interfaces package generated if action server is used --- .../CMakeLists.txt.jinja | 2 +- .../package.xml.jinja | 2 +- .../{{ package_name }}/CMakeLists.txt.jinja | 4 ++-- .../{{ package_name }}/{{ node_name }}.hpp.jinja | 12 ++++++------ .../{{ package_name }}/package.xml.jinja | 2 +- .../src/{{ node_name }}.cpp.jinja | 14 +++++++------- 6 files changed, 18 insertions(+), 18 deletions(-) diff --git a/templates/ros2_cpp_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/CMakeLists.txt.jinja b/templates/ros2_cpp_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/CMakeLists.txt.jinja index 52dbb82..d66679b 100644 --- a/templates/ros2_cpp_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/CMakeLists.txt.jinja +++ b/templates/ros2_cpp_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/CMakeLists.txt.jinja @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.8) -project({{ package_name }}_actions) +project({{ package_name }}_interfaces) find_package(rosidl_default_generators REQUIRED) diff --git a/templates/ros2_cpp_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/package.xml.jinja b/templates/ros2_cpp_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/package.xml.jinja index f29b181..f7d17ba 100644 --- a/templates/ros2_cpp_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/package.xml.jinja +++ b/templates/ros2_cpp_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/package.xml.jinja @@ -2,7 +2,7 @@ - {{ package_name }}_actions + {{ package_name }}_interfaces 0.0.0 ROS interface definitions for {{ package_name }} diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/CMakeLists.txt.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/CMakeLists.txt.jinja index 6af82ee..9093c08 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/CMakeLists.txt.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/CMakeLists.txt.jinja @@ -9,7 +9,7 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) {% if has_action_server %} find_package(rclcpp_action REQUIRED) -find_package({{ package_name }}_actions REQUIRED) +find_package({{ package_name }}_interfaces REQUIRED) {% endif %} {% if is_component %} find_package(rclcpp_components REQUIRED) @@ -49,7 +49,7 @@ ament_target_dependencies(${TARGET_NAME} rclcpp {% if has_action_server %} rclcpp_action - {{ package_name }}_actions + {{ package_name }}_interfaces {% endif %} {% if is_component %} rclcpp_components diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/include/{{ package_name }}/{{ node_name }}.hpp.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/include/{{ package_name }}/{{ node_name }}.hpp.jinja index 1159569..821b4f2 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/include/{{ package_name }}/{{ node_name }}.hpp.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/include/{{ package_name }}/{{ node_name }}.hpp.jinja @@ -22,7 +22,7 @@ {% endif %} {% if has_action_server %} -#include <{{ package_name }}_actions/action/fibonacci.hpp> +#include <{{ package_name }}_interfaces/action/fibonacci.hpp> {% endif %} @@ -98,13 +98,13 @@ class {{ node_class_name }} : public rclcpp::Node { {% endif %} {% if has_action_server %} - rclcpp_action::GoalResponse actionHandleGoal(const rclcpp_action::GoalUUID& uuid, std::shared_ptr goal); + rclcpp_action::GoalResponse actionHandleGoal(const rclcpp_action::GoalUUID& uuid, std::shared_ptr goal); - rclcpp_action::CancelResponse actionHandleCancel(const std::shared_ptr> goal_handle); + rclcpp_action::CancelResponse actionHandleCancel(const std::shared_ptr> goal_handle); - void actionHandleAccepted(const std::shared_ptr> goal_handle); + void actionHandleAccepted(const std::shared_ptr> goal_handle); - void actionExecute(const std::shared_ptr> goal_handle); + void actionExecute(const std::shared_ptr> goal_handle); {% endif %} {% if has_timer %} @@ -142,7 +142,7 @@ class {{ node_class_name }} : public rclcpp::Node { {% endif %} {% if has_action_server %} - rclcpp_action::Server<{{ package_name }}_actions::action::Fibonacci>::SharedPtr action_server_; + rclcpp_action::Server<{{ package_name }}_interfaces::action::Fibonacci>::SharedPtr action_server_; {% endif %} {% if has_timer %} diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/package.xml.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/package.xml.jinja index 3c08819..f5f3339 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/package.xml.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/package.xml.jinja @@ -28,7 +28,7 @@ std_srvs {% endif %} {% if has_action_server %} - {{ package_name }}_actions + {{ package_name }}_interfaces {% endif %} diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja index 0048240..25cf7c4 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja @@ -187,7 +187,7 @@ void {{ node_class_name }}::setup() { {% if has_action_server %} // action server for handling action goal requests - action_server_ = rclcpp_action::create_server<{{ package_name }}_actions::action::Fibonacci>( + action_server_ = rclcpp_action::create_server<{{ package_name }}_interfaces::action::Fibonacci>( this, "~/action", std::bind(&{{ node_class_name }}::actionHandleGoal, this, std::placeholders::_1, std::placeholders::_2), @@ -246,7 +246,7 @@ void {{ node_class_name }}::serviceCallback(const std_srvs::srv::SetBool::Reques * @param goal action goal * @return goal response */ -rclcpp_action::GoalResponse {{ node_class_name }}::actionHandleGoal(const rclcpp_action::GoalUUID& uuid, {{ package_name }}_actions::action::Fibonacci::Goal::ConstSharedPtr goal) { +rclcpp_action::GoalResponse {{ node_class_name }}::actionHandleGoal(const rclcpp_action::GoalUUID& uuid, {{ package_name }}_interfaces::action::Fibonacci::Goal::ConstSharedPtr goal) { (void)uuid; (void)goal; @@ -263,7 +263,7 @@ rclcpp_action::GoalResponse {{ node_class_name }}::actionHandleGoal(const rclcpp * @param goal_handle action goal handle * @return cancel response */ -rclcpp_action::CancelResponse {{ node_class_name }}::actionHandleCancel(const std::shared_ptr> goal_handle) { +rclcpp_action::CancelResponse {{ node_class_name }}::actionHandleCancel(const std::shared_ptr> goal_handle) { (void)goal_handle; @@ -278,7 +278,7 @@ rclcpp_action::CancelResponse {{ node_class_name }}::actionHandleCancel(const st * * @param goal_handle action goal handle */ -void {{ node_class_name }}::actionHandleAccepted(const std::shared_ptr> goal_handle) { +void {{ node_class_name }}::actionHandleAccepted(const std::shared_ptr> goal_handle) { // execute action in a separate thread to avoid blocking std::thread{std::bind(&{{ node_class_name }}::actionExecute, this, std::placeholders::_1), goal_handle}.detach(); @@ -290,7 +290,7 @@ void {{ node_class_name }}::actionHandleAccepted(const std::shared_ptr> goal_handle) { +void {{ node_class_name }}::actionExecute(const std::shared_ptr> goal_handle) { RCLCPP_INFO(this->get_logger(), "Executing action goal"); @@ -299,8 +299,8 @@ void {{ node_class_name }}::actionExecute(const std::shared_ptrget_goal(); - auto feedback = std::make_shared<{{ package_name }}_actions::action::Fibonacci::Feedback>(); - auto result = std::make_shared<{{ package_name }}_actions::action::Fibonacci::Result>(); + auto feedback = std::make_shared<{{ package_name }}_interfaces::action::Fibonacci::Feedback>(); + auto result = std::make_shared<{{ package_name }}_interfaces::action::Fibonacci::Result>(); // initialize the Fibonacci sequence auto& partial_sequence = feedback->partial_sequence; From 5ec5bd5836b1a4b64ef5d6159be7d3fd0d7c0e69 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 9 Sep 2024 16:22:59 +0000 Subject: [PATCH 25/67] fix sample gen ci vs existing samples --- .github/workflows/check-samples.yml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.github/workflows/check-samples.yml b/.github/workflows/check-samples.yml index 743a89d..8979e8b 100644 --- a/.github/workflows/check-samples.yml +++ b/.github/workflows/check-samples.yml @@ -13,6 +13,7 @@ jobs: include: - package_name: ros2_cpp_pkg template: ros2_cpp_pkg + node_name: ros2_cpp_node is_component: false is_lifecycle: false has_launch_file: true @@ -24,6 +25,7 @@ jobs: has_timer: false - package_name: ros2_cpp_component_pkg template: ros2_cpp_pkg + node_name: ros2_cpp_node is_component: true is_lifecycle: false has_launch_file: true @@ -35,6 +37,7 @@ jobs: has_timer: false - package_name: ros2_cpp_lifecycle_pkg template: ros2_cpp_pkg + node_name: ros2_cpp_node is_component: false is_lifecycle: true has_launch_file: true @@ -66,6 +69,7 @@ jobs: copier copy --trust --defaults \ -d template=${{ matrix.template }} \ -d package_name=${{ matrix.package_name }} \ + -d node_name=${{ matrix.node_name }} \ -d is_component=${{ matrix.is_component }} \ -d is_lifecycle=${{ matrix.is_lifecycle }} \ -d has_launch_file=${{ matrix.has_launch_file }} \ From acb3725df6fa4d3ef5de8a34361100385cec1f3c Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 9 Sep 2024 16:28:17 +0000 Subject: [PATCH 26/67] dont remove all samples in each matrix step of sample check ci job --- .github/workflows/check-samples.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/check-samples.yml b/.github/workflows/check-samples.yml index 8979e8b..336e7d4 100644 --- a/.github/workflows/check-samples.yml +++ b/.github/workflows/check-samples.yml @@ -83,8 +83,8 @@ jobs: . packages - name: Check for repository changes run: | - rm -rf samples - mv packages samples + rm -rf samples/${{ matrix.package_name }} + mv packages/${{ matrix.package_name }} samples/ if [[ ! -z "$(git status --porcelain)" ]]; then echo "Sample generation resulted in changes to the repository" git diff From 972a0a2001bed280e03ead135a3a6f09cd0e48d3 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 9 Sep 2024 16:28:24 +0000 Subject: [PATCH 27/67] upgrade versions of publish ci job --- .github/workflows/publish.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/publish.yml b/.github/workflows/publish.yml index 4d41f2c..843a804 100644 --- a/.github/workflows/publish.yml +++ b/.github/workflows/publish.yml @@ -21,7 +21,7 @@ jobs: - name: Checkout repository uses: actions/checkout@v3 - name: Set up Python - uses: actions/setup-python@v4 + uses: actions/setup-python@v5.2.0 with: python-version: "3.x" - name: Install pypa/build @@ -29,14 +29,14 @@ jobs: - name: Build wheel and tarball run: python3 -m build --sdist --wheel --outdir dist/ ${{ matrix.package }} - name: Publish to TestPyPI - uses: pypa/gh-action-pypi-publish@v1.8.6 + uses: pypa/gh-action-pypi-publish@v1.10.1 with: password: ${{ secrets.TEST_PYPI_API_TOKEN }} repository-url: https://test.pypi.org/legacy/ skip-existing: true - name: Publish to PyPI if: startsWith(github.ref, 'refs/tags') - uses: pypa/gh-action-pypi-publish@v1.8.6 + uses: pypa/gh-action-pypi-publish@v1.10.1 with: password: ${{ secrets.PYPI_API_TOKEN }} skip-existing: true From 7782b8aec3e9b942cbc4060a82d95953dd8b4667 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 9 Sep 2024 16:35:09 +0000 Subject: [PATCH 28/67] finally match samples and ci generation --- .github/workflows/check-samples.yml | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/.github/workflows/check-samples.yml b/.github/workflows/check-samples.yml index 336e7d4..189d741 100644 --- a/.github/workflows/check-samples.yml +++ b/.github/workflows/check-samples.yml @@ -37,7 +37,7 @@ jobs: has_timer: false - package_name: ros2_cpp_lifecycle_pkg template: ros2_cpp_pkg - node_name: ros2_cpp_node + node_name: ros2_cpp_lifecycle_node is_component: false is_lifecycle: true has_launch_file: true @@ -49,7 +49,6 @@ jobs: has_timer: false - package_name: ros2_interfaces_pkg template: ros2_interfaces_pkg - interface_types: Message,Service,Action steps: - name: Checkout code uses: actions/checkout@v4 @@ -79,7 +78,6 @@ jobs: -d has_service_server=${{ matrix.has_service_server }} \ -d has_action_server=${{ matrix.has_action_server }} \ -d has_timer=${{ matrix.has_timer }} \ - -d interface_types=${{ matrix.interface_types }} \ . packages - name: Check for repository changes run: | From ae708ebccd14138f7b8c0e6f3c67b968e59e8084 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 9 Sep 2024 16:35:13 +0000 Subject: [PATCH 29/67] remove gitlab ci --- .gitlab-ci.yml | 113 ------------------------------------------------- 1 file changed, 113 deletions(-) delete mode 100644 .gitlab-ci.yml diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml deleted file mode 100644 index fe2ca3a..0000000 --- a/.gitlab-ci.yml +++ /dev/null @@ -1,113 +0,0 @@ -stages: - - generate - - ros2_cpp_pkg - - ros2_interfaces_pkg - - -generate: - stage: generate - image: python:3.10 - before_script: - - pip install "copier~=9.2.0" "jinja2-strcase~=0.0.2" - - git config --global user.name "dummy" - - git config --global user.email "dummy@dummy.com" - script: - - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_default . packages - - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_component -d is_component=true . packages - - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_lifecycle -d is_lifecycle=true . packages - - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_service -d has_service_server=true . packages - - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_action -d has_action_server=true . packages - - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_timer -d has_timer=true . packages - - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_no_params -d has_params=false . packages - - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_no_launch_file -d has_launch_file=false . packages - - copier copy --trust --defaults -d template=ros2_cpp_pkg -d auto_shutdown=true -d package_name=pkg_all -d is_component=true -d is_lifecycle=true -d has_service_server=true -d has_action_server=true -d has_timer=true . packages - - copier copy --trust --defaults -d template=ros2_interfaces_pkg -d package_name=pkg_interfaces . packages - artifacts: - paths: - - packages/ - expire_in: 1 week - - -.build: - image: rwthika/ros2:latest - needs: [generate] - -.build-ros2_cpp_pkg: - extends: .build - stage: ros2_cpp_pkg - -.build-ros2_interfaces_pkg: - extends: .build - stage: ros2_interfaces_pkg - -pkg_default: - extends: .build-ros2_cpp_pkg - script: - - colcon build --packages-up-to pkg_default - - source install/setup.bash - - ros2 launch pkg_default pkg_default_launch.py - -pkg_component: - extends: .build-ros2_cpp_pkg - script: - - colcon build --packages-up-to pkg_component - - source install/setup.bash - - ros2 launch pkg_component pkg_component_launch.py - -pkg_lifecycle: - extends: .build-ros2_cpp_pkg - script: - - colcon build --packages-up-to pkg_lifecycle - - source install/setup.bash - - ros2 launch pkg_lifecycle pkg_lifecycle_launch.py - -pkg_service: - extends: .build-ros2_cpp_pkg - script: - - colcon build --packages-up-to pkg_service - - source install/setup.bash - - ros2 launch pkg_service pkg_service_launch.py - -pkg_action: - extends: .build-ros2_cpp_pkg - script: - - colcon build --packages-up-to pkg_action - - source install/setup.bash - - ros2 launch pkg_action pkg_action_launch.py - -pkg_timer: - extends: .build-ros2_cpp_pkg - script: - - colcon build --packages-up-to pkg_timer - - source install/setup.bash - - ros2 launch pkg_timer pkg_timer_launch.py - -pkg_no_params: - extends: .build-ros2_cpp_pkg - script: - - colcon build --packages-up-to pkg_no_params - - source install/setup.bash - - ros2 launch pkg_no_params pkg_no_params_launch.py - -pkg_no_launch_file: - extends: .build-ros2_cpp_pkg - script: - - colcon build --packages-up-to pkg_no_launch_file - - source install/setup.bash - - ros2 run pkg_no_launch_file pkg_no_launch_file --ros-args -p param:=1.0 - -pkg_all: - extends: .build-ros2_cpp_pkg - script: - - colcon build --packages-up-to pkg_all - - source install/setup.bash - - ros2 launch pkg_all pkg_all_launch.py - -pkg_interfaces: - extends: .build-ros2_interfaces_pkg - script: - - colcon build --packages-up-to pkg_interfaces - - source install/setup.bash - - ros2 interface show pkg_interfaces/msg/Message - - ros2 interface show pkg_interfaces/srv/Service - - ros2 interface show pkg_interfaces/action/Action From 2d7fe4d00a1038b4351f2782ea0de3311daaf31d Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 9 Sep 2024 18:43:19 +0200 Subject: [PATCH 30/67] point remote template location to github --- ros2-pkg-create/src/ros2_pkg_create/__main__.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros2-pkg-create/src/ros2_pkg_create/__main__.py b/ros2-pkg-create/src/ros2_pkg_create/__main__.py index 80f70ed..3d367d2 100644 --- a/ros2-pkg-create/src/ros2_pkg_create/__main__.py +++ b/ros2-pkg-create/src/ros2_pkg_create/__main__.py @@ -69,7 +69,7 @@ def main(): if args.use_local_templates: template_location = os.path.join(os.path.dirname(__file__), os.pardir, os.pardir, os.pardir) else: - template_location = "https://gitlab.ika.rwth-aachen.de/fb-fi/ops/templates/ros2/ros2-pkg-create.git" + template_location = "https://github.com/ika-rwth-aachen/ros2-pkg-create.git" copier.run_copy(template_location, os.path.join(os.getcwd(), args.destination), data=answers, From 21b31747a348e70fda3ea80c098b1ef670cf43af Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 9 Sep 2024 16:44:54 +0000 Subject: [PATCH 31/67] bump version to 0.1.0 --- ros2-pkg-create/pyproject.toml | 2 +- ros2-pkg-create/src/ros2_pkg_create/__init__.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ros2-pkg-create/pyproject.toml b/ros2-pkg-create/pyproject.toml index a6b1006..95bc68b 100644 --- a/ros2-pkg-create/pyproject.toml +++ b/ros2-pkg-create/pyproject.toml @@ -4,7 +4,7 @@ build-backend = "setuptools.build_meta" [project] name = "ros2-pkg-create" -version = "0.0.8" +version = "0.1.0" description = "TODO" license = {file = "LICENSE"} readme = "README.md" diff --git a/ros2-pkg-create/src/ros2_pkg_create/__init__.py b/ros2-pkg-create/src/ros2_pkg_create/__init__.py index 9a4db72..96f4cfc 100644 --- a/ros2-pkg-create/src/ros2_pkg_create/__init__.py +++ b/ros2-pkg-create/src/ros2_pkg_create/__init__.py @@ -1,2 +1,2 @@ __name__ = "ros2-pkg-create" -__version__ = "0.0.8" \ No newline at end of file +__version__ = "0.1.0" \ No newline at end of file From 84d03f79ff96618df1693a5fab8e29c377e82140 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 10 Sep 2024 20:47:28 +0000 Subject: [PATCH 32/67] add file and folder structure for ros2_python_pkg template --- copier.yml | 26 ++++++------ .../CMakeLists.txt.jinja | 12 ++++++ .../action/Fibonacci.action | 5 +++ .../package.xml.jinja | 24 +++++++++++ .../{{ package_name }}/package.xml.jinja | 22 ++++++++++ .../resource/{{ package_name }}.jinja | 0 .../{{ package_name }}/setup.cfg.jinja | 4 ++ .../{{ package_name }}/setup.py.jinja | 29 +++++++++++++ ...cker_ros %}.gitlab-ci.yml{% endif %}.jinja | 8 ++++ ...{{ node_name }}_launch.py{% endif %}.jinja | 42 +++++++++++++++++++ ...{ node_name }}_launch.xml{% endif %}.jinja | 12 ++++++ ...{ node_name }}_launch.yml{% endif %}.jinja | 20 +++++++++ .../params.yml.jinja | 3 ++ .../{{ package_name }}/__init__.py | 0 .../{{ node_name }}.py.jinja | 19 +++++++++ 15 files changed, 213 insertions(+), 13 deletions(-) create mode 100644 templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/CMakeLists.txt.jinja create mode 100644 templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/action/Fibonacci.action create mode 100644 templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/package.xml.jinja create mode 100644 templates/ros2_python_pkg/{{ package_name }}/package.xml.jinja create mode 100644 templates/ros2_python_pkg/{{ package_name }}/resource/{{ package_name }}.jinja create mode 100644 templates/ros2_python_pkg/{{ package_name }}/setup.cfg.jinja create mode 100644 templates/ros2_python_pkg/{{ package_name }}/setup.py.jinja create mode 100644 templates/ros2_python_pkg/{{ package_name }}/{% if has_docker_ros %}.gitlab-ci.yml{% endif %}.jinja create mode 100644 templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja create mode 100644 templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja create mode 100644 templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'yml' %}{{ node_name }}_launch.yml{% endif %}.jinja create mode 100644 templates/ros2_python_pkg/{{ package_name }}/{% if has_params %}config{% endif %}/params.yml.jinja create mode 100644 templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/__init__.py create mode 100644 templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja diff --git a/copier.yml b/copier.yml index 887d50c..5e92e79 100644 --- a/copier.yml +++ b/copier.yml @@ -12,12 +12,12 @@ template: help: Template type: str default: ros2_cpp_pkg - choices: [ros2_cpp_pkg, ros2_interfaces_pkg] + choices: [ros2_cpp_pkg, ros2_interfaces_pkg, ros2_python_pkg] package_name: help: Package name type: str - placeholder: ros2_cpp_pkg + placeholder: "{{ template }}" validator: "{% if not package_name %}Package name is required{% endif %}" description: @@ -53,13 +53,13 @@ license: node_name: help: Node name - when: "{{ template == 'ros2_cpp_pkg' }}" + when: "{{ template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg' }}" type: str default: "{{ package_name }}" node_class_name: help: Class name of node - when: "{{ template == 'ros2_cpp_pkg' }}" + when: "{{ template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg' }}" type: str default: "{{ node_name | to_camel }}" @@ -77,56 +77,56 @@ is_lifecycle: has_launch_file: help: Add a launch file? - when: "{{ template == 'ros2_cpp_pkg' }}" + when: "{{ template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg' }}" type: bool default: true launch_file_type: help: Type of launch file - when: "{{ template == 'ros2_cpp_pkg' and has_launch_file }}" + when: "{{ template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg' }}" type: str default: py choices: [py, xml, yml] has_params: help: Add parameter loading? - when: "{{ template == 'ros2_cpp_pkg' }}" + when: "{{ template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg' }}" type: bool default: true has_subscriber: help: Add a subscriber? - when: "{{ template == 'ros2_cpp_pkg' }}" + when: "{{ template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg' }}" type: bool default: true has_publisher: help: Add a publisher? - when: "{{ template == 'ros2_cpp_pkg' }}" + when: "{{ template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg' }}" type: bool default: true has_service_server: help: Add a service server? - when: "{{ template == 'ros2_cpp_pkg' }}" + when: "{{ template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg' }}" type: bool default: false has_action_server: help: Add an action server? - when: "{{ template == 'ros2_cpp_pkg' }}" + when: "{{ template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg' }}" type: bool default: false has_timer: help: Add a timer callback? - when: "{{ template == 'ros2_cpp_pkg' }}" + when: "{{ template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg' }}" type: bool default: false auto_shutdown: help: Automatically shutdown the node after launch (useful in CI/CD)? - when: "{{ template == 'ros2_cpp_pkg' }}" + when: "{{ template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg' }}" when: false type: bool default: false diff --git a/templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/CMakeLists.txt.jinja b/templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/CMakeLists.txt.jinja new file mode 100644 index 0000000..d66679b --- /dev/null +++ b/templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/CMakeLists.txt.jinja @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 3.8) +project({{ package_name }}_interfaces) + +find_package(rosidl_default_generators REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + action/Fibonacci.action +) + +ament_export_dependencies(rosidl_default_runtime) + +ament_package() diff --git a/templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/action/Fibonacci.action b/templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/action/Fibonacci.action new file mode 100644 index 0000000..32b18f2 --- /dev/null +++ b/templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/action/Fibonacci.action @@ -0,0 +1,5 @@ +int32 order +--- +int32[] sequence +--- +int32[] partial_sequence \ No newline at end of file diff --git a/templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/package.xml.jinja b/templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/package.xml.jinja new file mode 100644 index 0000000..f7d17ba --- /dev/null +++ b/templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/package.xml.jinja @@ -0,0 +1,24 @@ + + + + + {{ package_name }}_interfaces + 0.0.0 + ROS interface definitions for {{ package_name }} + + {{ maintainer }} + {{ author }} + + {{ license }} + + ament_cmake + rosidl_default_generators + rosidl_default_runtime + + rosidl_interface_packages + + + ament_cmake + + + diff --git a/templates/ros2_python_pkg/{{ package_name }}/package.xml.jinja b/templates/ros2_python_pkg/{{ package_name }}/package.xml.jinja new file mode 100644 index 0000000..234e93f --- /dev/null +++ b/templates/ros2_python_pkg/{{ package_name }}/package.xml.jinja @@ -0,0 +1,22 @@ + + + + + {{ package_name }} + 0.0.0 + {{ description }} + + {{ maintainer }} + {{ author }} + + {{ license }} + + ament_python + + rclpy + + + ament_python + + + diff --git a/templates/ros2_python_pkg/{{ package_name }}/resource/{{ package_name }}.jinja b/templates/ros2_python_pkg/{{ package_name }}/resource/{{ package_name }}.jinja new file mode 100644 index 0000000..e69de29 diff --git a/templates/ros2_python_pkg/{{ package_name }}/setup.cfg.jinja b/templates/ros2_python_pkg/{{ package_name }}/setup.cfg.jinja new file mode 100644 index 0000000..e35a7b9 --- /dev/null +++ b/templates/ros2_python_pkg/{{ package_name }}/setup.cfg.jinja @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/{{ package_name }} +[install] +install_scripts=$base/lib/{{ package_name }} diff --git a/templates/ros2_python_pkg/{{ package_name }}/setup.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/setup.py.jinja new file mode 100644 index 0000000..6f65446 --- /dev/null +++ b/templates/ros2_python_pkg/{{ package_name }}/setup.py.jinja @@ -0,0 +1,29 @@ +import os +from glob import glob +from setuptools import setup + +package_name = '{{ package_name }}' + +setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + (os.path.join('share', package_name), ['package.xml']), + (os.path.join('share', package_name, + 'launch'), glob('launch/*launch.[pxy][yma]*')), + (os.path.join('share', package_name, + 'config'), glob('config/*.yaml'))], + install_requires=['setuptools'], + zip_safe=True, + maintainer='root', + maintainer_email='root@todo.todo', + description='TODO: Package description', + license='TODO: License declaration', + tests_require=['pytest'], + entry_points={ + 'console_scripts': + ['{{ node_name }} = {{ package_name }}.{{ node_name }}:main'], + }, +) diff --git a/templates/ros2_python_pkg/{{ package_name }}/{% if has_docker_ros %}.gitlab-ci.yml{% endif %}.jinja b/templates/ros2_python_pkg/{{ package_name }}/{% if has_docker_ros %}.gitlab-ci.yml{% endif %}.jinja new file mode 100644 index 0000000..c01306a --- /dev/null +++ b/templates/ros2_python_pkg/{{ package_name }}/{% if has_docker_ros %}.gitlab-ci.yml{% endif %}.jinja @@ -0,0 +1,8 @@ +include: + - remote: https://raw.githubusercontent.com/ika-rwth-aachen/docker-ros/main/.gitlab-ci/docker-ros.yml + +variables: + PLATFORM: amd64,arm64 + TARGET: dev,run + BASE_IMAGE: rwthika/ros2:latest + COMMAND: ros2 run {{ package_name }} {{ node_name }} diff --git a/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja new file mode 100644 index 0000000..8fbd350 --- /dev/null +++ b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja @@ -0,0 +1,42 @@ +#!/usr/bin/env python3 + +import os + +from ament_index_python import get_package_share_directory +from launch import LaunchDescription +{% if is_lifecycle %} +from launch.actions import DeclareLaunchArgument, GroupAction +from launch.conditions import LaunchConfigurationNotEquals +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import LifecycleNode, SetParameter +{% else %} +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node +{% endif %} + + +def generate_launch_description(): + + arg_name = DeclareLaunchArgument("name", default_value="{{ node_name }}", description="node name") + arg_namespace = DeclareLaunchArgument("namespace", default_value="", description="node namespace") + + node = Node( + package="{{ package_name }}", + executable="{{ node_name }}", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), +{% if has_params %} + parameters=[ + os.path.join(get_package_share_directory("{{ package_name }}"), "config", "params.yml"), + ], +{% endif %} + output="screen", + emulate_tty=True, + ) + + return LaunchDescription([ + arg_name, + arg_namespace, + node + ]) diff --git a/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja new file mode 100644 index 0000000..745aea4 --- /dev/null +++ b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja @@ -0,0 +1,12 @@ + + + + + + +{% if has_params %} + +{% endif %} + + + diff --git a/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'yml' %}{{ node_name }}_launch.yml{% endif %}.jinja b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'yml' %}{{ node_name }}_launch.yml{% endif %}.jinja new file mode 100644 index 0000000..3216122 --- /dev/null +++ b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'yml' %}{{ node_name }}_launch.yml{% endif %}.jinja @@ -0,0 +1,20 @@ +launch: + - arg: + name: name + default: {{ node_name }} + description: node name + - arg: + name: namespace + default: "" + description: node namespace + - node: + pkg: {{ package_name }} + exec: {{ node_name }} + namespace: "$(var namespace)" + name: "$(var name)" + output: screen +{% if has_params %} + param: + - name: param + value: 1.0 +{% endif %} diff --git a/templates/ros2_python_pkg/{{ package_name }}/{% if has_params %}config{% endif %}/params.yml.jinja b/templates/ros2_python_pkg/{{ package_name }}/{% if has_params %}config{% endif %}/params.yml.jinja new file mode 100644 index 0000000..809c91b --- /dev/null +++ b/templates/ros2_python_pkg/{{ package_name }}/{% if has_params %}config{% endif %}/params.yml.jinja @@ -0,0 +1,3 @@ +/**/*: + ros__parameters: + param: 1.0 \ No newline at end of file diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/__init__.py b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja new file mode 100644 index 0000000..c52c018 --- /dev/null +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -0,0 +1,19 @@ +import rclpy + +from rclpy import Node + + +class {{ node_class_name }}(Node): + def __init__(self): + pass + + +def main(): + + rclpy.init() + rclpy.spin({{ node_class_name }}()) + rclpy.shutdown() + + +if __name__ == "__main__": + main() From c4dbde0144c8a563017d56fc5f9f0e924102e50b Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 30 Sep 2024 23:26:34 +0000 Subject: [PATCH 33/67] prepare default python template node --- .../src/{{ node_name }}.cpp.jinja | 11 +- .../{{ node_name }}.py.jinja | 155 +++++++++++++++++- 2 files changed, 157 insertions(+), 9 deletions(-) diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja index 25cf7c4..3d81d6f 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja @@ -88,16 +88,16 @@ void {{ node_class_name }}::declareAndLoadParameter(const std::string& name, if (from_value.has_value() && to_value.has_value()) { if constexpr (std::is_integral_v) { rcl_interfaces::msg::IntegerRange range; - T step = static_cast(step_value.has_value() ? step_value.value() : 0); + T step = static_cast(step_value.has_value() ? step_value.value() : 1); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.integer_range = {range}; } else if constexpr (std::is_floating_point_v) { rcl_interfaces::msg::FloatingPointRange range; - T step = static_cast(step_value.has_value() ? step_value.value() : 0.0); + T step = static_cast(step_value.has_value() ? step_value.value() : 1.0); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.floating_point_range = {range}; } else { - RCLCPP_WARN(this->get_logger(), "Parameter type does not support specifying a range"); + RCLCPP_WARN(this->get_logger(), "Parameter type of parameter '%s' does not support specifying a range", name.c_str()); } } @@ -108,7 +108,7 @@ void {{ node_class_name }}::declareAndLoadParameter(const std::string& name, } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); - exit(EXIT_FAILURE); + exit(EXIT_FAILURE); // TODO: rclpy shutdown? } else { std::stringstream ss; ss << "Missing parameter '" << name << "', using default value: "; @@ -123,6 +123,7 @@ void {{ node_class_name }}::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { + // why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; @@ -145,11 +146,11 @@ rcl_interfaces::msg::SetParametersResult {{ node_class_name }}::parametersCallba for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { std::get<1>(auto_reconfigurable_param)(param); + break; } } } - // mark parameter change successful rcl_interfaces::msg::SetParametersResult result; result.successful = true; diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja index c52c018..dc74000 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -1,11 +1,158 @@ -import rclpy +# TODO: is_lifecycle +# TODO: has_service_server +# TODO: has_action_server +# TODO: has_timer +# TODO: auto_shutdown +import sys +from typing import Any, Optional, Union -from rclpy import Node +import rclpy +from rclpy.node import Node +from rcl_interfaces.msg import (FloatingPointRange, IntegerRange, ParameterDescriptor, SetParametersResult) +from std_msgs.msg import Int32 class {{ node_class_name }}(Node): + def __init__(self): - pass + """Constructor""" + + super().__init__("{{ node_name }}") + +{% if has_params %} + self.auto_reconfigurable_params = [] + self.parameters_callback = None +{% endif %} + self.subscriber = None + self.publisher = None + +{% if has_params %} + self.param = 1.0 + + self.param = self.declareAndLoadParameter(name="param", + param_type=rclpy.Parameter.Type.DOUBLE, + description="TODO", + default=self.param, + from_value=0.0, + to_value=10.0, + step_value=0.1) +{% endif %} + self.setup() + +{% if has_params %} + def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, description: str, default: Optional[Any] = None, add_to_auto_reconfigurable_params: bool = True, is_required: bool = False , read_only: bool = False, from_value: Optional[Union[int, float]] = None, to_value: Optional[Union[int, float]] = None, step_value: Optional[Union[int, float]] = None, additional_constraints: str = "") -> Any: + """Declares and loads a ROS parameter + + Args: + name (str): name + param_type (rclpy.Parameter.Type): parameter type + description (str): description + default (Optional[Any], optional): default value + add_to_auto_reconfigurable_params (bool, optional): enable reconfiguration of parameter + is_required (bool, optional): whether failure to load parameter will stop node + read_only (bool, optional): set parameter to read-only + from_value (Optional[Union[int, float]], optional): parameter range minimum + to_value (Optional[Union[int, float]], optional): parameter range maximum + step_value (Optional[Union[int, float]], optional): parameter range step + additional_constraints (str, optional): additional constraints description + + Returns: + Any: parameter value + """ + + param_desc = ParameterDescriptor() + param_desc.description = description + param_desc.additional_constraints = additional_constraints + param_desc.read_only = read_only + + if from_value is not None and to_value is not None: + if param_type == rclpy.Parameter.Type.INTEGER: + step_value = step_value if step_value is not None else 1 + param_desc.integer_range = [IntegerRange(from_value=from_value, to_value=to_value, step=step_value)] + elif param_type == rclpy.Parameter.Type.DOUBLE: + step_value = step_value if step_value is not None else 1.0 + param_desc.floating_point_range = [FloatingPointRange(from_value=from_value, to_value=to_value, step=step_value)] + else: + self.get_logger().warn(f"Parameter type of parameter '{name}' does not support specifying a range") + + self.declare_parameter(name, param_type, param_desc) + + try: + param = self.get_parameter(name).value + except rclpy.exceptions.ParameterUninitializedException: + if is_required: + self.get_logger().fatal(f"Missing required parameter '{name}', exiting") + sys.exit(1) # TODO: rclpy shutdown? + else: + self.get_logger().warn(f"Missing parameter '{name}', using default value: {default}") + param = default + + if add_to_auto_reconfigurable_params: + # TODO: this probably doesn't work + self.auto_reconfigurable_params.append((name, param)) + + return param + + def parametersCallback(self, + parameters: rclpy.Parameter) -> SetParametersResult: + """Handles reconfiguration when a parameter value is changed + + Args: + parameters (rclpy.Parameter): parameters + + Returns: + SetParametersResult: parameter change result + """ + + for param in parameters: + for auto_reconfigurable_param in self.auto_reconfigurable_params: + if param.name == auto_reconfigurable_param[0]: + # TODO: this probably doesn't work + auto_reconfigurable_param[1] = param.value + break + + result = SetParametersResult() + result.successful = True + + return result +{% endif %} + + def setup(self): + """Sets up subscribers, publishers, etc. to configure the node""" +{% if has_params %} + + # callback for dynamic parameter configuration + self.parameters_callback = self.add_on_set_parameters_callback( + self.parametersCallback) +{% endif %} +{% if has_subscriber %} + + # subscriber for handling incoming messages + self.subscriber = self.create_subscription(Int32, + "~/input", + self.topicCallback, + qos_profile=10) + self.get_logger().info(f"Subscribed to '{self.subscriber.topic_name}'") +{% endif %} +{% if has_publisher %} + + # publisher for publishing messages + self.publisher = self.create_publisher(Int32, + "~/output", + qos_profile=10) + self.get_logger().info(f"Publishing to '{self.publisher.topic_name}'") +{% endif %} +{% if has_subscriber %} + + def topicCallback(self, msg: Int32): + """Processes messages received by a subscriber + + Args: + msg (Int32): message + """ + + rclpy.get_logger().info(f"Message received: '{msg.data}'") +{% endif %} def main(): @@ -15,5 +162,5 @@ def main(): rclpy.shutdown() -if __name__ == "__main__": +if __name__ == '__main__': main() From 797385682a26ddf7a7383ef0ebbaf4585823d1a7 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 30 Sep 2024 23:28:48 +0000 Subject: [PATCH 34/67] add python template to ci --- .github/workflows/check-samples.yml | 11 ++ .github/workflows/generate-and-test.yml | 114 +++++++++---- samples/ros2_python_pkg/config/params.yml | 3 + .../launch/ros2_python_node_launch.py | 33 ++++ samples/ros2_python_pkg/package.xml | 22 +++ .../ros2_python_pkg/resource/ros2_python_pkg | 0 .../ros2_python_pkg/__init__.py | 0 .../ros2_python_pkg/ros2_python_node.py | 152 ++++++++++++++++++ samples/ros2_python_pkg/setup.cfg | 4 + samples/ros2_python_pkg/setup.py | 29 ++++ 10 files changed, 336 insertions(+), 32 deletions(-) create mode 100644 samples/ros2_python_pkg/config/params.yml create mode 100644 samples/ros2_python_pkg/launch/ros2_python_node_launch.py create mode 100644 samples/ros2_python_pkg/package.xml create mode 100644 samples/ros2_python_pkg/resource/ros2_python_pkg create mode 100644 samples/ros2_python_pkg/ros2_python_pkg/__init__.py create mode 100644 samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py create mode 100644 samples/ros2_python_pkg/setup.cfg create mode 100644 samples/ros2_python_pkg/setup.py diff --git a/.github/workflows/check-samples.yml b/.github/workflows/check-samples.yml index 189d741..44a5881 100644 --- a/.github/workflows/check-samples.yml +++ b/.github/workflows/check-samples.yml @@ -47,6 +47,17 @@ jobs: has_service_server: false has_action_server: false has_timer: false + - package_name: ros2_python_pkg + template: ros2_python_pkg + node_name: ros2_python_node + is_lifecycle: false + has_launch_file: true + has_params: true + has_subscriber: true + has_publisher: true + has_service_server: false + has_action_server: false + has_timer: false - package_name: ros2_interfaces_pkg template: ros2_interfaces_pkg steps: diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index b90c938..74742b0 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -11,38 +11,38 @@ jobs: strategy: matrix: include: - - package_name: pkg_default + - package_name: default_cpp_pkg template: ros2_cpp_pkg auto_shutdown: true - - package_name: pkg_component + - package_name: component_cpp_pkg template: ros2_cpp_pkg is_component: true auto_shutdown: true - - package_name: pkg_lifecycle + - package_name: lifecycle_cpp_pkg template: ros2_cpp_pkg is_lifecycle: true auto_shutdown: true - - package_name: pkg_service + - package_name: service_cpp_pkg template: ros2_cpp_pkg has_service_server: true auto_shutdown: true - - package_name: pkg_action + - package_name: action_cpp_pkg template: ros2_cpp_pkg has_action_server: true auto_shutdown: true - - package_name: pkg_timer + - package_name: timer_cpp_pkg template: ros2_cpp_pkg has_timer: true auto_shutdown: true - - package_name: pkg_no_params + - package_name: no_params_cpp_pkg template: ros2_cpp_pkg has_params: false auto_shutdown: true - - package_name: pkg_no_launch_file + - package_name: no_launch_file_cpp_pkg template: ros2_cpp_pkg has_launch_file: false auto_shutdown: true - - package_name: pkg_all + - package_name: all_cpp_pkg template: ros2_cpp_pkg is_component: true is_lifecycle: true @@ -50,7 +50,41 @@ jobs: has_action_server: true has_timer: true auto_shutdown: true - - package_name: pkg_interfaces + - package_name: default_python_pkg + template: ros2_python_pkg + auto_shutdown: true + - package_name: lifecycle_python_pkg + template: ros2_python_pkg + is_lifecycle: true + auto_shutdown: true + - package_name: service_python_pkg + template: ros2_python_pkg + has_service_server: true + auto_shutdown: true + - package_name: action_python_pkg + template: ros2_python_pkg + has_action_server: true + auto_shutdown: true + - package_name: timer_python_pkg + template: ros2_python_pkg + has_timer: true + auto_shutdown: true + - package_name: no_params_python_pkg + template: ros2_python_pkg + has_params: false + auto_shutdown: true + - package_name: no_launch_file_python_pkg + template: ros2_python_pkg + has_launch_file: false + auto_shutdown: true + - package_name: all_python_pkg + template: ros2_python_pkg + is_lifecycle: true + has_service_server: true + has_action_server: true + has_timer: true + auto_shutdown: true + - package_name: interfaces_pkg template: ros2_interfaces_pkg steps: - name: Checkout code @@ -95,29 +129,45 @@ jobs: strategy: matrix: include: - - package: pkg_default - command: ros2 launch pkg_default pkg_default_launch.py - - package: pkg_component - command: ros2 launch pkg_component pkg_component_launch.py - - package: pkg_lifecycle - command: ros2 launch pkg_lifecycle pkg_lifecycle_launch.py - - package: pkg_service - command: ros2 launch pkg_service pkg_service_launch.py - - package: pkg_action - command: ros2 launch pkg_action pkg_action_launch.py - - package: pkg_timer - command: ros2 launch pkg_timer pkg_timer_launch.py - - package: pkg_no_params - command: ros2 launch pkg_no_params pkg_no_params_launch.py - - package: pkg_no_launch_file - command: ros2 run pkg_no_launch_file pkg_no_launch_file --ros-args -p param:=1.0 - - package: pkg_all - command: ros2 launch pkg_all pkg_all_launch.py - - package: pkg_interfaces + - package: default_cpp_pkg + command: ros2 launch default_cpp_pkg default_cpp_pkg_launch.py + - package: component_cpp_pkg + command: ros2 launch component_cpp_pkg component_cpp_pkg_launch.py + - package: lifecycle_cpp_pkg + command: ros2 launch lifecycle_cpp_pkg lifecycle_cpp_pkg_launch.py + - package: service_cpp_pkg + command: ros2 launch service_cpp_pkg service_cpp_pkg_launch.py + - package: action_cpp_pkg + command: ros2 launch action_cpp_pkg action_cpp_pkg_launch.py + - package: timer_cpp_pkg + command: ros2 launch timer_cpp_pkg timer_cpp_pkg_launch.py + - package: no_params_cpp_pkg + command: ros2 launch no_params_cpp_pkg no_params_cpp_pkg_launch.py + - package: no_launch_file_cpp_pkg + command: ros2 run no_launch_file_cpp_pkg no_launch_file_cpp_pkg --ros-args -p param:=1.0 + - package: all_cpp_pkg + command: ros2 launch all_cpp_pkg all_cpp_pkg_launch.py + - package: default_python_pkg + command: ros2 launch default_python_pkg default_python_pkg_launch.py + - package: lifecycle_python_pkg + command: ros2 launch lifecycle_python_pkg lifecycle_python_pkg_launch.py + - package: service_python_pkg + command: ros2 launch service_python_pkg service_python_pkg_launch.py + - package: action_python_pkg + command: ros2 launch action_python_pkg action_python_pkg_launch.py + - package: timer_python_pkg + command: ros2 launch timer_python_pkg timer_python_pkg_launch.py + - package: no_params_python_pkg + command: ros2 launch no_params_python_pkg no_params_python_pkg_launch.py + - package: no_launch_file_python_pkg + command: ros2 run no_launch_file_python_pkg no_launch_file_python_pkg --ros-args -p param:=1.0 + - package: all_python_pkg + command: ros2 launch all_python_pkg all_python_pkg_launch.py + - package: interfaces_pkg command: | - ros2 interface show pkg_interfaces/msg/Message && \ - ros2 interface show pkg_interfaces/srv/Service && \ - ros2 interface show pkg_interfaces/action/Action + ros2 interface show interfaces_pkg/msg/Message && \ + ros2 interface show interfaces_pkg/srv/Service && \ + ros2 interface show interfaces_pkg/action/Action steps: - name: Checkout code uses: actions/checkout@v4 diff --git a/samples/ros2_python_pkg/config/params.yml b/samples/ros2_python_pkg/config/params.yml new file mode 100644 index 0000000..809c91b --- /dev/null +++ b/samples/ros2_python_pkg/config/params.yml @@ -0,0 +1,3 @@ +/**/*: + ros__parameters: + param: 1.0 \ No newline at end of file diff --git a/samples/ros2_python_pkg/launch/ros2_python_node_launch.py b/samples/ros2_python_pkg/launch/ros2_python_node_launch.py new file mode 100644 index 0000000..5fb8372 --- /dev/null +++ b/samples/ros2_python_pkg/launch/ros2_python_node_launch.py @@ -0,0 +1,33 @@ +#!/usr/bin/env python3 + +import os + +from ament_index_python import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + + +def generate_launch_description(): + + arg_name = DeclareLaunchArgument("name", default_value="ros2_python_node", description="node name") + arg_namespace = DeclareLaunchArgument("namespace", default_value="", description="node namespace") + + node = Node( + package="ros2_python_pkg", + executable="ros2_python_node", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), + parameters=[ + os.path.join(get_package_share_directory("ros2_python_pkg"), "config", "params.yml"), + ], + output="screen", + emulate_tty=True, + ) + + return LaunchDescription([ + arg_name, + arg_namespace, + node + ]) diff --git a/samples/ros2_python_pkg/package.xml b/samples/ros2_python_pkg/package.xml new file mode 100644 index 0000000..24cf684 --- /dev/null +++ b/samples/ros2_python_pkg/package.xml @@ -0,0 +1,22 @@ + + + + + ros2_python_pkg + 0.0.0 + TODO + + TODO + TODO + + TODO + + ament_python + + rclpy + + + ament_python + + + diff --git a/samples/ros2_python_pkg/resource/ros2_python_pkg b/samples/ros2_python_pkg/resource/ros2_python_pkg new file mode 100644 index 0000000..e69de29 diff --git a/samples/ros2_python_pkg/ros2_python_pkg/__init__.py b/samples/ros2_python_pkg/ros2_python_pkg/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py new file mode 100644 index 0000000..cf937bb --- /dev/null +++ b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py @@ -0,0 +1,152 @@ +# TODO: is_lifecycle +# TODO: has_service_server +# TODO: has_action_server +# TODO: has_timer +# TODO: auto_shutdown +import sys +from typing import Any, Optional, Union + +import rclpy +from rclpy.node import Node +from rcl_interfaces.msg import (FloatingPointRange, IntegerRange, ParameterDescriptor, SetParametersResult) +from std_msgs.msg import Int32 + + +class Ros2PythonNode(Node): + + def __init__(self): + """Constructor""" + + super().__init__("ros2_python_node") + + self.auto_reconfigurable_params = [] + self.parameters_callback = None + self.subscriber = None + self.publisher = None + + self.param = 1.0 + + self.param = self.declareAndLoadParameter(name="param", + param_type=rclpy.Parameter.Type.DOUBLE, + description="TODO", + default=self.param, + from_value=0.0, + to_value=10.0, + step_value=0.1) + self.setup() + + def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, description: str, default: Optional[Any] = None, add_to_auto_reconfigurable_params: bool = True, is_required: bool = False , read_only: bool = False, from_value: Optional[Union[int, float]] = None, to_value: Optional[Union[int, float]] = None, step_value: Optional[Union[int, float]] = None, additional_constraints: str = "") -> Any: + """Declares and loads a ROS parameter + + Args: + name (str): name + param_type (rclpy.Parameter.Type): parameter type + description (str): description + default (Optional[Any], optional): default value + add_to_auto_reconfigurable_params (bool, optional): enable reconfiguration of parameter + is_required (bool, optional): whether failure to load parameter will stop node + read_only (bool, optional): set parameter to read-only + from_value (Optional[Union[int, float]], optional): parameter range minimum + to_value (Optional[Union[int, float]], optional): parameter range maximum + step_value (Optional[Union[int, float]], optional): parameter range step + additional_constraints (str, optional): additional constraints description + + Returns: + Any: parameter value + """ + + param_desc = ParameterDescriptor() + param_desc.description = description + param_desc.additional_constraints = additional_constraints + param_desc.read_only = read_only + + if from_value is not None and to_value is not None: + if param_type == rclpy.Parameter.Type.INTEGER: + step_value = step_value if step_value is not None else 1 + param_desc.integer_range = [IntegerRange(from_value=from_value, to_value=to_value, step=step_value)] + elif param_type == rclpy.Parameter.Type.DOUBLE: + step_value = step_value if step_value is not None else 1.0 + param_desc.floating_point_range = [FloatingPointRange(from_value=from_value, to_value=to_value, step=step_value)] + else: + self.get_logger().warn(f"Parameter type of parameter '{name}' does not support specifying a range") + + self.declare_parameter(name, param_type, param_desc) + + try: + param = self.get_parameter(name).value + except rclpy.exceptions.ParameterUninitializedException: + if is_required: + self.get_logger().fatal(f"Missing required parameter '{name}', exiting") + sys.exit(1) # TODO: rclpy shutdown? + else: + self.get_logger().warn(f"Missing parameter '{name}', using default value: {default}") + param = default + + if add_to_auto_reconfigurable_params: + # TODO: this probably doesn't work + self.auto_reconfigurable_params.append((name, param)) + + return param + + def parametersCallback(self, + parameters: rclpy.Parameter) -> SetParametersResult: + """Handles reconfiguration when a parameter value is changed + + Args: + parameters (rclpy.Parameter): parameters + + Returns: + SetParametersResult: parameter change result + """ + + for param in parameters: + for auto_reconfigurable_param in self.auto_reconfigurable_params: + if param.name == auto_reconfigurable_param[0]: + # TODO: this probably doesn't work + auto_reconfigurable_param[1] = param.value + break + + result = SetParametersResult() + result.successful = True + + return result + + def setup(self): + """Sets up subscribers, publishers, etc. to configure the node""" + + # callback for dynamic parameter configuration + self.parameters_callback = self.add_on_set_parameters_callback( + self.parametersCallback) + + # subscriber for handling incoming messages + self.subscriber = self.create_subscription(Int32, + "~/input", + self.topicCallback, + qos_profile=10) + self.get_logger().info(f"Subscribed to '{self.subscriber.topic_name}'") + + # publisher for publishing messages + self.publisher = self.create_publisher(Int32, + "~/output", + qos_profile=10) + self.get_logger().info(f"Publishing to '{self.publisher.topic_name}'") + + def topicCallback(self, msg: Int32): + """Processes messages received by a subscriber + + Args: + msg (Int32): message + """ + + rclpy.get_logger().info(f"Message received: '{msg.data}'") + + +def main(): + + rclpy.init() + rclpy.spin(Ros2PythonNode()) + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/samples/ros2_python_pkg/setup.cfg b/samples/ros2_python_pkg/setup.cfg new file mode 100644 index 0000000..6d39edb --- /dev/null +++ b/samples/ros2_python_pkg/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/ros2_python_pkg +[install] +install_scripts=$base/lib/ros2_python_pkg diff --git a/samples/ros2_python_pkg/setup.py b/samples/ros2_python_pkg/setup.py new file mode 100644 index 0000000..c7e404f --- /dev/null +++ b/samples/ros2_python_pkg/setup.py @@ -0,0 +1,29 @@ +import os +from glob import glob +from setuptools import setup + +package_name = 'ros2_python_pkg' + +setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + (os.path.join('share', package_name), ['package.xml']), + (os.path.join('share', package_name, + 'launch'), glob('launch/*launch.[pxy][yma]*')), + (os.path.join('share', package_name, + 'config'), glob('config/*.yaml'))], + install_requires=['setuptools'], + zip_safe=True, + maintainer='root', + maintainer_email='root@todo.todo', + description='TODO: Package description', + license='TODO: License declaration', + tests_require=['pytest'], + entry_points={ + 'console_scripts': + ['ros2_python_node = ros2_python_pkg.ros2_python_node:main'], + }, +) From 28fc442437ad103a94a7d48bdfb5c5df26318b01 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 22:35:11 +0200 Subject: [PATCH 35/67] improve python launch file template --- .../launch/ros2_cpp_node_launch.py | 34 ++++---- .../src/ros2_cpp_node.cpp | 11 +-- .../launch/ros2_cpp_lifecycle_node_launch.py | 59 +++++++------- .../src/ros2_cpp_lifecycle_node.cpp | 11 +-- .../launch/ros2_cpp_node_launch.py | 34 ++++---- samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp | 11 +-- .../launch/ros2_python_node_launch.py | 34 ++++---- ...{{ node_name }}_launch.py{% endif %}.jinja | 81 ++++++++++--------- ...{{ node_name }}_launch.py{% endif %}.jinja | 43 +++++----- 9 files changed, 165 insertions(+), 153 deletions(-) diff --git a/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py index cf54c4b..66440fb 100644 --- a/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py +++ b/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py @@ -11,23 +11,25 @@ def generate_launch_description(): - arg_name = DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name") - arg_namespace = DeclareLaunchArgument("namespace", default_value="", description="node namespace") + args = [ + DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name"), + DeclareLaunchArgument("namespace", default_value="", description="node namespace"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + ] - node = Node( - package="ros2_cpp_component_pkg", - executable="ros2_cpp_node", - namespace=LaunchConfiguration("namespace"), - name=LaunchConfiguration("name"), - parameters=[ - os.path.join(get_package_share_directory("ros2_cpp_component_pkg"), "config", "params.yml"), - ], - output="screen", - emulate_tty=True, - ) + nodes = [ + Node( + package="ros2_cpp_component_pkg", + executable="ros2_cpp_node", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), + parameters=[LaunchConfiguration("params")], + output="screen", + emulate_tty=True, + ) + ] return LaunchDescription([ - arg_name, - arg_namespace, - node + *args, + *nodes, ]) diff --git a/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp index 67d06b4..5225a8a 100644 --- a/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp @@ -57,16 +57,16 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, if (from_value.has_value() && to_value.has_value()) { if constexpr (std::is_integral_v) { rcl_interfaces::msg::IntegerRange range; - T step = static_cast(step_value.has_value() ? step_value.value() : 0); + T step = static_cast(step_value.has_value() ? step_value.value() : 1); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.integer_range = {range}; } else if constexpr (std::is_floating_point_v) { rcl_interfaces::msg::FloatingPointRange range; - T step = static_cast(step_value.has_value() ? step_value.value() : 0.0); + T step = static_cast(step_value.has_value() ? step_value.value() : 1.0); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.floating_point_range = {range}; } else { - RCLCPP_WARN(this->get_logger(), "Parameter type does not support specifying a range"); + RCLCPP_WARN(this->get_logger(), "Parameter type of parameter '%s' does not support specifying a range", name.c_str()); } } @@ -77,7 +77,7 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); - exit(EXIT_FAILURE); + exit(EXIT_FAILURE); // TODO: rclpy shutdown? } else { std::stringstream ss; ss << "Missing parameter '" << name << "', using default value: "; @@ -92,6 +92,7 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { + // why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; @@ -112,11 +113,11 @@ rcl_interfaces::msg::SetParametersResult Ros2CppNode::parametersCallback(const s for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { std::get<1>(auto_reconfigurable_param)(param); + break; } } } - // mark parameter change successful rcl_interfaces::msg::SetParametersResult result; result.successful = true; diff --git a/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_lifecycle_node_launch.py b/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_lifecycle_node_launch.py index 693b511..0bad658 100644 --- a/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_lifecycle_node_launch.py +++ b/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_lifecycle_node_launch.py @@ -12,36 +12,35 @@ def generate_launch_description(): - arg_name = DeclareLaunchArgument("name", default_value="ros2_cpp_lifecycle_node", description="node name") - arg_namespace = DeclareLaunchArgument("namespace", default_value="", description="node namespace") - arg_startup_state = DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state") - - node = LifecycleNode( - package="ros2_cpp_lifecycle_pkg", - executable="ros2_cpp_lifecycle_node", - namespace=LaunchConfiguration("namespace"), - name=LaunchConfiguration("name"), - parameters=[ - os.path.join(get_package_share_directory("ros2_cpp_lifecycle_pkg"), "config", "params.yml"), - ], - output="screen", - emulate_tty=True, - ) - - node_with_startup_state = GroupAction( - actions=[ - SetParameter( - name="startup_state", - value=LaunchConfiguration("startup_state"), - condition=LaunchConfigurationNotEquals("startup_state", "None") - ), - node - ] - ) + args = [ + DeclareLaunchArgument("name", default_value="ros2_cpp_lifecycle_node", description="node name"), + DeclareLaunchArgument("namespace", default_value="", description="node namespace"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state"), + ] + + nodes = [ + GroupAction( + actions=[ + SetParameter( + name="startup_state", + value=LaunchConfiguration("startup_state"), + condition=LaunchConfigurationNotEquals("startup_state", "None") + ), + LifecycleNode( + package="event_detector", + executable="event_detector", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), + parameters=[LaunchConfiguration("params")], + output="screen", + emulate_tty=True, + ) + ] + ) + ] return LaunchDescription([ - arg_name, - arg_namespace, - arg_startup_state, - node_with_startup_state, + *args, + *nodes, ]) diff --git a/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_lifecycle_node.cpp b/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_lifecycle_node.cpp index b79f4a0..8a84fec 100644 --- a/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_lifecycle_node.cpp +++ b/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_lifecycle_node.cpp @@ -59,16 +59,16 @@ void Ros2CppLifecycleNode::declareAndLoadParameter(const std::string& name, if (from_value.has_value() && to_value.has_value()) { if constexpr (std::is_integral_v) { rcl_interfaces::msg::IntegerRange range; - T step = static_cast(step_value.has_value() ? step_value.value() : 0); + T step = static_cast(step_value.has_value() ? step_value.value() : 1); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.integer_range = {range}; } else if constexpr (std::is_floating_point_v) { rcl_interfaces::msg::FloatingPointRange range; - T step = static_cast(step_value.has_value() ? step_value.value() : 0.0); + T step = static_cast(step_value.has_value() ? step_value.value() : 1.0); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.floating_point_range = {range}; } else { - RCLCPP_WARN(this->get_logger(), "Parameter type does not support specifying a range"); + RCLCPP_WARN(this->get_logger(), "Parameter type of parameter '%s' does not support specifying a range", name.c_str()); } } @@ -79,7 +79,7 @@ void Ros2CppLifecycleNode::declareAndLoadParameter(const std::string& name, } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); - exit(EXIT_FAILURE); + exit(EXIT_FAILURE); // TODO: rclpy shutdown? } else { std::stringstream ss; ss << "Missing parameter '" << name << "', using default value: "; @@ -94,6 +94,7 @@ void Ros2CppLifecycleNode::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { + // why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; @@ -114,11 +115,11 @@ rcl_interfaces::msg::SetParametersResult Ros2CppLifecycleNode::parametersCallbac for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { std::get<1>(auto_reconfigurable_param)(param); + break; } } } - // mark parameter change successful rcl_interfaces::msg::SetParametersResult result; result.successful = true; diff --git a/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py index d530982..f4d5597 100644 --- a/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py +++ b/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py @@ -11,23 +11,25 @@ def generate_launch_description(): - arg_name = DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name") - arg_namespace = DeclareLaunchArgument("namespace", default_value="", description="node namespace") + args = [ + DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name"), + DeclareLaunchArgument("namespace", default_value="", description="node namespace"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + ] - node = Node( - package="ros2_cpp_pkg", - executable="ros2_cpp_node", - namespace=LaunchConfiguration("namespace"), - name=LaunchConfiguration("name"), - parameters=[ - os.path.join(get_package_share_directory("ros2_cpp_pkg"), "config", "params.yml"), - ], - output="screen", - emulate_tty=True, - ) + nodes = [ + Node( + package="ros2_cpp_pkg", + executable="ros2_cpp_node", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), + parameters=[LaunchConfiguration("params")], + output="screen", + emulate_tty=True, + ) + ] return LaunchDescription([ - arg_name, - arg_namespace, - node + *args, + *nodes, ]) diff --git a/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp index 0670004..57b4cc2 100644 --- a/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp @@ -54,16 +54,16 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, if (from_value.has_value() && to_value.has_value()) { if constexpr (std::is_integral_v) { rcl_interfaces::msg::IntegerRange range; - T step = static_cast(step_value.has_value() ? step_value.value() : 0); + T step = static_cast(step_value.has_value() ? step_value.value() : 1); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.integer_range = {range}; } else if constexpr (std::is_floating_point_v) { rcl_interfaces::msg::FloatingPointRange range; - T step = static_cast(step_value.has_value() ? step_value.value() : 0.0); + T step = static_cast(step_value.has_value() ? step_value.value() : 1.0); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.floating_point_range = {range}; } else { - RCLCPP_WARN(this->get_logger(), "Parameter type does not support specifying a range"); + RCLCPP_WARN(this->get_logger(), "Parameter type of parameter '%s' does not support specifying a range", name.c_str()); } } @@ -74,7 +74,7 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); - exit(EXIT_FAILURE); + exit(EXIT_FAILURE); // TODO: rclpy shutdown? } else { std::stringstream ss; ss << "Missing parameter '" << name << "', using default value: "; @@ -89,6 +89,7 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { + // why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; @@ -109,11 +110,11 @@ rcl_interfaces::msg::SetParametersResult Ros2CppNode::parametersCallback(const s for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { std::get<1>(auto_reconfigurable_param)(param); + break; } } } - // mark parameter change successful rcl_interfaces::msg::SetParametersResult result; result.successful = true; diff --git a/samples/ros2_python_pkg/launch/ros2_python_node_launch.py b/samples/ros2_python_pkg/launch/ros2_python_node_launch.py index 5fb8372..b073324 100644 --- a/samples/ros2_python_pkg/launch/ros2_python_node_launch.py +++ b/samples/ros2_python_pkg/launch/ros2_python_node_launch.py @@ -11,23 +11,25 @@ def generate_launch_description(): - arg_name = DeclareLaunchArgument("name", default_value="ros2_python_node", description="node name") - arg_namespace = DeclareLaunchArgument("namespace", default_value="", description="node namespace") + args = [ + DeclareLaunchArgument("name", default_value="ros2_python_node", description="node name"), + DeclareLaunchArgument("namespace", default_value="", description="node namespace"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + ] - node = Node( - package="ros2_python_pkg", - executable="ros2_python_node", - namespace=LaunchConfiguration("namespace"), - name=LaunchConfiguration("name"), - parameters=[ - os.path.join(get_package_share_directory("ros2_python_pkg"), "config", "params.yml"), - ], - output="screen", - emulate_tty=True, - ) + nodes = [ + Node( + package="ros2_python_pkg", + executable="ros2_python_node", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), + parameters=[LaunchConfiguration("params")], + output="screen", + emulate_tty=True, + ) + ] return LaunchDescription([ - arg_name, - arg_namespace, - node + *args, + *nodes, ]) diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja index 3a398d2..7fe8b18 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja @@ -18,52 +18,59 @@ from launch_ros.actions import Node def generate_launch_description(): - arg_name = DeclareLaunchArgument("name", default_value="{{ node_name }}", description="node name") - arg_namespace = DeclareLaunchArgument("namespace", default_value="", description="node namespace") + args = [ + DeclareLaunchArgument("name", default_value="{{ node_name }}", description="node name"), + DeclareLaunchArgument("namespace", default_value="", description="node namespace"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), {% if is_lifecycle %} - arg_startup_state = DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state") + DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state"), {% endif %} + ] {% if is_lifecycle %} - node = LifecycleNode( + nodes = [ + GroupAction( + actions=[ + SetParameter( + name="startup_state", + value=LaunchConfiguration("startup_state"), + condition=LaunchConfigurationNotEquals("startup_state", "None") + ), + LifecycleNode( + package="event_detector", + executable="event_detector", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), +{% if has_params %} + parameters=[LaunchConfiguration("params")], {% else %} - node = Node( + parameters=[], {% endif %} - package="{{ package_name }}", - executable="{{ node_name }}", - namespace=LaunchConfiguration("namespace"), - name=LaunchConfiguration("name"), + output="screen", + emulate_tty=True, + ) + ] + ) + ] +{% else %} + nodes = [ + Node( + package="{{ package_name }}", + executable="{{ node_name }}", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), {% if has_params %} - parameters=[ - os.path.join(get_package_share_directory("{{ package_name }}"), "config", "params.yml"), - ], + parameters=[LaunchConfiguration("params")], +{% else %} + parameters=[], {% endif %} - output="screen", - emulate_tty=True, - ) -{% if is_lifecycle %} - - node_with_startup_state = GroupAction( - actions=[ - SetParameter( - name="startup_state", - value=LaunchConfiguration("startup_state"), - condition=LaunchConfigurationNotEquals("startup_state", "None") - ), - node - ] - ) + output="screen", + emulate_tty=True, + ) + ] {% endif %} return LaunchDescription([ - arg_name, - arg_namespace, -{% if is_lifecycle %} - arg_startup_state, -{% endif %} -{% if is_lifecycle %} - node_with_startup_state, -{% else %} - node -{% endif %} + *args, + *nodes, ]) diff --git a/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja index 8fbd350..6ef4e0c 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja @@ -4,39 +4,36 @@ import os from ament_index_python import get_package_share_directory from launch import LaunchDescription -{% if is_lifecycle %} -from launch.actions import DeclareLaunchArgument, GroupAction -from launch.conditions import LaunchConfigurationNotEquals -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import LifecycleNode, SetParameter -{% else %} from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node -{% endif %} def generate_launch_description(): - arg_name = DeclareLaunchArgument("name", default_value="{{ node_name }}", description="node name") - arg_namespace = DeclareLaunchArgument("namespace", default_value="", description="node namespace") + args = [ + DeclareLaunchArgument("name", default_value="{{ node_name }}", description="node name"), + DeclareLaunchArgument("namespace", default_value="", description="node namespace"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + ] - node = Node( - package="{{ package_name }}", - executable="{{ node_name }}", - namespace=LaunchConfiguration("namespace"), - name=LaunchConfiguration("name"), + nodes = [ + Node( + package="{{ package_name }}", + executable="{{ node_name }}", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), {% if has_params %} - parameters=[ - os.path.join(get_package_share_directory("{{ package_name }}"), "config", "params.yml"), - ], + parameters=[LaunchConfiguration("params")], +{% else %} + parameters=[], {% endif %} - output="screen", - emulate_tty=True, - ) + output="screen", + emulate_tty=True, + ) + ] return LaunchDescription([ - arg_name, - arg_namespace, - node + *args, + *nodes, ]) From e6ba2ea32fbb65dba0e4c6d4e3f4f26d18587714 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 22:41:29 +0200 Subject: [PATCH 36/67] add support for timer in python template --- .../src/{{ node_name }}.cpp.jinja | 2 +- .../{{ node_name }}.py.jinja | 21 ++++++++++++++----- 2 files changed, 17 insertions(+), 6 deletions(-) diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja index 3d81d6f..8db8e81 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja @@ -199,7 +199,7 @@ void {{ node_class_name }}::setup() { {% if has_timer and not is_lifecycle %} // timer for repeatedly invoking a callback to publish messages - timer_ = this->create_wall_timer(std::chrono::duration(param_), std::bind(&{{ node_class_name }}::timerCallback, this)); + timer_ = this->create_wall_timer(std::chrono::duration(1.0), std::bind(&{{ node_class_name }}::timerCallback, this)); {% endif %} {% if auto_shutdown and not is_lifecycle %} diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja index dc74000..0bbac69 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -1,7 +1,6 @@ # TODO: is_lifecycle # TODO: has_service_server # TODO: has_action_server -# TODO: has_timer # TODO: auto_shutdown import sys from typing import Any, Optional, Union @@ -37,7 +36,7 @@ class {{ node_class_name }}(Node): to_value=10.0, step_value=0.1) {% endif %} - self.setup() + self.setup() {% if has_params %} def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, description: str, default: Optional[Any] = None, add_to_auto_reconfigurable_params: bool = True, is_required: bool = False , read_only: bool = False, from_value: Optional[Union[int, float]] = None, to_value: Optional[Union[int, float]] = None, step_value: Optional[Union[int, float]] = None, additional_constraints: str = "") -> Any: @@ -55,7 +54,7 @@ class {{ node_class_name }}(Node): to_value (Optional[Union[int, float]], optional): parameter range maximum step_value (Optional[Union[int, float]], optional): parameter range step additional_constraints (str, optional): additional constraints description - + Returns: Any: parameter value """ @@ -86,7 +85,7 @@ class {{ node_class_name }}(Node): else: self.get_logger().warn(f"Missing parameter '{name}', using default value: {default}") param = default - + if add_to_auto_reconfigurable_params: # TODO: this probably doesn't work self.auto_reconfigurable_params.append((name, param)) @@ -136,12 +135,16 @@ class {{ node_class_name }}(Node): {% endif %} {% if has_publisher %} - # publisher for publishing messages + # publisher for publishing outgoing messages self.publisher = self.create_publisher(Int32, "~/output", qos_profile=10) self.get_logger().info(f"Publishing to '{self.publisher.topic_name}'") {% endif %} +{% if has_timer %} + + # timer for repeatedly invoking a callback to publish messages + self.timer = self.create_timer(1.0, self.timerCallback) {% if has_subscriber %} def topicCallback(self, msg: Int32): @@ -153,6 +156,14 @@ class {{ node_class_name }}(Node): rclpy.get_logger().info(f"Message received: '{msg.data}'") {% endif %} +{% if has_timer %} + + def timerCallback(self): + """Processes timer triggers + """ + + rclpy.get_logger().info("Timer triggered") +{% endif %} def main(): From bb9cf15b167e9c660a00187e93e9d931c7d0306c Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 22:47:59 +0200 Subject: [PATCH 37/67] add support for service server in python template --- .../{{ node_name }}.py.jinja | 31 ++++++++++++++++++- 1 file changed, 30 insertions(+), 1 deletion(-) diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja index 0bbac69..487f09d 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -1,5 +1,4 @@ # TODO: is_lifecycle -# TODO: has_service_server # TODO: has_action_server # TODO: auto_shutdown import sys @@ -7,8 +6,15 @@ from typing import Any, Optional, Union import rclpy from rclpy.node import Node +{% if has_params %} from rcl_interfaces.msg import (FloatingPointRange, IntegerRange, ParameterDescriptor, SetParametersResult) +{% endif %} +{% if has_subscriber or has_publisher %} from std_msgs.msg import Int32 +{% endif %} +{% if has_service_server %} +from std_srvs.srv import SetBool +{% endif %} class {{ node_class_name }}(Node): @@ -141,6 +147,11 @@ class {{ node_class_name }}(Node): qos_profile=10) self.get_logger().info(f"Publishing to '{self.publisher.topic_name}'") {% endif %} +{% if has_service_server %} + + # service server for handling service calls + self.service_server = self.create_service(SetBool, "~/service", self.serviceCallback) +{% endif %} {% if has_timer %} # timer for repeatedly invoking a callback to publish messages @@ -156,6 +167,24 @@ class {{ node_class_name }}(Node): rclpy.get_logger().info(f"Message received: '{msg.data}'") {% endif %} +{% if has_service_server %} + + def serviceCallback(self, request: SetBool.Request, response: SetBool.Response) -> SetBool.Response: + """Processes service requests + + Args: + request (SetBool.Request): service request + response (SetBool.Response): service response + + Returns: + SetBool.Response: service response + """ + + rclpy.get_logger().info("Received service request") + response.success = True + + return response +{% endif %} {% if has_timer %} def timerCallback(self): From 0f5d91e3a4a7cee03e734f4dc00baa7f7fac3841 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:02:03 +0200 Subject: [PATCH 38/67] add support for action server in python template --- .../{{ package_name }}/package.xml.jinja | 10 ++ .../{{ node_name }}.py.jinja | 110 +++++++++++++++++- 2 files changed, 118 insertions(+), 2 deletions(-) diff --git a/templates/ros2_python_pkg/{{ package_name }}/package.xml.jinja b/templates/ros2_python_pkg/{{ package_name }}/package.xml.jinja index 234e93f..9610124 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/package.xml.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/package.xml.jinja @@ -14,6 +14,16 @@ ament_python rclpy +{% if has_action_server %} + rclcpp_action +{% endif %} +std_msgs +{% if has_service_server %} + std_srvs +{% endif %} +{% if has_action_server %} + {{ package_name }}_interfaces +{% endif %} ament_python diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja index 487f09d..f5c15af 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -1,5 +1,3 @@ -# TODO: is_lifecycle -# TODO: has_action_server # TODO: auto_shutdown import sys from typing import Any, Optional, Union @@ -15,6 +13,9 @@ from std_msgs.msg import Int32 {% if has_service_server %} from std_srvs.srv import SetBool {% endif %} +{% if has_action_server %} +from {{ package_name }}_interfaces.action import Fibonacci +{% endif %} class {{ node_class_name }}(Node): @@ -152,6 +153,19 @@ class {{ node_class_name }}(Node): # service server for handling service calls self.service_server = self.create_service(SetBool, "~/service", self.serviceCallback) {% endif %} +{% if has_action_server %} + + # action server for handling action goal requests + self.action_server = rclpy.action.ActionServer( + self, + Fibonacci, + "~/action", + execute_callback=self.actionExecute, + goal_callback=self.actionHandleGoal, + cancel_callback=self.actionHandleCancel, + handle_accepted_callback=self.actionHandleAccepted + ) +{% endif %} {% if has_timer %} # timer for repeatedly invoking a callback to publish messages @@ -185,6 +199,98 @@ class {{ node_class_name }}(Node): return response {% endif %} +{% if has_action_server %} + + def actionHandleGoal(self, goal: Fibonacci.Goal) -> rclpy.action.server.GoalResponse: + """Processes action goal requests + + Args: + goal (Fibonacci.Goal): action goal + + Returns: + rclpy.action.server.GoalResponse: goal response + """ + + self.get_logger().info("Received action goal request") + + return rclpy.action.server.GoalResponse.ACCEPT + + def actionHandleCancel(self, goal_handle: Fibonacci.GoalHandle) -> rclpy.action.server.CancelResponse: + """Processes action cancel requests + + Args: + goal_handle (Fibonacci.GoalHandle): action goal handle + + Returns: + rclpy.action.server.CancelResponse: cancel response + """ + + self.get_logger().info("Received request to cancel action goal") + + return rclpy.action.server.CancelResponse.ACCEPT + + def actionHandleAccepted(self, goal_handle: Fibonacci.GoalHandle): + """Processes accepted action goal requests + + Args: + goal_handle (Fibonacci.Goal): action goal handle + """ + + # execute action in a separate thread to avoid blocking + goal_handle.execute() + + async def actionExecute(self, goal_handle: Fibonacci.Goal) -> Fibonacci.Result: + """Executes an action + + Args: + goal_handle (Fibonacci.Goal): action goal handle + + Returns: + Fibonacci.Result: action goal result + """ + + self.get_logger().info("Executing action goal") + + # define a sleeping rate between computing individual Fibonacci numbers + loop_rate = 1 + + # create the action feedback and result + feedback = SampleAction.Feedback() + result = SampleAction.Result() + + # initialize the Fibonacci sequence + feedback.partial_fibonacci = [0, 1] + + # compute the Fibonacci sequence up to the requested order n + for i in range(1, goal_handle.request.n): + + # cancel, if requested + if goal_handle.is_cancel_requested: + result.fibonacci = feedback.partial_fibonacci + goal_handle.canceled() + self.get_logger().info("Action goal canceled") + return result + + # compute the next Fibonacci number + feedback.partial_fibonacci.append(feedback.partial_fibonacci[i] + + feedback.partial_fibonacci[i - + 1]) + + # publish the current sequence as action feedback + goal_handle.publish_feedback(feedback) + self.get_logger().info("Publishing action feedback") + + # sleep before computing the next Fibonacci number + time.sleep(loop_rate) + + # finish by publishing the action result + if rclpy.ok(): + result.fibonacci = feedback.partial_fibonacci + goal_handle.succeed() + self.get_logger().info("Goal succeeded") + + return result +{% endif %} {% if has_timer %} def timerCallback(self): From 0a59bc454d64e020138774178aeb240004d81fde Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:04:35 +0200 Subject: [PATCH 39/67] add support for auto shutdown to python template --- .../{{ package_name }}/{{ node_name }}.py.jinja | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja index f5c15af..cd872cd 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -1,4 +1,3 @@ -# TODO: auto_shutdown import sys from typing import Any, Optional, Union @@ -170,6 +169,10 @@ class {{ node_class_name }}(Node): # timer for repeatedly invoking a callback to publish messages self.timer = self.create_timer(1.0, self.timerCallback) +{% if auto_shutdown %} + + self.auto_shutdown_timer = self.create_timer(3.0, self.autoShutdownTimerCallback) +{% endif %} {% if has_subscriber %} def topicCallback(self, msg: Int32): @@ -299,6 +302,15 @@ class {{ node_class_name }}(Node): rclpy.get_logger().info("Timer triggered") {% endif %} +{% if auto_shutdown %} + + def autoShutdownTimerCallback(self): + """Processes timer triggers to auto-shutdown the node + """ + + rclpy.get_logger().info("Shutting down") + rclpy.shutdown() +{% endif %} def main(): From 9e1e15f23e5b39f86cd4e829c6ceb24e414e9db0 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:08:36 +0200 Subject: [PATCH 40/67] mention python template in readme --- README.md | 34 ++++++++++++++++++++++++++++------ 1 file changed, 28 insertions(+), 6 deletions(-) diff --git a/README.md b/README.md index aeda448..719135d 100644 --- a/README.md +++ b/README.md @@ -34,6 +34,7 @@ ros2-pkg-create --template ros2_cpp_pkg . *ros2-pkg-create* provides multiple templates, each covering a different questionnaire for generating all the components you need. See below for the list of options. Note that all options can also be passed directly to the command, bypassing the interactive questionnaire (see [Usage](#usage)). - [C++ Package](#c-package-template-ros2_cpp_pkg) +- [Python Package](#python-package---template-ros2_python_pkg) - [Interfaces Package](#interfaces-package-template-ros2_interfaces_pkg) ### C++ Package (`--template ros2_cpp_pkg`) @@ -56,6 +57,24 @@ ros2-pkg-create --template ros2_cpp_pkg . - Add a timer callback? - Add the docker-ros CI integration? +### Python Package (`--template ros2_python_pkg`) + +- Package name +- Description +- Maintainer | Maintainer email +- Author | Author email +- License +- Node name +- Class name of node +- Add a launch file? | Type of launch file +- Add parameter loading? +- Add a subscriber? +- Add a publisher? +- Add a service server? +- Add an action server? +- Add a timer callback? +- Add the docker-ros CI integration? + ### Interfaces Package (`--template ros2_interfaces_pkg`) - Package name @@ -90,11 +109,14 @@ eval "$(register-python-argcomplete ros2-pkg-create)" ## Usage ``` -usage: ros2-pkg-create [-h] [--defaults] [--use-local-templates] --template {ros2_cpp_pkg,ros2_interfaces_pkg} [--package-name PACKAGE_NAME] [--description DESCRIPTION] [--maintainer MAINTAINER] [--maintainer-email MAINTAINER_EMAIL] - [--author AUTHOR] [--author-email AUTHOR_EMAIL] [--license {Apache-2.0,BSL-1.0,BSD-2.0,BSD-2-Clause,BSD-3-Clause,GPL-3.0-only,LGPL-2.1-only,LGPL-3.0-only,MIT,MIT-0}] [--node-name NODE_NAME] - [--node-class-name NODE_CLASS_NAME] [--is-component] [--no-is-component] [--is-lifecycle] [--no-is-lifecycle] [--has-launch-file] [--no-has-launch-file] [--launch-file-type {xml,py,yml}] [--has-params] - [--no-has-params] [--has-subscriber] [--no-has-subscriber] [--has-publisher] [--no-has-publisher] [--has-service-server] [--no-has-service-server] [--has-action-server] [--no-has-action-server] [--has-timer] - [--no-has-timer] [--auto-shutdown] [--no-auto-shutdown] [--interface-types {Message,Service,Action}] [--msg-name MSG_NAME] [--srv-name SRV_NAME] [--action-name ACTION_NAME] [--has-docker-ros] [--version] +usage: ros2-pkg-create [-h] [--defaults] [--use-local-templates] --template {ros2_interfaces_pkg,ros2_python_pkg,ros2_cpp_pkg} [--package-name PACKAGE_NAME] [--description DESCRIPTION] + [--maintainer MAINTAINER] [--maintainer-email MAINTAINER_EMAIL] [--author AUTHOR] [--author-email AUTHOR_EMAIL] + [--license {Apache-2.0,BSL-1.0,BSD-2.0,BSD-2-Clause,BSD-3-Clause,GPL-3.0-only,LGPL-2.1-only,LGPL-3.0-only,MIT,MIT-0}] [--node-name NODE_NAME] + [--node-class-name NODE_CLASS_NAME] [--is-component] [--no-is-component] [--is-lifecycle] [--no-is-lifecycle] [--has-launch-file] [--no-has-launch-file] + [--launch-file-type {xml,py,yml}] [--has-params] [--no-has-params] [--has-subscriber] [--no-has-subscriber] [--has-publisher] [--no-has-publisher] + [--has-service-server] [--no-has-service-server] [--has-action-server] [--no-has-action-server] [--has-timer] [--no-has-timer] [--auto-shutdown] + [--no-auto-shutdown] [--interface-types {Message,Service,Action}] [--msg-name MSG_NAME] [--srv-name SRV_NAME] [--action-name ACTION_NAME] [--has-docker-ros] + [--version] destination Creates a ROS 2 package from templates @@ -107,7 +129,7 @@ options: --defaults Use defaults for all options --use-local-templates Use locally installed templates instead of remotely pulling most recent ones - --template {ros2_cpp_pkg,ros2_interfaces_pkg} + --template {ros2_interfaces_pkg,ros2_python_pkg,ros2_cpp_pkg} Template --package-name PACKAGE_NAME Package name From c1872f63fe53036916337db4fa5a460e8adb64bf Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:14:02 +0200 Subject: [PATCH 41/67] fix missing jinja tag in python template --- .../{{ package_name }}/{{ node_name }}.py.jinja | 1 + 1 file changed, 1 insertion(+) diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja index cd872cd..a4f8a9d 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -169,6 +169,7 @@ class {{ node_class_name }}(Node): # timer for repeatedly invoking a callback to publish messages self.timer = self.create_timer(1.0, self.timerCallback) +{% endif %} {% if auto_shutdown %} self.auto_shutdown_timer = self.create_timer(3.0, self.autoShutdownTimerCallback) From 0acff6d65039f0b85a2b1f424188e9c454711c90 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:16:43 +0200 Subject: [PATCH 42/67] add samples including all options --- .github/workflows/check-samples.yml | 25 +- samples/ros2_cpp_all_pkg/CMakeLists.txt | 58 +++ samples/ros2_cpp_all_pkg/README.md | 62 +++ samples/ros2_cpp_all_pkg/config/params.yml | 3 + .../ros2_cpp_all_pkg/ros2_cpp_node.hpp | 98 +++++ .../launch/ros2_cpp_node_launch.py} | 2 +- samples/ros2_cpp_all_pkg/package.xml | 28 ++ .../ros2_cpp_all_pkg/src/ros2_cpp_node.cpp | 391 ++++++++++++++++++ .../CMakeLists.txt | 12 + .../action/Fibonacci.action | 5 + .../ros2_cpp_all_pkg_interfaces/package.xml | 24 ++ samples/ros2_cpp_lifecycle_pkg/CMakeLists.txt | 4 +- samples/ros2_cpp_lifecycle_pkg/README.md | 6 +- ...p_lifecycle_node.hpp => ros2_cpp_node.hpp} | 4 +- .../launch/ros2_cpp_node_launch.py | 46 +++ ...p_lifecycle_node.cpp => ros2_cpp_node.cpp} | 28 +- samples/ros2_python_all_pkg/config/params.yml | 3 + .../launch/ros2_python_node_launch.py | 35 ++ samples/ros2_python_all_pkg/package.xml | 26 ++ .../resource/ros2_python_all_pkg | 0 .../ros2_python_all_pkg/__init__.py | 0 .../ros2_python_all_pkg/ros2_python_node.py | 278 +++++++++++++ samples/ros2_python_all_pkg/setup.cfg | 4 + samples/ros2_python_all_pkg/setup.py | 29 ++ .../CMakeLists.txt | 12 + .../action/Fibonacci.action | 5 + .../package.xml | 24 ++ samples/ros2_python_pkg/package.xml | 1 + .../ros2_python_pkg/ros2_python_node.py | 13 +- 29 files changed, 1194 insertions(+), 32 deletions(-) create mode 100644 samples/ros2_cpp_all_pkg/CMakeLists.txt create mode 100644 samples/ros2_cpp_all_pkg/README.md create mode 100644 samples/ros2_cpp_all_pkg/config/params.yml create mode 100644 samples/ros2_cpp_all_pkg/include/ros2_cpp_all_pkg/ros2_cpp_node.hpp rename samples/{ros2_cpp_lifecycle_pkg/launch/ros2_cpp_lifecycle_node_launch.py => ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py} (93%) create mode 100644 samples/ros2_cpp_all_pkg/package.xml create mode 100644 samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp create mode 100644 samples/ros2_cpp_all_pkg_interfaces/CMakeLists.txt create mode 100644 samples/ros2_cpp_all_pkg_interfaces/action/Fibonacci.action create mode 100644 samples/ros2_cpp_all_pkg_interfaces/package.xml rename samples/ros2_cpp_lifecycle_pkg/include/ros2_cpp_lifecycle_pkg/{ros2_cpp_lifecycle_node.hpp => ros2_cpp_node.hpp} (96%) create mode 100644 samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py rename samples/ros2_cpp_lifecycle_pkg/src/{ros2_cpp_lifecycle_node.cpp => ros2_cpp_node.cpp} (87%) create mode 100644 samples/ros2_python_all_pkg/config/params.yml create mode 100644 samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py create mode 100644 samples/ros2_python_all_pkg/package.xml create mode 100644 samples/ros2_python_all_pkg/resource/ros2_python_all_pkg create mode 100644 samples/ros2_python_all_pkg/ros2_python_all_pkg/__init__.py create mode 100644 samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py create mode 100644 samples/ros2_python_all_pkg/setup.cfg create mode 100644 samples/ros2_python_all_pkg/setup.py create mode 100644 samples/ros2_python_all_pkg_interfaces/CMakeLists.txt create mode 100644 samples/ros2_python_all_pkg_interfaces/action/Fibonacci.action create mode 100644 samples/ros2_python_all_pkg_interfaces/package.xml diff --git a/.github/workflows/check-samples.yml b/.github/workflows/check-samples.yml index 44a5881..647a545 100644 --- a/.github/workflows/check-samples.yml +++ b/.github/workflows/check-samples.yml @@ -37,7 +37,7 @@ jobs: has_timer: false - package_name: ros2_cpp_lifecycle_pkg template: ros2_cpp_pkg - node_name: ros2_cpp_lifecycle_node + node_name: ros2_cpp_node is_component: false is_lifecycle: true has_launch_file: true @@ -47,6 +47,18 @@ jobs: has_service_server: false has_action_server: false has_timer: false + - package_name: ros2_cpp_all_pkg + template: ros2_cpp_pkg + node_name: ros2_cpp_node + is_component: true + is_lifecycle: true + has_launch_file: true + has_params: true + has_subscriber: true + has_publisher: true + has_service_server: true + has_action_server: true + has_timer: true - package_name: ros2_python_pkg template: ros2_python_pkg node_name: ros2_python_node @@ -58,6 +70,17 @@ jobs: has_service_server: false has_action_server: false has_timer: false + - package_name: ros2_python_all_pkg + template: ros2_python_pkg + node_name: ros2_python_node + is_lifecycle: false + has_launch_file: true + has_params: true + has_subscriber: true + has_publisher: true + has_service_server: true + has_action_server: true + has_timer: true - package_name: ros2_interfaces_pkg template: ros2_interfaces_pkg steps: diff --git a/samples/ros2_cpp_all_pkg/CMakeLists.txt b/samples/ros2_cpp_all_pkg/CMakeLists.txt new file mode 100644 index 0000000..d8a7367 --- /dev/null +++ b/samples/ros2_cpp_all_pkg/CMakeLists.txt @@ -0,0 +1,58 @@ +cmake_minimum_required(VERSION 3.8) +project(ros2_cpp_all_pkg) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_action REQUIRED) +find_package(ros2_cpp_all_pkg_interfaces REQUIRED) +find_package(rclcpp_components REQUIRED) +find_package(rclcpp_lifecycle REQUIRED) +find_package(std_msgs REQUIRED) +find_package(std_srvs REQUIRED) + +set(TARGET_NAME ros2_cpp_node_component) + +add_library(${TARGET_NAME} SHARED src/ros2_cpp_node.cpp) + +rclcpp_components_register_node(${TARGET_NAME} + PLUGIN "ros2_cpp_all_pkg::Ros2CppNode" + EXECUTABLE ros2_cpp_node +) + +target_include_directories(${TARGET_NAME} PUBLIC + $ + $ +) +target_compile_features(${TARGET_NAME} PUBLIC c_std_99 cxx_std_17) + +ament_target_dependencies(${TARGET_NAME} + rclcpp + rclcpp_action + ros2_cpp_all_pkg_interfaces + rclcpp_components + rclcpp_lifecycle + std_msgs + std_srvs +) + +install(TARGETS ${TARGET_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME} + OPTIONAL +) + +install(DIRECTORY config + DESTINATION share/${PROJECT_NAME} + OPTIONAL +) + +ament_package() diff --git a/samples/ros2_cpp_all_pkg/README.md b/samples/ros2_cpp_all_pkg/README.md new file mode 100644 index 0000000..51c45a2 --- /dev/null +++ b/samples/ros2_cpp_all_pkg/README.md @@ -0,0 +1,62 @@ +# ros2_cpp_all_pkg + +TODO + +- [Container Images](#container-images) +- [ros2_cpp_node](#ros2_cpp_node) +- [Official Documentation](#official-documentation) + + +## Container Images + +| Description | Image | Command | +| --- | --- | -- | +| | ` + +| Topic | Type | Description | +| --- | --- | --- | +| `` | `/msg/` | \ | + +### Published Topics + + + +| Topic | Type | Description | +| --- | --- | --- | +| `` | `/msg/` | \ | + +### Services + + + +| Service | Type | Description | +| --- | --- | --- | +| `` | `/srv/` | \ | + +### Actions + + + +| Action | Type | Description | +| --- | --- | --- | +| `` | `/action/` | \ | + +### Parameters + + + +| Parameter | Type | Description | +| --- | --- | --- | +| `` | `` | \ | + + +## Official Documentation + +\ \ No newline at end of file diff --git a/samples/ros2_cpp_all_pkg/config/params.yml b/samples/ros2_cpp_all_pkg/config/params.yml new file mode 100644 index 0000000..809c91b --- /dev/null +++ b/samples/ros2_cpp_all_pkg/config/params.yml @@ -0,0 +1,3 @@ +/**/*: + ros__parameters: + param: 1.0 \ No newline at end of file diff --git a/samples/ros2_cpp_all_pkg/include/ros2_cpp_all_pkg/ros2_cpp_node.hpp b/samples/ros2_cpp_all_pkg/include/ros2_cpp_all_pkg/ros2_cpp_node.hpp new file mode 100644 index 0000000..cf591f3 --- /dev/null +++ b/samples/ros2_cpp_all_pkg/include/ros2_cpp_all_pkg/ros2_cpp_node.hpp @@ -0,0 +1,98 @@ +#pragma once + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + + +namespace ros2_cpp_all_pkg { + +template struct is_vector : std::false_type {}; +template struct is_vector< std::vector > : std::true_type {}; +template inline constexpr bool is_vector_v = is_vector::value; + + +class Ros2CppNode : public rclcpp_lifecycle::LifecycleNode { + + public: + + explicit Ros2CppNode(const rclcpp::NodeOptions& options); + + protected: + + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(const rclcpp_lifecycle::State& state) override; + + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(const rclcpp_lifecycle::State& state) override; + + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State& state) override; + + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State& state) override; + + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State& state) override; + + private: + + template + void declareAndLoadParameter(const std::string &name, + T ¶m, + const std::string &description, + const bool add_to_auto_reconfigurable_params = true, + const bool is_required = false, + const bool read_only = false, + const std::optional &from_value = std::nullopt, + const std::optional &to_value = std::nullopt, + const std::optional &step_value = std::nullopt, + const std::string &additional_constraints = ""); + + rcl_interfaces::msg::SetParametersResult parametersCallback(const std::vector& parameters); + + void setup(); + + void cleanUp(); + + void topicCallback(const std_msgs::msg::Int32& msg); + + void serviceCallback(const std::shared_ptrrequest, std::shared_ptr response); + + rclcpp_action::GoalResponse actionHandleGoal(const rclcpp_action::GoalUUID& uuid, std::shared_ptr goal); + + rclcpp_action::CancelResponse actionHandleCancel(const std::shared_ptr> goal_handle); + + void actionHandleAccepted(const std::shared_ptr> goal_handle); + + void actionExecute(const std::shared_ptr> goal_handle); + + void timerCallback(); + + private: + + std::vector>> auto_reconfigurable_params_; + + OnSetParametersCallbackHandle::SharedPtr parameters_callback_; + + rclcpp::Subscription::SharedPtr subscriber_; + + rclcpp_lifecycle::LifecyclePublisher::SharedPtr publisher_; + + rclcpp::Service::SharedPtr service_server_; + + rclcpp_action::Server::SharedPtr action_server_; + + rclcpp::TimerBase::SharedPtr timer_; + + double param_ = 1.0; +}; + + +} diff --git a/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_lifecycle_node_launch.py b/samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py similarity index 93% rename from samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_lifecycle_node_launch.py rename to samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py index 0bad658..24ce2af 100644 --- a/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_lifecycle_node_launch.py +++ b/samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py @@ -13,7 +13,7 @@ def generate_launch_description(): args = [ - DeclareLaunchArgument("name", default_value="ros2_cpp_lifecycle_node", description="node name"), + DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state"), diff --git a/samples/ros2_cpp_all_pkg/package.xml b/samples/ros2_cpp_all_pkg/package.xml new file mode 100644 index 0000000..e5f4d0c --- /dev/null +++ b/samples/ros2_cpp_all_pkg/package.xml @@ -0,0 +1,28 @@ + + + + + ros2_cpp_all_pkg + 0.0.0 + TODO + + TODO + TODO + + TODO + + ament_cmake + + rclcpp + rclcpp_action + rclcpp_components + rclcpp_lifecycle + std_msgs + std_srvs + ros2_cpp_all_pkg_interfaces + + + ament_cmake + + + diff --git a/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp new file mode 100644 index 0000000..a9e56a9 --- /dev/null +++ b/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp @@ -0,0 +1,391 @@ +#include +#include +#include +#include + +#include + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(ros2_cpp_all_pkg::Ros2CppNode) + + +namespace ros2_cpp_all_pkg { + + +/** + * @brief Constructor + * + * @param options node options + */ +Ros2CppNode::Ros2CppNode(const rclcpp::NodeOptions& options) : rclcpp_lifecycle::LifecycleNode("ros2_cpp_node", options) { + + int startup_state = lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE; + this->declareAndLoadParameter("startup_state", startup_state, "Initial lifecycle state", false, false, false); + if (startup_state > lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED) + this->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE); + if (startup_state > lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) + this->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE); +} + + +/** + * @brief Declares and loads a ROS parameter + * + * @param name name + * @param param parameter variable to load into + * @param description description + * @param add_to_auto_reconfigurable_params enable reconfiguration of parameter + * @param is_required whether failure to load parameter will stop node + * @param read_only set parameter to read-only + * @param from_value parameter range minimum + * @param to_value parameter range maximum + * @param step_value parameter range step + * @param additional_constraints additional constraints description + */ +template +void Ros2CppNode::declareAndLoadParameter(const std::string& name, + T& param, + const std::string& description, + const bool add_to_auto_reconfigurable_params, + const bool is_required, + const bool read_only, + const std::optional& from_value, + const std::optional& to_value, + const std::optional& step_value, + const std::string& additional_constraints) { + + rcl_interfaces::msg::ParameterDescriptor param_desc; + param_desc.description = description; + param_desc.additional_constraints = additional_constraints; + param_desc.read_only = read_only; + + auto type = rclcpp::ParameterValue(param).get_type(); + + if (from_value.has_value() && to_value.has_value()) { + if constexpr (std::is_integral_v) { + rcl_interfaces::msg::IntegerRange range; + T step = static_cast(step_value.has_value() ? step_value.value() : 1); + range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); + param_desc.integer_range = {range}; + } else if constexpr (std::is_floating_point_v) { + rcl_interfaces::msg::FloatingPointRange range; + T step = static_cast(step_value.has_value() ? step_value.value() : 1.0); + range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); + param_desc.floating_point_range = {range}; + } else { + RCLCPP_WARN(this->get_logger(), "Parameter type of parameter '%s' does not support specifying a range", name.c_str()); + } + } + + this->declare_parameter(name, type, param_desc); + + try { + param = this->get_parameter(name).get_value(); + } catch (rclcpp::exceptions::ParameterUninitializedException&) { + if (is_required) { + RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); + exit(EXIT_FAILURE); // TODO: rclpy shutdown? + } else { + std::stringstream ss; + ss << "Missing parameter '" << name << "', using default value: "; + if constexpr (is_vector_v) { + ss << "["; + for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); + } else { + ss << param; + } + RCLCPP_WARN_STREAM(this->get_logger(), ss.str()); + } + } + + if (add_to_auto_reconfigurable_params) { + // why so complicated, storing lambda functions? / why vector, not map? + std::function setter = [¶m](const rclcpp::Parameter& p) { + param = p.get_value(); + }; + auto_reconfigurable_params_.push_back(std::make_tuple(name, setter)); + } +} + + +/** + * @brief Handles reconfiguration when a parameter value is changed + * + * @param parameters parameters + * @return parameter change result + */ +rcl_interfaces::msg::SetParametersResult Ros2CppNode::parametersCallback(const std::vector& parameters) { + + for (const auto& param : parameters) { + for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { + if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { + std::get<1>(auto_reconfigurable_param)(param); + break; + } + } + } + + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + + return result; +} + + +/** + * @brief Sets up subscribers, publishers, etc. to configure the node + */ +void Ros2CppNode::setup() { + + // callback for dynamic parameter configuration + parameters_callback_ = this->add_on_set_parameters_callback(std::bind(&Ros2CppNode::parametersCallback, this, std::placeholders::_1)); + + // subscriber for handling incoming messages + subscriber_ = this->create_subscription("~/input", 10, std::bind(&Ros2CppNode::topicCallback, this, std::placeholders::_1)); + RCLCPP_INFO(this->get_logger(), "Subscribed to '%s'", subscriber_->get_topic_name()); + + // publisher for publishing outgoing messages + publisher_ = this->create_publisher("~/output", 10); + RCLCPP_INFO(this->get_logger(), "Publishing to '%s'", publisher_->get_topic_name()); + + // service server for handling service calls + service_server_ = this->create_service("~/service", std::bind(&Ros2CppNode::serviceCallback, this, std::placeholders::_1, std::placeholders::_2)); + + // action server for handling action goal requests + action_server_ = rclcpp_action::create_server( + this, + "~/action", + std::bind(&Ros2CppNode::actionHandleGoal, this, std::placeholders::_1, std::placeholders::_2), + std::bind(&Ros2CppNode::actionHandleCancel, this, std::placeholders::_1), + std::bind(&Ros2CppNode::actionHandleAccepted, this, std::placeholders::_1) + ); +} + + +/** + * @brief Processes messages received by a subscriber + * + * @param msg message + */ +void Ros2CppNode::topicCallback(const std_msgs::msg::Int32& msg) { + + RCLCPP_INFO(this->get_logger(), "Message received: '%d'", msg.data); +} + + +/** + * @brief Processes service requests + * + * @param request service request + * @param response service response + */ +void Ros2CppNode::serviceCallback(const std_srvs::srv::SetBool::Request::SharedPtr request, std_srvs::srv::SetBool::Response::SharedPtr response) { + + (void)request; + + RCLCPP_INFO(this->get_logger(), "Received service request"); + + response->success = true; +} + + +/** + * @brief Processes action goal requests + * + * @param uuid unique goal identifier + * @param goal action goal + * @return goal response + */ +rclcpp_action::GoalResponse Ros2CppNode::actionHandleGoal(const rclcpp_action::GoalUUID& uuid, ros2_cpp_all_pkg_interfaces::action::Fibonacci::Goal::ConstSharedPtr goal) { + + (void)uuid; + (void)goal; + + RCLCPP_INFO(this->get_logger(), "Received action goal request"); + + return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; +} + + +/** + * @brief Processes action cancel requests + * + * @param goal_handle action goal handle + * @return cancel response + */ +rclcpp_action::CancelResponse Ros2CppNode::actionHandleCancel(const std::shared_ptr> goal_handle) { + + (void)goal_handle; + + RCLCPP_INFO(this->get_logger(), "Received request to cancel action goal"); + + return rclcpp_action::CancelResponse::ACCEPT; +} + + +/** + * @brief Processes accepted action goal requests + * + * @param goal_handle action goal handle + */ +void Ros2CppNode::actionHandleAccepted(const std::shared_ptr> goal_handle) { + + // execute action in a separate thread to avoid blocking + std::thread{std::bind(&Ros2CppNode::actionExecute, this, std::placeholders::_1), goal_handle}.detach(); +} + + +/** + * @brief Executes an action + * + * @param goal_handle action goal handle + */ +void Ros2CppNode::actionExecute(const std::shared_ptr> goal_handle) { + + RCLCPP_INFO(this->get_logger(), "Executing action goal"); + + // define a sleeping rate between computing individual Fibonacci numbers + rclcpp::Rate loop_rate(1); + + // create handy accessors for the action goal, feedback, and result + const auto goal = goal_handle->get_goal(); + auto feedback = std::make_shared(); + auto result = std::make_shared(); + + // initialize the Fibonacci sequence + auto& partial_sequence = feedback->partial_sequence; + partial_sequence.push_back(0); + partial_sequence.push_back(1); + + // compute the Fibonacci sequence up to the requested order n + for (int i = 1; i < goal->order && rclcpp::ok(); ++i) { + + // cancel, if requested + if (goal_handle->is_canceling()) { + result->sequence = feedback->partial_sequence; + goal_handle->canceled(result); + RCLCPP_INFO(this->get_logger(), "Action goal canceled"); + return; + } + + // compute the next Fibonacci number + partial_sequence.push_back(partial_sequence[i] + partial_sequence[i - 1]); + + // publish the current sequence as action feedback + goal_handle->publish_feedback(feedback); + RCLCPP_INFO(this->get_logger(), "Publishing action feedback"); + + // sleep before computing the next Fibonacci number + loop_rate.sleep(); + } + + // finish by publishing the action result + if (rclcpp::ok()) { + result->sequence = partial_sequence; + goal_handle->succeed(result); + RCLCPP_INFO(this->get_logger(), "Goal succeeded"); + } +} + + +/** + * @brief Processes timer triggers + */ +void Ros2CppNode::timerCallback() { + + RCLCPP_INFO(this->get_logger(), "Timer triggered"); +} + + +/** + * @brief Processes 'configuring' transitions to 'inactive' state + * + * @param state previous state + * @return transition result + */ +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppNode::on_configure(const rclcpp_lifecycle::State& state) { + + RCLCPP_INFO(get_logger(), "Configuring to enter 'inactive' state from '%s' state", state.label().c_str()); + + this->declareAndLoadParameter("param", param_, "TODO", true, false, false, 0.0, 10.0, 1.0); + setup(); + + return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; +} + + +/** + * @brief Processes 'activating' transitions to 'active' state + * + * @param state previous state + * @return transition result + */ +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppNode::on_activate(const rclcpp_lifecycle::State& state) { + + RCLCPP_INFO(get_logger(), "Activating to enter 'active' state from '%s' state", state.label().c_str()); + + publisher_->on_activate(); + timer_ = this->create_wall_timer(std::chrono::duration(param_), std::bind(&Ros2CppNode::timerCallback, this)); + + return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; +} + + +/** + * @brief Processes 'deactivating' transitions to 'inactive' state + * + * @param state previous state + * @return transition result + */ +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppNode::on_deactivate(const rclcpp_lifecycle::State& state) { + + RCLCPP_INFO(get_logger(), "Deactivating to enter 'inactive' state from '%s' state", state.label().c_str()); + + timer_.reset(); + publisher_->on_deactivate(); + + return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; +} + + +/** + * @brief Processes 'cleningup' transitions to 'unconfigured' state + * + * @param state previous state + * @return transition result + */ +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppNode::on_cleanup(const rclcpp_lifecycle::State& state) { + + RCLCPP_INFO(get_logger(), "Cleaning up to enter 'unconfigured' state from '%s' state", state.label().c_str()); + + subscriber_.reset(); + publisher_.reset(); + service_server_.reset(); + action_server_.reset(); + parameters_callback_.reset(); + timer_.reset(); + + return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; +} + + +/** + * @brief Processes 'shuttingdown' transitions to 'finalized' state + * + * @param state previous state + * @return transition result + */ +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppNode::on_shutdown(const rclcpp_lifecycle::State& state) { + + RCLCPP_INFO(get_logger(), "Shutting down to enter 'finalized' state from '%s' state", state.label().c_str()); + + if (state.id() >= lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) + on_deactivate(state); + if (state.id() >= lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) + on_cleanup(state); + + return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; +} + + +} diff --git a/samples/ros2_cpp_all_pkg_interfaces/CMakeLists.txt b/samples/ros2_cpp_all_pkg_interfaces/CMakeLists.txt new file mode 100644 index 0000000..8d2a48d --- /dev/null +++ b/samples/ros2_cpp_all_pkg_interfaces/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 3.8) +project(ros2_cpp_all_pkg_interfaces) + +find_package(rosidl_default_generators REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + action/Fibonacci.action +) + +ament_export_dependencies(rosidl_default_runtime) + +ament_package() diff --git a/samples/ros2_cpp_all_pkg_interfaces/action/Fibonacci.action b/samples/ros2_cpp_all_pkg_interfaces/action/Fibonacci.action new file mode 100644 index 0000000..32b18f2 --- /dev/null +++ b/samples/ros2_cpp_all_pkg_interfaces/action/Fibonacci.action @@ -0,0 +1,5 @@ +int32 order +--- +int32[] sequence +--- +int32[] partial_sequence \ No newline at end of file diff --git a/samples/ros2_cpp_all_pkg_interfaces/package.xml b/samples/ros2_cpp_all_pkg_interfaces/package.xml new file mode 100644 index 0000000..cb83e42 --- /dev/null +++ b/samples/ros2_cpp_all_pkg_interfaces/package.xml @@ -0,0 +1,24 @@ + + + + + ros2_cpp_all_pkg_interfaces + 0.0.0 + ROS interface definitions for ros2_cpp_all_pkg + + TODO + TODO + + TODO + + ament_cmake + rosidl_default_generators + rosidl_default_runtime + + rosidl_interface_packages + + + ament_cmake + + + diff --git a/samples/ros2_cpp_lifecycle_pkg/CMakeLists.txt b/samples/ros2_cpp_lifecycle_pkg/CMakeLists.txt index 4188128..3fc8de1 100644 --- a/samples/ros2_cpp_lifecycle_pkg/CMakeLists.txt +++ b/samples/ros2_cpp_lifecycle_pkg/CMakeLists.txt @@ -10,9 +10,9 @@ find_package(rclcpp REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(std_msgs REQUIRED) -set(TARGET_NAME ros2_cpp_lifecycle_node) +set(TARGET_NAME ros2_cpp_node) -add_executable(${TARGET_NAME} src/ros2_cpp_lifecycle_node.cpp) +add_executable(${TARGET_NAME} src/ros2_cpp_node.cpp) target_include_directories(${TARGET_NAME} PUBLIC $ diff --git a/samples/ros2_cpp_lifecycle_pkg/README.md b/samples/ros2_cpp_lifecycle_pkg/README.md index b3d5e1d..3d8a240 100644 --- a/samples/ros2_cpp_lifecycle_pkg/README.md +++ b/samples/ros2_cpp_lifecycle_pkg/README.md @@ -3,7 +3,7 @@ TODO - [Container Images](#container-images) -- [ros2_cpp_lifecycle_node](#ros2_cpp_lifecycle_node) +- [ros2_cpp_node](#ros2_cpp_node) - [Official Documentation](#official-documentation) @@ -11,10 +11,10 @@ TODO | Description | Image | Command | | --- | --- | -- | -| | ` | ` struct is_vector< std::vector > : std::tru template inline constexpr bool is_vector_v = is_vector::value; -class Ros2CppLifecycleNode : public rclcpp_lifecycle::LifecycleNode { +class Ros2CppNode : public rclcpp_lifecycle::LifecycleNode { public: - Ros2CppLifecycleNode(); + Ros2CppNode(); protected: diff --git a/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py new file mode 100644 index 0000000..24ce2af --- /dev/null +++ b/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py @@ -0,0 +1,46 @@ +#!/usr/bin/env python3 + +import os + +from ament_index_python import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, GroupAction +from launch.conditions import LaunchConfigurationNotEquals +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import LifecycleNode, SetParameter + + +def generate_launch_description(): + + args = [ + DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name"), + DeclareLaunchArgument("namespace", default_value="", description="node namespace"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state"), + ] + + nodes = [ + GroupAction( + actions=[ + SetParameter( + name="startup_state", + value=LaunchConfiguration("startup_state"), + condition=LaunchConfigurationNotEquals("startup_state", "None") + ), + LifecycleNode( + package="event_detector", + executable="event_detector", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), + parameters=[LaunchConfiguration("params")], + output="screen", + emulate_tty=True, + ) + ] + ) + ] + + return LaunchDescription([ + *args, + *nodes, + ]) diff --git a/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_lifecycle_node.cpp b/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp similarity index 87% rename from samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_lifecycle_node.cpp rename to samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp index 8a84fec..a39a8ed 100644 --- a/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_lifecycle_node.cpp +++ b/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp @@ -1,7 +1,7 @@ #include #include -#include +#include namespace ros2_cpp_lifecycle_pkg { @@ -12,7 +12,7 @@ namespace ros2_cpp_lifecycle_pkg { * * @param options node options */ -Ros2CppLifecycleNode::Ros2CppLifecycleNode() : rclcpp_lifecycle::LifecycleNode("ros2_cpp_lifecycle_node") { +Ros2CppNode::Ros2CppNode() : rclcpp_lifecycle::LifecycleNode("ros2_cpp_node") { int startup_state = lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE; this->declareAndLoadParameter("startup_state", startup_state, "Initial lifecycle state", false, false, false); @@ -38,7 +38,7 @@ Ros2CppLifecycleNode::Ros2CppLifecycleNode() : rclcpp_lifecycle::LifecycleNode(" * @param additional_constraints additional constraints description */ template -void Ros2CppLifecycleNode::declareAndLoadParameter(const std::string& name, +void Ros2CppNode::declareAndLoadParameter(const std::string& name, T& param, const std::string& description, const bool add_to_auto_reconfigurable_params, @@ -109,7 +109,7 @@ void Ros2CppLifecycleNode::declareAndLoadParameter(const std::string& name, * @param parameters parameters * @return parameter change result */ -rcl_interfaces::msg::SetParametersResult Ros2CppLifecycleNode::parametersCallback(const std::vector& parameters) { +rcl_interfaces::msg::SetParametersResult Ros2CppNode::parametersCallback(const std::vector& parameters) { for (const auto& param : parameters) { for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { @@ -130,13 +130,13 @@ rcl_interfaces::msg::SetParametersResult Ros2CppLifecycleNode::parametersCallbac /** * @brief Sets up subscribers, publishers, etc. to configure the node */ -void Ros2CppLifecycleNode::setup() { +void Ros2CppNode::setup() { // callback for dynamic parameter configuration - parameters_callback_ = this->add_on_set_parameters_callback(std::bind(&Ros2CppLifecycleNode::parametersCallback, this, std::placeholders::_1)); + parameters_callback_ = this->add_on_set_parameters_callback(std::bind(&Ros2CppNode::parametersCallback, this, std::placeholders::_1)); // subscriber for handling incoming messages - subscriber_ = this->create_subscription("~/input", 10, std::bind(&Ros2CppLifecycleNode::topicCallback, this, std::placeholders::_1)); + subscriber_ = this->create_subscription("~/input", 10, std::bind(&Ros2CppNode::topicCallback, this, std::placeholders::_1)); RCLCPP_INFO(this->get_logger(), "Subscribed to '%s'", subscriber_->get_topic_name()); // publisher for publishing outgoing messages @@ -150,7 +150,7 @@ void Ros2CppLifecycleNode::setup() { * * @param msg message */ -void Ros2CppLifecycleNode::topicCallback(const std_msgs::msg::Int32& msg) { +void Ros2CppNode::topicCallback(const std_msgs::msg::Int32& msg) { RCLCPP_INFO(this->get_logger(), "Message received: '%d'", msg.data); } @@ -162,7 +162,7 @@ void Ros2CppLifecycleNode::topicCallback(const std_msgs::msg::Int32& msg) { * @param state previous state * @return transition result */ -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppLifecycleNode::on_configure(const rclcpp_lifecycle::State& state) { +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppNode::on_configure(const rclcpp_lifecycle::State& state) { RCLCPP_INFO(get_logger(), "Configuring to enter 'inactive' state from '%s' state", state.label().c_str()); @@ -179,7 +179,7 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2Cp * @param state previous state * @return transition result */ -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppLifecycleNode::on_activate(const rclcpp_lifecycle::State& state) { +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppNode::on_activate(const rclcpp_lifecycle::State& state) { RCLCPP_INFO(get_logger(), "Activating to enter 'active' state from '%s' state", state.label().c_str()); @@ -195,7 +195,7 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2Cp * @param state previous state * @return transition result */ -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppLifecycleNode::on_deactivate(const rclcpp_lifecycle::State& state) { +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppNode::on_deactivate(const rclcpp_lifecycle::State& state) { RCLCPP_INFO(get_logger(), "Deactivating to enter 'inactive' state from '%s' state", state.label().c_str()); @@ -211,7 +211,7 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2Cp * @param state previous state * @return transition result */ -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppLifecycleNode::on_cleanup(const rclcpp_lifecycle::State& state) { +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppNode::on_cleanup(const rclcpp_lifecycle::State& state) { RCLCPP_INFO(get_logger(), "Cleaning up to enter 'unconfigured' state from '%s' state", state.label().c_str()); @@ -229,7 +229,7 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2Cp * @param state previous state * @return transition result */ -rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppLifecycleNode::on_shutdown(const rclcpp_lifecycle::State& state) { +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2CppNode::on_shutdown(const rclcpp_lifecycle::State& state) { RCLCPP_INFO(get_logger(), "Shutting down to enter 'finalized' state from '%s' state", state.label().c_str()); @@ -248,7 +248,7 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2Cp int main(int argc, char *argv[]) { rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()->get_node_base_interface()); + rclcpp::spin(std::make_shared()->get_node_base_interface()); rclcpp::shutdown(); return 0; diff --git a/samples/ros2_python_all_pkg/config/params.yml b/samples/ros2_python_all_pkg/config/params.yml new file mode 100644 index 0000000..809c91b --- /dev/null +++ b/samples/ros2_python_all_pkg/config/params.yml @@ -0,0 +1,3 @@ +/**/*: + ros__parameters: + param: 1.0 \ No newline at end of file diff --git a/samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py b/samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py new file mode 100644 index 0000000..8a30da3 --- /dev/null +++ b/samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py @@ -0,0 +1,35 @@ +#!/usr/bin/env python3 + +import os + +from ament_index_python import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + + +def generate_launch_description(): + + args = [ + DeclareLaunchArgument("name", default_value="ros2_python_node", description="node name"), + DeclareLaunchArgument("namespace", default_value="", description="node namespace"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + ] + + nodes = [ + Node( + package="ros2_python_all_pkg", + executable="ros2_python_node", + namespace=LaunchConfiguration("namespace"), + name=LaunchConfiguration("name"), + parameters=[LaunchConfiguration("params")], + output="screen", + emulate_tty=True, + ) + ] + + return LaunchDescription([ + *args, + *nodes, + ]) diff --git a/samples/ros2_python_all_pkg/package.xml b/samples/ros2_python_all_pkg/package.xml new file mode 100644 index 0000000..39e0c5a --- /dev/null +++ b/samples/ros2_python_all_pkg/package.xml @@ -0,0 +1,26 @@ + + + + + ros2_python_all_pkg + 0.0.0 + TODO + + TODO + TODO + + TODO + + ament_python + + rclpy + rclcpp_action +std_msgs + std_srvs + ros2_python_all_pkg_interfaces + + + ament_python + + + diff --git a/samples/ros2_python_all_pkg/resource/ros2_python_all_pkg b/samples/ros2_python_all_pkg/resource/ros2_python_all_pkg new file mode 100644 index 0000000..e69de29 diff --git a/samples/ros2_python_all_pkg/ros2_python_all_pkg/__init__.py b/samples/ros2_python_all_pkg/ros2_python_all_pkg/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py new file mode 100644 index 0000000..1688392 --- /dev/null +++ b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py @@ -0,0 +1,278 @@ +import sys +from typing import Any, Optional, Union + +import rclpy +from rclpy.node import Node +from rcl_interfaces.msg import (FloatingPointRange, IntegerRange, ParameterDescriptor, SetParametersResult) +from std_msgs.msg import Int32 +from std_srvs.srv import SetBool +from ros2_python_all_pkg_interfaces.action import Fibonacci + + +class Ros2PythonNode(Node): + + def __init__(self): + """Constructor""" + + super().__init__("ros2_python_node") + + self.auto_reconfigurable_params = [] + self.parameters_callback = None + self.subscriber = None + self.publisher = None + + self.param = 1.0 + + self.param = self.declareAndLoadParameter(name="param", + param_type=rclpy.Parameter.Type.DOUBLE, + description="TODO", + default=self.param, + from_value=0.0, + to_value=10.0, + step_value=0.1) + self.setup() + + def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, description: str, default: Optional[Any] = None, add_to_auto_reconfigurable_params: bool = True, is_required: bool = False , read_only: bool = False, from_value: Optional[Union[int, float]] = None, to_value: Optional[Union[int, float]] = None, step_value: Optional[Union[int, float]] = None, additional_constraints: str = "") -> Any: + """Declares and loads a ROS parameter + + Args: + name (str): name + param_type (rclpy.Parameter.Type): parameter type + description (str): description + default (Optional[Any], optional): default value + add_to_auto_reconfigurable_params (bool, optional): enable reconfiguration of parameter + is_required (bool, optional): whether failure to load parameter will stop node + read_only (bool, optional): set parameter to read-only + from_value (Optional[Union[int, float]], optional): parameter range minimum + to_value (Optional[Union[int, float]], optional): parameter range maximum + step_value (Optional[Union[int, float]], optional): parameter range step + additional_constraints (str, optional): additional constraints description + + Returns: + Any: parameter value + """ + + param_desc = ParameterDescriptor() + param_desc.description = description + param_desc.additional_constraints = additional_constraints + param_desc.read_only = read_only + + if from_value is not None and to_value is not None: + if param_type == rclpy.Parameter.Type.INTEGER: + step_value = step_value if step_value is not None else 1 + param_desc.integer_range = [IntegerRange(from_value=from_value, to_value=to_value, step=step_value)] + elif param_type == rclpy.Parameter.Type.DOUBLE: + step_value = step_value if step_value is not None else 1.0 + param_desc.floating_point_range = [FloatingPointRange(from_value=from_value, to_value=to_value, step=step_value)] + else: + self.get_logger().warn(f"Parameter type of parameter '{name}' does not support specifying a range") + + self.declare_parameter(name, param_type, param_desc) + + try: + param = self.get_parameter(name).value + except rclpy.exceptions.ParameterUninitializedException: + if is_required: + self.get_logger().fatal(f"Missing required parameter '{name}', exiting") + sys.exit(1) # TODO: rclpy shutdown? + else: + self.get_logger().warn(f"Missing parameter '{name}', using default value: {default}") + param = default + + if add_to_auto_reconfigurable_params: + # TODO: this probably doesn't work + self.auto_reconfigurable_params.append((name, param)) + + return param + + def parametersCallback(self, + parameters: rclpy.Parameter) -> SetParametersResult: + """Handles reconfiguration when a parameter value is changed + + Args: + parameters (rclpy.Parameter): parameters + + Returns: + SetParametersResult: parameter change result + """ + + for param in parameters: + for auto_reconfigurable_param in self.auto_reconfigurable_params: + if param.name == auto_reconfigurable_param[0]: + # TODO: this probably doesn't work + auto_reconfigurable_param[1] = param.value + break + + result = SetParametersResult() + result.successful = True + + return result + + def setup(self): + """Sets up subscribers, publishers, etc. to configure the node""" + + # callback for dynamic parameter configuration + self.parameters_callback = self.add_on_set_parameters_callback( + self.parametersCallback) + + # subscriber for handling incoming messages + self.subscriber = self.create_subscription(Int32, + "~/input", + self.topicCallback, + qos_profile=10) + self.get_logger().info(f"Subscribed to '{self.subscriber.topic_name}'") + + # publisher for publishing outgoing messages + self.publisher = self.create_publisher(Int32, + "~/output", + qos_profile=10) + self.get_logger().info(f"Publishing to '{self.publisher.topic_name}'") + + # service server for handling service calls + self.service_server = self.create_service(SetBool, "~/service", self.serviceCallback) + + # action server for handling action goal requests + self.action_server = rclpy.action.ActionServer( + self, + Fibonacci, + "~/action", + execute_callback=self.actionExecute, + goal_callback=self.actionHandleGoal, + cancel_callback=self.actionHandleCancel, + handle_accepted_callback=self.actionHandleAccepted + ) + + # timer for repeatedly invoking a callback to publish messages + self.timer = self.create_timer(1.0, self.timerCallback) + + def topicCallback(self, msg: Int32): + """Processes messages received by a subscriber + + Args: + msg (Int32): message + """ + + rclpy.get_logger().info(f"Message received: '{msg.data}'") + + def serviceCallback(self, request: SetBool.Request, response: SetBool.Response) -> SetBool.Response: + """Processes service requests + + Args: + request (SetBool.Request): service request + response (SetBool.Response): service response + + Returns: + SetBool.Response: service response + """ + + rclpy.get_logger().info("Received service request") + response.success = True + + return response + + def actionHandleGoal(self, goal: Fibonacci.Goal) -> rclpy.action.server.GoalResponse: + """Processes action goal requests + + Args: + goal (Fibonacci.Goal): action goal + + Returns: + rclpy.action.server.GoalResponse: goal response + """ + + self.get_logger().info("Received action goal request") + + return rclpy.action.server.GoalResponse.ACCEPT + + def actionHandleCancel(self, goal_handle: Fibonacci.GoalHandle) -> rclpy.action.server.CancelResponse: + """Processes action cancel requests + + Args: + goal_handle (Fibonacci.GoalHandle): action goal handle + + Returns: + rclpy.action.server.CancelResponse: cancel response + """ + + self.get_logger().info("Received request to cancel action goal") + + return rclpy.action.server.CancelResponse.ACCEPT + + def actionHandleAccepted(self, goal_handle: Fibonacci.GoalHandle): + """Processes accepted action goal requests + + Args: + goal_handle (Fibonacci.Goal): action goal handle + """ + + # execute action in a separate thread to avoid blocking + goal_handle.execute() + + async def actionExecute(self, goal_handle: Fibonacci.Goal) -> Fibonacci.Result: + """Executes an action + + Args: + goal_handle (Fibonacci.Goal): action goal handle + + Returns: + Fibonacci.Result: action goal result + """ + + self.get_logger().info("Executing action goal") + + # define a sleeping rate between computing individual Fibonacci numbers + loop_rate = 1 + + # create the action feedback and result + feedback = SampleAction.Feedback() + result = SampleAction.Result() + + # initialize the Fibonacci sequence + feedback.partial_fibonacci = [0, 1] + + # compute the Fibonacci sequence up to the requested order n + for i in range(1, goal_handle.request.n): + + # cancel, if requested + if goal_handle.is_cancel_requested: + result.fibonacci = feedback.partial_fibonacci + goal_handle.canceled() + self.get_logger().info("Action goal canceled") + return result + + # compute the next Fibonacci number + feedback.partial_fibonacci.append(feedback.partial_fibonacci[i] + + feedback.partial_fibonacci[i - + 1]) + + # publish the current sequence as action feedback + goal_handle.publish_feedback(feedback) + self.get_logger().info("Publishing action feedback") + + # sleep before computing the next Fibonacci number + time.sleep(loop_rate) + + # finish by publishing the action result + if rclpy.ok(): + result.fibonacci = feedback.partial_fibonacci + goal_handle.succeed() + self.get_logger().info("Goal succeeded") + + return result + + def timerCallback(self): + """Processes timer triggers + """ + + rclpy.get_logger().info("Timer triggered") + + +def main(): + + rclpy.init() + rclpy.spin(Ros2PythonNode()) + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/samples/ros2_python_all_pkg/setup.cfg b/samples/ros2_python_all_pkg/setup.cfg new file mode 100644 index 0000000..1908e6c --- /dev/null +++ b/samples/ros2_python_all_pkg/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/ros2_python_all_pkg +[install] +install_scripts=$base/lib/ros2_python_all_pkg diff --git a/samples/ros2_python_all_pkg/setup.py b/samples/ros2_python_all_pkg/setup.py new file mode 100644 index 0000000..aa35513 --- /dev/null +++ b/samples/ros2_python_all_pkg/setup.py @@ -0,0 +1,29 @@ +import os +from glob import glob +from setuptools import setup + +package_name = 'ros2_python_all_pkg' + +setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + (os.path.join('share', package_name), ['package.xml']), + (os.path.join('share', package_name, + 'launch'), glob('launch/*launch.[pxy][yma]*')), + (os.path.join('share', package_name, + 'config'), glob('config/*.yaml'))], + install_requires=['setuptools'], + zip_safe=True, + maintainer='root', + maintainer_email='root@todo.todo', + description='TODO: Package description', + license='TODO: License declaration', + tests_require=['pytest'], + entry_points={ + 'console_scripts': + ['ros2_python_node = ros2_python_all_pkg.ros2_python_node:main'], + }, +) diff --git a/samples/ros2_python_all_pkg_interfaces/CMakeLists.txt b/samples/ros2_python_all_pkg_interfaces/CMakeLists.txt new file mode 100644 index 0000000..4adc66e --- /dev/null +++ b/samples/ros2_python_all_pkg_interfaces/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 3.8) +project(ros2_python_all_pkg_interfaces) + +find_package(rosidl_default_generators REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + action/Fibonacci.action +) + +ament_export_dependencies(rosidl_default_runtime) + +ament_package() diff --git a/samples/ros2_python_all_pkg_interfaces/action/Fibonacci.action b/samples/ros2_python_all_pkg_interfaces/action/Fibonacci.action new file mode 100644 index 0000000..32b18f2 --- /dev/null +++ b/samples/ros2_python_all_pkg_interfaces/action/Fibonacci.action @@ -0,0 +1,5 @@ +int32 order +--- +int32[] sequence +--- +int32[] partial_sequence \ No newline at end of file diff --git a/samples/ros2_python_all_pkg_interfaces/package.xml b/samples/ros2_python_all_pkg_interfaces/package.xml new file mode 100644 index 0000000..940d76e --- /dev/null +++ b/samples/ros2_python_all_pkg_interfaces/package.xml @@ -0,0 +1,24 @@ + + + + + ros2_python_all_pkg_interfaces + 0.0.0 + ROS interface definitions for ros2_python_all_pkg + + TODO + TODO + + TODO + + ament_cmake + rosidl_default_generators + rosidl_default_runtime + + rosidl_interface_packages + + + ament_cmake + + + diff --git a/samples/ros2_python_pkg/package.xml b/samples/ros2_python_pkg/package.xml index 24cf684..bf17ef9 100644 --- a/samples/ros2_python_pkg/package.xml +++ b/samples/ros2_python_pkg/package.xml @@ -14,6 +14,7 @@ ament_python rclpy +std_msgs ament_python diff --git a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py index cf937bb..af2cb79 100644 --- a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py +++ b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py @@ -1,8 +1,3 @@ -# TODO: is_lifecycle -# TODO: has_service_server -# TODO: has_action_server -# TODO: has_timer -# TODO: auto_shutdown import sys from typing import Any, Optional, Union @@ -33,7 +28,7 @@ def __init__(self): from_value=0.0, to_value=10.0, step_value=0.1) - self.setup() + self.setup() def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, description: str, default: Optional[Any] = None, add_to_auto_reconfigurable_params: bool = True, is_required: bool = False , read_only: bool = False, from_value: Optional[Union[int, float]] = None, to_value: Optional[Union[int, float]] = None, step_value: Optional[Union[int, float]] = None, additional_constraints: str = "") -> Any: """Declares and loads a ROS parameter @@ -50,7 +45,7 @@ def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, d to_value (Optional[Union[int, float]], optional): parameter range maximum step_value (Optional[Union[int, float]], optional): parameter range step additional_constraints (str, optional): additional constraints description - + Returns: Any: parameter value """ @@ -81,7 +76,7 @@ def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, d else: self.get_logger().warn(f"Missing parameter '{name}', using default value: {default}") param = default - + if add_to_auto_reconfigurable_params: # TODO: this probably doesn't work self.auto_reconfigurable_params.append((name, param)) @@ -125,7 +120,7 @@ def setup(self): qos_profile=10) self.get_logger().info(f"Subscribed to '{self.subscriber.topic_name}'") - # publisher for publishing messages + # publisher for publishing outgoing messages self.publisher = self.create_publisher(Int32, "~/output", qos_profile=10) From afb4e934b7156eb90f88fa91dc06c3a50897cd7b Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:18:00 +0200 Subject: [PATCH 43/67] remove lifecycle python pkg from ci --- .github/workflows/generate-and-test.yml | 6 ------ 1 file changed, 6 deletions(-) diff --git a/.github/workflows/generate-and-test.yml b/.github/workflows/generate-and-test.yml index 74742b0..9af7bad 100644 --- a/.github/workflows/generate-and-test.yml +++ b/.github/workflows/generate-and-test.yml @@ -53,10 +53,6 @@ jobs: - package_name: default_python_pkg template: ros2_python_pkg auto_shutdown: true - - package_name: lifecycle_python_pkg - template: ros2_python_pkg - is_lifecycle: true - auto_shutdown: true - package_name: service_python_pkg template: ros2_python_pkg has_service_server: true @@ -149,8 +145,6 @@ jobs: command: ros2 launch all_cpp_pkg all_cpp_pkg_launch.py - package: default_python_pkg command: ros2 launch default_python_pkg default_python_pkg_launch.py - - package: lifecycle_python_pkg - command: ros2 launch lifecycle_python_pkg lifecycle_python_pkg_launch.py - package: service_python_pkg command: ros2 launch service_python_pkg service_python_pkg_launch.py - package: action_python_pkg From 350e4346ad565ff4129d32fd149fd3abf44a74de Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:31:25 +0200 Subject: [PATCH 44/67] create script to regenerate all samples --- samples/generate_samples.sh | 94 +++++++++++++++++++++++++++++++++++++ 1 file changed, 94 insertions(+) create mode 100755 samples/generate_samples.sh diff --git a/samples/generate_samples.sh b/samples/generate_samples.sh new file mode 100755 index 0000000..107ea2b --- /dev/null +++ b/samples/generate_samples.sh @@ -0,0 +1,94 @@ +#!/bin/bash + +script_dir=$(dirname $0) + +copier copy --trust --defaults \ + -d template=ros2_cpp_pkg \ + -d package_name=ros2_cpp_pkg \ + -d node_name=ros2_cpp_node \ + -d is_component=false \ + -d is_lifecycle=false \ + -d has_launch_file=true \ + -d has_params=true \ + -d has_subscriber=true \ + -d has_publisher=true \ + -d has_service_server=false \ + -d has_action_server=false \ + -d has_timer=false \ + . $script_dir + +copier copy --trust --defaults \ + -d template=ros2_cpp_pkg \ + -d package_name=ros2_cpp_component_pkg \ + -d node_name=ros2_cpp_node \ + -d is_component=true \ + -d is_lifecycle=false \ + -d has_launch_file=true \ + -d has_params=true \ + -d has_subscriber=true \ + -d has_publisher=true \ + -d has_service_server=false \ + -d has_action_server=false \ + -d has_timer=false \ + . $script_dir + +copier copy --trust --defaults \ + -d template=ros2_cpp_pkg \ + -d package_name=ros2_cpp_lifecycle_pkg \ + -d node_name=ros2_cpp_node \ + -d is_component=false \ + -d is_lifecycle=true \ + -d has_launch_file=true \ + -d has_params=true \ + -d has_subscriber=true \ + -d has_publisher=true \ + -d has_service_server=false \ + -d has_action_server=false \ + -d has_timer=false \ + . $script_dir + +copier copy --trust --defaults \ + -d template=ros2_cpp_pkg \ + -d package_name=ros2_cpp_all_pkg \ + -d node_name=ros2_cpp_node \ + -d is_component=true \ + -d is_lifecycle=true \ + -d has_launch_file=true \ + -d has_params=true \ + -d has_subscriber=true \ + -d has_publisher=true \ + -d has_service_server=true \ + -d has_action_server=true \ + -d has_timer=true \ + . $script_dir + +copier copy --trust --defaults \ + -d template=ros2_python_pkg \ + -d package_name=ros2_python_pkg \ + -d node_name=ros2_python_node \ + -d has_launch_file=true \ + -d has_params=true \ + -d has_subscriber=true \ + -d has_publisher=true \ + -d has_service_server=false \ + -d has_action_server=false \ + -d has_timer=false \ + . $script_dir + +copier copy --trust --defaults \ + -d template=ros2_python_pkg \ + -d package_name=ros2_python_all_pkg \ + -d node_name=ros2_python_node \ + -d has_launch_file=true \ + -d has_params=true \ + -d has_subscriber=true \ + -d has_publisher=true \ + -d has_service_server=true \ + -d has_action_server=true \ + -d has_timer=true \ + . $script_dir + +copier copy --trust --defaults \ + -d template=ros2_interfaces_pkg \ + -d package_name=ros2_interfaces_pkg \ + . $script_dir From 0945dd41b1b58e324c7e62435a5cb7485124570f Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:31:51 +0200 Subject: [PATCH 45/67] fix copy-paste leftover in improved launch file template --- samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py | 6 +++--- .../ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py | 2 +- .../ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py | 6 +++--- samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py | 2 +- .../ros2_python_all_pkg/launch/ros2_python_node_launch.py | 2 +- samples/ros2_python_pkg/launch/ros2_python_node_launch.py | 2 +- ...ype == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja | 6 +++--- ...ype == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja | 2 +- 8 files changed, 14 insertions(+), 14 deletions(-) diff --git a/samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py index 24ce2af..6fd9e5d 100644 --- a/samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py +++ b/samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py @@ -15,7 +15,7 @@ def generate_launch_description(): args = [ DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), - DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("ros2_cpp_all_pkg"), "config", "params.yml"), description="path to parameter file"), DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state"), ] @@ -28,8 +28,8 @@ def generate_launch_description(): condition=LaunchConfigurationNotEquals("startup_state", "None") ), LifecycleNode( - package="event_detector", - executable="event_detector", + package="ros2_cpp_all_pkg", + executable="ros2_cpp_node", namespace=LaunchConfiguration("namespace"), name=LaunchConfiguration("name"), parameters=[LaunchConfiguration("params")], diff --git a/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py index 66440fb..80f3c93 100644 --- a/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py +++ b/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py @@ -14,7 +14,7 @@ def generate_launch_description(): args = [ DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), - DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("ros2_cpp_component_pkg"), "config", "params.yml"), description="path to parameter file"), ] nodes = [ diff --git a/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py index 24ce2af..4cc845e 100644 --- a/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py +++ b/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py @@ -15,7 +15,7 @@ def generate_launch_description(): args = [ DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), - DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("ros2_cpp_lifecycle_pkg"), "config", "params.yml"), description="path to parameter file"), DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state"), ] @@ -28,8 +28,8 @@ def generate_launch_description(): condition=LaunchConfigurationNotEquals("startup_state", "None") ), LifecycleNode( - package="event_detector", - executable="event_detector", + package="ros2_cpp_lifecycle_pkg", + executable="ros2_cpp_node", namespace=LaunchConfiguration("namespace"), name=LaunchConfiguration("name"), parameters=[LaunchConfiguration("params")], diff --git a/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py index f4d5597..dd3496a 100644 --- a/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py +++ b/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py @@ -14,7 +14,7 @@ def generate_launch_description(): args = [ DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), - DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("ros2_cpp_pkg"), "config", "params.yml"), description="path to parameter file"), ] nodes = [ diff --git a/samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py b/samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py index 8a30da3..3f0c3fb 100644 --- a/samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py +++ b/samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py @@ -14,7 +14,7 @@ def generate_launch_description(): args = [ DeclareLaunchArgument("name", default_value="ros2_python_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), - DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("ros2_python_all_pkg"), "config", "params.yml"), description="path to parameter file"), ] nodes = [ diff --git a/samples/ros2_python_pkg/launch/ros2_python_node_launch.py b/samples/ros2_python_pkg/launch/ros2_python_node_launch.py index b073324..4cc344c 100644 --- a/samples/ros2_python_pkg/launch/ros2_python_node_launch.py +++ b/samples/ros2_python_pkg/launch/ros2_python_node_launch.py @@ -14,7 +14,7 @@ def generate_launch_description(): args = [ DeclareLaunchArgument("name", default_value="ros2_python_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), - DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("ros2_python_pkg"), "config", "params.yml"), description="path to parameter file"), ] nodes = [ diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja index 7fe8b18..c675764 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja @@ -21,7 +21,7 @@ def generate_launch_description(): args = [ DeclareLaunchArgument("name", default_value="{{ node_name }}", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), - DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("{{ package_name }}"), "config", "params.yml"), description="path to parameter file"), {% if is_lifecycle %} DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state"), {% endif %} @@ -37,8 +37,8 @@ def generate_launch_description(): condition=LaunchConfigurationNotEquals("startup_state", "None") ), LifecycleNode( - package="event_detector", - executable="event_detector", + package="{{ package_name }}", + executable="{{ node_name }}", namespace=LaunchConfiguration("namespace"), name=LaunchConfiguration("name"), {% if has_params %} diff --git a/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja index 6ef4e0c..e56f26f 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja @@ -14,7 +14,7 @@ def generate_launch_description(): args = [ DeclareLaunchArgument("name", default_value="{{ node_name }}", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), - DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("event_detector"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("{{ package_name }}"), "config", "params.yml"), description="path to parameter file"), ] nodes = [ From 712f0f0887e0183c3949c691da75369546b56670 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:37:34 +0200 Subject: [PATCH 46/67] fix typo in python templates --- .../ros2_python_all_pkg/ros2_python_node.py | 6 +++--- .../ros2_python_pkg/ros2_python_pkg/ros2_python_node.py | 2 +- .../{{ package_name }}/{{ node_name }}.py.jinja | 8 ++++---- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py index 1688392..f94290f 100644 --- a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py +++ b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py @@ -152,7 +152,7 @@ def topicCallback(self, msg: Int32): msg (Int32): message """ - rclpy.get_logger().info(f"Message received: '{msg.data}'") + self.get_logger().info(f"Message received: '{msg.data}'") def serviceCallback(self, request: SetBool.Request, response: SetBool.Response) -> SetBool.Response: """Processes service requests @@ -165,7 +165,7 @@ def serviceCallback(self, request: SetBool.Request, response: SetBool.Response) SetBool.Response: service response """ - rclpy.get_logger().info("Received service request") + self.get_logger().info("Received service request") response.success = True return response @@ -264,7 +264,7 @@ def timerCallback(self): """Processes timer triggers """ - rclpy.get_logger().info("Timer triggered") + self.get_logger().info("Timer triggered") def main(): diff --git a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py index af2cb79..84c5fac 100644 --- a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py +++ b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py @@ -133,7 +133,7 @@ def topicCallback(self, msg: Int32): msg (Int32): message """ - rclpy.get_logger().info(f"Message received: '{msg.data}'") + self.get_logger().info(f"Message received: '{msg.data}'") def main(): diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja index a4f8a9d..ddb5095 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -183,7 +183,7 @@ class {{ node_class_name }}(Node): msg (Int32): message """ - rclpy.get_logger().info(f"Message received: '{msg.data}'") + self.get_logger().info(f"Message received: '{msg.data}'") {% endif %} {% if has_service_server %} @@ -198,7 +198,7 @@ class {{ node_class_name }}(Node): SetBool.Response: service response """ - rclpy.get_logger().info("Received service request") + self.get_logger().info("Received service request") response.success = True return response @@ -301,7 +301,7 @@ class {{ node_class_name }}(Node): """Processes timer triggers """ - rclpy.get_logger().info("Timer triggered") + self.get_logger().info("Timer triggered") {% endif %} {% if auto_shutdown %} @@ -309,7 +309,7 @@ class {{ node_class_name }}(Node): """Processes timer triggers to auto-shutdown the node """ - rclpy.get_logger().info("Shutting down") + self.get_logger().info("Shutting down") rclpy.shutdown() {% endif %} From b7c75861fed2c9556951cad5d5991e8fb218adbc Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:39:30 +0200 Subject: [PATCH 47/67] add git status to sample checking ci --- .github/workflows/check-samples.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/check-samples.yml b/.github/workflows/check-samples.yml index 647a545..f77ce87 100644 --- a/.github/workflows/check-samples.yml +++ b/.github/workflows/check-samples.yml @@ -119,6 +119,7 @@ jobs: mv packages/${{ matrix.package_name }} samples/ if [[ ! -z "$(git status --porcelain)" ]]; then echo "Sample generation resulted in changes to the repository" + git status git diff exit 1 fi From 025371d06b7da553856495bd77305522d112158e Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:41:21 +0200 Subject: [PATCH 48/67] fix sample checking ci for packages including separate action pkg --- .github/workflows/check-samples.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/check-samples.yml b/.github/workflows/check-samples.yml index f77ce87..7d494f4 100644 --- a/.github/workflows/check-samples.yml +++ b/.github/workflows/check-samples.yml @@ -116,7 +116,7 @@ jobs: - name: Check for repository changes run: | rm -rf samples/${{ matrix.package_name }} - mv packages/${{ matrix.package_name }} samples/ + mv packages/${{ matrix.package_name }}* samples/ if [[ ! -z "$(git status --porcelain)" ]]; then echo "Sample generation resulted in changes to the repository" git status From 29a57f57a80983a37671f7a24e9618758b9294de Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:42:23 +0200 Subject: [PATCH 49/67] really fix sample checking ci for packages including separate action pkg --- .github/workflows/check-samples.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/check-samples.yml b/.github/workflows/check-samples.yml index 7d494f4..b852d7c 100644 --- a/.github/workflows/check-samples.yml +++ b/.github/workflows/check-samples.yml @@ -115,7 +115,7 @@ jobs: . packages - name: Check for repository changes run: | - rm -rf samples/${{ matrix.package_name }} + rm -rf samples/${{ matrix.package_name }}* mv packages/${{ matrix.package_name }}* samples/ if [[ ! -z "$(git status --porcelain)" ]]; then echo "Sample generation resulted in changes to the repository" From 218a6e718f727d77d4b06fb1363b10f260cf8bf1 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:53:07 +0200 Subject: [PATCH 50/67] add ci badge to readme --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index 719135d..c8bb5fd 100644 --- a/README.md +++ b/README.md @@ -2,6 +2,7 @@ From 1ff4979d60b4e7bcbae1427df67e9d6b7a445ad7 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Tue, 15 Oct 2024 23:53:26 +0200 Subject: [PATCH 51/67] only ask for launch file type if launch file is enabled --- copier.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/copier.yml b/copier.yml index 5e92e79..847ae16 100644 --- a/copier.yml +++ b/copier.yml @@ -83,7 +83,7 @@ has_launch_file: launch_file_type: help: Type of launch file - when: "{{ template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg' }}" + when: "{{ (template == 'ros2_cpp_pkg' or template == 'ros2_python_pkg') and has_launch_file }}" type: str default: py choices: [py, xml, yml] From 07620d8d37670ee3da4ba4fe09d49056ae6be080 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Wed, 16 Oct 2024 21:45:35 +0200 Subject: [PATCH 52/67] add log level arg to launch files --- samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py | 2 ++ samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py | 2 ++ samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py | 2 ++ samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py | 2 ++ samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py | 2 ++ samples/ros2_python_pkg/launch/ros2_python_node_launch.py | 2 ++ ...e_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja | 3 +++ ...e_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja | 2 ++ 8 files changed, 17 insertions(+) diff --git a/samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py index 6fd9e5d..9e9b252 100644 --- a/samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py +++ b/samples/ros2_cpp_all_pkg/launch/ros2_cpp_node_launch.py @@ -16,6 +16,7 @@ def generate_launch_description(): DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("ros2_cpp_all_pkg"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("log_level", default_value="info", description="ROS logging level (debug, info, warn, error, fatal)"), DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state"), ] @@ -33,6 +34,7 @@ def generate_launch_description(): namespace=LaunchConfiguration("namespace"), name=LaunchConfiguration("name"), parameters=[LaunchConfiguration("params")], + arguments=["--ros-args", "--log-level", LaunchConfiguration("log_level")], output="screen", emulate_tty=True, ) diff --git a/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py index 80f3c93..c1cb24f 100644 --- a/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py +++ b/samples/ros2_cpp_component_pkg/launch/ros2_cpp_node_launch.py @@ -15,6 +15,7 @@ def generate_launch_description(): DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("ros2_cpp_component_pkg"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("log_level", default_value="info", description="ROS logging level (debug, info, warn, error, fatal)"), ] nodes = [ @@ -24,6 +25,7 @@ def generate_launch_description(): namespace=LaunchConfiguration("namespace"), name=LaunchConfiguration("name"), parameters=[LaunchConfiguration("params")], + arguments=["--ros-args", "--log-level", LaunchConfiguration("log_level")], output="screen", emulate_tty=True, ) diff --git a/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py index 4cc845e..98ba960 100644 --- a/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py +++ b/samples/ros2_cpp_lifecycle_pkg/launch/ros2_cpp_node_launch.py @@ -16,6 +16,7 @@ def generate_launch_description(): DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("ros2_cpp_lifecycle_pkg"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("log_level", default_value="info", description="ROS logging level (debug, info, warn, error, fatal)"), DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state"), ] @@ -33,6 +34,7 @@ def generate_launch_description(): namespace=LaunchConfiguration("namespace"), name=LaunchConfiguration("name"), parameters=[LaunchConfiguration("params")], + arguments=["--ros-args", "--log-level", LaunchConfiguration("log_level")], output="screen", emulate_tty=True, ) diff --git a/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py b/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py index dd3496a..c270c91 100644 --- a/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py +++ b/samples/ros2_cpp_pkg/launch/ros2_cpp_node_launch.py @@ -15,6 +15,7 @@ def generate_launch_description(): DeclareLaunchArgument("name", default_value="ros2_cpp_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("ros2_cpp_pkg"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("log_level", default_value="info", description="ROS logging level (debug, info, warn, error, fatal)"), ] nodes = [ @@ -24,6 +25,7 @@ def generate_launch_description(): namespace=LaunchConfiguration("namespace"), name=LaunchConfiguration("name"), parameters=[LaunchConfiguration("params")], + arguments=["--ros-args", "--log-level", LaunchConfiguration("log_level")], output="screen", emulate_tty=True, ) diff --git a/samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py b/samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py index 3f0c3fb..9d31fcf 100644 --- a/samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py +++ b/samples/ros2_python_all_pkg/launch/ros2_python_node_launch.py @@ -15,6 +15,7 @@ def generate_launch_description(): DeclareLaunchArgument("name", default_value="ros2_python_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("ros2_python_all_pkg"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("log_level", default_value="info", description="ROS logging level (debug, info, warn, error, fatal)"), ] nodes = [ @@ -24,6 +25,7 @@ def generate_launch_description(): namespace=LaunchConfiguration("namespace"), name=LaunchConfiguration("name"), parameters=[LaunchConfiguration("params")], + arguments=["--ros-args", "--log-level", LaunchConfiguration("log_level")], output="screen", emulate_tty=True, ) diff --git a/samples/ros2_python_pkg/launch/ros2_python_node_launch.py b/samples/ros2_python_pkg/launch/ros2_python_node_launch.py index 4cc344c..c4d5a5b 100644 --- a/samples/ros2_python_pkg/launch/ros2_python_node_launch.py +++ b/samples/ros2_python_pkg/launch/ros2_python_node_launch.py @@ -15,6 +15,7 @@ def generate_launch_description(): DeclareLaunchArgument("name", default_value="ros2_python_node", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("ros2_python_pkg"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("log_level", default_value="info", description="ROS logging level (debug, info, warn, error, fatal)"), ] nodes = [ @@ -24,6 +25,7 @@ def generate_launch_description(): namespace=LaunchConfiguration("namespace"), name=LaunchConfiguration("name"), parameters=[LaunchConfiguration("params")], + arguments=["--ros-args", "--log-level", LaunchConfiguration("log_level")], output="screen", emulate_tty=True, ) diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja index c675764..98e5dac 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja @@ -22,6 +22,7 @@ def generate_launch_description(): DeclareLaunchArgument("name", default_value="{{ node_name }}", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("{{ package_name }}"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("log_level", default_value="info", description="ROS logging level (debug, info, warn, error, fatal)"), {% if is_lifecycle %} DeclareLaunchArgument("startup_state", default_value="None", description="initial lifecycle state"), {% endif %} @@ -46,6 +47,7 @@ def generate_launch_description(): {% else %} parameters=[], {% endif %} + arguments=["--ros-args", "--log-level", LaunchConfiguration("log_level")], output="screen", emulate_tty=True, ) @@ -64,6 +66,7 @@ def generate_launch_description(): {% else %} parameters=[], {% endif %} + arguments=["--ros-args", "--log-level", LaunchConfiguration("log_level")], output="screen", emulate_tty=True, ) diff --git a/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja index e56f26f..59ad2ac 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'py' %}{{ node_name }}_launch.py{% endif %}.jinja @@ -15,6 +15,7 @@ def generate_launch_description(): DeclareLaunchArgument("name", default_value="{{ node_name }}", description="node name"), DeclareLaunchArgument("namespace", default_value="", description="node namespace"), DeclareLaunchArgument("params", default_value=os.path.join(get_package_share_directory("{{ package_name }}"), "config", "params.yml"), description="path to parameter file"), + DeclareLaunchArgument("log_level", default_value="info", description="ROS logging level (debug, info, warn, error, fatal)"), ] nodes = [ @@ -28,6 +29,7 @@ def generate_launch_description(): {% else %} parameters=[], {% endif %} + arguments=["--ros-args", "--log-level", LaunchConfiguration("log_level")], output="screen", emulate_tty=True, ) From f6f267bbfd6797af221c8a5c654578b6c71302f9 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Wed, 16 Oct 2024 21:52:29 +0200 Subject: [PATCH 53/67] improve xml launch files --- ...type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja | 3 ++- ...type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja index 745aea4..5a80568 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja @@ -2,10 +2,11 @@ + {% if has_params %} - + {% endif %} diff --git a/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja index 745aea4..5a80568 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{% if has_launch_file %}launch{% endif %}/{% if launch_file_type == 'xml' %}{{ node_name }}_launch.xml{% endif %}.jinja @@ -2,10 +2,11 @@ + {% if has_params %} - + {% endif %} From b39d9ffbb1061175f83f29841002171e3ae4f59d Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Wed, 16 Oct 2024 21:59:47 +0200 Subject: [PATCH 54/67] improve formatting of python nodes --- .../ros2_python_all_pkg/ros2_python_node.py | 24 ++++++++++++---- .../ros2_python_pkg/ros2_python_node.py | 20 ++++++++++--- .../{{ node_name }}.py.jinja | 28 +++++++++++++------ 3 files changed, 54 insertions(+), 18 deletions(-) diff --git a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py index f94290f..75e7573 100644 --- a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py +++ b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py @@ -22,7 +22,6 @@ def __init__(self): self.publisher = None self.param = 1.0 - self.param = self.declareAndLoadParameter(name="param", param_type=rclpy.Parameter.Type.DOUBLE, description="TODO", @@ -30,9 +29,21 @@ def __init__(self): from_value=0.0, to_value=10.0, step_value=0.1) + self.setup() - def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, description: str, default: Optional[Any] = None, add_to_auto_reconfigurable_params: bool = True, is_required: bool = False , read_only: bool = False, from_value: Optional[Union[int, float]] = None, to_value: Optional[Union[int, float]] = None, step_value: Optional[Union[int, float]] = None, additional_constraints: str = "") -> Any: + def declareAndLoadParameter(self, + name: str, + param_type: rclpy.Parameter.Type, + description: str, + default: Optional[Any] = None, + add_to_auto_reconfigurable_params: bool = True, + is_required: bool = False, + read_only: bool = False, + from_value: Optional[Union[int, float]] = None, + to_value: Optional[Union[int, float]] = None, + step_value: Optional[Union[int, float]] = None, + additional_constraints: str = "") -> Any: """Declares and loads a ROS parameter Args: @@ -52,11 +63,11 @@ def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, d Any: parameter value """ + # declare parameter param_desc = ParameterDescriptor() param_desc.description = description param_desc.additional_constraints = additional_constraints param_desc.read_only = read_only - if from_value is not None and to_value is not None: if param_type == rclpy.Parameter.Type.INTEGER: step_value = step_value if step_value is not None else 1 @@ -66,9 +77,9 @@ def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, d param_desc.floating_point_range = [FloatingPointRange(from_value=from_value, to_value=to_value, step=step_value)] else: self.get_logger().warn(f"Parameter type of parameter '{name}' does not support specifying a range") - self.declare_parameter(name, param_type, param_desc) + # load parameter try: param = self.get_parameter(name).value except rclpy.exceptions.ParameterUninitializedException: @@ -79,6 +90,7 @@ def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, d self.get_logger().warn(f"Missing parameter '{name}', using default value: {default}") param = default + # add parameter to auto-reconfigurable parameters if add_to_auto_reconfigurable_params: # TODO: this probably doesn't work self.auto_reconfigurable_params.append((name, param)) @@ -224,8 +236,8 @@ async def actionExecute(self, goal_handle: Fibonacci.Goal) -> Fibonacci.Result: loop_rate = 1 # create the action feedback and result - feedback = SampleAction.Feedback() - result = SampleAction.Result() + feedback = Fibonacci.Feedback() + result = Fibonacci.Result() # initialize the Fibonacci sequence feedback.partial_fibonacci = [0, 1] diff --git a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py index 84c5fac..8daf514 100644 --- a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py +++ b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py @@ -20,7 +20,6 @@ def __init__(self): self.publisher = None self.param = 1.0 - self.param = self.declareAndLoadParameter(name="param", param_type=rclpy.Parameter.Type.DOUBLE, description="TODO", @@ -28,9 +27,21 @@ def __init__(self): from_value=0.0, to_value=10.0, step_value=0.1) + self.setup() - def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, description: str, default: Optional[Any] = None, add_to_auto_reconfigurable_params: bool = True, is_required: bool = False , read_only: bool = False, from_value: Optional[Union[int, float]] = None, to_value: Optional[Union[int, float]] = None, step_value: Optional[Union[int, float]] = None, additional_constraints: str = "") -> Any: + def declareAndLoadParameter(self, + name: str, + param_type: rclpy.Parameter.Type, + description: str, + default: Optional[Any] = None, + add_to_auto_reconfigurable_params: bool = True, + is_required: bool = False, + read_only: bool = False, + from_value: Optional[Union[int, float]] = None, + to_value: Optional[Union[int, float]] = None, + step_value: Optional[Union[int, float]] = None, + additional_constraints: str = "") -> Any: """Declares and loads a ROS parameter Args: @@ -50,11 +61,11 @@ def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, d Any: parameter value """ + # declare parameter param_desc = ParameterDescriptor() param_desc.description = description param_desc.additional_constraints = additional_constraints param_desc.read_only = read_only - if from_value is not None and to_value is not None: if param_type == rclpy.Parameter.Type.INTEGER: step_value = step_value if step_value is not None else 1 @@ -64,9 +75,9 @@ def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, d param_desc.floating_point_range = [FloatingPointRange(from_value=from_value, to_value=to_value, step=step_value)] else: self.get_logger().warn(f"Parameter type of parameter '{name}' does not support specifying a range") - self.declare_parameter(name, param_type, param_desc) + # load parameter try: param = self.get_parameter(name).value except rclpy.exceptions.ParameterUninitializedException: @@ -77,6 +88,7 @@ def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, d self.get_logger().warn(f"Missing parameter '{name}', using default value: {default}") param = default + # add parameter to auto-reconfigurable parameters if add_to_auto_reconfigurable_params: # TODO: this probably doesn't work self.auto_reconfigurable_params.append((name, param)) diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja index ddb5095..3404980 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -30,10 +30,9 @@ class {{ node_class_name }}(Node): {% endif %} self.subscriber = None self.publisher = None - {% if has_params %} - self.param = 1.0 + self.param = 1.0 self.param = self.declareAndLoadParameter(name="param", param_type=rclpy.Parameter.Type.DOUBLE, description="TODO", @@ -42,10 +41,22 @@ class {{ node_class_name }}(Node): to_value=10.0, step_value=0.1) {% endif %} - self.setup() + self.setup() {% if has_params %} - def declareAndLoadParameter(self, name: str, param_type: rclpy.Parameter.Type, description: str, default: Optional[Any] = None, add_to_auto_reconfigurable_params: bool = True, is_required: bool = False , read_only: bool = False, from_value: Optional[Union[int, float]] = None, to_value: Optional[Union[int, float]] = None, step_value: Optional[Union[int, float]] = None, additional_constraints: str = "") -> Any: + + def declareAndLoadParameter(self, + name: str, + param_type: rclpy.Parameter.Type, + description: str, + default: Optional[Any] = None, + add_to_auto_reconfigurable_params: bool = True, + is_required: bool = False, + read_only: bool = False, + from_value: Optional[Union[int, float]] = None, + to_value: Optional[Union[int, float]] = None, + step_value: Optional[Union[int, float]] = None, + additional_constraints: str = "") -> Any: """Declares and loads a ROS parameter Args: @@ -65,11 +76,11 @@ class {{ node_class_name }}(Node): Any: parameter value """ + # declare parameter param_desc = ParameterDescriptor() param_desc.description = description param_desc.additional_constraints = additional_constraints param_desc.read_only = read_only - if from_value is not None and to_value is not None: if param_type == rclpy.Parameter.Type.INTEGER: step_value = step_value if step_value is not None else 1 @@ -79,9 +90,9 @@ class {{ node_class_name }}(Node): param_desc.floating_point_range = [FloatingPointRange(from_value=from_value, to_value=to_value, step=step_value)] else: self.get_logger().warn(f"Parameter type of parameter '{name}' does not support specifying a range") - self.declare_parameter(name, param_type, param_desc) + # load parameter try: param = self.get_parameter(name).value except rclpy.exceptions.ParameterUninitializedException: @@ -92,6 +103,7 @@ class {{ node_class_name }}(Node): self.get_logger().warn(f"Missing parameter '{name}', using default value: {default}") param = default + # add parameter to auto-reconfigurable parameters if add_to_auto_reconfigurable_params: # TODO: this probably doesn't work self.auto_reconfigurable_params.append((name, param)) @@ -259,8 +271,8 @@ class {{ node_class_name }}(Node): loop_rate = 1 # create the action feedback and result - feedback = SampleAction.Feedback() - result = SampleAction.Result() + feedback = Fibonacci.Feedback() + result = Fibonacci.Result() # initialize the Fibonacci sequence feedback.partial_fibonacci = [0, 1] From 408f6300746cc22b670d4839c65eced81db7b505 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Wed, 16 Oct 2024 22:12:35 +0200 Subject: [PATCH 55/67] fix installation of python config file --- templates/ros2_python_pkg/{{ package_name }}/setup.py.jinja | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/templates/ros2_python_pkg/{{ package_name }}/setup.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/setup.py.jinja index 6f65446..6b068c1 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/setup.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/setup.py.jinja @@ -14,7 +14,7 @@ setup( (os.path.join('share', package_name, 'launch'), glob('launch/*launch.[pxy][yma]*')), (os.path.join('share', package_name, - 'config'), glob('config/*.yaml'))], + 'config'), glob('config/*'))], install_requires=['setuptools'], zip_safe=True, maintainer='root', From 4c367d47ba7f3731f7e2e6685312d080f8594a3a Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Wed, 16 Oct 2024 22:12:48 +0200 Subject: [PATCH 56/67] log loaded params --- samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp | 11 ++++++++++- samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp | 11 ++++++++++- samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp | 11 ++++++++++- samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp | 11 ++++++++++- .../ros2_python_all_pkg/ros2_python_node.py | 1 + samples/ros2_python_all_pkg/setup.py | 2 +- .../ros2_python_pkg/ros2_python_node.py | 1 + samples/ros2_python_pkg/setup.py | 2 +- .../{{ package_name }}/src/{{ node_name }}.cpp.jinja | 11 ++++++++++- .../{{ package_name }}/{{ node_name }}.py.jinja | 1 + 10 files changed, 55 insertions(+), 7 deletions(-) diff --git a/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp index a9e56a9..d732f9b 100644 --- a/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp @@ -81,6 +81,15 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, try { param = this->get_parameter(name).get_value(); + std::stringstream ss; + ss << "Loaded parameter '" << name << "': "; + if constexpr (is_vector_v) { + ss << "["; + for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); + } else { + ss << param; + } + RCLCPP_INFO_STREAM(this->get_logger(), ss.str()); } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); @@ -99,7 +108,7 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { - // why so complicated, storing lambda functions? / why vector, not map? + // TODO: why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; diff --git a/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp index 5225a8a..c201aff 100644 --- a/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp @@ -74,6 +74,15 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, try { param = this->get_parameter(name).get_value(); + std::stringstream ss; + ss << "Loaded parameter '" << name << "': "; + if constexpr (is_vector_v) { + ss << "["; + for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); + } else { + ss << param; + } + RCLCPP_INFO_STREAM(this->get_logger(), ss.str()); } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); @@ -92,7 +101,7 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { - // why so complicated, storing lambda functions? / why vector, not map? + // TODO: why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; diff --git a/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp index a39a8ed..cd111a2 100644 --- a/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp @@ -76,6 +76,15 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, try { param = this->get_parameter(name).get_value(); + std::stringstream ss; + ss << "Loaded parameter '" << name << "': "; + if constexpr (is_vector_v) { + ss << "["; + for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); + } else { + ss << param; + } + RCLCPP_INFO_STREAM(this->get_logger(), ss.str()); } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); @@ -94,7 +103,7 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { - // why so complicated, storing lambda functions? / why vector, not map? + // TODO: why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; diff --git a/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp index 57b4cc2..e5adf81 100644 --- a/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp @@ -71,6 +71,15 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, try { param = this->get_parameter(name).get_value(); + std::stringstream ss; + ss << "Loaded parameter '" << name << "': "; + if constexpr (is_vector_v) { + ss << "["; + for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); + } else { + ss << param; + } + RCLCPP_INFO_STREAM(this->get_logger(), ss.str()); } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); @@ -89,7 +98,7 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { - // why so complicated, storing lambda functions? / why vector, not map? + // TODO: why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; diff --git a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py index 75e7573..7bc6bf7 100644 --- a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py +++ b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py @@ -82,6 +82,7 @@ def declareAndLoadParameter(self, # load parameter try: param = self.get_parameter(name).value + self.get_logger().info(f"Loaded parameter '{name}': {param}") except rclpy.exceptions.ParameterUninitializedException: if is_required: self.get_logger().fatal(f"Missing required parameter '{name}', exiting") diff --git a/samples/ros2_python_all_pkg/setup.py b/samples/ros2_python_all_pkg/setup.py index aa35513..20fa2ab 100644 --- a/samples/ros2_python_all_pkg/setup.py +++ b/samples/ros2_python_all_pkg/setup.py @@ -14,7 +14,7 @@ (os.path.join('share', package_name, 'launch'), glob('launch/*launch.[pxy][yma]*')), (os.path.join('share', package_name, - 'config'), glob('config/*.yaml'))], + 'config'), glob('config/*'))], install_requires=['setuptools'], zip_safe=True, maintainer='root', diff --git a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py index 8daf514..ba36d89 100644 --- a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py +++ b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py @@ -80,6 +80,7 @@ def declareAndLoadParameter(self, # load parameter try: param = self.get_parameter(name).value + self.get_logger().info(f"Loaded parameter '{name}': {param}") except rclpy.exceptions.ParameterUninitializedException: if is_required: self.get_logger().fatal(f"Missing required parameter '{name}', exiting") diff --git a/samples/ros2_python_pkg/setup.py b/samples/ros2_python_pkg/setup.py index c7e404f..6884337 100644 --- a/samples/ros2_python_pkg/setup.py +++ b/samples/ros2_python_pkg/setup.py @@ -14,7 +14,7 @@ (os.path.join('share', package_name, 'launch'), glob('launch/*launch.[pxy][yma]*')), (os.path.join('share', package_name, - 'config'), glob('config/*.yaml'))], + 'config'), glob('config/*'))], install_requires=['setuptools'], zip_safe=True, maintainer='root', diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja index 8db8e81..da21abd 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja @@ -105,6 +105,15 @@ void {{ node_class_name }}::declareAndLoadParameter(const std::string& name, try { param = this->get_parameter(name).get_value(); + std::stringstream ss; + ss << "Loaded parameter '" << name << "': "; + if constexpr (is_vector_v) { + ss << "["; + for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); + } else { + ss << param; + } + RCLCPP_INFO_STREAM(this->get_logger(), ss.str()); } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); @@ -123,7 +132,7 @@ void {{ node_class_name }}::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { - // why so complicated, storing lambda functions? / why vector, not map? + // TODO: why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja index 3404980..0f7f5f7 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -95,6 +95,7 @@ class {{ node_class_name }}(Node): # load parameter try: param = self.get_parameter(name).value + self.get_logger().info(f"Loaded parameter '{name}': {param}") except rclpy.exceptions.ParameterUninitializedException: if is_required: self.get_logger().fatal(f"Missing required parameter '{name}', exiting") From 45b77e0ce703feb6b9eb2285b64fbe9fb17936a4 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Wed, 16 Oct 2024 22:24:45 +0200 Subject: [PATCH 57/67] improve python node shutdown behavior --- .../ros2_python_all_pkg/ros2_python_node.py | 13 +++++++---- .../ros2_python_pkg/ros2_python_node.py | 22 +++++++++++++++---- .../{{ node_name }}.py.jinja | 15 ++++++++----- 3 files changed, 37 insertions(+), 13 deletions(-) diff --git a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py index 7bc6bf7..8995557 100644 --- a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py +++ b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py @@ -1,4 +1,3 @@ -import sys from typing import Any, Optional, Union import rclpy @@ -86,7 +85,7 @@ def declareAndLoadParameter(self, except rclpy.exceptions.ParameterUninitializedException: if is_required: self.get_logger().fatal(f"Missing required parameter '{name}', exiting") - sys.exit(1) # TODO: rclpy shutdown? + raise SystemExit(1) else: self.get_logger().warn(f"Missing parameter '{name}', using default value: {default}") param = default @@ -283,8 +282,14 @@ def timerCallback(self): def main(): rclpy.init() - rclpy.spin(Ros2PythonNode()) - rclpy.shutdown() + node = Ros2PythonNode() + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + rclpy.try_shutdown() if __name__ == '__main__': diff --git a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py index ba36d89..e43a2d4 100644 --- a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py +++ b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py @@ -1,4 +1,3 @@ -import sys from typing import Any, Optional, Union import rclpy @@ -84,7 +83,7 @@ def declareAndLoadParameter(self, except rclpy.exceptions.ParameterUninitializedException: if is_required: self.get_logger().fatal(f"Missing required parameter '{name}', exiting") - sys.exit(1) # TODO: rclpy shutdown? + raise SystemExit(1) else: self.get_logger().warn(f"Missing parameter '{name}', using default value: {default}") param = default @@ -139,6 +138,8 @@ def setup(self): qos_profile=10) self.get_logger().info(f"Publishing to '{self.publisher.topic_name}'") + self.auto_shutdown_timer = self.create_timer(3.0, self.autoShutdownTimerCallback) + def topicCallback(self, msg: Int32): """Processes messages received by a subscriber @@ -148,12 +149,25 @@ def topicCallback(self, msg: Int32): self.get_logger().info(f"Message received: '{msg.data}'") + def autoShutdownTimerCallback(self): + """Processes timer triggers to auto-shutdown the node + """ + + self.get_logger().info("Shutting down") + raise SystemExit(0) + def main(): rclpy.init() - rclpy.spin(Ros2PythonNode()) - rclpy.shutdown() + node = Ros2PythonNode() + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + rclpy.try_shutdown() if __name__ == '__main__': diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja index 0f7f5f7..701ef3c 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -1,4 +1,3 @@ -import sys from typing import Any, Optional, Union import rclpy @@ -99,7 +98,7 @@ class {{ node_class_name }}(Node): except rclpy.exceptions.ParameterUninitializedException: if is_required: self.get_logger().fatal(f"Missing required parameter '{name}', exiting") - sys.exit(1) # TODO: rclpy shutdown? + raise SystemExit(1) else: self.get_logger().warn(f"Missing parameter '{name}', using default value: {default}") param = default @@ -323,15 +322,21 @@ class {{ node_class_name }}(Node): """ self.get_logger().info("Shutting down") - rclpy.shutdown() + raise SystemExit(0) {% endif %} def main(): rclpy.init() - rclpy.spin({{ node_class_name }}()) - rclpy.shutdown() + node = {{ node_class_name }}() + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + rclpy.try_shutdown() if __name__ == '__main__': From 8ac670068752b5ac79f57ee9b8a9e80c3e2dc998 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Wed, 16 Oct 2024 22:47:37 +0200 Subject: [PATCH 58/67] fix python actions in jazzy --- samples/ros2_python_all_pkg/package.xml | 5 +- .../ros2_python_all_pkg/ros2_python_node.py | 48 ++++++++--------- samples/ros2_python_pkg/package.xml | 4 +- .../ros2_python_pkg/ros2_python_node.py | 9 ---- .../{{ package_name }}/package.xml.jinja | 7 +-- .../{{ node_name }}.py.jinja | 52 ++++++++++--------- 6 files changed, 55 insertions(+), 70 deletions(-) diff --git a/samples/ros2_python_all_pkg/package.xml b/samples/ros2_python_all_pkg/package.xml index 39e0c5a..e3bf6a9 100644 --- a/samples/ros2_python_all_pkg/package.xml +++ b/samples/ros2_python_all_pkg/package.xml @@ -11,11 +11,8 @@ TODO - ament_python - rclpy - rclcpp_action -std_msgs + std_msgs std_srvs ros2_python_all_pkg_interfaces diff --git a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py index 8995557..60547d4 100644 --- a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py +++ b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py @@ -1,6 +1,8 @@ +import time from typing import Any, Optional, Union import rclpy +from rclpy.action import ActionServer, CancelResponse, GoalResponse from rclpy.node import Node from rcl_interfaces.msg import (FloatingPointRange, IntegerRange, ParameterDescriptor, SetParametersResult) from std_msgs.msg import Int32 @@ -144,7 +146,7 @@ def setup(self): self.service_server = self.create_service(SetBool, "~/service", self.serviceCallback) # action server for handling action goal requests - self.action_server = rclpy.action.ActionServer( + self.action_server = ActionServer( self, Fibonacci, "~/action", @@ -182,49 +184,49 @@ def serviceCallback(self, request: SetBool.Request, response: SetBool.Response) return response - def actionHandleGoal(self, goal: Fibonacci.Goal) -> rclpy.action.server.GoalResponse: + def actionHandleGoal(self, goal: Fibonacci.Goal) -> GoalResponse: """Processes action goal requests Args: goal (Fibonacci.Goal): action goal Returns: - rclpy.action.server.GoalResponse: goal response + GoalResponse: goal response """ self.get_logger().info("Received action goal request") - return rclpy.action.server.GoalResponse.ACCEPT + return GoalResponse.ACCEPT - def actionHandleCancel(self, goal_handle: Fibonacci.GoalHandle) -> rclpy.action.server.CancelResponse: + def actionHandleCancel(self, goal: Fibonacci.Goal) -> CancelResponse: """Processes action cancel requests Args: - goal_handle (Fibonacci.GoalHandle): action goal handle + goal (Fibonacci.Goal): action goal Returns: - rclpy.action.server.CancelResponse: cancel response + CancelResponse: cancel response """ self.get_logger().info("Received request to cancel action goal") - return rclpy.action.server.CancelResponse.ACCEPT + return CancelResponse.ACCEPT - def actionHandleAccepted(self, goal_handle: Fibonacci.GoalHandle): + def actionHandleAccepted(self, goal: Fibonacci.Goal): """Processes accepted action goal requests Args: - goal_handle (Fibonacci.Goal): action goal handle + goal (Fibonacci.Goal): action goal """ # execute action in a separate thread to avoid blocking - goal_handle.execute() + goal.execute() - async def actionExecute(self, goal_handle: Fibonacci.Goal) -> Fibonacci.Result: + async def actionExecute(self, goal: Fibonacci.Goal) -> Fibonacci.Result: """Executes an action Args: - goal_handle (Fibonacci.Goal): action goal handle + goal (Fibonacci.Goal): action goal Returns: Fibonacci.Result: action goal result @@ -240,25 +242,23 @@ async def actionExecute(self, goal_handle: Fibonacci.Goal) -> Fibonacci.Result: result = Fibonacci.Result() # initialize the Fibonacci sequence - feedback.partial_fibonacci = [0, 1] + feedback.partial_sequence = [0, 1] # compute the Fibonacci sequence up to the requested order n - for i in range(1, goal_handle.request.n): + for i in range(1, goal.request.order): # cancel, if requested - if goal_handle.is_cancel_requested: - result.fibonacci = feedback.partial_fibonacci - goal_handle.canceled() + if goal.is_cancel_requested: + result.sequence = feedback.partial_sequence + goal.canceled() self.get_logger().info("Action goal canceled") return result # compute the next Fibonacci number - feedback.partial_fibonacci.append(feedback.partial_fibonacci[i] + - feedback.partial_fibonacci[i - - 1]) + feedback.partial_sequence.append(feedback.partial_sequence[i] + feedback.partial_sequence[i-1]) # publish the current sequence as action feedback - goal_handle.publish_feedback(feedback) + goal.publish_feedback(feedback) self.get_logger().info("Publishing action feedback") # sleep before computing the next Fibonacci number @@ -266,8 +266,8 @@ async def actionExecute(self, goal_handle: Fibonacci.Goal) -> Fibonacci.Result: # finish by publishing the action result if rclpy.ok(): - result.fibonacci = feedback.partial_fibonacci - goal_handle.succeed() + result.sequence = feedback.partial_sequence + goal.succeed() self.get_logger().info("Goal succeeded") return result diff --git a/samples/ros2_python_pkg/package.xml b/samples/ros2_python_pkg/package.xml index bf17ef9..e37ac9c 100644 --- a/samples/ros2_python_pkg/package.xml +++ b/samples/ros2_python_pkg/package.xml @@ -11,10 +11,8 @@ TODO - ament_python - rclpy -std_msgs + std_msgs ament_python diff --git a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py index e43a2d4..9f95a64 100644 --- a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py +++ b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py @@ -138,8 +138,6 @@ def setup(self): qos_profile=10) self.get_logger().info(f"Publishing to '{self.publisher.topic_name}'") - self.auto_shutdown_timer = self.create_timer(3.0, self.autoShutdownTimerCallback) - def topicCallback(self, msg: Int32): """Processes messages received by a subscriber @@ -149,13 +147,6 @@ def topicCallback(self, msg: Int32): self.get_logger().info(f"Message received: '{msg.data}'") - def autoShutdownTimerCallback(self): - """Processes timer triggers to auto-shutdown the node - """ - - self.get_logger().info("Shutting down") - raise SystemExit(0) - def main(): diff --git a/templates/ros2_python_pkg/{{ package_name }}/package.xml.jinja b/templates/ros2_python_pkg/{{ package_name }}/package.xml.jinja index 9610124..6c08f14 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/package.xml.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/package.xml.jinja @@ -11,13 +11,8 @@ {{ license }} - ament_python - rclpy -{% if has_action_server %} - rclcpp_action -{% endif %} -std_msgs + std_msgs {% if has_service_server %} std_srvs {% endif %} diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja index 701ef3c..9f7793b 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -1,6 +1,12 @@ +{% if has_action_server %} +import time +{% endif %} from typing import Any, Optional, Union import rclpy +{% if has_action_server %} +from rclpy.action import ActionServer, CancelResponse, GoalResponse +{% endif %} from rclpy.node import Node {% if has_params %} from rcl_interfaces.msg import (FloatingPointRange, IntegerRange, ParameterDescriptor, SetParametersResult) @@ -167,7 +173,7 @@ class {{ node_class_name }}(Node): {% if has_action_server %} # action server for handling action goal requests - self.action_server = rclpy.action.ActionServer( + self.action_server = ActionServer( self, Fibonacci, "~/action", @@ -217,49 +223,49 @@ class {{ node_class_name }}(Node): {% endif %} {% if has_action_server %} - def actionHandleGoal(self, goal: Fibonacci.Goal) -> rclpy.action.server.GoalResponse: + def actionHandleGoal(self, goal: Fibonacci.Goal) -> GoalResponse: """Processes action goal requests Args: goal (Fibonacci.Goal): action goal Returns: - rclpy.action.server.GoalResponse: goal response + GoalResponse: goal response """ self.get_logger().info("Received action goal request") - return rclpy.action.server.GoalResponse.ACCEPT + return GoalResponse.ACCEPT - def actionHandleCancel(self, goal_handle: Fibonacci.GoalHandle) -> rclpy.action.server.CancelResponse: + def actionHandleCancel(self, goal: Fibonacci.Goal) -> CancelResponse: """Processes action cancel requests Args: - goal_handle (Fibonacci.GoalHandle): action goal handle + goal (Fibonacci.Goal): action goal Returns: - rclpy.action.server.CancelResponse: cancel response + CancelResponse: cancel response """ self.get_logger().info("Received request to cancel action goal") - return rclpy.action.server.CancelResponse.ACCEPT + return CancelResponse.ACCEPT - def actionHandleAccepted(self, goal_handle: Fibonacci.GoalHandle): + def actionHandleAccepted(self, goal: Fibonacci.Goal): """Processes accepted action goal requests Args: - goal_handle (Fibonacci.Goal): action goal handle + goal (Fibonacci.Goal): action goal """ # execute action in a separate thread to avoid blocking - goal_handle.execute() + goal.execute() - async def actionExecute(self, goal_handle: Fibonacci.Goal) -> Fibonacci.Result: + async def actionExecute(self, goal: Fibonacci.Goal) -> Fibonacci.Result: """Executes an action Args: - goal_handle (Fibonacci.Goal): action goal handle + goal (Fibonacci.Goal): action goal Returns: Fibonacci.Result: action goal result @@ -275,25 +281,23 @@ class {{ node_class_name }}(Node): result = Fibonacci.Result() # initialize the Fibonacci sequence - feedback.partial_fibonacci = [0, 1] + feedback.partial_sequence = [0, 1] # compute the Fibonacci sequence up to the requested order n - for i in range(1, goal_handle.request.n): + for i in range(1, goal.request.order): # cancel, if requested - if goal_handle.is_cancel_requested: - result.fibonacci = feedback.partial_fibonacci - goal_handle.canceled() + if goal.is_cancel_requested: + result.sequence = feedback.partial_sequence + goal.canceled() self.get_logger().info("Action goal canceled") return result # compute the next Fibonacci number - feedback.partial_fibonacci.append(feedback.partial_fibonacci[i] + - feedback.partial_fibonacci[i - - 1]) + feedback.partial_sequence.append(feedback.partial_sequence[i] + feedback.partial_sequence[i-1]) # publish the current sequence as action feedback - goal_handle.publish_feedback(feedback) + goal.publish_feedback(feedback) self.get_logger().info("Publishing action feedback") # sleep before computing the next Fibonacci number @@ -301,8 +305,8 @@ class {{ node_class_name }}(Node): # finish by publishing the action result if rclpy.ok(): - result.fibonacci = feedback.partial_fibonacci - goal_handle.succeed() + result.sequence = feedback.partial_sequence + goal.succeed() self.get_logger().info("Goal succeeded") return result From d06687a169bda73b33d1cdc0c1ac5d3146f66c46 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Wed, 16 Oct 2024 23:02:36 +0200 Subject: [PATCH 59/67] fix auto_reconfigurable_params in python node --- samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp | 11 ++++++----- samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp | 11 ++++++----- samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp | 11 ++++++----- samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp | 11 ++++++----- .../ros2_python_all_pkg/ros2_python_node.py | 11 ++++------- .../ros2_python_pkg/ros2_python_node.py | 11 ++++------- .../{{ package_name }}/src/{{ node_name }}.cpp.jinja | 11 ++++++----- .../{{ package_name }}/{{ node_name }}.py.jinja | 11 ++++------- 8 files changed, 42 insertions(+), 46 deletions(-) diff --git a/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp index d732f9b..7a45362 100644 --- a/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp @@ -62,12 +62,12 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, auto type = rclcpp::ParameterValue(param).get_type(); if (from_value.has_value() && to_value.has_value()) { - if constexpr (std::is_integral_v) { + if constexpr(std::is_integral_v) { rcl_interfaces::msg::IntegerRange range; T step = static_cast(step_value.has_value() ? step_value.value() : 1); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.integer_range = {range}; - } else if constexpr (std::is_floating_point_v) { + } else if constexpr(std::is_floating_point_v) { rcl_interfaces::msg::FloatingPointRange range; T step = static_cast(step_value.has_value() ? step_value.value() : 1.0); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); @@ -83,7 +83,7 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, param = this->get_parameter(name).get_value(); std::stringstream ss; ss << "Loaded parameter '" << name << "': "; - if constexpr (is_vector_v) { + if constexpr(is_vector_v) { ss << "["; for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); } else { @@ -93,11 +93,11 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); - exit(EXIT_FAILURE); // TODO: rclpy shutdown? + exit(EXIT_FAILURE); } else { std::stringstream ss; ss << "Missing parameter '" << name << "', using default value: "; - if constexpr (is_vector_v) { + if constexpr(is_vector_v) { ss << "["; for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); } else { @@ -129,6 +129,7 @@ rcl_interfaces::msg::SetParametersResult Ros2CppNode::parametersCallback(const s for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { std::get<1>(auto_reconfigurable_param)(param); + RCLCPP_INFO(this->get_logger(), "Reconfigured parameter '%s'", param.get_name().c_str()); break; } } diff --git a/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp index c201aff..11867d8 100644 --- a/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp @@ -55,12 +55,12 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, auto type = rclcpp::ParameterValue(param).get_type(); if (from_value.has_value() && to_value.has_value()) { - if constexpr (std::is_integral_v) { + if constexpr(std::is_integral_v) { rcl_interfaces::msg::IntegerRange range; T step = static_cast(step_value.has_value() ? step_value.value() : 1); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.integer_range = {range}; - } else if constexpr (std::is_floating_point_v) { + } else if constexpr(std::is_floating_point_v) { rcl_interfaces::msg::FloatingPointRange range; T step = static_cast(step_value.has_value() ? step_value.value() : 1.0); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); @@ -76,7 +76,7 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, param = this->get_parameter(name).get_value(); std::stringstream ss; ss << "Loaded parameter '" << name << "': "; - if constexpr (is_vector_v) { + if constexpr(is_vector_v) { ss << "["; for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); } else { @@ -86,11 +86,11 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); - exit(EXIT_FAILURE); // TODO: rclpy shutdown? + exit(EXIT_FAILURE); } else { std::stringstream ss; ss << "Missing parameter '" << name << "', using default value: "; - if constexpr (is_vector_v) { + if constexpr(is_vector_v) { ss << "["; for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); } else { @@ -122,6 +122,7 @@ rcl_interfaces::msg::SetParametersResult Ros2CppNode::parametersCallback(const s for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { std::get<1>(auto_reconfigurable_param)(param); + RCLCPP_INFO(this->get_logger(), "Reconfigured parameter '%s'", param.get_name().c_str()); break; } } diff --git a/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp index cd111a2..94d7da6 100644 --- a/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp @@ -57,12 +57,12 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, auto type = rclcpp::ParameterValue(param).get_type(); if (from_value.has_value() && to_value.has_value()) { - if constexpr (std::is_integral_v) { + if constexpr(std::is_integral_v) { rcl_interfaces::msg::IntegerRange range; T step = static_cast(step_value.has_value() ? step_value.value() : 1); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.integer_range = {range}; - } else if constexpr (std::is_floating_point_v) { + } else if constexpr(std::is_floating_point_v) { rcl_interfaces::msg::FloatingPointRange range; T step = static_cast(step_value.has_value() ? step_value.value() : 1.0); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); @@ -78,7 +78,7 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, param = this->get_parameter(name).get_value(); std::stringstream ss; ss << "Loaded parameter '" << name << "': "; - if constexpr (is_vector_v) { + if constexpr(is_vector_v) { ss << "["; for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); } else { @@ -88,11 +88,11 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); - exit(EXIT_FAILURE); // TODO: rclpy shutdown? + exit(EXIT_FAILURE); } else { std::stringstream ss; ss << "Missing parameter '" << name << "', using default value: "; - if constexpr (is_vector_v) { + if constexpr(is_vector_v) { ss << "["; for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); } else { @@ -124,6 +124,7 @@ rcl_interfaces::msg::SetParametersResult Ros2CppNode::parametersCallback(const s for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { std::get<1>(auto_reconfigurable_param)(param); + RCLCPP_INFO(this->get_logger(), "Reconfigured parameter '%s'", param.get_name().c_str()); break; } } diff --git a/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp index e5adf81..712e97a 100644 --- a/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp @@ -52,12 +52,12 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, auto type = rclcpp::ParameterValue(param).get_type(); if (from_value.has_value() && to_value.has_value()) { - if constexpr (std::is_integral_v) { + if constexpr(std::is_integral_v) { rcl_interfaces::msg::IntegerRange range; T step = static_cast(step_value.has_value() ? step_value.value() : 1); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.integer_range = {range}; - } else if constexpr (std::is_floating_point_v) { + } else if constexpr(std::is_floating_point_v) { rcl_interfaces::msg::FloatingPointRange range; T step = static_cast(step_value.has_value() ? step_value.value() : 1.0); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); @@ -73,7 +73,7 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, param = this->get_parameter(name).get_value(); std::stringstream ss; ss << "Loaded parameter '" << name << "': "; - if constexpr (is_vector_v) { + if constexpr(is_vector_v) { ss << "["; for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); } else { @@ -83,11 +83,11 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); - exit(EXIT_FAILURE); // TODO: rclpy shutdown? + exit(EXIT_FAILURE); } else { std::stringstream ss; ss << "Missing parameter '" << name << "', using default value: "; - if constexpr (is_vector_v) { + if constexpr(is_vector_v) { ss << "["; for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); } else { @@ -119,6 +119,7 @@ rcl_interfaces::msg::SetParametersResult Ros2CppNode::parametersCallback(const s for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { std::get<1>(auto_reconfigurable_param)(param); + RCLCPP_INFO(this->get_logger(), "Reconfigured parameter '%s'", param.get_name().c_str()); break; } } diff --git a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py index 60547d4..f5b1016 100644 --- a/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py +++ b/samples/ros2_python_all_pkg/ros2_python_all_pkg/ros2_python_node.py @@ -94,8 +94,7 @@ def declareAndLoadParameter(self, # add parameter to auto-reconfigurable parameters if add_to_auto_reconfigurable_params: - # TODO: this probably doesn't work - self.auto_reconfigurable_params.append((name, param)) + self.auto_reconfigurable_params.append(name) return param @@ -111,11 +110,9 @@ def parametersCallback(self, """ for param in parameters: - for auto_reconfigurable_param in self.auto_reconfigurable_params: - if param.name == auto_reconfigurable_param[0]: - # TODO: this probably doesn't work - auto_reconfigurable_param[1] = param.value - break + if param.name in self.auto_reconfigurable_params: + setattr(self, param.name, param.value) + self.get_logger().info(f"Reconfigured parameter '{param.name}' to: {param.value}") result = SetParametersResult() result.successful = True diff --git a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py index 9f95a64..664bd43 100644 --- a/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py +++ b/samples/ros2_python_pkg/ros2_python_pkg/ros2_python_node.py @@ -90,8 +90,7 @@ def declareAndLoadParameter(self, # add parameter to auto-reconfigurable parameters if add_to_auto_reconfigurable_params: - # TODO: this probably doesn't work - self.auto_reconfigurable_params.append((name, param)) + self.auto_reconfigurable_params.append(name) return param @@ -107,11 +106,9 @@ def parametersCallback(self, """ for param in parameters: - for auto_reconfigurable_param in self.auto_reconfigurable_params: - if param.name == auto_reconfigurable_param[0]: - # TODO: this probably doesn't work - auto_reconfigurable_param[1] = param.value - break + if param.name in self.auto_reconfigurable_params: + setattr(self, param.name, param.value) + self.get_logger().info(f"Reconfigured parameter '{param.name}' to: {param.value}") result = SetParametersResult() result.successful = True diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja index da21abd..cb791c7 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja @@ -86,12 +86,12 @@ void {{ node_class_name }}::declareAndLoadParameter(const std::string& name, auto type = rclcpp::ParameterValue(param).get_type(); if (from_value.has_value() && to_value.has_value()) { - if constexpr (std::is_integral_v) { + if constexpr(std::is_integral_v) { rcl_interfaces::msg::IntegerRange range; T step = static_cast(step_value.has_value() ? step_value.value() : 1); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); param_desc.integer_range = {range}; - } else if constexpr (std::is_floating_point_v) { + } else if constexpr(std::is_floating_point_v) { rcl_interfaces::msg::FloatingPointRange range; T step = static_cast(step_value.has_value() ? step_value.value() : 1.0); range.set__from_value(static_cast(from_value.value())).set__to_value(static_cast(to_value.value())).set__step(step); @@ -107,7 +107,7 @@ void {{ node_class_name }}::declareAndLoadParameter(const std::string& name, param = this->get_parameter(name).get_value(); std::stringstream ss; ss << "Loaded parameter '" << name << "': "; - if constexpr (is_vector_v) { + if constexpr(is_vector_v) { ss << "["; for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); } else { @@ -117,11 +117,11 @@ void {{ node_class_name }}::declareAndLoadParameter(const std::string& name, } catch (rclcpp::exceptions::ParameterUninitializedException&) { if (is_required) { RCLCPP_FATAL_STREAM(this->get_logger(), "Missing required parameter '" << name << "', exiting"); - exit(EXIT_FAILURE); // TODO: rclpy shutdown? + exit(EXIT_FAILURE); } else { std::stringstream ss; ss << "Missing parameter '" << name << "', using default value: "; - if constexpr (is_vector_v) { + if constexpr(is_vector_v) { ss << "["; for (const auto& element : param) ss << element << (&element != ¶m.back() ? ", " : "]"); } else { @@ -155,6 +155,7 @@ rcl_interfaces::msg::SetParametersResult {{ node_class_name }}::parametersCallba for (auto& auto_reconfigurable_param : auto_reconfigurable_params_) { if (param.get_name() == std::get<0>(auto_reconfigurable_param)) { std::get<1>(auto_reconfigurable_param)(param); + RCLCPP_INFO(this->get_logger(), "Reconfigured parameter '%s'", param.get_name().c_str()); break; } } diff --git a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja index 9f7793b..784b2ef 100644 --- a/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja +++ b/templates/ros2_python_pkg/{{ package_name }}/{{ package_name }}/{{ node_name }}.py.jinja @@ -111,8 +111,7 @@ class {{ node_class_name }}(Node): # add parameter to auto-reconfigurable parameters if add_to_auto_reconfigurable_params: - # TODO: this probably doesn't work - self.auto_reconfigurable_params.append((name, param)) + self.auto_reconfigurable_params.append(name) return param @@ -128,11 +127,9 @@ class {{ node_class_name }}(Node): """ for param in parameters: - for auto_reconfigurable_param in self.auto_reconfigurable_params: - if param.name == auto_reconfigurable_param[0]: - # TODO: this probably doesn't work - auto_reconfigurable_param[1] = param.value - break + if param.name in self.auto_reconfigurable_params: + setattr(self, param.name, param.value) + self.get_logger().info(f"Reconfigured parameter '{param.name}' to: {param.value}") result = SetParametersResult() result.successful = True From 3ac3608389d713c63bec73e7d9585ddb6faac456 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Wed, 16 Oct 2024 23:09:49 +0200 Subject: [PATCH 60/67] remove leftover comment that is not relevant anymore --- samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp | 1 - samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp | 1 - samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp | 1 - samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp | 1 - .../{{ package_name }}/src/{{ node_name }}.cpp.jinja | 1 - 5 files changed, 5 deletions(-) diff --git a/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp index 7a45362..c6fb53d 100644 --- a/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_all_pkg/src/ros2_cpp_node.cpp @@ -108,7 +108,6 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { - // TODO: why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; diff --git a/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp index 11867d8..9a59593 100644 --- a/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_component_pkg/src/ros2_cpp_node.cpp @@ -101,7 +101,6 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { - // TODO: why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; diff --git a/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp index 94d7da6..f0bdd4e 100644 --- a/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_lifecycle_pkg/src/ros2_cpp_node.cpp @@ -103,7 +103,6 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { - // TODO: why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; diff --git a/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp b/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp index 712e97a..15ae866 100644 --- a/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp +++ b/samples/ros2_cpp_pkg/src/ros2_cpp_node.cpp @@ -98,7 +98,6 @@ void Ros2CppNode::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { - // TODO: why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja index cb791c7..02ee49d 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/src/{{ node_name }}.cpp.jinja @@ -132,7 +132,6 @@ void {{ node_class_name }}::declareAndLoadParameter(const std::string& name, } if (add_to_auto_reconfigurable_params) { - // TODO: why so complicated, storing lambda functions? / why vector, not map? std::function setter = [¶m](const rclcpp::Parameter& p) { param = p.get_value(); }; From 02c6848538eff7588ff768d4a94bf5e68fb3af01 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 17 Oct 2024 07:02:34 +0000 Subject: [PATCH 61/67] add and improve generated package readmes --- samples/ros2_cpp_all_pkg/README.md | 32 ++++--------- samples/ros2_cpp_all_pkg_interfaces/README.md | 22 +++++++++ samples/ros2_cpp_component_pkg/README.md | 32 ++++--------- samples/ros2_cpp_lifecycle_pkg/README.md | 32 ++++--------- samples/ros2_cpp_pkg/README.md | 32 ++++--------- samples/ros2_interfaces_pkg/README.md | 22 +++++++++ samples/ros2_python_all_pkg/README.md | 46 +++++++++++++++++++ .../ros2_python_all_pkg_interfaces/README.md | 22 +++++++++ samples/ros2_python_pkg/README.md | 46 +++++++++++++++++++ .../README.md.jinja | 22 +++++++++ .../{{ package_name }}/README.md.jinja | 32 ++++--------- .../{{ package_name }}/README.md.jinja | 22 +++++++++ .../README.md.jinja | 22 +++++++++ .../{{ package_name }}/README.md.jinja | 46 +++++++++++++++++++ 14 files changed, 310 insertions(+), 120 deletions(-) create mode 100644 samples/ros2_cpp_all_pkg_interfaces/README.md create mode 100644 samples/ros2_interfaces_pkg/README.md create mode 100644 samples/ros2_python_all_pkg/README.md create mode 100644 samples/ros2_python_all_pkg_interfaces/README.md create mode 100644 samples/ros2_python_pkg/README.md create mode 100644 templates/ros2_cpp_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/README.md.jinja create mode 100644 templates/ros2_interfaces_pkg/{{ package_name }}/README.md.jinja create mode 100644 templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/README.md.jinja create mode 100644 templates/ros2_python_pkg/{{ package_name }}/README.md.jinja diff --git a/samples/ros2_cpp_all_pkg/README.md b/samples/ros2_cpp_all_pkg/README.md index 51c45a2..8971d96 100644 --- a/samples/ros2_cpp_all_pkg/README.md +++ b/samples/ros2_cpp_all_pkg/README.md @@ -4,59 +4,43 @@ TODO - [Container Images](#container-images) - [ros2_cpp_node](#ros2_cpp_node) -- [Official Documentation](#official-documentation) -## Container Images +### Container Images -| Description | Image | Command | +| Description | Image:Tag | Default Command | | --- | --- | -- | -| | ` - | Topic | Type | Description | | --- | --- | --- | -| `` | `/msg/` | \ | +| | | | ### Published Topics - - | Topic | Type | Description | | --- | --- | --- | -| `` | `/msg/` | \ | +| | | | ### Services - - | Service | Type | Description | | --- | --- | --- | -| `` | `/srv/` | \ | +| | | | ### Actions - - | Action | Type | Description | | --- | --- | --- | -| `` | `/action/` | \ | +| | | | ### Parameters - - | Parameter | Type | Description | | --- | --- | --- | -| `` | `` | \ | - - -## Official Documentation - -\ \ No newline at end of file +| | | | diff --git a/samples/ros2_cpp_all_pkg_interfaces/README.md b/samples/ros2_cpp_all_pkg_interfaces/README.md new file mode 100644 index 0000000..599dcf8 --- /dev/null +++ b/samples/ros2_cpp_all_pkg_interfaces/README.md @@ -0,0 +1,22 @@ +# ros2_cpp_all_pkg_interfaces + +ROS interface definitions for ros2_cpp_all_pkg + + +### Messages + +| Type | Description | +| --- | --- | +| | | + +### Services + +| Type | Description | +| --- | --- | +| | | + +### Actions + +| Type | Description | +| --- | --- | +| | | diff --git a/samples/ros2_cpp_component_pkg/README.md b/samples/ros2_cpp_component_pkg/README.md index 97c3167..b42cd02 100644 --- a/samples/ros2_cpp_component_pkg/README.md +++ b/samples/ros2_cpp_component_pkg/README.md @@ -4,59 +4,43 @@ TODO - [Container Images](#container-images) - [ros2_cpp_node](#ros2_cpp_node) -- [Official Documentation](#official-documentation) -## Container Images +### Container Images -| Description | Image | Command | +| Description | Image:Tag | Default Command | | --- | --- | -- | -| | ` - | Topic | Type | Description | | --- | --- | --- | -| `` | `/msg/` | \ | +| | | | ### Published Topics - - | Topic | Type | Description | | --- | --- | --- | -| `` | `/msg/` | \ | +| | | | ### Services - - | Service | Type | Description | | --- | --- | --- | -| `` | `/srv/` | \ | +| | | | ### Actions - - | Action | Type | Description | | --- | --- | --- | -| `` | `/action/` | \ | +| | | | ### Parameters - - | Parameter | Type | Description | | --- | --- | --- | -| `` | `` | \ | - - -## Official Documentation - -\ \ No newline at end of file +| | | | diff --git a/samples/ros2_cpp_lifecycle_pkg/README.md b/samples/ros2_cpp_lifecycle_pkg/README.md index 3d8a240..d61f6d2 100644 --- a/samples/ros2_cpp_lifecycle_pkg/README.md +++ b/samples/ros2_cpp_lifecycle_pkg/README.md @@ -4,59 +4,43 @@ TODO - [Container Images](#container-images) - [ros2_cpp_node](#ros2_cpp_node) -- [Official Documentation](#official-documentation) -## Container Images +### Container Images -| Description | Image | Command | +| Description | Image:Tag | Default Command | | --- | --- | -- | -| | ` - | Topic | Type | Description | | --- | --- | --- | -| `` | `/msg/` | \ | +| | | | ### Published Topics - - | Topic | Type | Description | | --- | --- | --- | -| `` | `/msg/` | \ | +| | | | ### Services - - | Service | Type | Description | | --- | --- | --- | -| `` | `/srv/` | \ | +| | | | ### Actions - - | Action | Type | Description | | --- | --- | --- | -| `` | `/action/` | \ | +| | | | ### Parameters - - | Parameter | Type | Description | | --- | --- | --- | -| `` | `` | \ | - - -## Official Documentation - -\ \ No newline at end of file +| | | | diff --git a/samples/ros2_cpp_pkg/README.md b/samples/ros2_cpp_pkg/README.md index 55c8b62..60372bb 100644 --- a/samples/ros2_cpp_pkg/README.md +++ b/samples/ros2_cpp_pkg/README.md @@ -4,59 +4,43 @@ TODO - [Container Images](#container-images) - [ros2_cpp_node](#ros2_cpp_node) -- [Official Documentation](#official-documentation) -## Container Images +### Container Images -| Description | Image | Command | +| Description | Image:Tag | Default Command | | --- | --- | -- | -| | ` - | Topic | Type | Description | | --- | --- | --- | -| `` | `/msg/` | \ | +| | | | ### Published Topics - - | Topic | Type | Description | | --- | --- | --- | -| `` | `/msg/` | \ | +| | | | ### Services - - | Service | Type | Description | | --- | --- | --- | -| `` | `/srv/` | \ | +| | | | ### Actions - - | Action | Type | Description | | --- | --- | --- | -| `` | `/action/` | \ | +| | | | ### Parameters - - | Parameter | Type | Description | | --- | --- | --- | -| `` | `` | \ | - - -## Official Documentation - -\ \ No newline at end of file +| | | | diff --git a/samples/ros2_interfaces_pkg/README.md b/samples/ros2_interfaces_pkg/README.md new file mode 100644 index 0000000..7f761b3 --- /dev/null +++ b/samples/ros2_interfaces_pkg/README.md @@ -0,0 +1,22 @@ +# ros2_interfaces_pkg + +TODO + + +### Messages + +| Type | Description | +| --- | --- | +| | | + +### Services + +| Type | Description | +| --- | --- | +| | | + +### Actions + +| Type | Description | +| --- | --- | +| | | diff --git a/samples/ros2_python_all_pkg/README.md b/samples/ros2_python_all_pkg/README.md new file mode 100644 index 0000000..9b349ad --- /dev/null +++ b/samples/ros2_python_all_pkg/README.md @@ -0,0 +1,46 @@ +# ros2_python_all_pkg + +TODO + +- [Container Images](#container-images) +- [ros2_python_node](#ros2_python_node) + + +### Container Images + +| Description | Image:Tag | Default Command | +| --- | --- | -- | +| | | | + + +## `ros2_python_node` + +### Subscribed Topics + +| Topic | Type | Description | +| --- | --- | --- | +| | | | + +### Published Topics + +| Topic | Type | Description | +| --- | --- | --- | +| | | | + +### Services + +| Service | Type | Description | +| --- | --- | --- | +| | | | + +### Actions + +| Action | Type | Description | +| --- | --- | --- | +| | | | + +### Parameters + +| Parameter | Type | Description | +| --- | --- | --- | +| | | | diff --git a/samples/ros2_python_all_pkg_interfaces/README.md b/samples/ros2_python_all_pkg_interfaces/README.md new file mode 100644 index 0000000..0c8d8f6 --- /dev/null +++ b/samples/ros2_python_all_pkg_interfaces/README.md @@ -0,0 +1,22 @@ +# ros2_python_all_pkg_interfaces + +ROS interface definitions for ros2_python_all_pkg + + +### Messages + +| Type | Description | +| --- | --- | +| | | + +### Services + +| Type | Description | +| --- | --- | +| | | + +### Actions + +| Type | Description | +| --- | --- | +| | | diff --git a/samples/ros2_python_pkg/README.md b/samples/ros2_python_pkg/README.md new file mode 100644 index 0000000..558c4cd --- /dev/null +++ b/samples/ros2_python_pkg/README.md @@ -0,0 +1,46 @@ +# ros2_python_pkg + +TODO + +- [Container Images](#container-images) +- [ros2_python_node](#ros2_python_node) + + +### Container Images + +| Description | Image:Tag | Default Command | +| --- | --- | -- | +| | | | + + +## `ros2_python_node` + +### Subscribed Topics + +| Topic | Type | Description | +| --- | --- | --- | +| | | | + +### Published Topics + +| Topic | Type | Description | +| --- | --- | --- | +| | | | + +### Services + +| Service | Type | Description | +| --- | --- | --- | +| | | | + +### Actions + +| Action | Type | Description | +| --- | --- | --- | +| | | | + +### Parameters + +| Parameter | Type | Description | +| --- | --- | --- | +| | | | diff --git a/templates/ros2_cpp_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/README.md.jinja b/templates/ros2_cpp_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/README.md.jinja new file mode 100644 index 0000000..05acf0d --- /dev/null +++ b/templates/ros2_cpp_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/README.md.jinja @@ -0,0 +1,22 @@ +# {{ package_name }}_interfaces + +ROS interface definitions for {{ package_name }} + + +### Messages + +| Type | Description | +| --- | --- | +| | | + +### Services + +| Type | Description | +| --- | --- | +| | | + +### Actions + +| Type | Description | +| --- | --- | +| | | diff --git a/templates/ros2_cpp_pkg/{{ package_name }}/README.md.jinja b/templates/ros2_cpp_pkg/{{ package_name }}/README.md.jinja index fe26b02..f95f0c2 100644 --- a/templates/ros2_cpp_pkg/{{ package_name }}/README.md.jinja +++ b/templates/ros2_cpp_pkg/{{ package_name }}/README.md.jinja @@ -4,59 +4,43 @@ - [Container Images](#container-images) - [{{ node_name }}](#{{ node_name }}) -- [Official Documentation](#official-documentation) -## Container Images +### Container Images -| Description | Image | Command | +| Description | Image:Tag | Default Command | | --- | --- | -- | -| | ` - | Topic | Type | Description | | --- | --- | --- | -| `` | `/msg/` | \ | +| | | | ### Published Topics - - | Topic | Type | Description | | --- | --- | --- | -| `` | `/msg/` | \ | +| | | | ### Services - - | Service | Type | Description | | --- | --- | --- | -| `` | `/srv/` | \ | +| | | | ### Actions - - | Action | Type | Description | | --- | --- | --- | -| `` | `/action/` | \ | +| | | | ### Parameters - - | Parameter | Type | Description | | --- | --- | --- | -| `` | `` | \ | - - -## Official Documentation - -\ \ No newline at end of file +| | | | diff --git a/templates/ros2_interfaces_pkg/{{ package_name }}/README.md.jinja b/templates/ros2_interfaces_pkg/{{ package_name }}/README.md.jinja new file mode 100644 index 0000000..0dab93b --- /dev/null +++ b/templates/ros2_interfaces_pkg/{{ package_name }}/README.md.jinja @@ -0,0 +1,22 @@ +# {{ package_name }} + +{{ description }} + + +### Messages + +| Type | Description | +| --- | --- | +| | | + +### Services + +| Type | Description | +| --- | --- | +| | | + +### Actions + +| Type | Description | +| --- | --- | +| | | diff --git a/templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/README.md.jinja b/templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/README.md.jinja new file mode 100644 index 0000000..05acf0d --- /dev/null +++ b/templates/ros2_python_pkg/{% if has_action_server %}{{ package_name }}_interfaces{% endif %}/README.md.jinja @@ -0,0 +1,22 @@ +# {{ package_name }}_interfaces + +ROS interface definitions for {{ package_name }} + + +### Messages + +| Type | Description | +| --- | --- | +| | | + +### Services + +| Type | Description | +| --- | --- | +| | | + +### Actions + +| Type | Description | +| --- | --- | +| | | diff --git a/templates/ros2_python_pkg/{{ package_name }}/README.md.jinja b/templates/ros2_python_pkg/{{ package_name }}/README.md.jinja new file mode 100644 index 0000000..f95f0c2 --- /dev/null +++ b/templates/ros2_python_pkg/{{ package_name }}/README.md.jinja @@ -0,0 +1,46 @@ +# {{ package_name }} + +{{ description }} + +- [Container Images](#container-images) +- [{{ node_name }}](#{{ node_name }}) + + +### Container Images + +| Description | Image:Tag | Default Command | +| --- | --- | -- | +| | | | + + +## `{{ node_name }}` + +### Subscribed Topics + +| Topic | Type | Description | +| --- | --- | --- | +| | | | + +### Published Topics + +| Topic | Type | Description | +| --- | --- | --- | +| | | | + +### Services + +| Service | Type | Description | +| --- | --- | --- | +| | | | + +### Actions + +| Action | Type | Description | +| --- | --- | --- | +| | | | + +### Parameters + +| Parameter | Type | Description | +| --- | --- | --- | +| | | | From 5f697684f2d51f42fb28aa442a558cae1d09e853 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Mon, 28 Oct 2024 17:05:38 +0100 Subject: [PATCH 62/67] fix links and add acknowledgements to readme --- README.md | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index c8bb5fd..5b1405f 100644 --- a/README.md +++ b/README.md @@ -10,9 +10,10 @@ *ros2-pkg-create* is an interactive CLI tool for quickly generating ROS 2 packages from basic pub/sub nodes to complex lifecycle components. It is meant to replace the official [`ros2 pkg create`](https://docs.ros.org/en/latest/Tutorials/Beginner-Client-Libraries/Creating-Your-First-ROS2-Package.html#create-a-package) command. - [Quick Demo](#quick-demo) -- [Templates \& Features](#templates-features) +- [Templates \& Features](#templates--features) - [Installation](#installation) - [Usage](#usage) +- [Acknowledgements](#acknowledgements) > [!IMPORTANT] > This repository is open-sourced and maintained by the [**Institute for Automotive Engineering (ika) at RWTH Aachen University**](https://www.ika.rwth-aachen.de/). @@ -24,6 +25,7 @@ ## Quick Demo ```bash +pip install ros2-pkg-create ros2-pkg-create --template ros2_cpp_pkg . ``` @@ -34,9 +36,9 @@ ros2-pkg-create --template ros2_cpp_pkg . *ros2-pkg-create* provides multiple templates, each covering a different questionnaire for generating all the components you need. See below for the list of options. Note that all options can also be passed directly to the command, bypassing the interactive questionnaire (see [Usage](#usage)). -- [C++ Package](#c-package-template-ros2_cpp_pkg) +- [C++ Package](#c-package---template-ros2_cpp_pkg) - [Python Package](#python-package---template-ros2_python_pkg) -- [Interfaces Package](#interfaces-package-template-ros2_interfaces_pkg) +- [Interfaces Package](#interfaces-package---template-ros2_interfaces_pkg) ### C++ Package (`--template ros2_cpp_pkg`) @@ -180,3 +182,7 @@ options: --has-docker-ros Add the docker-ros CI integration? --version show program's version number and exit ``` + +## Acknowledgements + +This work is accomplished within the projects [6GEM](https://6gem.de/en/) (FKZ 16KISK036K) and [autotech.agil](https://www.autotechagil.de/) (FKZ 01IS22088A). We acknowledge the financial support for the projects by the *Federal Ministry of Education and Research of Germany (BMBF)*. From f435f7917937569f52898cb21f3234fec9551210 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Wed, 30 Oct 2024 16:53:19 +0000 Subject: [PATCH 63/67] improve readme --- README.md | 57 ++++++++++++++++++++++++++++++++++++------------------- 1 file changed, 38 insertions(+), 19 deletions(-) diff --git a/README.md b/README.md index 5b1405f..c179534 100644 --- a/README.md +++ b/README.md @@ -10,8 +10,8 @@ *ros2-pkg-create* is an interactive CLI tool for quickly generating ROS 2 packages from basic pub/sub nodes to complex lifecycle components. It is meant to replace the official [`ros2 pkg create`](https://docs.ros.org/en/latest/Tutorials/Beginner-Client-Libraries/Creating-Your-First-ROS2-Package.html#create-a-package) command. - [Quick Demo](#quick-demo) -- [Templates \& Features](#templates--features) - [Installation](#installation) +- [Templates \& Features](#templates--features) - [Usage](#usage) - [Acknowledgements](#acknowledgements) @@ -32,9 +32,27 @@ ros2-pkg-create --template ros2_cpp_pkg . +## Installation + +```bash +pip install ros2-pkg-create + +# (optional) bash auto-completion +activate-global-python-argcomplete +eval "$(register-python-argcomplete ros2-pkg-create)" +``` + +> [!WARNING] +> Outside of a virtual environment, *pip* may default to a user-site installation of executables to `~/.local/bin`, which may not be present in your shell's `PATH`. If running `ros2-pkg-create` errors with `ros2-pkg-create: command not found`, add the directory to your path. [*(More information)*](https://packaging.python.org/en/latest/tutorials/installing-packages/#installing-to-the-user-site) +> ```bash +> echo "export PATH=\$HOME/.local/bin:\$PATH" >> ~/.bashrc +> source ~/.bashrc +> ``` + + ## Templates & Features -*ros2-pkg-create* provides multiple templates, each covering a different questionnaire for generating all the components you need. See below for the list of options. Note that all options can also be passed directly to the command, bypassing the interactive questionnaire (see [Usage](#usage)). +*ros2-pkg-create* provides multiple templates, each covering a different questionnaire for generating all the components you need. See below for the list of supported features and questionnarie options. Note that all options can also be passed directly to the command, bypassing the interactive questionnaire (see [Usage](#usage)). - [C++ Package](#c-package---template-ros2_cpp_pkg) - [Python Package](#python-package---template-ros2_python_pkg) @@ -42,6 +60,11 @@ ros2-pkg-create --template ros2_cpp_pkg . ### C++ Package (`--template ros2_cpp_pkg`) +**Supported Features:** publisher, subscriber, parameter loading, launch file, service server, action server, timer callback, component, lifecycle node, docker-ros + +
+Questionnaire + - Package name - Description - Maintainer | Maintainer email @@ -59,9 +82,15 @@ ros2-pkg-create --template ros2_cpp_pkg . - Add an action server? - Add a timer callback? - Add the docker-ros CI integration? +
### Python Package (`--template ros2_python_pkg`) +**Supported Features:** publisher, subscriber, parameter loading, launch file, service server, action server, timer callback, docker-ros + +
+Questionnaire + - Package name - Description - Maintainer | Maintainer email @@ -77,9 +106,15 @@ ros2-pkg-create --template ros2_cpp_pkg . - Add an action server? - Add a timer callback? - Add the docker-ros CI integration? +
### Interfaces Package (`--template ros2_interfaces_pkg`) +**Supported Features:** message, service, action + +
+Questionnaire + - Package name - Description - Maintainer | Maintainer email @@ -90,23 +125,7 @@ ros2-pkg-create --template ros2_cpp_pkg . - Service name - Action name - Add the docker-ros CI integration? - -## Installation - -```bash -pip install ros2-pkg-create - -# (optional) bash auto-completion -activate-global-python-argcomplete -eval "$(register-python-argcomplete ros2-pkg-create)" -``` - -> [!WARNING] -> Outside of a virtual environment, *pip* may default to a user-site installation of executables to `~/.local/bin`, which may not be present in your shell's `PATH`. If running `ros2-pkg-create` errors with `ros2-pkg-create: command not found`, add the directory to your path. [*(More information)*](https://packaging.python.org/en/latest/tutorials/installing-packages/#installing-to-the-user-site) -> ```bash -> echo "export PATH=\$HOME/.local/bin:\$PATH" >> ~/.bashrc -> source ~/.bashrc -> ``` +
## Usage From f9fa4912b6a435a1dcf9b6b616120142fde6f005 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Wed, 30 Oct 2024 16:57:58 +0000 Subject: [PATCH 64/67] add docker-ros integration to samples --- .github/workflows/check-samples.yml | 7 +++++++ samples/generate_samples.sh | 6 ++++++ samples/ros2_cpp_all_pkg/.gitlab-ci.yml | 8 ++++++++ samples/ros2_cpp_component_pkg/.gitlab-ci.yml | 8 ++++++++ samples/ros2_cpp_lifecycle_pkg/.gitlab-ci.yml | 8 ++++++++ samples/ros2_cpp_pkg/.gitlab-ci.yml | 8 ++++++++ samples/ros2_python_all_pkg/.gitlab-ci.yml | 8 ++++++++ samples/ros2_python_pkg/.gitlab-ci.yml | 8 ++++++++ 8 files changed, 61 insertions(+) create mode 100644 samples/ros2_cpp_all_pkg/.gitlab-ci.yml create mode 100644 samples/ros2_cpp_component_pkg/.gitlab-ci.yml create mode 100644 samples/ros2_cpp_lifecycle_pkg/.gitlab-ci.yml create mode 100644 samples/ros2_cpp_pkg/.gitlab-ci.yml create mode 100644 samples/ros2_python_all_pkg/.gitlab-ci.yml create mode 100644 samples/ros2_python_pkg/.gitlab-ci.yml diff --git a/.github/workflows/check-samples.yml b/.github/workflows/check-samples.yml index b852d7c..0a54ffb 100644 --- a/.github/workflows/check-samples.yml +++ b/.github/workflows/check-samples.yml @@ -23,6 +23,7 @@ jobs: has_service_server: false has_action_server: false has_timer: false + has_docker_ros: true - package_name: ros2_cpp_component_pkg template: ros2_cpp_pkg node_name: ros2_cpp_node @@ -35,6 +36,7 @@ jobs: has_service_server: false has_action_server: false has_timer: false + has_docker_ros: true - package_name: ros2_cpp_lifecycle_pkg template: ros2_cpp_pkg node_name: ros2_cpp_node @@ -47,6 +49,7 @@ jobs: has_service_server: false has_action_server: false has_timer: false + has_docker_ros: true - package_name: ros2_cpp_all_pkg template: ros2_cpp_pkg node_name: ros2_cpp_node @@ -59,6 +62,7 @@ jobs: has_service_server: true has_action_server: true has_timer: true + has_docker_ros: true - package_name: ros2_python_pkg template: ros2_python_pkg node_name: ros2_python_node @@ -70,6 +74,7 @@ jobs: has_service_server: false has_action_server: false has_timer: false + has_docker_ros: true - package_name: ros2_python_all_pkg template: ros2_python_pkg node_name: ros2_python_node @@ -81,6 +86,7 @@ jobs: has_service_server: true has_action_server: true has_timer: true + has_docker_ros: true - package_name: ros2_interfaces_pkg template: ros2_interfaces_pkg steps: @@ -112,6 +118,7 @@ jobs: -d has_service_server=${{ matrix.has_service_server }} \ -d has_action_server=${{ matrix.has_action_server }} \ -d has_timer=${{ matrix.has_timer }} \ + -d has_docker_ros=${{ matrix.has_docker_ros }} \ . packages - name: Check for repository changes run: | diff --git a/samples/generate_samples.sh b/samples/generate_samples.sh index 107ea2b..a000239 100755 --- a/samples/generate_samples.sh +++ b/samples/generate_samples.sh @@ -15,6 +15,7 @@ copier copy --trust --defaults \ -d has_service_server=false \ -d has_action_server=false \ -d has_timer=false \ + -d has_docker_ros=true \ . $script_dir copier copy --trust --defaults \ @@ -30,6 +31,7 @@ copier copy --trust --defaults \ -d has_service_server=false \ -d has_action_server=false \ -d has_timer=false \ + -d has_docker_ros=true \ . $script_dir copier copy --trust --defaults \ @@ -45,6 +47,7 @@ copier copy --trust --defaults \ -d has_service_server=false \ -d has_action_server=false \ -d has_timer=false \ + -d has_docker_ros=true \ . $script_dir copier copy --trust --defaults \ @@ -60,6 +63,7 @@ copier copy --trust --defaults \ -d has_service_server=true \ -d has_action_server=true \ -d has_timer=true \ + -d has_docker_ros=true \ . $script_dir copier copy --trust --defaults \ @@ -73,6 +77,7 @@ copier copy --trust --defaults \ -d has_service_server=false \ -d has_action_server=false \ -d has_timer=false \ + -d has_docker_ros=true \ . $script_dir copier copy --trust --defaults \ @@ -86,6 +91,7 @@ copier copy --trust --defaults \ -d has_service_server=true \ -d has_action_server=true \ -d has_timer=true \ + -d has_docker_ros=true \ . $script_dir copier copy --trust --defaults \ diff --git a/samples/ros2_cpp_all_pkg/.gitlab-ci.yml b/samples/ros2_cpp_all_pkg/.gitlab-ci.yml new file mode 100644 index 0000000..f642e55 --- /dev/null +++ b/samples/ros2_cpp_all_pkg/.gitlab-ci.yml @@ -0,0 +1,8 @@ +include: + - remote: https://raw.githubusercontent.com/ika-rwth-aachen/docker-ros/main/.gitlab-ci/docker-ros.yml + +variables: + PLATFORM: amd64,arm64 + TARGET: dev,run + BASE_IMAGE: rwthika/ros2:latest + COMMAND: ros2 run ros2_cpp_all_pkg ros2_cpp_node diff --git a/samples/ros2_cpp_component_pkg/.gitlab-ci.yml b/samples/ros2_cpp_component_pkg/.gitlab-ci.yml new file mode 100644 index 0000000..e1fbb8d --- /dev/null +++ b/samples/ros2_cpp_component_pkg/.gitlab-ci.yml @@ -0,0 +1,8 @@ +include: + - remote: https://raw.githubusercontent.com/ika-rwth-aachen/docker-ros/main/.gitlab-ci/docker-ros.yml + +variables: + PLATFORM: amd64,arm64 + TARGET: dev,run + BASE_IMAGE: rwthika/ros2:latest + COMMAND: ros2 run ros2_cpp_component_pkg ros2_cpp_node diff --git a/samples/ros2_cpp_lifecycle_pkg/.gitlab-ci.yml b/samples/ros2_cpp_lifecycle_pkg/.gitlab-ci.yml new file mode 100644 index 0000000..595a118 --- /dev/null +++ b/samples/ros2_cpp_lifecycle_pkg/.gitlab-ci.yml @@ -0,0 +1,8 @@ +include: + - remote: https://raw.githubusercontent.com/ika-rwth-aachen/docker-ros/main/.gitlab-ci/docker-ros.yml + +variables: + PLATFORM: amd64,arm64 + TARGET: dev,run + BASE_IMAGE: rwthika/ros2:latest + COMMAND: ros2 run ros2_cpp_lifecycle_pkg ros2_cpp_node diff --git a/samples/ros2_cpp_pkg/.gitlab-ci.yml b/samples/ros2_cpp_pkg/.gitlab-ci.yml new file mode 100644 index 0000000..3f0d862 --- /dev/null +++ b/samples/ros2_cpp_pkg/.gitlab-ci.yml @@ -0,0 +1,8 @@ +include: + - remote: https://raw.githubusercontent.com/ika-rwth-aachen/docker-ros/main/.gitlab-ci/docker-ros.yml + +variables: + PLATFORM: amd64,arm64 + TARGET: dev,run + BASE_IMAGE: rwthika/ros2:latest + COMMAND: ros2 run ros2_cpp_pkg ros2_cpp_node diff --git a/samples/ros2_python_all_pkg/.gitlab-ci.yml b/samples/ros2_python_all_pkg/.gitlab-ci.yml new file mode 100644 index 0000000..2bd5e7c --- /dev/null +++ b/samples/ros2_python_all_pkg/.gitlab-ci.yml @@ -0,0 +1,8 @@ +include: + - remote: https://raw.githubusercontent.com/ika-rwth-aachen/docker-ros/main/.gitlab-ci/docker-ros.yml + +variables: + PLATFORM: amd64,arm64 + TARGET: dev,run + BASE_IMAGE: rwthika/ros2:latest + COMMAND: ros2 run ros2_python_all_pkg ros2_python_node diff --git a/samples/ros2_python_pkg/.gitlab-ci.yml b/samples/ros2_python_pkg/.gitlab-ci.yml new file mode 100644 index 0000000..333fe08 --- /dev/null +++ b/samples/ros2_python_pkg/.gitlab-ci.yml @@ -0,0 +1,8 @@ +include: + - remote: https://raw.githubusercontent.com/ika-rwth-aachen/docker-ros/main/.gitlab-ci/docker-ros.yml + +variables: + PLATFORM: amd64,arm64 + TARGET: dev,run + BASE_IMAGE: rwthika/ros2:latest + COMMAND: ros2 run ros2_python_pkg ros2_python_node From ee44677502c4a8c7da8ab7191cc792165c6d3a63 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Wed, 30 Oct 2024 17:00:54 +0000 Subject: [PATCH 65/67] add second author to package info --- ros2-pkg-create/pyproject.toml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ros2-pkg-create/pyproject.toml b/ros2-pkg-create/pyproject.toml index 95bc68b..1408a4f 100644 --- a/ros2-pkg-create/pyproject.toml +++ b/ros2-pkg-create/pyproject.toml @@ -10,9 +10,11 @@ license = {file = "LICENSE"} readme = "README.md" authors = [ {name = "Lennart Reiher", email = "lennart.reiher@rwth-aachen.de"}, + {name = "Jean-Pierre Busch", email = "jean-pierre.busch@rwth-aachen.de"}, ] maintainers = [ {name = "Lennart Reiher", email = "lennart.reiher@rwth-aachen.de"}, + {name = "Jean-Pierre Busch", email = "jean-pierre.busch@rwth-aachen.de"}, ] classifiers = [ "License :: OSI Approved :: MIT License", From 0dedd83c22cdc282ac216f52bc98c1ac350bb9bb Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 7 Nov 2024 10:19:26 +0000 Subject: [PATCH 66/67] bump version to v1.0.0 --- ros2-pkg-create/pyproject.toml | 2 +- ros2-pkg-create/src/ros2_pkg_create/__init__.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ros2-pkg-create/pyproject.toml b/ros2-pkg-create/pyproject.toml index 1408a4f..f0a733b 100644 --- a/ros2-pkg-create/pyproject.toml +++ b/ros2-pkg-create/pyproject.toml @@ -4,7 +4,7 @@ build-backend = "setuptools.build_meta" [project] name = "ros2-pkg-create" -version = "0.1.0" +version = "1.0.0" description = "TODO" license = {file = "LICENSE"} readme = "README.md" diff --git a/ros2-pkg-create/src/ros2_pkg_create/__init__.py b/ros2-pkg-create/src/ros2_pkg_create/__init__.py index 96f4cfc..e7f535a 100644 --- a/ros2-pkg-create/src/ros2_pkg_create/__init__.py +++ b/ros2-pkg-create/src/ros2_pkg_create/__init__.py @@ -1,2 +1,2 @@ __name__ = "ros2-pkg-create" -__version__ = "0.1.0" \ No newline at end of file +__version__ = "1.0.0" \ No newline at end of file From dc87b99234d28e49ea9e2bd7e3f73f8721a87fd9 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Thu, 7 Nov 2024 10:24:40 +0000 Subject: [PATCH 67/67] add pyproject description --- ros2-pkg-create/pyproject.toml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros2-pkg-create/pyproject.toml b/ros2-pkg-create/pyproject.toml index f0a733b..d90fbf7 100644 --- a/ros2-pkg-create/pyproject.toml +++ b/ros2-pkg-create/pyproject.toml @@ -5,7 +5,7 @@ build-backend = "setuptools.build_meta" [project] name = "ros2-pkg-create" version = "1.0.0" -description = "TODO" +description = "Powerful ROS 2 Package Generator" license = {file = "LICENSE"} readme = "README.md" authors = [

+