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.
inlanecruising_plugin::InLaneCruisingPluginNode Class Reference

ROS node for the InLaneCruisingPlugin. More...

#include <inlanecruising_plugin_node.hpp>

Inheritance diagram for inlanecruising_plugin::InLaneCruisingPluginNode:
Inheritance graph
Collaboration diagram for inlanecruising_plugin::InLaneCruisingPluginNode:
Collaboration graph

Public Member Functions

 InLaneCruisingPluginNode (const rclcpp::NodeOptions &)
 Node constructor. More...
 
carma_ros2_utils::CallbackReturn on_configure_plugin ()
 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...
 
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...
 
rcl_interfaces::msg::SetParametersResult parameter_update_callback (const std::vector< rclcpp::Parameter > &parameters)
 
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...
 
- 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::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

 FRIEND_TEST (InLaneCruisingPluginTest, rostest1)
 

Private Attributes

InLaneCruisingPluginConfig config_
 
std::string plugin_name_
 
std::string version_id_
 
carma_ros2_utils::PubPtr< carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds > trajectory_debug_pub_
 
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > yield_client_
 
std::shared_ptr< InLaneCruisingPluginworker_
 

Detailed Description

ROS node for the InLaneCruisingPlugin.

Definition at line 37 of file inlanecruising_plugin_node.hpp.

Constructor & Destructor Documentation

◆ InLaneCruisingPluginNode()

inlanecruising_plugin::InLaneCruisingPluginNode::InLaneCruisingPluginNode ( const rclcpp::NodeOptions &  options)
explicit

Node constructor.

Definition at line 23 of file inlanecruising_plugin_node.cpp.

26 version_id_("v4.0"),
28 {
29 // Declare parameters
30 config_.trajectory_time_length = declare_parameter<double>("trajectory_time_length", config_.trajectory_time_length);
31 config_.curve_resample_step_size = declare_parameter<double>("curve_resample_step_size", config_.curve_resample_step_size);
32 config_.default_downsample_ratio = declare_parameter<int>("default_downsample_ratio", config_.default_downsample_ratio);
33 config_.turn_downsample_ratio = declare_parameter<int>("turn_downsample_ratio", config_.turn_downsample_ratio);
34 config_.minimum_speed = declare_parameter<double>("minimum_speed", config_.minimum_speed);
35 config_.max_accel_multiplier = declare_parameter<double>("max_accel_multiplier", config_.max_accel_multiplier);
36 config_.lat_accel_multiplier = declare_parameter<double>("lat_accel_multiplier", config_.lat_accel_multiplier);
37 config_.back_distance = declare_parameter<double>("back_distance", config_.back_distance);
38 config_.speed_moving_average_window_size = declare_parameter<int>("speed_moving_average_window_size", config_.speed_moving_average_window_size);
39 config_.curvature_moving_average_window_size = declare_parameter<int>("curvature_moving_average_window_size", config_.curvature_moving_average_window_size);
40 config_.buffer_ending_downtrack = declare_parameter<double>("buffer_ending_downtrack", config_.buffer_ending_downtrack);
41 config_.max_accel = declare_parameter<double>("vehicle_acceleration_limit", config_.max_accel);
42 config_.lateral_accel_limit = declare_parameter<double>("vehicle_lateral_accel_limit", config_.lateral_accel_limit);
43 config_.enable_object_avoidance = declare_parameter<bool>("enable_object_avoidance", config_.enable_object_avoidance);
44 config_.tactical_plugin_service_call_timeout = declare_parameter<int>("tactical_plugin_service_call_timeout", config_.tactical_plugin_service_call_timeout);
45 }
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,...
TacticalPlugin base class which can be extended by user provided plugins which wish to implement the ...
Stuct containing the algorithm configuration values for the InLaneCruisingPlugin.

References InLaneCruisingPluginConfig::back_distance, InLaneCruisingPluginConfig::buffer_ending_downtrack, config_, InLaneCruisingPluginConfig::curvature_moving_average_window_size, InLaneCruisingPluginConfig::curve_resample_step_size, InLaneCruisingPluginConfig::default_downsample_ratio, InLaneCruisingPluginConfig::enable_object_avoidance, InLaneCruisingPluginConfig::lat_accel_multiplier, InLaneCruisingPluginConfig::lateral_accel_limit, InLaneCruisingPluginConfig::max_accel, InLaneCruisingPluginConfig::max_accel_multiplier, InLaneCruisingPluginConfig::minimum_speed, InLaneCruisingPluginConfig::speed_moving_average_window_size, InLaneCruisingPluginConfig::tactical_plugin_service_call_timeout, InLaneCruisingPluginConfig::trajectory_time_length, and InLaneCruisingPluginConfig::turn_downsample_ratio.

Member Function Documentation

◆ FRIEND_TEST()

inlanecruising_plugin::InLaneCruisingPluginNode::FRIEND_TEST ( InLaneCruisingPluginTest  ,
rostest1   
)
private

