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_base_node.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2022 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#pragma once
18
19#include <gtest/gtest_prod.h>
20#include <rclcpp/rclcpp.hpp>
21#include <carma_planning_msgs/msg/plugin.hpp>
24
25#include <carma_ros2_utils/carma_lifecycle_node.hpp>
26
28{
29
40 class PluginBaseNode : public carma_ros2_utils::CarmaLifecycleNode
41 {
42
43 private:
44 // Publishers
46 //immediately on node construction regardless of lifecycle state. This is meant to allow for fast plugin activation on startup.
47 rclcpp::Publisher<carma_planning_msgs::msg::Plugin>::SharedPtr plugin_discovery_pub_;
48
49 // Timers
51 rclcpp::TimerBase::SharedPtr discovery_timer_;
52
53 // WorldModel listener
54 // This variable is intentionally private, so that is can be lazily initialized
55 // when the extending class calls get_world_model_listener(); or get_world_model();
56 std::shared_ptr<carma_wm::WMListener> wm_listener_;
57
58 // World Model populated by the listener at runtime
59 // This variable is intentionally private, so that is can be lazily initialized
60 // when the extending class calls get_world_model_listener(); or get_world_model();
62
67
72
73 public:
77 explicit PluginBaseNode(const rclcpp::NodeOptions &);
78
80 virtual ~PluginBaseNode() = default;
81
89 virtual std::shared_ptr<carma_wm::WMListener> get_world_model_listener() final;
90
99
106 virtual bool get_activation_status() final;
107
108
115 virtual uint8_t get_type();
116
123 std::string get_plugin_name_and_ns() const;
124
130 std::string get_plugin_name() const;
131
139 virtual bool get_availability() = 0;
140
148 virtual std::string get_capability() = 0;
149
155 virtual std::string get_version_id() = 0;
156
163 virtual carma_ros2_utils::CallbackReturn on_configure_plugin() = 0;
164
171 virtual carma_ros2_utils::CallbackReturn on_activate_plugin();
172
179 virtual carma_ros2_utils::CallbackReturn on_deactivate_plugin();
180
188 virtual carma_ros2_utils::CallbackReturn on_cleanup_plugin();
189
196 virtual carma_ros2_utils::CallbackReturn on_shutdown_plugin();
197
206 virtual carma_ros2_utils::CallbackReturn on_error_plugin(const std::string &exception_string);
207
209 // Overrides
211 // For simplicity of managing the plugin state machine all lifecycle callbacks are implemented as final by the core extending classes (strategic, tactical, control)
212 // Plugins will use the plugin specific callbacks via the template pattern
213 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &) override;
214 carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &) override;
215 carma_ros2_utils::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &) override;
216 carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &) override;
217 carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &) override;
218 carma_ros2_utils::CallbackReturn handle_on_error(const rclcpp_lifecycle::State &, const std::string &exception_string) override;
219
220 // Unit Test Accessors
221 FRIEND_TEST(carma_guidance_plugins_test, connections_test);
222
223 };
224
225} // carma_guidance_plugins
PluginBaseNode provides default functionality for all carma guidance plugins. This includes basic sta...
virtual uint8_t get_type()
Returns the type of this plugin according to the carma_planning_msgs::Plugin type enum....
virtual bool get_activation_status() final
Returns the activation status of this plugin. The plugins API callbacks will only be triggered when t...
virtual carma_ros2_utils::CallbackReturn on_deactivate_plugin()
Method which is triggered when this plugin is moved from the ACTIVE to INACTIVE states....
carma_ros2_utils::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_error(const rclcpp_lifecycle::State &, const std::string &exception_string) override
carma_wm::WorldModelConstPtr wm_
virtual std::string get_capability()=0
Get the capability string representing this plugins capabilities Method must be overriden by extendin...
virtual ~PluginBaseNode()=default
Virtual destructor for safe deletion.
carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &) override
std::string get_plugin_name() const
Return the name of this plugin.
virtual carma_wm::WorldModelConstPtr get_world_model() final
Method to return the default world model provided as a convience by this base class If this method or...
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &) override
virtual carma_ros2_utils::CallbackReturn on_cleanup_plugin()
Method which is triggered when this plugin is moved from the INACTIVE to UNCONFIGURED states....
virtual bool get_availability()=0
Get the availability status of this plugin based on the current operating environment....
PluginBaseNode(const rclcpp::NodeOptions &)
PluginBaseNode constructor.
virtual carma_ros2_utils::CallbackReturn on_configure_plugin()=0
Method which is triggered when this plugin is moved from the UNCONFIGURED to INACTIVE states....
rclcpp::Publisher< carma_planning_msgs::msg::Plugin >::SharedPtr plugin_discovery_pub_
Publisher for plugin discovery. This publisher will begin publishing.
void lazy_wm_initialization()
Helper function for lazy initialization of wm_listener_. If already initialized method returns (ie....
std::shared_ptr< carma_wm::WMListener > wm_listener_
virtual std::shared_ptr< carma_wm::WMListener > get_world_model_listener() final
Method to return the default world model listener provided as a convience by this base class If this ...
virtual carma_ros2_utils::CallbackReturn on_shutdown_plugin()
Method which is triggered when this plugin is moved from any state to FINALIZED This method should be...
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &) override
std::string get_plugin_name_and_ns() const
Return the name of this plugin with namespace. NOTE: If only the name of the plugin is required,...
virtual carma_ros2_utils::CallbackReturn on_error_plugin(const std::string &exception_string)
Method which is triggered when an unhandled exception occurs in this plugin This method should be use...
virtual std::string get_version_id()=0
Returns the version id of this plugin.
void discovery_timer_callback()
Callback for the plugin discovery timer which will publish the plugin discovery message.
carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &) override
virtual carma_ros2_utils::CallbackReturn on_activate_plugin()
Method which is triggered when this plugin is moved from the INACTIVE to ACTIVE states....
rclcpp::TimerBase::SharedPtr discovery_timer_
Timer to trigger publication of the plugin discovery message at a fixed frequency.
FRIEND_TEST(carma_guidance_plugins_test, connections_test)
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452