Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
base_subsystem_controller.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2021 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18
19
20
21#include <memory>
22
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"
28
30{
39 class BaseSubsystemController : public carma_ros2_utils::CarmaLifecycleNode
40 {
41 public:
42
44
50 explicit BaseSubsystemController(const rclcpp::NodeOptions &options);
51
53
55
56 virtual void on_system_alert(const carma_msgs::msg::SystemAlert::UniquePtr msg);
57
59 // Overrides
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);
67
68 protected:
69
77 std::vector<std::string> get_nodes_in_namespace(const std::string& node_namespace) const;
78
87 std::vector<std::string> get_non_intersecting_set(const std::vector<std::string>& set_a, const std::vector<std::string>& set_b) const;
88
90 ros2_lifecycle_manager::Ros2LifecycleManager lifecycle_mgr_;
91
93 rclcpp::Subscription<carma_msgs::msg::SystemAlert>::SharedPtr system_alert_sub_;
94
97
99 // when ever the respective handle_on_<event> methods (ie. handle_on_configure) are called.
100 // by setting these flags to false an extending class chooses to implement that call itself.
101 // flags for on_shutdown and on_error are explicitly not provided since either should always result in subsystem shutdown.
102 // Overriding the respective methods without calling the base version will achieve the same external behavior but will also result in some internal variables not being populated.
103 // For correct behavior these flags should be set in the constructor
108 };
109
110} // namespace subsystem_controllers
111
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)
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.
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)
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)
ros2_lifecycle_manager::Ros2LifecycleManager lifecycle_mgr_
Lifecycle Manager which will track the managed nodes and call their lifecycle services on request.
virtual carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &prev_state)
Stuct containing the algorithm configuration values for the BaseSubsystemController.