◆ get_availability()

bool inlanecruising_plugin::InLaneCruisingPluginNode::get_availability ( )
overridevirtual

Get the availability status of this plugin based on the current operating environment. Method must be overriden by extending classes.

Returns
This method should return true if the plugin's current understanding of the world means it would be capable of planning or executing its capability.

Implements carma_guidance_plugins::PluginBaseNode.

Definition at line 126 of file inlanecruising_plugin_node.cpp.

127 {
128 return true;
129 }

◆ get_version_id()

std::string inlanecruising_plugin::InLaneCruisingPluginNode::get_version_id ( )
finaloverridevirtual

Returns the version id of this plugin.

Returns
The version id represented as a string

Implements carma_guidance_plugins::PluginBaseNode.

Definition at line 131 of file inlanecruising_plugin_node.cpp.

132 {
133 return version_id_;
134 }

References version_id_.

◆ on_configure_plugin()

carma_ros2_utils::CallbackReturn inlanecruising_plugin::InLaneCruisingPluginNode::on_configure_plugin ( )
virtual

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.

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

Implements carma_guidance_plugins::PluginBaseNode.

Definition at line 47 of file inlanecruising_plugin_node.cpp.

48 {
49 trajectory_debug_pub_ = create_publisher<carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds>("debug/trajectory_planning", 1);
50
52
53 get_parameter<double>("trajectory_time_length", config_.trajectory_time_length);
54 get_parameter<double>("curve_resample_step_size", config_.curve_resample_step_size);
55 get_parameter<int>("default_downsample_ratio", config_.default_downsample_ratio);
56 get_parameter<int>("turn_downsample_ratio", config_.turn_downsample_ratio);
57 get_parameter<double>("minimum_speed", config_.minimum_speed);
58 get_parameter<double>("max_accel_multiplier", config_.max_accel_multiplier);
59 get_parameter<double>("lat_accel_multiplier", config_.lat_accel_multiplier);
60 get_parameter<double>("back_distance", config_.back_distance);
61 get_parameter<int>("speed_moving_average_window_size", config_.speed_moving_average_window_size);
62 get_parameter<int>("curvature_moving_average_window_size", config_.curvature_moving_average_window_size);
63 get_parameter<double>("buffer_ending_downtrack", config_.buffer_ending_downtrack);
64 get_parameter<double>("vehicle_acceleration_limit", config_.max_accel);
65 get_parameter<double>("vehicle_lateral_accel_limit", config_.lateral_accel_limit);
66 get_parameter<bool>("enable_object_avoidance", config_.enable_object_avoidance);
67 get_parameter<int>("tactical_plugin_service_call_timeout", config_.tactical_plugin_service_call_timeout);
68
69 // Register runtime parameter update callback
70 add_on_set_parameters_callback(std::bind(&InLaneCruisingPluginNode::parameter_update_callback, this, std_ph::_1));
71
72 RCLCPP_INFO_STREAM(rclcpp::get_logger("inlanecruising_plugin"), "InLaneCruisingPlugin Params" << config_);
73
76
77 // Determine if we will enable debug publishing by checking the current log level of the node
78 auto level = rcutils_logging_get_logger_level(get_logger().get_name());
79
80 config_.publish_debug = level == RCUTILS_LOG_SEVERITY_DEBUG;
81
82 RCLCPP_INFO_STREAM(rclcpp::get_logger("inlanecruising_plugin"), "InLaneCruisingPlugin Params After Accel Change" << config_);
83
84 worker_ = std::make_shared<InLaneCruisingPlugin>(shared_from_this(), get_world_model(), config_,
85 [this](const carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds& msg) { trajectory_debug_pub_->publish(msg); },
88
89 //TODO: Update yield client to use the Plugin Manager capabilities query, in case someone else wants to add an alternate yield implementation
90 yield_client_ = create_client<carma_planning_msgs::srv::PlanTrajectory>("yield_plugin/plan_trajectory");
91 worker_->set_yield_client(yield_client_);
92 RCLCPP_INFO(rclcpp::get_logger("inlanecruising_plugin"), "Yield Client Set");
93
94 // Return success if everything initialized successfully
95 return CallbackReturn::SUCCESS;
96
97 }
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::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > yield_client_
carma_ros2_utils::PubPtr< carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds > trajectory_debug_pub_
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)

