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.
|
ControlPlugin base class which can be extended by user provided plugins which wish to implement the Control Plugin ROS API. More...
#include <control_plugin.hpp>
Public Member Functions | |
ControlPlugin (const rclcpp::NodeOptions &) | |
ControlPlugin constructor. More... | |
virtual | ~ControlPlugin ()=default |
Virtual destructor for safe deletion. More... | |
virtual autoware_msgs::msg::ControlCommandStamped | generate_command ()=0 |
Extending class provided method which should generate a command message which will be published to the required topic by the base class. 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::WMListener > | get_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) | |
Protected Member Functions | |
void | current_pose_callback (geometry_msgs::msg::PoseStamped::UniquePtr msg) |
void | current_twist_callback (geometry_msgs::msg::TwistStamped::UniquePtr msg) |
virtual void | current_trajectory_callback (carma_planning_msgs::msg::TrajectoryPlan::UniquePtr msg) |
Extending class provided method which can optionally handle trajectory plan callbacks. More... | |
Protected Attributes | |
boost::optional< geometry_msgs::msg::PoseStamped > | current_pose_ |
The most recent pose message received by this node. More... | |
boost::optional< geometry_msgs::msg::TwistStamped > | current_twist_ |
The most recent velocity message received by this node. More... | |
boost::optional< carma_planning_msgs::msg::TrajectoryPlan > | current_trajectory_ |
The most recent trajectory received by this plugin. More... | |
Private Attributes | |
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > | current_pose_sub_ |
carma_ros2_utils::SubPtr< geometry_msgs::msg::TwistStamped > | current_velocity_sub_ |
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::TrajectoryPlan > | trajectory_plan_sub_ |
carma_ros2_utils::PubPtr< autoware_msgs::msg::ControlCommandStamped > | vehicle_cmd_pub_ |
rclcpp::TimerBase::SharedPtr | command_timer_ |
ControlPlugin base class which can be extended by user provided plugins which wish to implement the Control Plugin ROS API.
A control plugin is responsible for generating high frequency vehicle speed and steering commands to execute the currently planned trajectory. This plugin provides default subscribers to track the pose, velocity, and current trajectory in the system. Extending classes must implement the generate_command() method to use that data and or additional data to plan commands at a 30Hz frequency.
Definition at line 38 of file control_plugin.hpp.
|
explicit |
ControlPlugin constructor.
Definition at line 25 of file control_plugin.cpp.
|
virtualdefault |
Virtual destructor for safe deletion.
|
protected |
Definition at line 39 of file control_plugin.cpp.
References current_pose_.
Referenced by handle_on_configure().
|
protectedvirtual |
Extending class provided method which can optionally handle trajectory plan callbacks.
Reimplemented in platooning_control::PlatooningControlPlugin.
Definition at line 51 of file control_plugin.cpp.
References current_trajectory_.
Referenced by handle_on_configure().
|
protected |
Definition at line 45 of file control_plugin.cpp.
References current_twist_.
Referenced by handle_on_configure().
|
pure virtual |
Extending class provided method which should generate a command message which will be published to the required topic by the base class.
NOTE: Implementer can determine if trajectory has changed based on current_trajectory_->trajectory_id
Implemented in platooning_control::PlatooningControlPlugin, pure_pursuit_wrapper::PurePursuitWrapperNode, SUB::Node, and trajectory_follower_wrapper::TrajectoryFollowerWrapperNode.
Referenced by handle_on_configure().
|
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.
Implements carma_guidance_plugins::PluginBaseNode.
Definition at line 29 of file control_plugin.cpp.
|
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.
Reimplemented from carma_guidance_plugins::PluginBaseNode.
Definition at line 34 of file control_plugin.cpp.
|
finaloverride |
Definition at line 85 of file control_plugin.cpp.
References carma_guidance_plugins::PluginBaseNode::handle_on_activate().
|
finaloverride |
Definition at line 95 of file control_plugin.cpp.
References carma_guidance_plugins::PluginBaseNode::handle_on_cleanup().
|
finaloverride |
Definition at line 57 of file control_plugin.cpp.
References command_timer_, current_pose_callback(), current_pose_sub_, current_trajectory_callback(), current_twist_callback(), current_velocity_sub_, generate_command(), carma_guidance_plugins::PluginBaseNode::get_activation_status(), carma_guidance_plugins::PluginBaseNode::handle_on_configure(), trajectory_plan_sub_, and vehicle_cmd_pub_.
|
finaloverride |
Definition at line 90 of file control_plugin.cpp.
References carma_guidance_plugins::PluginBaseNode::handle_on_deactivate().
|
finaloverride |
Definition at line 105 of file control_plugin.cpp.
References carma_guidance_plugins::PluginBaseNode::handle_on_error().
|
finaloverride |
Definition at line 100 of file control_plugin.cpp.
References carma_guidance_plugins::PluginBaseNode::handle_on_shutdown().
|
private |
Definition at line 51 of file control_plugin.hpp.
Referenced by handle_on_configure().
|
protected |
The most recent pose message received by this node.
Definition at line 57 of file control_plugin.hpp.
Referenced by trajectory_follower_wrapper::TrajectoryFollowerWrapperNode::autoware_info_timer_callback(), current_pose_callback(), platooning_control::PlatooningControlPlugin::generate_command(), pure_pursuit_wrapper::PurePursuitWrapperNode::generate_command(), and trajectory_follower_wrapper::TrajectoryFollowerWrapperNode::generate_command().
|
private |
Definition at line 43 of file control_plugin.hpp.
Referenced by handle_on_configure().
|
protected |
The most recent trajectory received by this plugin.
Definition at line 64 of file control_plugin.hpp.
Referenced by trajectory_follower_wrapper::TrajectoryFollowerWrapperNode::autoware_info_timer_callback(), current_trajectory_callback(), platooning_control::PlatooningControlPlugin::current_trajectory_callback(), platooning_control::PlatooningControlPlugin::generate_command(), pure_pursuit_wrapper::PurePursuitWrapperNode::generate_command(), trajectory_follower_wrapper::TrajectoryFollowerWrapperNode::generate_command(), and platooning_control::PlatooningControlPlugin::generate_control_signals().
|
protected |
The most recent velocity message received by this node.
Definition at line 61 of file control_plugin.hpp.
Referenced by trajectory_follower_wrapper::TrajectoryFollowerWrapperNode::autoware_info_timer_callback(), current_twist_callback(), platooning_control::PlatooningControlPlugin::generate_command(), pure_pursuit_wrapper::PurePursuitWrapperNode::generate_command(), and trajectory_follower_wrapper::TrajectoryFollowerWrapperNode::generate_command().
|
private |
Definition at line 44 of file control_plugin.hpp.
Referenced by handle_on_configure().
|
private |
Definition at line 45 of file control_plugin.hpp.
Referenced by handle_on_configure().
|
private |
Definition at line 48 of file control_plugin.hpp.
Referenced by handle_on_configure().