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.
plugin_manager.h
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2019-2022LEIDOS.
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#include <carma_planning_msgs/msg/plugin.hpp>
20#include <carma_planning_msgs/srv/get_plugin_api.hpp>
21#include <carma_planning_msgs/srv/plugin_list.hpp>
22#include <carma_planning_msgs/srv/plugin_activation.hpp>
23#include <ros2_lifecycle_manager/lifecycle_manager_interface.hpp>
24#include <unordered_set>
25#include <functional>
26#include <vector>
27#include <memory>
28#include <chrono>
29#include <rmw/types.h>
30#include <map>
31#include "entry_manager.h"
32#include "entry.h"
33
34
36{
37
38 using GetParentNodeStateFunc = std::function<uint8_t()>;
39 using SrvHeader = const std::shared_ptr<rmw_request_id_t>;
43 using ServiceNamesAndTypesFunc = std::function<std::map<std::string, std::vector<std::string, std::allocator<std::string>>>(const std::string &,const std::string &)>;
44
49 {
50 public:
51
52 // TODO do we need a system alert callback in this manager as well
53
65 PluginManager(const std::vector<std::string>& required_plugins,
66 const std::vector<std::string>& auto_activated_plugins,
67 std::shared_ptr<ros2_lifecycle_manager::LifecycleManagerInterface> plugin_lifecycle_mgr,
68 GetParentNodeStateFunc get_parent_state_func,
69 ServiceNamesAndTypesFunc get_service_names_and_types_func,
70 std::chrono::nanoseconds service_timeout, std::chrono::nanoseconds call_timeout);
71
79 bool configure();
80 bool activate();
81 bool deactivate();
82 bool cleanup();
83 bool shutdown();
84
90 void update_plugin_status(carma_planning_msgs::msg::Plugin::UniquePtr msg);
91
98 void get_registered_plugins(SrvHeader, carma_planning_msgs::srv::PluginList::Request::SharedPtr req, carma_planning_msgs::srv::PluginList::Response::SharedPtr res);
99
107 void get_active_plugins(SrvHeader, carma_planning_msgs::srv::PluginList::Request::SharedPtr req, carma_planning_msgs::srv::PluginList::Response::SharedPtr res);
108
116 void activate_plugin(SrvHeader, carma_planning_msgs::srv::PluginActivation::Request::SharedPtr req, carma_planning_msgs::srv::PluginActivation::Response::SharedPtr res);
117
125 void get_strategic_plugins_by_capability(SrvHeader, carma_planning_msgs::srv::GetPluginApi::Request::SharedPtr req, carma_planning_msgs::srv::GetPluginApi::Response::SharedPtr res);
126
134 void get_tactical_plugins_by_capability(SrvHeader, carma_planning_msgs::srv::GetPluginApi::Request::SharedPtr req, carma_planning_msgs::srv::GetPluginApi::Response::SharedPtr res);
135
143 void get_control_plugins_by_capability(SrvHeader, carma_planning_msgs::srv::GetPluginApi::Request::SharedPtr req, carma_planning_msgs::srv::GetPluginApi::Response::SharedPtr res);
144
145 protected:
146
156 void add_plugin(const Entry& plugin);
157
178 bool matching_capability(const std::vector<std::string>& base_capability_levels, const std::vector<std::string>& compared_capability_levels);
179
187 bool is_ros2_lifecycle_node(const std::string& node);
188
190 std::unordered_set<std::string> required_plugins_;
191
193 // These will only be activated once, if the user later deactivates them then that behavior will be preserved
194 std::unordered_set<std::string> auto_activated_plugins_;
195
197 std::shared_ptr<ros2_lifecycle_manager::LifecycleManagerInterface> plugin_lifecycle_mgr_;
198
201
204
207
209 std::chrono::nanoseconds service_timeout_;
210
212 std::chrono::nanoseconds call_timeout_;
213
215 const std::string plan_maneuvers_suffix_ = "/plan_maneuvers";
216
218 const std::string plan_trajectory_suffix_ = "/plan_trajectory";
219
221 const std::string control_trajectory_suffix_ = "/plan_trajectory";
222
223 };
224}
An entry manager keeps track of the set of entries and makes it easy to add or remove entries.
Definition: entry_manager.h:30
The PluginManager serves as a component to manage CARMA Guidance Plugins via their ros2 lifecycle int...
std::shared_ptr< ros2_lifecycle_manager::LifecycleManagerInterface > plugin_lifecycle_mgr_
Lifecycle Manager which will track the plugin nodes and call their lifecycle services on request.
void add_plugin(const Entry &plugin)
Add the specified entry to our plugin management This function will attempt to move the newly detecte...
void get_control_plugins_by_capability(SrvHeader, carma_planning_msgs::srv::GetPluginApi::Request::SharedPtr req, carma_planning_msgs::srv::GetPluginApi::Response::SharedPtr res)
Get control plugins by capability.
PluginManager(const std::vector< std::string > &required_plugins, const std::vector< std::string > &auto_activated_plugins, std::shared_ptr< ros2_lifecycle_manager::LifecycleManagerInterface > plugin_lifecycle_mgr, GetParentNodeStateFunc get_parent_state_func, ServiceNamesAndTypesFunc get_service_names_and_types_func, std::chrono::nanoseconds service_timeout, std::chrono::nanoseconds call_timeout)
Constructor for PluginManager.
std::unordered_set< std::string > auto_activated_plugins_
Set of use specified auto activated plugins which will automatically started without need for user in...
const std::string plan_trajectory_suffix_
Base service name of plan_trajectory service.
std::unordered_set< std::string > required_plugins_
Set of required plugins a failure of which necessitates system shutdown.
const std::string plan_maneuvers_suffix_
Base service name of plan_trajectory service.
bool matching_capability(const std::vector< std::string > &base_capability_levels, const std::vector< std::string > &compared_capability_levels)
Returns true if the provided base capability hierarchy can achieve the requested capability hierarchy...
std::chrono::nanoseconds call_timeout_
The timeout for service calls to return.
void get_registered_plugins(SrvHeader, carma_planning_msgs::srv::PluginList::Request::SharedPtr req, carma_planning_msgs::srv::PluginList::Response::SharedPtr res)
Returns the list of known plugins.
GetParentNodeStateFunc get_parent_state_func_
Callback to retrieve the lifecycle state of the parent process.
void update_plugin_status(carma_planning_msgs::msg::Plugin::UniquePtr msg)
Update the status of a certain plugin.
void get_active_plugins(SrvHeader, carma_planning_msgs::srv::PluginList::Request::SharedPtr req, carma_planning_msgs::srv::PluginList::Response::SharedPtr res)
Get the list of currently active plugins.
std::chrono::nanoseconds service_timeout_
The timeout for services to be available.
void get_strategic_plugins_by_capability(SrvHeader, carma_planning_msgs::srv::GetPluginApi::Request::SharedPtr req, carma_planning_msgs::srv::GetPluginApi::Response::SharedPtr res)
Get strategic plugins by capability.
void get_tactical_plugins_by_capability(SrvHeader, carma_planning_msgs::srv::GetPluginApi::Request::SharedPtr req, carma_planning_msgs::srv::GetPluginApi::Response::SharedPtr res)
Get tactical plugins by capability.
void activate_plugin(SrvHeader, carma_planning_msgs::srv::PluginActivation::Request::SharedPtr req, carma_planning_msgs::srv::PluginActivation::Response::SharedPtr res)
Activate the specified plugin.
ServiceNamesAndTypesFunc get_service_names_and_types_func_
Callback to get service names and types for the given node.
bool is_ros2_lifecycle_node(const std::string &node)
Returns true if the specified fully qualified node name is a ROS2 lifecycle node.
EntryManager em_
Entry manager to keep track of detected plugins.
const std::string control_trajectory_suffix_
Base topic name of control plugin trajectory input topic.
std::function< uint8_t()> GetParentNodeStateFunc
std::function< std::map< std::string, std::vector< std::string, std::allocator< std::string > > >(const std::string &, const std::string &)> ServiceNamesAndTypesFunc
Function which will return a map of service names and their message types based on the provided base ...
const std::shared_ptr< rmw_request_id_t > SrvHeader
An entry represents a driver details for the purposes of tracking.
Definition: entry.hpp:27