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_driver_msgs/msg/driver_status.hpp>
30#include <boost/algorithm/string.hpp>
68 carma_ros2_utils::CallbackReturn
handle_on_configure(
const rclcpp_lifecycle::State &prev_state);
69 carma_ros2_utils::CallbackReturn
handle_on_activate(
const rclcpp_lifecycle::State &prev_state);
81 boost::optional<carma_msgs::msg::SystemAlert>
prev_alert;
A base class for all subsystem_controllers which provides default lifecycle behavior for subsystems.
std::vector< std::string > ros1_required_drivers_
ROS parameters.
std::shared_ptr< DriverManager > driver_manager_
std::vector< std::string > ros1_camera_drivers_
~DriversControllerNode()=default
DriversControllerConfig config_
Config for user provided parameters.
carma_ros2_utils::SubPtr< carma_driver_msgs::msg::DriverStatus > driver_status_sub_
ROS handles.
DriversControllerNode()=delete
rclcpp::TimerBase::SharedPtr timer_
boost::optional< carma_msgs::msg::SystemAlert > prev_alert
void driver_discovery_cb(const carma_driver_msgs::msg::DriverStatus::SharedPtr msg)
void timer_callback()
Timer callback function to check status of required ros1 drivers.
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &prev_state)
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &prev_state)
Stuct containing the algorithm configuration values for the GuidanceController.