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.
carma_guidance_plugins::PluginBaseNode Class Referenceabstract

PluginBaseNode provides default functionality for all carma guidance plugins. This includes basic state machine management (largely delegated to ROS2 lifecycle behavior), required interfaces, and plugin discovery. More...

#include <plugin_base_node.hpp>

Inheritance diagram for carma_guidance_plugins::PluginBaseNode:
Inheritance graph
Collaboration diagram for carma_guidance_plugins::PluginBaseNode:
Collaboration graph

Public Member Functions

 PluginBaseNode (const rclcpp::NodeOptions &)
 PluginBaseNode constructor. More...
 
virtual ~PluginBaseNode ()=default
 Virtual destructor for safe deletion. More...
 
virtual std::shared_ptr< carma_wm::WMListenerget_world_model_listener () final
 Method to return the default world model listener provided as a convience by this base class If this method or get_world_model() are not called then the world model remains uninitialized and will not create unnecessary subscriptions. More...
 
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 get_world_model_listener() are not called then the world model remains uninitialized and will not create unnecessary subscriptions. More...
 
virtual bool get_activation_status () final
 Returns the activation status of this plugin. The plugins API callbacks will only be triggered when this method returns true. More...
 
virtual uint8_t get_type ()
 Returns the type of this plugin according to the carma_planning_msgs::Plugin type enum. Extending classes for the specific type should override this method. More...
 
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, use get_plugin_name() More...
 
std::string get_plugin_name () const
 Return the name of this plugin. More...
 
virtual bool get_availability ()=0
 Get the availability status of this plugin based on the current operating environment. Method must be overriden by extending classes. More...
 
virtual std::string get_capability ()=0
 Get the capability string representing this plugins capabilities Method must be overriden by extending classes. Expectation is that abstract plugin type parent classes will provide a default implementation. More...
 
virtual std::string get_version_id ()=0
 Returns the version id of this plugin. More...
 
virtual carma_ros2_utils::CallbackReturn on_configure_plugin ()=0
 Method which is triggered when this plugin is moved from the UNCONFIGURED to INACTIVE states. This method should be used to load parameters and is required to be implemented. More...
 
virtual carma_ros2_utils::CallbackReturn on_activate_plugin ()
 Method which is triggered when this plugin is moved from the INACTIVE to ACTIVE states. This method should be used to prepare for future callbacks for plugin's capabilites. More...
 
virtual carma_ros2_utils::CallbackReturn on_deactivate_plugin ()
 Method which is triggered when this plugin is moved from the ACTIVE to INACTIVE states. This method should be used to disable any functionality which should cease execution when plugin is inactive. More...
 
virtual carma_ros2_utils::CallbackReturn on_cleanup_plugin ()
 Method which is triggered when this plugin is moved from the INACTIVE to UNCONFIGURED states. This method should be used to fully reset the plugin such that a future call to on_configure_plugin would leave the plugin in a fresh state as though just launched. More...
 
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 used to generate any shutdown logs or final cleanup. More...
 
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 used to cleanup such that the plugin could be moved to UNCONFIGURED state if possible. More...
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &) override
 
carma_ros2_utils::CallbackReturn handle_on_activate (const rclcpp_lifecycle::State &) override
 
carma_ros2_utils::CallbackReturn handle_on_deactivate (const rclcpp_lifecycle::State &) override
 
carma_ros2_utils::CallbackReturn handle_on_cleanup (const rclcpp_lifecycle::State &) override
 
carma_ros2_utils::CallbackReturn handle_on_shutdown (const rclcpp_lifecycle::State &) override
 
carma_ros2_utils::CallbackReturn handle_on_error (const rclcpp_lifecycle::State &, const std::string &exception_string) override
 
 FRIEND_TEST (carma_guidance_plugins_test, connections_test)
 

Private Member Functions

void discovery_timer_callback ()
 Callback for the plugin discovery timer which will publish the plugin discovery message. More...
 
