17#ifndef SYSTEM_CONTROLLER__SYSTEM_CONTROLLER_NODE_HPP_
18#define SYSTEM_CONTROLLER__SYSTEM_CONTROLLER_NODE_HPP_
22#include "carma_msgs/msg/system_alert.hpp"
23#include "ros2_lifecycle_manager/ros2_lifecycle_manager.hpp"
25#include "rclcpp/rclcpp.hpp"
64 void on_system_alert(
const carma_msgs::msg::SystemAlert::UniquePtr msg);
74 void on_error(
const std::exception &e);
void set_config(SystemControllerConfig config)
Reset the configurations of this node. This is mean to support testing or other non-standard launch m...
SystemControllerNode()=delete
void startup_delay_callback()
Callback to be triggered when the startup delay has passed.
std::shared_ptr< rclcpp::Publisher< carma_msgs::msg::SystemAlert > > system_alert_pub_
System alert publisher.
rclcpp::TimerBase::SharedPtr startup_timer_
Timer which triggers when the startup delay has passed.
rclcpp::Subscription< carma_msgs::msg::SystemAlert >::SharedPtr system_alert_sub_
The subscriber for the system alert topic.
void on_system_alert(const carma_msgs::msg::SystemAlert::UniquePtr msg)
Callback for system alert messages used to evaluate system fault handling.
~SystemControllerNode()=default
ros2_lifecycle_manager::Ros2LifecycleManager lifecycle_mgr_
Lifecycle Manager which will track the managed nodes and call their lifecycle services on request.
void initialize()
Initialize this node by loading parameters from the ROS Network.
void publish_system_alert(carma_msgs::msg::SystemAlert msg)
Publishes a SystemAlert message to the rest of the carma-platform system. NOTE: This callback will au...
void on_error(const std::exception &e)
Exception handling method for processing all internal exceptions;.
SystemControllerConfig config_
The configuration of this node.
const std::string system_alert_topic_
The default topic name for the system alert topic.
Stuct containing the algorithm configuration values for the SystemController.