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.
light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode Class Reference

ROS node for the LightControlledIntersectionTransitPluginNode. More...

#include <light_controlled_intersection_tactical_plugin_node.hpp>

Inheritance diagram for light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode:
Inheritance graph
Collaboration diagram for light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode:
Collaboration graph

Public Member Functions

 LightControlledIntersectionTransitPluginNode (const rclcpp::NodeOptions &)
 LightControlledIntersectionTransitPluginNode constructor. More...
 
rcl_interfaces::msg::SetParametersResult parameter_update_callback (const std::vector< rclcpp::Parameter > &parameters)
 Callback for dynamic parameter updates. More...
 
void plan_trajectory_callback (std::shared_ptr< rmw_request_id_t >, 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
 Returns the version id of this plugin. More...
 
carma_ros2_utils::CallbackReturn on_configure_plugin () override
 This method should be used to load parameters and will be called on the configure state transition. 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 Attributes

Config config_
 
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > yield_client_
 
std::shared_ptr< LightControlledIntersectionTacticalPluginworker_
 

Detailed Description

Constructor & Destructor Documentation

◆ LightControlledIntersectionTransitPluginNode()

light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode::LightControlledIntersectionTransitPluginNode ( const rclcpp::NodeOptions &  options)
explicit

LightControlledIntersectionTransitPluginNode constructor.

Definition at line 22 of file light_controlled_intersection_tactical_plugin_node.cpp.

24 {
25 // Create initial config
26 config_ = Config();
27
28 // Declare parameters
29 config_.centerline_sampling_spacing = declare_parameter<double>("centerline_sampling_spacing", config_.centerline_sampling_spacing);
30 config_.trajectory_time_length = declare_parameter<double>("trajectory_time_length", config_.trajectory_time_length);
31 config_.default_downsample_ratio = declare_parameter<int>("default_downsample_ratio", config_.default_downsample_ratio);
32 config_.turn_downsample_ratio = declare_parameter<int>("turn_downsample_ratio", config_.turn_downsample_ratio);
33 config_.curve_resample_step_size = declare_parameter<double>("curve_resample_step_size", config_.curve_resample_step_size);
34 config_.curvature_moving_average_window_size = declare_parameter<int>("curvature_moving_average_window_size", config_.curvature_moving_average_window_size);
35 config_.speed_moving_average_window_size = declare_parameter<int>("speed_moving_average_window_size", config_.speed_moving_average_window_size);
36 config_.back_distance = declare_parameter<double>("back_distance", config_.back_distance);
37 config_.buffer_ending_downtrack = declare_parameter<double>("buffer_ending_downtrack", config_.buffer_ending_downtrack);
38 config_.vehicle_decel_limit_multiplier = declare_parameter<double>("vehicle_decel_limit_multiplier", config_.vehicle_decel_limit_multiplier);
39 config_.vehicle_accel_limit_multiplier = declare_parameter<double>("vehicle_accel_limit_multiplier", config_.vehicle_accel_limit_multiplier);
40 config_.lat_accel_multiplier = declare_parameter<double>("lat_accel_multiplier", config_.lat_accel_multiplier);
41 config_.stop_line_buffer = declare_parameter<double>("stop_line_buffer", config_.stop_line_buffer);
42 config_.minimum_speed = declare_parameter<double>("minimum_speed", config_.minimum_speed);
43 config_.algorithm_evaluation_distance = declare_parameter<double>("algorithm_evaluation_distance", config_.algorithm_evaluation_distance);
44 config_.algorithm_evaluation_period = declare_parameter<double>("algorithm_evaluation_period", config_.algorithm_evaluation_period);
45
46 config_.lateral_accel_limit = declare_parameter<double>("vehicle_lateral_accel_limit", config_.lateral_accel_limit);
47 config_.vehicle_accel_limit = declare_parameter<double>("vehicle_acceleration_limit", config_.vehicle_accel_limit);
48 config_.vehicle_decel_limit = declare_parameter<double>("vehicle_deceleration_limit", config_.vehicle_decel_limit);
49 config_.tactical_plugin_service_call_timeout = declare_parameter<int>("tactical_plugin_service_call_timeout", config_.tactical_plugin_service_call_timeout);
50 config_.enable_object_avoidance = declare_parameter<bool>("enable_object_avoidance", config_.enable_object_avoidance);
51
52 }
TacticalPlugin base class which can be extended by user provided plugins which wish to implement the ...

References light_controlled_intersection_tactical_plugin::Config::algorithm_evaluation_distance, light_controlled_intersection_tactical_plugin::Config::algorithm_evaluation_period, light_controlled_intersection_tactical_plugin::Config::back_distance, light_controlled_intersection_tactical_plugin::Config::buffer_ending_downtrack, light_controlled_intersection_tactical_plugin::Config::centerline_sampling_spacing, config_, light_controlled_intersection_tactical_plugin::Config::curvature_moving_average_window_size, light_controlled_intersection_tactical_plugin::Config::curve_resample_step_size, light_controlled_intersection_tactical_plugin::Config::default_downsample_ratio, light_controlled_intersection_tactical_plugin::Config::enable_object_avoidance, light_controlled_intersection_tactical_plugin::Config::lat_accel_multiplier, light_controlled_intersection_tactical_plugin::Config::lateral_accel_limit, light_controlled_intersection_tactical_plugin::Config::minimum_speed, light_controlled_intersection_tactical_plugin::Config::speed_moving_average_window_size, light_controlled_intersection_tactical_plugin::Config::stop_line_buffer, light_controlled_intersection_tactical_plugin::Config::tactical_plugin_service_call_timeout, light_controlled_intersection_tactical_plugin::Config::trajectory_time_length, light_controlled_intersection_tactical_plugin::Config::turn_downsample_ratio, light_controlled_intersection_tactical_plugin::Config::vehicle_accel_limit, light_controlled_intersection_tactical_plugin::Config::vehicle_accel_limit_multiplier, light_controlled_intersection_tactical_plugin::Config::vehicle_decel_limit, and light_controlled_intersection_tactical_plugin::Config::vehicle_decel_limit_multiplier.

Member Function Documentation

◆ get_availability()

bool light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode::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 138 of file light_controlled_intersection_tactical_plugin_node.cpp.

138 {
139 return true;
140 }

◆ get_version_id()

std::string light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode::get_version_id ( )
overridevirtual

Returns the version id of this plugin.

Returns
The version id represented as a string

Implements carma_guidance_plugins::PluginBaseNode.

Definition at line 142 of file light_controlled_intersection_tactical_plugin_node.cpp.

142 {
143 return "v4.0"; // Version ID matches the value set in this package's package.xml
144 }

◆ on_configure_plugin()

carma_ros2_utils::CallbackReturn light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode::on_configure_plugin ( )
overridevirtual

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 87 of file light_controlled_intersection_tactical_plugin_node.cpp.

88 {
89 RCLCPP_INFO_STREAM(rclcpp::get_logger("light_controlled_intersection_tactical_plugin"), "LightControlledIntersectionTransitPluginNode trying to configure");
90
91 // Reset config
92 config_ = Config();
93
94 // Load parameters
95 get_parameter<double>("centerline_sampling_spacing", config_.centerline_sampling_spacing);
96 get_parameter<double>("trajectory_time_length", config_.trajectory_time_length);
97 get_parameter<int>("default_downsample_ratio", config_.default_downsample_ratio);
98 get_parameter<int>("turn_downsample_ratio", config_.turn_downsample_ratio);
99 get_parameter<double>("curve_resample_step_size", config_.curve_resample_step_size);
100 get_parameter<int>("curvature_moving_average_window_size", config_.curvature_moving_average_window_size);
101 get_parameter<int>("speed_moving_average_window_size", config_.speed_moving_average_window_size);
102 get_parameter<double>("back_distance", config_.back_distance);
103 get_parameter<double>("buffer_ending_downtrack", config_.buffer_ending_downtrack);
104 get_parameter<double>("vehicle_decel_limit_multiplier", config_.vehicle_decel_limit_multiplier);
105 get_parameter<double>("vehicle_accel_limit_multiplier", config_.vehicle_accel_limit_multiplier);
106 get_parameter<double>("lat_accel_multiplier", config_.lat_accel_multiplier);
107 get_parameter<double>("stop_line_buffer", config_.stop_line_buffer);
108 get_parameter<double>("minimum_speed", config_.minimum_speed);
109 get_parameter<double>("algorithm_evaluation_distance", config_.algorithm_evaluation_distance);
110 get_parameter<double>("algorithm_evaluation_period", config_.algorithm_evaluation_period);
111 get_parameter<double>("vehicle_lateral_accel_limit", config_.lateral_accel_limit);
112 get_parameter<double>("vehicle_acceleration_limit", config_.vehicle_accel_limit);
113 get_parameter<double>("vehicle_deceleration_limit", config_.vehicle_decel_limit);
114 get_parameter<int>("tactical_plugin_service_call_timeout", config_.tactical_plugin_service_call_timeout);
115 get_parameter<bool>("enable_object_avoidance", config_.enable_object_avoidance);
116
117 // Use the configured multipliers to update the accel limits
121
122 // Register runtime parameter update callback
123 add_on_set_parameters_callback(std::bind(&LightControlledIntersectionTransitPluginNode::parameter_update_callback, this, std_ph::_1));
124
125 RCLCPP_INFO_STREAM(rclcpp::get_logger("light_controlled_intersection_tactical_plugin"), "Loaded params: " << config_);
126
127 // Initialize worker object
128 worker_ = std::make_shared<LightControlledIntersectionTacticalPlugin>(get_world_model(), config_, get_plugin_name(), shared_from_this());
129
130 yield_client_ = create_client<carma_planning_msgs::srv::PlanTrajectory>("yield_plugin/plan_trajectory");
131 worker_->set_yield_client(yield_client_);
132 RCLCPP_INFO(rclcpp::get_logger("light_controlled_intersection_tactical_plugin"), "Yield Client Set");
133
134 // Return success if everything initialized successfully
135 return CallbackReturn::SUCCESS;
136 }
std::string get_plugin_name() const
Return the name of this plugin.
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...
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Callback for dynamic parameter updates.

References light_controlled_intersection_tactical_plugin::Config::algorithm_evaluation_distance, light_controlled_intersection_tactical_plugin::Config::algorithm_evaluation_period, light_controlled_intersection_tactical_plugin::Config::back_distance, light_controlled_intersection_tactical_plugin::Config::buffer_ending_downtrack, light_controlled_intersection_tactical_plugin::Config::centerline_sampling_spacing, config_, light_controlled_intersection_tactical_plugin::Config::curvature_moving_average_window_size, light_controlled_intersection_tactical_plugin::Config::curve_resample_step_size, light_controlled_intersection_tactical_plugin::Config::default_downsample_ratio, light_controlled_intersection_tactical_plugin::Config::enable_object_avoidance, carma_guidance_plugins::PluginBaseNode::get_plugin_name(), carma_guidance_plugins::PluginBaseNode::get_world_model(), light_controlled_intersection_tactical_plugin::Config::lat_accel_multiplier, light_controlled_intersection_tactical_plugin::Config::lateral_accel_limit, light_controlled_intersection_tactical_plugin::Config::minimum_speed, parameter_update_callback(), light_controlled_intersection_tactical_plugin::Config::speed_moving_average_window_size, light_controlled_intersection_tactical_plugin::Config::stop_line_buffer, light_controlled_intersection_tactical_plugin::Config::tactical_plugin_service_call_timeout, light_controlled_intersection_tactical_plugin::Config::trajectory_time_length, light_controlled_intersection_tactical_plugin::Config::turn_downsample_ratio, light_controlled_intersection_tactical_plugin::Config::vehicle_accel_limit, light_controlled_intersection_tactical_plugin::Config::vehicle_accel_limit_multiplier, light_controlled_intersection_tactical_plugin::Config::vehicle_decel_limit, light_controlled_intersection_tactical_plugin::Config::vehicle_decel_limit_multiplier, worker_, and yield_client_.

Here is the call graph for this function:

◆ parameter_update_callback()

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

Callback for dynamic parameter updates.

Definition at line 54 of file light_controlled_intersection_tactical_plugin_node.cpp.

55 {
56 auto error = update_params<double>(
57 {{"centerline_sampling_spacing", config_.centerline_sampling_spacing},
58 {"trajectory_time_length", config_.trajectory_time_length},
59 {"curve_resample_step_size", config_.curve_resample_step_size},
60 {"back_distance", config_.back_distance},
61 {"buffer_ending_downtrack", config_.buffer_ending_downtrack},
62 {"vehicle_decel_limit_multiplier", config_.vehicle_decel_limit_multiplier},
63 {"vehicle_accel_limit_multiplier", config_.vehicle_accel_limit_multiplier},
64 {"lat_accel_multiplier", config_.lat_accel_multiplier},
65 {"stop_line_buffer", config_.stop_line_buffer},
66 {"minimum_speed", config_.minimum_speed},
67 {"algorithm_evaluation_distance", config_.algorithm_evaluation_distance},
68 {"algorithm_evaluation_period", config_.algorithm_evaluation_period}}, parameters); // Global acceleration limits not allowed to dynamically update
69 auto error_2 = update_params<int>(
70 {{"default_downsample_ratio", config_.default_downsample_ratio},
71 {"turn_downsample_ratio", config_.turn_downsample_ratio},
72 {"curvature_moving_average_window_size", config_.curvature_moving_average_window_size},
73 {"speed_moving_average_window_size", config_.speed_moving_average_window_size}}, parameters);
74
75 if (worker_)
76 {
77 worker_->setConfig(config_);
78 }
79
80 rcl_interfaces::msg::SetParametersResult result;
81
82 result.successful = !error && !error_2;
83
84 return result;
85 }

References light_controlled_intersection_tactical_plugin::Config::algorithm_evaluation_distance, light_controlled_intersection_tactical_plugin::Config::algorithm_evaluation_period, light_controlled_intersection_tactical_plugin::Config::back_distance, light_controlled_intersection_tactical_plugin::Config::buffer_ending_downtrack, light_controlled_intersection_tactical_plugin::Config::centerline_sampling_spacing, config_, light_controlled_intersection_tactical_plugin::Config::curvature_moving_average_window_size, light_controlled_intersection_tactical_plugin::Config::curve_resample_step_size, light_controlled_intersection_tactical_plugin::Config::default_downsample_ratio, light_controlled_intersection_tactical_plugin::Config::lat_accel_multiplier, light_controlled_intersection_tactical_plugin::Config::minimum_speed, light_controlled_intersection_tactical_plugin::Config::speed_moving_average_window_size, light_controlled_intersection_tactical_plugin::Config::stop_line_buffer, light_controlled_intersection_tactical_plugin::Config::trajectory_time_length, light_controlled_intersection_tactical_plugin::Config::turn_downsample_ratio, light_controlled_intersection_tactical_plugin::Config::vehicle_accel_limit_multiplier, light_controlled_intersection_tactical_plugin::Config::vehicle_decel_limit_multiplier, and worker_.

Referenced by on_configure_plugin().

Here is the caller graph for this function:

◆ plan_trajectory_callback()

void light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode::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 146 of file light_controlled_intersection_tactical_plugin_node.cpp.

150 {
151 worker_->planTrajectoryCB(req, resp);
152 }

References worker_.

Member Data Documentation

◆ config_

Config light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode::config_
private

◆ worker_

std::shared_ptr<LightControlledIntersectionTacticalPlugin> light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode::worker_
private

◆ yield_client_

carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> light_controlled_intersection_tactical_plugin::LightControlledIntersectionTransitPluginNode::yield_client_
private

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