void lazy_wm_initialization ()
 Helper function for lazy initialization of wm_listener_. If already initialized method returns (ie. not a reset) More...
 

Private Attributes

rclcpp::Publisher< carma_planning_msgs::msg::Plugin >::SharedPtr plugin_discovery_pub_
 Publisher for plugin discovery. This publisher will begin publishing. More...
 
rclcpp::TimerBase::SharedPtr discovery_timer_
 Timer to trigger publication of the plugin discovery message at a fixed frequency. More...
 
std::shared_ptr< carma_wm::WMListenerwm_listener_
 
carma_wm::WorldModelConstPtr wm_
 

Detailed Description

PluginBaseNode provides default functionality for all carma guidance plugins. This includes basic state machine management (largely delegated to ROS2 lifecycle behavior), required interfaces, and plugin discovery.

Extending classes must implement the on_configure_plugin method to load parameters, and my override the other state transitions methods on_<state>_plugin if desired. Additionally, extending classes must implement the methods such as get_version_id() which are used to populate the plugin discovery message.

NOTE: At the moment, this class and all extending classes are setup to support only single threading.

Definition at line 40 of file plugin_base_node.hpp.

Constructor & Destructor Documentation

◆ PluginBaseNode()

carma_guidance_plugins::PluginBaseNode::PluginBaseNode ( const rclcpp::NodeOptions &  options)
explicit

PluginBaseNode constructor.

Definition at line 25 of file plugin_base_node.cpp.

