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.
|
#include <stop_and_wait_node.hpp>
Public Member Functions | |
StopandWaitNode (const rclcpp::NodeOptions &) | |
Node constructor. More... | |
carma_ros2_utils::CallbackReturn | on_configure_plugin () |
This method should be used to load parameters and will be called on the configure state transition. More... | |
rcl_interfaces::msg::SetParametersResult | parameter_update_callback (const std::vector< rclcpp::Parameter > ¶meters) |
Callback for dynamic parameter updates. More... | |
void | plan_trajectory_callback (std::shared_ptr< rmw_request_id_t > srv_header, carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp) override |
Extending class provided callback which should return a planned trajectory based on the provided trajectory planning request. More... | |
bool | get_availability () override |
Get the availability status of this plugin based on the current operating environment. Method must be overriden by extending classes. More... | |
std::string | get_version_id () override final |
Returns the version id of this plugin. More... | |
Public Member Functions inherited from carma_guidance_plugins::TacticalPlugin | |
TacticalPlugin (const rclcpp::NodeOptions &) | |
TacticalPlugin constructor. More... | |
virtual | ~TacticalPlugin ()=default |
Virtual destructor for safe deletion. More... | |
virtual void | plan_trajectory_callback (std::shared_ptr< rmw_request_id_t > srv_header, carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::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::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) | |
Private Attributes | |
StopandWaitConfig | config_ |
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > | yield_client_ |
std::shared_ptr< StopandWait > | plugin_ |
std::string | version_id_ |
std::string | plugin_name_ |
Definition at line 51 of file stop_and_wait_node.hpp.
|
explicit |
Node constructor.
Definition at line 23 of file stop_and_wait_plugin_node.cpp.
References StopandWaitConfig::accel_limit, StopandWaitConfig::accel_limit_multiplier, StopandWaitConfig::centerline_sampling_spacing, config_, StopandWaitConfig::crawl_speed, StopandWaitConfig::default_stopping_buffer, StopandWaitConfig::enable_object_avoidance, StopandWaitConfig::minimal_trajectory_duration, StopandWaitConfig::stop_timestep, StopandWaitConfig::tactical_plugin_service_call_timeout, and StopandWaitConfig::trajectory_step_size.
|
overridevirtual |
Get the availability status of this plugin based on the current operating environment. Method must be overriden by extending classes.
Implements carma_guidance_plugins::PluginBaseNode.
Definition at line 100 of file stop_and_wait_plugin_node.cpp.
|
finaloverridevirtual |
Returns the version id of this plugin.
Implements carma_guidance_plugins::PluginBaseNode.
Definition at line 105 of file stop_and_wait_plugin_node.cpp.
References version_id_.
|
virtual |
This method should be used to load parameters and will be called on the configure state transition.
Implements carma_guidance_plugins::PluginBaseNode.
Definition at line 63 of file stop_and_wait_plugin_node.cpp.
References StopandWaitConfig::accel_limit, StopandWaitConfig::accel_limit_multiplier, StopandWaitConfig::centerline_sampling_spacing, config_, StopandWaitConfig::crawl_speed, StopandWaitConfig::default_stopping_buffer, StopandWaitConfig::enable_object_avoidance, carma_guidance_plugins::PluginBaseNode::get_world_model(), StopandWaitConfig::minimal_trajectory_duration, parameter_update_callback(), plugin_, plugin_name_, StopandWaitConfig::stop_timestep, StopandWaitConfig::tactical_plugin_service_call_timeout, StopandWaitConfig::trajectory_step_size, version_id_, and yield_client_.
rcl_interfaces::msg::SetParametersResult stop_and_wait_plugin::StopandWaitNode::parameter_update_callback | ( | const std::vector< rclcpp::Parameter > & | parameters | ) |
Callback for dynamic parameter updates.
Definition at line 43 of file stop_and_wait_plugin_node.cpp.
References StopandWaitConfig::accel_limit_multiplier, StopandWaitConfig::centerline_sampling_spacing, config_, StopandWaitConfig::crawl_speed, StopandWaitConfig::default_stopping_buffer, StopandWaitConfig::minimal_trajectory_duration, StopandWaitConfig::stop_timestep, and StopandWaitConfig::trajectory_step_size.
Referenced by on_configure_plugin().
|
overridevirtual |
Extending class provided callback which should return a planned trajectory based on the provided trajectory planning request.
srv_header | RCL header for services calls. Can usually be ignored by implementers. |
req | The service request containing the maneuvers to plan trajectories for and current vehicle state |
resp | The response containing the planned trajectory |
Implements carma_guidance_plugins::TacticalPlugin.
Definition at line 92 of file stop_and_wait_plugin_node.cpp.
References plugin_.
|
private |
Definition at line 56 of file stop_and_wait_node.hpp.
Referenced by StopandWaitNode(), on_configure_plugin(), and parameter_update_callback().
|
private |
Definition at line 62 of file stop_and_wait_node.hpp.
Referenced by on_configure_plugin(), and plan_trajectory_callback().
|
private |
Definition at line 65 of file stop_and_wait_node.hpp.
Referenced by on_configure_plugin().
|
private |
Definition at line 64 of file stop_and_wait_node.hpp.
Referenced by get_version_id(), and on_configure_plugin().
|
private |
Definition at line 59 of file stop_and_wait_node.hpp.
Referenced by on_configure_plugin().