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::StrategicPlugin Class Referenceabstract

StrategicPlugin base class which can be extended by user provided plugins which wish to implement the Strategic Plugin ROS API. A strategic plugin is responsible for planning sequences of maneuvers to achieve high-level objects for the vehicle (follow the route, efficiently get through an intersection, etc.) More...

#include <strategic_plugin.hpp>

Inheritance diagram for carma_guidance_plugins::StrategicPlugin:
Inheritance graph
Collaboration diagram for carma_guidance_plugins::StrategicPlugin:
Collaboration graph

Public Member Functions

 StrategicPlugin (const rclcpp::NodeOptions &)
 StrategicPlugin constructor. More...
 
virtual ~StrategicPlugin ()=default
 Virtual destructor for safe deletion. More...
 
virtual void plan_maneuvers_callback (std::shared_ptr< rmw_request_id_t > srv_header, carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp)=0
 Extending class provided callback which should return a planned trajectory based on the provided trajectory planning request. More...
 
std::string get_capability () override
 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...
 
uint8_t get_type () override final
 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...
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &) override final
 
carma_ros2_utils::CallbackReturn handle_on_activate (const rclcpp_lifecycle::State &) override final
 
carma_ros2_utils::CallbackReturn handle_on_deactivate (const rclcpp_lifecycle::State &) override final
 
carma_ros2_utils::CallbackReturn handle_on_cleanup (const rclcpp_lifecycle::State &) override final
 
carma_ros2_utils::CallbackReturn handle_on_shutdown (const rclcpp_lifecycle::State &) override final
 
carma_ros2_utils::CallbackReturn handle_on_error (const rclcpp_lifecycle::State &, const std::string &exception_string) override final
 
- Public Member Functions inherited from carma_guidance_plugins::PluginBaseNode
 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 Attributes

carma_ros2_utils::ServicePtr< carma_planning_msgs::srv::PlanManeuvers > plan_maneuvers_service_
 The service which will be called when a strategic plugin needs to plan maneuvers. More...
 

Detailed Description

StrategicPlugin base class which can be extended by user provided plugins which wish to implement the Strategic Plugin ROS API. A strategic plugin is responsible for planning sequences of maneuvers to achieve high-level objects for the vehicle (follow the route, efficiently get through an intersection, etc.)

Definition at line 32 of file strategic_plugin.hpp.

Constructor & Destructor Documentation

◆ StrategicPlugin()

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

StrategicPlugin constructor.

Definition at line 24 of file strategic_plugin.cpp.

25 : PluginBaseNode(options)
26 {}
PluginBaseNode(const rclcpp::NodeOptions &)
PluginBaseNode constructor.

◆ ~StrategicPlugin()

virtual carma_guidance_plugins::StrategicPlugin::~StrategicPlugin ( )
virtualdefault

Virtual destructor for safe deletion.

Member Function Documentation

◆ get_capability()

std::string carma_guidance_plugins::StrategicPlugin::get_capability ( )
overridevirtual

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

Implements carma_guidance_plugins::PluginBaseNode.

Definition at line 28 of file strategic_plugin.cpp.

29 {
30 return "strategic_plan/plan_maneuvers";
31 }

◆ get_type()

uint8_t carma_guidance_plugins::StrategicPlugin::get_type ( )
finaloverridevirtual

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

Definition at line 33 of file strategic_plugin.cpp.

34 {
35 return carma_planning_msgs::msg::Plugin::STRATEGIC;
36 }

◆ handle_on_activate()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::StrategicPlugin::handle_on_activate ( const rclcpp_lifecycle::State &  prev_state)
finaloverride

Definition at line 52 of file strategic_plugin.cpp.

53 {
54 return PluginBaseNode::handle_on_activate(prev_state);
55 }
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &) override

References carma_guidance_plugins::PluginBaseNode::handle_on_activate().

Here is the call graph for this function:

◆ handle_on_cleanup()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::StrategicPlugin::handle_on_cleanup ( const rclcpp_lifecycle::State &  prev_state)
finaloverride

Definition at line 62 of file strategic_plugin.cpp.

63 {
64 return PluginBaseNode::handle_on_cleanup(prev_state);
65 }
carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &) override

References carma_guidance_plugins::PluginBaseNode::handle_on_cleanup().

Here is the call graph for this function:

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::StrategicPlugin::handle_on_configure ( const rclcpp_lifecycle::State &  prev_state)
finaloverride

Definition at line 38 of file strategic_plugin.cpp.

39 {
40 // Initialize plan maneuvers service
41 plan_maneuvers_service_ = create_service<carma_planning_msgs::srv::PlanManeuvers>(std::string(get_name()) + "/plan_maneuvers",
42 [this] (auto header, auto req, auto resp) {
43 if (this->get_activation_status()) // Only trigger when activated
44 {
45 this->plan_maneuvers_callback(header, req, resp);
46 }
47 });
48
49 return PluginBaseNode::handle_on_configure(prev_state);
50 }
virtual bool get_activation_status() final
Returns the activation status of this plugin. The plugins API callbacks will only be triggered when t...
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &) override
carma_ros2_utils::ServicePtr< carma_planning_msgs::srv::PlanManeuvers > plan_maneuvers_service_
The service which will be called when a strategic plugin needs to plan maneuvers.
virtual void plan_maneuvers_callback(std::shared_ptr< rmw_request_id_t > srv_header, carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp)=0
Extending class provided callback which should return a planned trajectory based on the provided traj...

References carma_guidance_plugins::PluginBaseNode::get_activation_status(), carma_guidance_plugins::PluginBaseNode::handle_on_configure(), plan_maneuvers_callback(), and plan_maneuvers_service_.

Here is the call graph for this function:

◆ handle_on_deactivate()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::StrategicPlugin::handle_on_deactivate ( const rclcpp_lifecycle::State &  prev_state)
finaloverride

Definition at line 57 of file strategic_plugin.cpp.

58 {
59 return PluginBaseNode::handle_on_deactivate(prev_state);
60 }
carma_ros2_utils::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &) override

References carma_guidance_plugins::PluginBaseNode::handle_on_deactivate().

Here is the call graph for this function:

◆ handle_on_error()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::StrategicPlugin::handle_on_error ( const rclcpp_lifecycle::State &  prev_state,
const std::string &  exception_string 
)
finaloverride

Definition at line 72 of file strategic_plugin.cpp.

73 {
74 return PluginBaseNode::handle_on_error(prev_state, exception_string);
75 }
carma_ros2_utils::CallbackReturn handle_on_error(const rclcpp_lifecycle::State &, const std::string &exception_string) override

References carma_guidance_plugins::PluginBaseNode::handle_on_error().

Here is the call graph for this function:

◆ handle_on_shutdown()

carma_ros2_utils::CallbackReturn carma_guidance_plugins::StrategicPlugin::handle_on_shutdown ( const rclcpp_lifecycle::State &  prev_state)
finaloverride

Definition at line 67 of file strategic_plugin.cpp.

68 {
69 return PluginBaseNode::handle_on_shutdown(prev_state);
70 }
carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &) override

References carma_guidance_plugins::PluginBaseNode::handle_on_shutdown().

Here is the call graph for this function:

◆ plan_maneuvers_callback()

virtual void carma_guidance_plugins::StrategicPlugin::plan_maneuvers_callback ( std::shared_ptr< rmw_request_id_t >  srv_header,
carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr  req,
carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr  resp 
)
pure virtual

Extending class provided callback which should return a planned trajectory based on the provided trajectory planning request.

Parameters
srv_headerRCL header for services calls. Can usually be ignored by implementers.
reqThe service request containing the previously planned maneuvers and vehicle state
respThe response containing the additional maneuvers generated by this plugin

Implemented in lci_strategic_plugin::LCIStrategicPlugin, route_following_plugin::RouteFollowingPlugin, sci_strategic_plugin::SCIStrategicPlugin, stop_and_dwell_strategic_plugin::StopAndDwellStrategicPlugin, approaching_emergency_vehicle_plugin::ApproachingEmergencyVehiclePlugin, platoon_strategic_ihp::Node, and SUB::Node.

Referenced by handle_on_configure().

Here is the caller graph for this function:

Member Data Documentation

◆ plan_maneuvers_service_

carma_ros2_utils::ServicePtr<carma_planning_msgs::srv::PlanManeuvers> carma_guidance_plugins::StrategicPlugin::plan_maneuvers_service_
private

The service which will be called when a strategic plugin needs to plan maneuvers.

Definition at line 39 of file strategic_plugin.hpp.

Referenced by handle_on_configure().


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