23#include "carma_msgs/msg/system_alert.hpp"
24#include "ros2_lifecycle_manager/ros2_lifecycle_manager.hpp"
25#include "rclcpp/rclcpp.hpp"
26#include "carma_ros2_utils/carma_lifecycle_node.hpp"
56 virtual void on_system_alert(
const carma_msgs::msg::SystemAlert::UniquePtr msg);
61 virtual carma_ros2_utils::CallbackReturn
handle_on_configure(
const rclcpp_lifecycle::State &prev_state);
62 virtual carma_ros2_utils::CallbackReturn
handle_on_activate(
const rclcpp_lifecycle::State &prev_state);
63 virtual carma_ros2_utils::CallbackReturn
handle_on_deactivate(
const rclcpp_lifecycle::State &prev_state);
64 virtual carma_ros2_utils::CallbackReturn
handle_on_cleanup(
const rclcpp_lifecycle::State &prev_state);
65 virtual carma_ros2_utils::CallbackReturn
handle_on_error(
const rclcpp_lifecycle::State &prev_state,
const std::string &exception_string);
66 virtual carma_ros2_utils::CallbackReturn
handle_on_shutdown(
const rclcpp_lifecycle::State &prev_state);
87 std::vector<std::string>
get_non_intersecting_set(
const std::vector<std::string>& set_a,
const std::vector<std::string>& set_b)
const;
A base class for all subsystem_controllers which provides default lifecycle behavior for subsystems.
BaseSubSystemControllerConfig base_config_
The configuration struct.
virtual carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &prev_state)
bool trigger_managed_nodes_deactivate_from_base_class_
virtual carma_ros2_utils::CallbackReturn handle_on_error(const rclcpp_lifecycle::State &prev_state, const std::string &exception_string)
virtual carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &prev_state)
std::vector< std::string > get_nodes_in_namespace(const std::string &node_namespace) const
Returns the list of fully qualified node names for all ROS2 nodes in the provided namespace.
virtual carma_ros2_utils::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &prev_state)
rclcpp::Subscription< carma_msgs::msg::SystemAlert >::SharedPtr system_alert_sub_
The subscriber for the system alert topic.
bool trigger_managed_nodes_cleanup_from_base_class_
virtual carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &prev_state)
virtual void on_system_alert(const carma_msgs::msg::SystemAlert::UniquePtr msg)
~BaseSubsystemController()=default
std::vector< std::string > get_non_intersecting_set(const std::vector< std::string > &set_a, const std::vector< std::string > &set_b) const
Returns all elements of the provided set_a which are NOT contained in the provided set_b.
bool trigger_managed_nodes_configure_from_base_class_
Collection of flags which, if true, will cause the base class to make lifecycle service calls to mana...
void set_config(BaseSubSystemControllerConfig config)
bool trigger_managed_nodes_activate_from_base_class_
ros2_lifecycle_manager::Ros2LifecycleManager lifecycle_mgr_
Lifecycle Manager which will track the managed nodes and call their lifecycle services on request.
BaseSubsystemController()=delete
virtual carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &prev_state)
Stuct containing the algorithm configuration values for the BaseSubsystemController.