26 : carma_ros2_utils::CarmaLifecycleNode(options)
27 {
28
29 // Setup discovery timer to publish onto the plugin_discovery_pub
30 discovery_timer_ = create_timer(
31 get_clock(),
32 std::chrono::milliseconds(500), // 2 Hz frequency to account for 1Hz maneuver planning frequency
34 }
void discovery_timer_callback()
Callback for the plugin discovery timer which will publish the plugin discovery message.
rclcpp::TimerBase::SharedPtr discovery_timer_
Timer to trigger publication of the plugin discovery message at a fixed frequency.

References discovery_timer_, and discovery_timer_callback().

Here is the call graph for this function:

◆ ~PluginBaseNode()

virtual carma_guidance_plugins::PluginBaseNode::~PluginBaseNode ( )
virtualdefault

Virtual destructor for safe deletion.

Member Function Documentation

◆ discovery_timer_callback()

void carma_guidance_plugins::PluginBaseNode::discovery_timer_callback ( )
private

Callback for the plugin discovery timer which will publish the plugin discovery message.

Definition at line 141 of file plugin_base_node.cpp.

142 {
143
144 if (!plugin_discovery_pub_) // If the publisher has not been initalized then initialize it.
145 {
146 // Setup plugin publisher discovery which should bypass lifecycle behavior to ensure plugins are found
147 // prior to them needing to be activated.
148 // NOTE: Any other topics which need to be setup in the future should use handle_on_configure and the default this->create_publisher method to get a lifecycle publisher instead
149 auto this_shared = shared_from_this(); // Usage of shared_from_this() means this cannot be done in the constructor thus it is delegated to the timer callback
150 plugin_discovery_pub_ = rclcpp::create_publisher<carma_planning_msgs::msg::Plugin>(this_shared, "plugin_discovery", 1);
151
152 }
153
154 carma_planning_msgs::msg::Plugin msg;
155 msg.name = get_plugin_name_and_ns();
156 msg.version_id = get_version_id();
157 msg.type = get_type();
158 msg.available = get_availability();
159 msg.activated = get_activation_status();
160 msg.capability = get_capability();
161
162 plugin_discovery_pub_->publish(msg);
163 }
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 std::string get_capability()=0
Get the capability string representing this plugins capabilities Method must be overriden by extendin...
virtual bool get_availability()=0
Get the availability status of this plugin based on the current operating environment....
rclcpp::Publisher< carma_planning_msgs::msg::Plugin >::SharedPtr plugin_discovery_pub_
Publisher for plugin discovery. This publisher will begin publishing.
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 std::string get_version_id()=0
Returns the version id of this plugin.

References get_activation_status(), get_availability(), get_capability(), get_plugin_name_and_ns(), get_type(), get_version_id(), and plugin_discovery_pub_.

Referenced by PluginBaseNode().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ FRIEND_TEST()

carma_guidance_plugins::PluginBaseNode::FRIEND_TEST ( carma_guidance_plugins_test  ,
connections_test   
)

◆ get_activation_status()

bool carma_guidance_plugins::PluginBaseNode::get_activation_status ( )
finalvirtual

Returns the activation status of this plugin. The plugins API callbacks will only be triggered when this method returns true.

Returns
True if plugin is in the ACTIVE state. False otherwise.

Definition at line 72 of file plugin_base_node.cpp.

72 {
73 // Determine the plugin activation state by checking which lifecycle state we are in.
74 // If we are active then the plugin is active otherwise the plugin is inactive
75 return get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE;
76 }

Referenced by discovery_timer_callback(), carma_guidance_plugins::ControlPlugin::handle_on_configure(), carma_guidance_plugins::StrategicPlugin::handle_on_configure(), and carma_guidance_plugins::TacticalPlugin::handle_on_configure().

Here is the caller graph for this function:

◆ get_availability()

◆ get_capability()

virtual std::string carma_guidance_plugins::PluginBaseNode::get_capability ( )
pure virtual

Get the capability string representing this plugins capabilities Method must be overriden by extending classes. Expectation is that abstract plugin type parent classes will provide a default implementation.

Returns
Forward slash separated string describing the plugin's capabilities per the plugin capabilites API

Implemented in carma_guidance_plugins::ControlPlugin, carma_guidance_plugins::StrategicPlugin, and carma_guidance_plugins::TacticalPlugin.

Referenced by discovery_timer_callback().

Here is the caller graph for this function:

◆ get_plugin_name()

std::string carma_guidance_plugins::PluginBaseNode::get_plugin_name ( ) const

Return the name of this plugin.

Returns
Name of this plugin

Definition at line 50 of file plugin_base_node.cpp.

51 {
52 return std::string(get_name());
53 }

Referenced by light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode::on_configure_plugin(), and stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::plan_trajectory_callback().

Here is the caller graph for this function:

◆ get_plugin_name_and_ns()

std::string carma_guidance_plugins::PluginBaseNode::get_plugin_name_and_ns ( ) const

Return the name of this plugin with namespace. NOTE: If only the name of the plugin is required, use get_plugin_name()

Returns
Name of this plugin with namespace

Definition at line 55 of file plugin_base_node.cpp.

56 {
57 return std::string(get_namespace()) + "/" + std::string(get_name());
58 }

Referenced by discovery_timer_callback().

Here is the caller graph for this function:

◆ get_type()

uint8_t carma_guidance_plugins::PluginBaseNode::get_type ( )
virtual

Returns the type of this plugin according to the carma_planning_msgs::Plugin type enum. Extending classes for the specific type should override this method.

Returns
The extending class type or UNKOWN if the class or no parent class has implement this method.

Reimplemented in carma_guidance_plugins::ControlPlugin, carma_guidance_plugins::StrategicPlugin, and carma_guidance_plugins::TacticalPlugin.

Definition at line 134 of file plugin_base_node.cpp.

135 {
136 // Base class returns unknown.
137 // Its expected that 2nd level extending classes (strategic, tactical, control) will return correct type by overriding
138 return carma_planning_msgs::msg::Plugin::UNKNOWN;
139 }

Referenced by discovery_timer_callback().

Here is the caller graph for this function:

◆ get_version_id()

◆ get_world_model()

carma_wm::WorldModelConstPtr carma_guidance_plugins::PluginBaseNode::get_world_model ( )
finalvirtual

Method to return the default world model provided as a convience by this base class If this method or get_world_model_listener() are not called then the world model remains uninitialized and will not create unnecessary subscriptions.

Returns
Pointer to an initialized world model. Returned instance is that same as get_world_model_listener()->getWorldModel();

Definition at line 66 of file plugin_base_node.cpp.

67 {
69 return wm_;
70 }
carma_wm::WorldModelConstPtr wm_
void lazy_wm_initialization()
Helper function for lazy initialization of wm_listener_. If already initialized method returns (ie....

References lazy_wm_initialization(), and wm_.

Referenced by approaching_emergency_vehicle_plugin::ApproachingEmergencyVehiclePlugin::on_configure_plugin(), cooperative_lanechange::CooperativeLaneChangePlugin::on_configure_plugin(), inlanecruising_plugin::InLaneCruisingPluginNode::on_configure_plugin(), lci_strategic_plugin::LCIStrategicPlugin::on_configure_plugin(), platoon_strategic_ihp::Node::on_configure_plugin(), platooning_tactical_plugin::Node::on_configure_plugin(), route_following_plugin::RouteFollowingPlugin::on_configure_plugin(), sci_strategic_plugin::SCIStrategicPlugin::on_configure_plugin(), stop_and_dwell_strategic_plugin::StopAndDwellStrategicPlugin::on_configure_plugin(), stop_and_wait_plugin::StopandWaitNode::on_configure_plugin(), yield_plugin::YieldPluginNode::on_configure_plugin(), light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode::on_configure_plugin(), and stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::on_configure_plugin().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_world_model_listener()

std::shared_ptr< carma_wm::WMListener > carma_guidance_plugins::PluginBaseNode::get_world_model_listener ( )
finalvirtual

Method to return the default world model listener provided as a convience by this base class If this method or get_world_model() are not called then the world model remains uninitialized and will not create unnecessary subscriptions.

Returns
Pointer to an initialized world model listener

Definition at line 60 of file plugin_base_node.cpp.

61 {
63 return wm_listener_;
64 }
std::shared_ptr< carma_wm::WMListener > wm_listener_

References lazy_wm_initialization(), and wm_listener_.

Referenced by route_following_plugin::RouteFollowingPlugin::on_configure_plugin().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_on_activate()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::PluginBaseNode::handle_on_activate ( const rclcpp_lifecycle::State &  )
override

Definition at line 109 of file plugin_base_node.cpp.

110 {
111 return on_activate_plugin();
112 }
virtual carma_ros2_utils::CallbackReturn on_activate_plugin()
Method which is triggered when this plugin is moved from the INACTIVE to ACTIVE states....

References on_activate_plugin().

Referenced by carma_guidance_plugins::ControlPlugin::handle_on_activate(), carma_guidance_plugins::StrategicPlugin::handle_on_activate(), and carma_guidance_plugins::TacticalPlugin::handle_on_activate().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_on_cleanup()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::PluginBaseNode::handle_on_cleanup ( const rclcpp_lifecycle::State &  )
override

Definition at line 119 of file plugin_base_node.cpp.

120 {
121 return on_cleanup_plugin();
122 }
virtual carma_ros2_utils::CallbackReturn on_cleanup_plugin()
Method which is triggered when this plugin is moved from the INACTIVE to UNCONFIGURED states....

References on_cleanup_plugin().

Referenced by carma_guidance_plugins::ControlPlugin::handle_on_cleanup(), carma_guidance_plugins::StrategicPlugin::handle_on_cleanup(), and carma_guidance_plugins::TacticalPlugin::handle_on_cleanup().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::PluginBaseNode::handle_on_configure ( const rclcpp_lifecycle::State &  )
override

Definition at line 104 of file plugin_base_node.cpp.

105 {
106 return on_configure_plugin();
107 }
virtual carma_ros2_utils::CallbackReturn on_configure_plugin()=0
Method which is triggered when this plugin is moved from the UNCONFIGURED to INACTIVE states....

References on_configure_plugin().

Referenced by carma_guidance_plugins::ControlPlugin::handle_on_configure(), carma_guidance_plugins::StrategicPlugin::handle_on_configure(), and carma_guidance_plugins::TacticalPlugin::handle_on_configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_on_deactivate()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::PluginBaseNode::handle_on_deactivate ( const rclcpp_lifecycle::State &  )
override

Definition at line 114 of file plugin_base_node.cpp.

115 {
116 return on_deactivate_plugin();
117 }
virtual carma_ros2_utils::CallbackReturn on_deactivate_plugin()
Method which is triggered when this plugin is moved from the ACTIVE to INACTIVE states....

References on_deactivate_plugin().

Referenced by carma_guidance_plugins::ControlPlugin::handle_on_deactivate(), carma_guidance_plugins::StrategicPlugin::handle_on_deactivate(), and carma_guidance_plugins::TacticalPlugin::handle_on_deactivate().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_on_error()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::PluginBaseNode::handle_on_error ( const rclcpp_lifecycle::State &  ,
const std::string &  exception_string 
)
override

Definition at line 129 of file plugin_base_node.cpp.

130 {
131 return on_error_plugin(exception_string);
132 }
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...

References on_error_plugin().

Referenced by carma_guidance_plugins::ControlPlugin::handle_on_error(), carma_guidance_plugins::StrategicPlugin::handle_on_error(), and carma_guidance_plugins::TacticalPlugin::handle_on_error().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_on_shutdown()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::PluginBaseNode::handle_on_shutdown ( const rclcpp_lifecycle::State &  )
override

Definition at line 124 of file plugin_base_node.cpp.

125 {
126 return on_shutdown_plugin();
127 }
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...

References on_shutdown_plugin().

Referenced by carma_guidance_plugins::ControlPlugin::handle_on_shutdown(), carma_guidance_plugins::StrategicPlugin::handle_on_shutdown(), and carma_guidance_plugins::TacticalPlugin::handle_on_shutdown().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ lazy_wm_initialization()

void carma_guidance_plugins::PluginBaseNode::lazy_wm_initialization ( )
private

Helper function for lazy initialization of wm_listener_. If already initialized method returns (ie. not a reset)

Definition at line 36 of file plugin_base_node.cpp.

37 {
38 if (wm_listener_)
39 return; // Already initialized
40
41
42 wm_listener_ = std::make_shared<carma_wm::WMListener>(
43 this->get_node_base_interface(), this->get_node_logging_interface(),
44 this->get_node_topics_interface(), this->get_node_parameters_interface()
45 );
46
47 wm_ = wm_listener_->getWorldModel();
48 }

References wm_, and wm_listener_.

Referenced by get_world_model(), and get_world_model_listener().

Here is the caller graph for this function:

◆ on_activate_plugin()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::PluginBaseNode::on_activate_plugin ( )
virtual

Method which is triggered when this plugin is moved from the INACTIVE to ACTIVE states. This method should be used to prepare for future callbacks for plugin's capabilites.

Returns
SUCCESS, FAILURE, or ERROR. Transition to ACTIVE will only complete on SUCCESS.

Reimplemented in approaching_emergency_vehicle_plugin::ApproachingEmergencyVehiclePlugin, lci_strategic_plugin::LCIStrategicPlugin, route_following_plugin::RouteFollowingPlugin, sci_strategic_plugin::SCIStrategicPlugin, and stop_and_dwell_strategic_plugin::StopAndDwellStrategicPlugin.

Definition at line 78 of file plugin_base_node.cpp.

79 {
80 return carma_ros2_utils::CallbackReturn::SUCCESS;
81 }

Referenced by handle_on_activate().

Here is the caller graph for this function:

◆ on_cleanup_plugin()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::PluginBaseNode::on_cleanup_plugin ( )
virtual

Method which is triggered when this plugin is moved from the INACTIVE to UNCONFIGURED states. This method should be used to fully reset the plugin such that a future call to on_configure_plugin would leave the plugin in a fresh state as though just launched.

Returns
SUCCESS, FAILURE, or ERROR. Transition to UNCONFIGURED will only complete on SUCCESS.

Reimplemented in platoon_strategic_ihp::Node.

Definition at line 88 of file plugin_base_node.cpp.

89 {
90 return carma_ros2_utils::CallbackReturn::SUCCESS;
91 }

Referenced by handle_on_cleanup().

Here is the caller graph for this function:

◆ on_configure_plugin()

◆ on_deactivate_plugin()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::PluginBaseNode::on_deactivate_plugin ( )
virtual

Method which is triggered when this plugin is moved from the ACTIVE to INACTIVE states. This method should be used to disable any functionality which should cease execution when plugin is inactive.

Returns
SUCCESS, FAILURE, or ERROR. Transition to INACTIVE will only complete on SUCCESS.

Definition at line 83 of file plugin_base_node.cpp.

84 {
85 return carma_ros2_utils::CallbackReturn::SUCCESS;
86 }

Referenced by handle_on_deactivate().

Here is the caller graph for this function:

◆ on_error_plugin()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::PluginBaseNode::on_error_plugin ( const std::string &  exception_string)
virtual

Method which is triggered when an unhandled exception occurs in this plugin This method should be used to cleanup such that the plugin could be moved to UNCONFIGURED state if possible.

Parameters
exception_stringThe exception description
Returns
SUCCESS, FAILURE, or ERROR. On SUCCESS plugin moves to UNCONFIGURED state else FINALIZED. Default behavior is to move to FINALIZED.

Definition at line 98 of file plugin_base_node.cpp.

99 {
100 // On error should default to failure so user must explicitly implement error handling to get any other behavior
101 return carma_ros2_utils::CallbackReturn::FAILURE;
102 }

Referenced by handle_on_error().

Here is the caller graph for this function:

◆ on_shutdown_plugin()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::PluginBaseNode::on_shutdown_plugin ( )
virtual

Method which is triggered when this plugin is moved from any state to FINALIZED This method should be used to generate any shutdown logs or final cleanup.

Returns
SUCCESS, FAILURE, or ERROR. On ERROR, may temporarily go to on_error_plugin() before calling finalized.

Definition at line 93 of file plugin_base_node.cpp.

94 {
95 return carma_ros2_utils::CallbackReturn::SUCCESS;
96 }

Referenced by handle_on_shutdown().

Here is the caller graph for this function:

Member Data Documentation

◆ discovery_timer_

rclcpp::TimerBase::SharedPtr carma_guidance_plugins::PluginBaseNode::discovery_timer_
private

Timer to trigger publication of the plugin discovery message at a fixed frequency.

Definition at line 51 of file plugin_base_node.hpp.

Referenced by PluginBaseNode().

◆ plugin_discovery_pub_

rclcpp::Publisher<carma_planning_msgs::msg::Plugin>::SharedPtr carma_guidance_plugins::PluginBaseNode::plugin_discovery_pub_
private

Publisher for plugin discovery. This publisher will begin publishing.

Definition at line 47 of file plugin_base_node.hpp.

Referenced by discovery_timer_callback().

◆ wm_

carma_wm::WorldModelConstPtr carma_guidance_plugins::PluginBaseNode::wm_
private

Definition at line 61 of file plugin_base_node.hpp.

Referenced by get_world_model(), and lazy_wm_initialization().

◆ wm_listener_

std::shared_ptr<carma_wm::WMListener> carma_guidance_plugins::PluginBaseNode::wm_listener_
private

Definition at line 56 of file plugin_base_node.hpp.

Referenced by get_world_model_listener(), and lazy_wm_initialization().


The documentation for this class was generated from the following files: