#ifndef ENV_MANAGER_COMPONENT_MANAGER_SUBSCRIBER_COMPONENT_HPP_ #define ENV_MANAGER_COMPONENT_MANAGER_SUBSCRIBER_COMPONENT_HPP_ #include #include #include "rclcpp/rclcpp.hpp" namespace env_manager { namespace component_manager { const std::string DEFAULT_SUB_NODE_NAME = "env_manager_sub_node"; const std::string DEFAULT_SUB_TOPIC_NAME = "sub_topic"; template class SubscriberComponent : public rclcpp::Node { public: explicit SubscriberComponent(const rclcpp::NodeOptions& options) : Node(DEFAULT_SUB_NODE_NAME, options) { _sub = create_subscription( DEFAULT_SUB_TOPIC_NAME, 10, this->callback); auto ret = rcutils_logging_set_logger_level( get_logger().get_name(), RCUTILS_LOG_SEVERITY_FATAL); if (ret != RCUTILS_RET_OK) { RCLCPP_ERROR(get_logger(), "Error setting severity: %s", rcutils_get_error_string().str); rcutils_reset_error(); } } virtual void callback(const MessageT& msg) = 0; private: typename rclcpp::Subscription::SharedPtr _sub; }; } // namespace component_manager } // namespace env_manager #endif // ENV_MANAGER_COMPONENT_MANAGER_SUBSCRIBER_COMPONENT_HPP_