23#include <carma_msgs/msg/system_alert.hpp>
24#include <carma_planning_msgs/msg/plugin.hpp>
25#include <carma_planning_msgs/srv/get_plugin_api.hpp>
26#include <carma_planning_msgs/srv/plugin_list.hpp>
27#include <carma_planning_msgs/srv/plugin_activation.hpp>
28#include <ros2_lifecycle_manager/ros2_lifecycle_manager.hpp>
29#include <rclcpp/rclcpp.hpp>
36 namespace cr2 = carma_ros2_utils;
A base class for all subsystem_controllers which provides default lifecycle behavior for subsystems.
cr2::SubPtr< carma_planning_msgs::msg::Plugin > plugin_discovery_sub_
ROS handles.
cr2::ServicePtr< carma_planning_msgs::srv::GetPluginApi > get_control_plugins_by_capability_server_
cr2::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &)
~GuidanceControllerNode()=default
cr2::ServicePtr< carma_planning_msgs::srv::GetPluginApi > get_strategic_plugins_by_capability_server_
cr2::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &)
cr2::ServicePtr< carma_planning_msgs::srv::GetPluginApi > get_tactical_plugins_by_capability_server_
cr2::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
GuidanceControllerNode()=delete
cr2::ServicePtr< carma_planning_msgs::srv::PluginList > get_active_plugins_server_
cr2::ServicePtr< carma_planning_msgs::srv::PluginActivation > activate_plugin_server_
cr2::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &)
cr2::ServicePtr< carma_planning_msgs::srv::PluginList > get_registered_plugins_server_
GuidanceControllerConfig config_
Config for user provided parameters.
cr2::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &)
std::shared_ptr< PluginManager > plugin_manager_
Plugin manager to handle all the plugin specific discovery and reporting.
Stuct containing the algorithm configuration values for the GuidanceController.