References InLaneCruisingPluginConfig::back_distance, InLaneCruisingPluginConfig::buffer_ending_downtrack, config_, InLaneCruisingPluginConfig::curvature_moving_average_window_size, InLaneCruisingPluginConfig::curve_resample_step_size, InLaneCruisingPluginConfig::default_downsample_ratio, InLaneCruisingPluginConfig::enable_object_avoidance, carma_guidance_plugins::PluginBaseNode::get_world_model(), InLaneCruisingPluginConfig::lat_accel_multiplier, InLaneCruisingPluginConfig::lateral_accel_limit, InLaneCruisingPluginConfig::max_accel, InLaneCruisingPluginConfig::max_accel_multiplier, InLaneCruisingPluginConfig::minimum_speed, parameter_update_callback(), plugin_name_, InLaneCruisingPluginConfig::publish_debug, InLaneCruisingPluginConfig::speed_moving_average_window_size, InLaneCruisingPluginConfig::tactical_plugin_service_call_timeout, trajectory_debug_pub_, InLaneCruisingPluginConfig::trajectory_time_length, InLaneCruisingPluginConfig::turn_downsample_ratio, version_id_, worker_, and yield_client_.

Here is the call graph for this function:

◆ parameter_update_callback()

rcl_interfaces::msg::SetParametersResult inlanecruising_plugin::InLaneCruisingPluginNode::parameter_update_callback ( const std::vector< rclcpp::Parameter > &  parameters)

Definition at line 99 of file inlanecruising_plugin_node.cpp.

100 {
101 auto error_double = update_params<double>({
102 {"trajectory_time_length", config_.trajectory_time_length},
103 {"curve_resample_step_size", config_.curve_resample_step_size},
104 {"minimum_speed", config_.minimum_speed},
105 {"max_accel_multiplier", config_.max_accel_multiplier},
106 {"lat_accel_multiplier", config_.lat_accel_multiplier},
107 {"back_distance", config_.back_distance},
108 {"buffer_ending_downtrack", config_.buffer_ending_downtrack}}, parameters); // Global acceleration limits not allowed to dynamically update
109
110 auto error_bool = update_params<bool>({
111 {"enable_object_avoidance", config_.enable_object_avoidance}}, parameters);
112
113 auto error_int = update_params<int>({
114 {"default_downsample_ratio", config_.default_downsample_ratio},
115 {"turn_downsample_ratio", config_.turn_downsample_ratio},
116 {"speed_moving_average_window_size", config_.speed_moving_average_window_size},
117 {"curvature_moving_average_window_size", config_.curvature_moving_average_window_size}}, parameters);
118
119 rcl_interfaces::msg::SetParametersResult result;
120
121 result.successful = !error_double && !error_bool && !error_int;
122
123 return result;
124 }

References InLaneCruisingPluginConfig::back_distance, InLaneCruisingPluginConfig::buffer_ending_downtrack, config_, InLaneCruisingPluginConfig::curvature_moving_average_window_size, InLaneCruisingPluginConfig::curve_resample_step_size, InLaneCruisingPluginConfig::default_downsample_ratio, InLaneCruisingPluginConfig::enable_object_avoidance, InLaneCruisingPluginConfig::lat_accel_multiplier, InLaneCruisingPluginConfig::max_accel_multiplier, InLaneCruisingPluginConfig::minimum_speed, InLaneCruisingPluginConfig::speed_moving_average_window_size, InLaneCruisingPluginConfig::trajectory_time_length, and InLaneCruisingPluginConfig::turn_downsample_ratio.

Referenced by on_configure_plugin().

Here is the caller graph for this function:

◆ plan_trajectory_callback()

void inlanecruising_plugin::InLaneCruisingPluginNode::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 
)
overridevirtual

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 maneuvers to plan trajectories for and current vehicle state
respThe response containing the planned trajectory

Implements carma_guidance_plugins::TacticalPlugin.

Definition at line 136 of file inlanecruising_plugin_node.cpp.

140 {
141 worker_->plan_trajectory_callback(req, resp);
142 }

References worker_.

Member Data Documentation

◆ config_

InLaneCruisingPluginConfig inlanecruising_plugin::InLaneCruisingPluginNode::config_
private

◆ plugin_name_

std::string inlanecruising_plugin::InLaneCruisingPluginNode::plugin_name_
private

Definition at line 67 of file inlanecruising_plugin_node.hpp.

Referenced by on_configure_plugin().

◆ trajectory_debug_pub_

carma_ros2_utils::PubPtr<carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds> inlanecruising_plugin::InLaneCruisingPluginNode::trajectory_debug_pub_
private

Definition at line 70 of file inlanecruising_plugin_node.hpp.

Referenced by on_configure_plugin().

◆ version_id_

std::string inlanecruising_plugin::InLaneCruisingPluginNode::version_id_
private

Definition at line 68 of file inlanecruising_plugin_node.hpp.

Referenced by get_version_id(), and on_configure_plugin().

◆ worker_

std::shared_ptr<InLaneCruisingPlugin> inlanecruising_plugin::InLaneCruisingPluginNode::worker_
private

Definition at line 76 of file inlanecruising_plugin_node.hpp.

Referenced by on_configure_plugin(), and plan_trajectory_callback().

◆ yield_client_

carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> inlanecruising_plugin::InLaneCruisingPluginNode::yield_client_
private

Definition at line 73 of file inlanecruising_plugin_node.hpp.

Referenced by on_configure_plugin().


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