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.
stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin Class Reference

Class containing primary business logic for the Stop Controlled Intersection Tactical Plugin. More...

#include <stop_controlled_intersection_plugin.hpp>

Inheritance diagram for stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin:
Inheritance graph
Collaboration diagram for stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin:
Collaboration graph

Public Member Functions

 StopControlledIntersectionTacticalPlugin (const rclcpp::NodeOptions &options)
 
std::vector< PointSpeedPairmaneuvers_to_points (const std::vector< carma_planning_msgs::msg::Maneuver > &maneuvers, const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::VehicleState &state)
 Converts a set of requested stop controlled intersection maneuvers to point speed limit pairs. More...
 
std::vector< PointSpeedPaircreate_case_one_speed_profile (const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::Maneuver &maneuver, std::vector< lanelet::BasicPoint2d > &route_geometry_points, double starting_speed, const carma_planning_msgs::msg::VehicleState &states)
 Creates a speed profile according to case one of the stop controlled intersection, where the vehicle accelerates and then decelerates to a stop. More...
 
std::vector< PointSpeedPaircreate_case_two_speed_profile (const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::Maneuver &maneuver, std::vector< lanelet::BasicPoint2d > &route_geometry_points, double starting_speed)
 Creates a speed profile according to case two of the stop controlled intersection, where the vehicle first accelerates then cruises and finally decelerates to a stop. More...
 
std::vector< PointSpeedPaircreate_case_three_speed_profile (const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::Maneuver &maneuver, std::vector< lanelet::BasicPoint2d > &route_geometry_points, double starting_speed)
 Creates a speed profile according to case three of the stop controlled intersection, where the vehicle continuously decelerates to a stop. More...
 
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > compose_trajectory_from_centerline (const std::vector< PointSpeedPair > &points, const carma_planning_msgs::msg::VehicleState &state, const rclcpp::Time &state_time)
 Method converts a list of lanelet centerline points and current vehicle state into a usable list of trajectory points for trajectory planning. More...
 
carma_ros2_utils::CallbackReturn on_configure_plugin () override
 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 ()
 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 ()
 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 >, 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 (StopControlledIntersectionTacticalPlugin, TestSCIPlanning_case_one)
 
 FRIEND_TEST (StopControlledIntersectionTacticalPlugin, TestSCIPlanning_case_two)
 
 FRIEND_TEST (StopControlledIntersectionTacticalPlugin, TestSCIPlanning_case_three)
 

Private Attributes

carma_wm::WorldModelConstPtr wm_
 
StopControlledIntersectionTacticalPluginConfig config_
 
std::string stop_controlled_intersection_strategy_ = "Carma/stop_controlled_intersection"
 
double epsilon_ = 0.001
 

Detailed Description

Class containing primary business logic for the Stop Controlled Intersection Tactical Plugin.

Definition at line 63 of file stop_controlled_intersection_plugin.hpp.

Constructor & Destructor Documentation

◆ StopControlledIntersectionTacticalPlugin()

stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::StopControlledIntersectionTacticalPlugin ( const rclcpp::NodeOptions &  options)
explicit

Definition at line 51 of file stop_controlled_intersection_tactical_plugin.cpp.

52 : carma_guidance_plugins::TacticalPlugin(options), config_(StopControlledIntersectionTacticalPluginConfig())
53{
54 // Declare parameters
55 config_.trajectory_time_length = declare_parameter<double>("trajectory_time_length", config_.trajectory_time_length);
56 config_.curve_resample_step_size = declare_parameter<double>("curve_resample_step_size", config_.curve_resample_step_size);
57 config_.centerline_sampling_spacing = declare_parameter<double>("centerline_sampling_spacing", config_.centerline_sampling_spacing);
58 config_.curvature_moving_average_window_size = declare_parameter<int>("curvature_moving_average_window_size", config_.curvature_moving_average_window_size);
59 config_.lateral_accel_limit = declare_parameter<double>("lateral_accel_limit", config_.lateral_accel_limit);
60 config_.speed_moving_average_window_size = declare_parameter<int>("speed_moving_average_window_size", config_.speed_moving_average_window_size);
61 config_.back_distance = declare_parameter<double>("back_distance", config_.back_distance);
62}
TacticalPlugin base class which can be extended by user provided plugins which wish to implement the ...

References stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::back_distance, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::centerline_sampling_spacing, config_, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::curvature_moving_average_window_size, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::curve_resample_step_size, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::lateral_accel_limit, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::speed_moving_average_window_size, and stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::trajectory_time_length.

Member Function Documentation

◆ compose_trajectory_from_centerline()

std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::compose_trajectory_from_centerline ( const std::vector< PointSpeedPair > &  points,
const carma_planning_msgs::msg::VehicleState &  state,
const rclcpp::Time &  state_time 
)

Method converts a list of lanelet centerline points and current vehicle state into a usable list of trajectory points for trajectory planning.

Parameters
pointsThe set of points that define the current lane the vehicle is in and are defined based on the request planning maneuvers. These points must be in the same lane as the vehicle and must extend in front of it though it is fine if they also extend behind it.
stateThe current state of the vehicle
state_timeThe abosolute time which the provided vehicle state corresponds to
Returns
A list of trajectory points to send to the carma planning stack

Definition at line 477 of file stop_controlled_intersection_tactical_plugin.cpp.

478 {
479
480 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> trajectory;
481 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "VehicleState: "
482 << " x: " << state.x_pos_global << " y: " << state.y_pos_global << " yaw: " << state.orientation
483 << " speed: " << state.longitudinal_vel);
484
485 int nearest_pt_index = basic_autonomy::waypoint_generation::get_nearest_point_index(points, state);
486 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Nearest pt index: "<<nearest_pt_index);
487 std::vector<PointSpeedPair> future_points(points.begin() + nearest_pt_index + 1, points.end()); //Points in front of current vehicle position
488 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Future points size: "<<future_points.size());
490 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Got time bound points with size:" << time_bound_points.size());
491
492 //Attach past points
493 std::vector<PointSpeedPair> back_and_future = attach_past_points(points, time_bound_points, nearest_pt_index, config_.back_distance);
494 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Got back_and_future points with size: "<<back_and_future.size());
495
496 std::vector<double> speed_limits;
497 std::vector<lanelet::BasicPoint2d> curve_points;
498 split_point_speed_pairs(time_bound_points, &curve_points, &speed_limits);
499
500 std::unique_ptr<basic_autonomy::smoothing::SplineI> fit_curve = basic_autonomy::waypoint_generation::compute_fit(curve_points); //Compute splines based on curve points
501 if(!fit_curve)
502 {
503 throw std::invalid_argument("Could not fit a spline curve along the trajectory!");
504 }
505
506 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Got fit");
507 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Speed_limits.size(): "<<speed_limits.size());
508
509 std::vector<lanelet::BasicPoint2d> all_sampling_points;
510 all_sampling_points.reserve(1 + curve_points.size() * 2);
511
512 std::vector<double> distributed_speed_limits;
513 distributed_speed_limits.reserve(1+ curve_points.size() * 2);
514
515 //Compute total length of the trajectory to get correct number of points
516 // we expect using curve resample step size
517 std::vector<double> downtracks_raw = carma_wm::geometry::compute_arc_lengths(curve_points);
518
519 auto total_step_along_curve = static_cast<int>(downtracks_raw.back() / config_.curve_resample_step_size);
520
521 int current_speed_index = 0;
522 size_t total_point_size = curve_points.size();
523
524 double step_threshold_for_next_speed = (double)total_step_along_curve / (double)total_point_size;
525 double scaled_steps_along_curve = 0.0; // from 0 (start) to 1 (end) for the whole trajectory
526 std::vector<double> better_curvature;
527 better_curvature.reserve(1 + curve_points.size() * 2);
528
529 for (size_t steps_along_curve = 0; steps_along_curve < total_step_along_curve; steps_along_curve++) // Resample curve at tighter resolution
530 {
531 lanelet::BasicPoint2d p = (*fit_curve)(scaled_steps_along_curve);
532 all_sampling_points.push_back(p);
533 double c = basic_autonomy::waypoint_generation::compute_curvature_at((*fit_curve), scaled_steps_along_curve);
534 better_curvature.push_back(c);
535
536 if((double) steps_along_curve > step_threshold_for_next_speed)
537 {
538 step_threshold_for_next_speed += (double)total_step_along_curve / (double)total_point_size;
539 current_speed_index++;
540 }
541 distributed_speed_limits.push_back(speed_limits[current_speed_index]); //Identify speed limits for resampled points
542 scaled_steps_along_curve += 1.0 / total_step_along_curve; //adding steps_along_curve_step_size
543 }
544
545 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Got sampled points with size:" << all_sampling_points.size());
546
547 std::vector<double> final_yaw_values = carma_wm::geometry::compute_tangent_orientations(all_sampling_points);
548
549 std::vector<double> curvatures = basic_autonomy::smoothing::moving_average_filter(better_curvature, config_.curvature_moving_average_window_size, false);
550 std::vector<double> ideal_speeds =
551 trajectory_utils::constrained_speeds_for_curvatures(curvatures, config_.lateral_accel_limit);
552
553 std::vector<double> constrained_speed_limits = basic_autonomy::waypoint_generation::apply_speed_limits(ideal_speeds, distributed_speed_limits); //Speed min(ideal, calculated)
554 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Processed all points in computed fit");
555 std::vector<double> final_actual_speeds = constrained_speed_limits;
556
557 if (all_sampling_points.empty())
558 {
559 RCLCPP_WARN_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "No trajectory points could be generated");
560 return {};
561 }
562
563 //Drop Past points
564 nearest_pt_index = basic_autonomy::waypoint_generation::get_nearest_index_by_downtrack(all_sampling_points, wm_, state);
565 std::vector<lanelet::BasicPoint2d> future_basic_points(all_sampling_points.begin() + nearest_pt_index + 1,
566 all_sampling_points.end());
567 std::vector<double> future_speeds(final_actual_speeds.begin() + nearest_pt_index + 1,
568 final_actual_speeds.end());
569 std::vector<double> future_yaw(final_yaw_values.begin() + nearest_pt_index + 1,
570 final_yaw_values.end());
571
572 // Add current vehicle point to front of the trajectory
573 lanelet::BasicPoint2d cur_veh_point(state.x_pos_global, state.y_pos_global);
574
575 future_basic_points.insert(future_basic_points.begin(),
576 cur_veh_point); // Add current vehicle position to front of sample points
577 future_speeds.insert(future_speeds.begin(), state.longitudinal_vel);
578 future_yaw.insert(future_yaw.begin(), state.orientation);
579
580 // Compute points to local downtracks
581 std::vector<double> downtracks = carma_wm::geometry::compute_arc_lengths(future_basic_points);
582
584
585 // Convert speeds to times
586 std::vector<double> times;
587
588 //Force last point speed to 0.0 if close to end
589 if(lanelet::geometry::distance2d(future_basic_points.back(), points.back().point) < epsilon_){
590 final_actual_speeds.back() = 0.0;
591 }
592
593 trajectory_utils::conversions::speed_to_time(downtracks, final_actual_speeds, &times);
594
595 // Build trajectory points
596 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> traj_points =
597 basic_autonomy::waypoint_generation::trajectory_from_points_times_orientations(future_basic_points, times, future_yaw, state_time, "default");
598
599 return traj_points;
600}
std::vector< double > moving_average_filter(const std::vector< double > input, int window_size, bool ignore_first_point=true)
Extremely simplie moving average filter.
Definition: filters.cpp:24
void split_point_speed_pairs(const std::vector< PointSpeedPair > &points, std::vector< lanelet::BasicPoint2d > *basic_points, std::vector< double > *speeds)
Helper method to split a list of PointSpeedPair into separate point and speed lists.
int get_nearest_point_index(const std::vector< lanelet::BasicPoint2d > &points, const carma_planning_msgs::msg::VehicleState &state)
Returns the nearest point (in terms of cartesian 2d distance) to the provided vehicle pose in the pro...
std::unique_ptr< basic_autonomy::smoothing::SplineI > compute_fit(const std::vector< lanelet::BasicPoint2d > &basic_points)
Computes a spline based on the provided points.
int get_nearest_index_by_downtrack(const std::vector< lanelet::BasicPoint2d > &points, const carma_wm::WorldModelConstPtr &wm, double target_downtrack)
Returns the nearest "less than" point to the provided vehicle pose in the provided list by utilizing ...
std::vector< double > apply_speed_limits(const std::vector< double > speeds, const std::vector< double > speed_limits)
Applies the provided speed limits to the provided speeds such that each element is capped at its corr...
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > trajectory_from_points_times_orientations(const std::vector< lanelet::BasicPoint2d > &points, const std::vector< double > &times, const std::vector< double > &yaws, rclcpp::Time startTime, const std::string &desired_controller_plugin)
Method combines input points, times, orientations, and an absolute start time to form a valid carma p...
double compute_curvature_at(const basic_autonomy::smoothing::SplineI &fit_curve, double step_along_the_curve)
Given the curvature fit, computes the curvature at the given step along the curve.
std::vector< PointSpeedPair > constrain_to_time_boundary(const std::vector< PointSpeedPair > &points, double time_span)
Reduces the input points to only those points that fit within the provided time boundary.
std::vector< PointSpeedPair > attach_past_points(const std::vector< PointSpeedPair > &points_set, std::vector< PointSpeedPair > future_points, const int nearest_pt_index, double back_distance)
Attaches back_distance length of points behind the future points.
std::vector< double > compute_tangent_orientations(const lanelet::BasicLineString2d &centerline)
Compute an approximate orientation for the vehicle at each point along the provided centerline.
Definition: Geometry.cpp:559
std::vector< double > compute_arc_lengths(const std::vector< lanelet::BasicPoint2d > &data)
Compute the arc length at each point around the curve.
Definition: Geometry.cpp:498

References basic_autonomy::waypoint_generation::apply_speed_limits(), basic_autonomy::waypoint_generation::attach_past_points(), stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::back_distance, process_traj_logs::c, carma_wm::geometry::compute_arc_lengths(), basic_autonomy::waypoint_generation::compute_curvature_at(), basic_autonomy::waypoint_generation::compute_fit(), carma_wm::geometry::compute_tangent_orientations(), config_, basic_autonomy::waypoint_generation::constrain_to_time_boundary(), stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::curvature_moving_average_window_size, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::curve_resample_step_size, epsilon_, basic_autonomy::waypoint_generation::get_nearest_index_by_downtrack(), basic_autonomy::waypoint_generation::get_nearest_point_index(), stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::lateral_accel_limit, basic_autonomy::smoothing::moving_average_filter(), stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::speed_moving_average_window_size, basic_autonomy::waypoint_generation::split_point_speed_pairs(), basic_autonomy::waypoint_generation::trajectory_from_points_times_orientations(), stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::trajectory_time_length, and wm_.

Referenced by plan_trajectory_callback().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ create_case_one_speed_profile()

std::vector< PointSpeedPair > stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::create_case_one_speed_profile ( const carma_wm::WorldModelConstPtr wm,
const carma_planning_msgs::msg::Maneuver &  maneuver,
std::vector< lanelet::BasicPoint2d > &  route_geometry_points,
double  starting_speed,
const carma_planning_msgs::msg::VehicleState &  states 
)

Creates a speed profile according to case one of the stop controlled intersection, where the vehicle accelerates and then decelerates to a stop.

Parameters
wmPointer to intialized world model for semantic map access
maneuversThe maneuver to being planned for. Maneuver meta-dara parameters are used to create the trajectory profile.
route_geometry_pointsThe geometry points along the route which are associated with a speed in this method.
starting_speedThe current speed of the vehicle at the time of the trajectory planning request
Returns
List of centerline points paired with target speeds

Definition at line 232 of file stop_controlled_intersection_tactical_plugin.cpp.

233 {
234
235 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Planning for Case One");
236 //Derive meta data values from maneuver message - Using order in sci_strategic_plugin
237 double a_acc = GET_MANEUVER_PROPERTY(maneuver, parameters.float_valued_meta_data[0]);
238 double a_dec = GET_MANEUVER_PROPERTY(maneuver, parameters.float_valued_meta_data[1]); //a_dec is a -ve value
239 double t_acc = GET_MANEUVER_PROPERTY(maneuver, parameters.float_valued_meta_data[2]);
240 double t_dec = GET_MANEUVER_PROPERTY(maneuver, parameters.float_valued_meta_data[3]);
241 double speed_before_decel = GET_MANEUVER_PROPERTY(maneuver, parameters.float_valued_meta_data[4]);
242 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "a_acc received: "<< a_acc);
243 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "a_dec received: "<< a_dec);
244 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "t_acc received: "<< t_acc);
245 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "t_dec received: "<< t_dec);
246 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "speed before decel received: "<< speed_before_decel);
247
248 //Derive start and end dist from maneuver
249 double start_dist = GET_MANEUVER_PROPERTY(maneuver, start_dist);
250 double end_dist = GET_MANEUVER_PROPERTY(maneuver, end_dist);
251
252 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Maneuver starting downtrack: "<< start_dist);
253 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Maneuver ending downtrack: "<< end_dist);
254 //Checking state against start_dist and adjust profile
255 lanelet::BasicPoint2d state_point(state.x_pos_global, state.y_pos_global);
256 double route_starting_downtrack = wm->routeTrackPos(state_point).downtrack; //Starting downtrack based on geometry points
257 double dist_acc; //Distance for which acceleration lasts
258
259 if(route_starting_downtrack < start_dist){
260 //Update parameters
261 //Keeping the deceleration part the same
262 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Starting distance is less than maneuver start, updating parameters");
263 double dist_decel = pow(speed_before_decel, 2)/(2*std::abs(a_dec));
264
265 dist_acc = end_dist - dist_decel;
266 a_acc = (pow(speed_before_decel, 2) - pow(starting_speed,2))/(2*dist_acc);
267 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Updated a_acc: "<< a_acc);
268 }
269 else{
270 //Use parameters from maneuver message
271 dist_acc = (pow(speed_before_decel, 2) - pow(starting_speed, 2))/(2*a_acc);
272 }
273
274 std::vector<PointSpeedPair> points_and_target_speeds;
276 first_point.point = state_point;
277 first_point.speed = starting_speed;
278 points_and_target_speeds.push_back(first_point);
279
280 lanelet::BasicPoint2d prev_point = state_point;
281 double total_dist_covered = 0; //Starting dist for maneuver treated as 0.0
282
283 for(size_t i = 1; i < route_geometry_points.size(); i++){
284 lanelet::BasicPoint2d current_point = route_geometry_points[i];
285 double delta_d = lanelet::geometry::distance2d(prev_point, current_point);
286 total_dist_covered += delta_d;
287 //Find speed at dist covered
288 double speed_i;
289 if(total_dist_covered <= dist_acc){
290 //Acceleration part
291 speed_i = sqrt(pow(starting_speed,2) + 2*a_acc*total_dist_covered);
292 }
293 else{
294 //Deceleration part
295 speed_i = sqrt(std::max(pow(speed_before_decel,2) + 2*a_dec*(total_dist_covered - dist_acc),0.0)); //std::max to ensure negative value is not sqrt
296 if(speed_i < epsilon_){
297 speed_i = 0.0;
298 }
299 }
300
302 if(speed_i < epsilon_){
303 p.point = prev_point;
304 p.speed = 0.0;
305 }
306 else{
307 p.point = route_geometry_points[i];
308 p.speed = speed_i;
309 prev_point = current_point; //Advance prev point if speed changes
310 }
311 points_and_target_speeds.push_back(p);
312
313 }
314
315 return points_and_target_speeds;
316
317}
#define GET_MANEUVER_PROPERTY(mvr, property)
Macro definition to enable easier access to fields shared across the maneuver types.
list first_point
Definition: process_bag.py:52
basic_autonomy::waypoint_generation::PointSpeedPair PointSpeedPair

References epsilon_, process_bag::first_point, GET_MANEUVER_PROPERTY, process_bag::i, basic_autonomy::waypoint_generation::PointSpeedPair::point, and basic_autonomy::waypoint_generation::PointSpeedPair::speed.

Referenced by maneuvers_to_points().

Here is the caller graph for this function:

◆ create_case_three_speed_profile()

std::vector< PointSpeedPair > stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::create_case_three_speed_profile ( const carma_wm::WorldModelConstPtr wm,
const carma_planning_msgs::msg::Maneuver &  maneuver,
std::vector< lanelet::BasicPoint2d > &  route_geometry_points,
double  starting_speed 
)

Creates a speed profile according to case three of the stop controlled intersection, where the vehicle continuously decelerates to a stop.

Parameters
wmPointer to intialized world model for semantic map access
maneuversThe maneuver to being planned for. Maneuver meta-dara parameters are used to create the trajectory profile.
route_geometry_pointsThe geometry points along the route which are associated with a speed in this method.
starting_speedThe current speed of the vehicle at the time of the trajectory planning request
Returns
List of centerline points paired with speed limits

Definition at line 420 of file stop_controlled_intersection_tactical_plugin.cpp.

421 {
422 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Planning for Case three");
423 //Derive meta data values from maneuver message - Using order in sci_strategic_plugin
424 double a_dec = GET_MANEUVER_PROPERTY(maneuver, parameters.float_valued_meta_data[0]);
425
426 //Derive start and end dist from maneuver
427 double start_dist = GET_MANEUVER_PROPERTY(maneuver, start_dist);
428 double end_dist = GET_MANEUVER_PROPERTY(maneuver, end_dist);
429 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Maneuver starting downtrack: "<< start_dist);
430 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Maneuver ending downtrack: "<< end_dist);
431
432 //Checking route geometry start against start_dist and adjust profile
433 double route_starting_downtrack = wm->routeTrackPos(route_geometry_points[0]).downtrack; //Starting downtrack based on geometry points
434
435 if(route_starting_downtrack < start_dist){
436 //update parameter
437 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Starting distance is less than maneuver start, updating parameters");
438 a_dec = pow(starting_speed, 2)/(2*(end_dist - route_starting_downtrack));
439 }
440
441 std::vector<PointSpeedPair> points_and_target_speeds;
443 first_point.point = route_geometry_points[0];
444 first_point.speed = starting_speed;
445 points_and_target_speeds.push_back(first_point);
446
447 lanelet::BasicPoint2d prev_point = route_geometry_points[0];
448 double total_dist_covered = 0; //Starting dist for maneuver treated as 0.0
449
450 for(size_t i = 0;i < route_geometry_points.size(); i++){
451 lanelet::BasicPoint2d current_point = route_geometry_points[i];
452 double delta_d = lanelet::geometry::distance2d(prev_point, current_point);
453 total_dist_covered +=delta_d;
454 //Find speed at dist covered
455 double speed_i = sqrt(std::max(pow(starting_speed,2) + 2 * a_dec * total_dist_covered, 0.0)); //std::max to ensure negative value is not sqrt
456
458
459 if(speed_i < epsilon_){
460 p.point = prev_point;
461 p.speed = 0.0;
462 }
463 else{
464 p.point = route_geometry_points[i];
465 p.speed = speed_i;
466 prev_point = current_point; //Advance prev point if speed changes
467 }
468
469 points_and_target_speeds.push_back(p);
470
471
472 }
473
474 return points_and_target_speeds;
475}

References epsilon_, process_bag::first_point, GET_MANEUVER_PROPERTY, process_bag::i, basic_autonomy::waypoint_generation::PointSpeedPair::point, and basic_autonomy::waypoint_generation::PointSpeedPair::speed.

Referenced by maneuvers_to_points().

Here is the caller graph for this function:

◆ create_case_two_speed_profile()

std::vector< PointSpeedPair > stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::create_case_two_speed_profile ( const carma_wm::WorldModelConstPtr wm,
const carma_planning_msgs::msg::Maneuver &  maneuver,
std::vector< lanelet::BasicPoint2d > &  route_geometry_points,
double  starting_speed 
)

Creates a speed profile according to case two of the stop controlled intersection, where the vehicle first accelerates then cruises and finally decelerates to a stop.

Parameters
wmPointer to intialized world model for semantic map access
maneuversThe maneuver to being planned for. Maneuver meta-dara parameters are used to create the trajectory profile.
route_geometry_pointsThe geometry points along the route which are associated with a speed in this method.
starting_speedThe current speed of the vehicle at the time of the trajectory planning request
Returns
List of centerline points paired with speed limits

Definition at line 319 of file stop_controlled_intersection_tactical_plugin.cpp.

320 {
321 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Planning for Case Two");
322 //Derive meta data values from maneuver message - Using order in sci_strategic_plugin
323 double a_acc = GET_MANEUVER_PROPERTY(maneuver, parameters.float_valued_meta_data[0]);
324 double a_dec = GET_MANEUVER_PROPERTY(maneuver, parameters.float_valued_meta_data[1]); //a_dec is a -ve value
325 double t_acc = GET_MANEUVER_PROPERTY(maneuver, parameters.float_valued_meta_data[2]);
326 double t_dec = GET_MANEUVER_PROPERTY(maneuver, parameters.float_valued_meta_data[3]);
327 double t_cruise = GET_MANEUVER_PROPERTY(maneuver, parameters.float_valued_meta_data[4]);
328 double speed_before_decel = GET_MANEUVER_PROPERTY(maneuver, parameters.float_valued_meta_data[5]);
329
330 //Derive start and end dist from maneuver
331 double start_dist = GET_MANEUVER_PROPERTY(maneuver, start_dist);
332 double end_dist = GET_MANEUVER_PROPERTY(maneuver, end_dist);
333 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Maneuver starting downtrack: "<< start_dist);
334 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Maneuver ending downtrack: "<< end_dist);
335
336 //Checking route geometry start against start_dist and adjust profile
337 double route_starting_downtrack = wm->routeTrackPos(route_geometry_points[0]).downtrack; //Starting downtrack based on geometry points
338 double dist_acc; //Distance over which acceleration happens
339 double dist_cruise; //Distance over which cruising happens
340 double dist_decel; //Distance over which deceleration happens
341
342 if(route_starting_downtrack < start_dist){
343 //update parameters
344 //Keeping acceleration and deceleration part same as planned in strategic plugin
345 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Starting distance is less than maneuver start, updating parameters");
346 dist_acc = starting_speed*t_acc + 0.5 * a_acc * pow(t_acc,2);
347 dist_decel = speed_before_decel*t_dec + 0.5 * a_dec * pow(t_dec,2);
348 dist_cruise = end_dist - route_starting_downtrack - (dist_acc + dist_decel);
349 }
350 else{
351 //Use maneuver parameters to create speed profile
352 dist_acc = starting_speed*t_acc + 0.5 * a_acc * pow(t_acc,2);
353 dist_cruise = speed_before_decel*t_cruise;
354 dist_decel = speed_before_decel*t_dec + 0.5 * a_dec * pow(t_dec,2);
355 }
356
357 //Check calculated total dist against maneuver limits
358 double total_distance_needed = dist_acc + dist_cruise + dist_decel;
359 if(total_distance_needed - (end_dist - start_dist) > epsilon_ ){
360 //Requested maneuver needs to be modified to meet start and end dist req
361 //Sacrifice on cruising and then acceleration if needed
362 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Updating maneuver to meet start and end dist req.");
363 double delta_total_dist = total_distance_needed - (end_dist - start_dist);
364 dist_cruise -= delta_total_dist;
365 if(dist_cruise < 0){
366 dist_acc += dist_cruise;
367 dist_cruise = 0;
368 }
369 //Not considering dist_acc < 0 after this.
370 }
371
372 std::vector<PointSpeedPair> points_and_target_speeds;
374 first_point.point = route_geometry_points[0];
375 first_point.speed = starting_speed;
376 points_and_target_speeds.push_back(first_point);
377
378 lanelet::BasicPoint2d prev_point = route_geometry_points.front();
379 double total_dist_planned = 0; //Starting dist for maneuver treated as 0.0
380 double prev_speed = starting_speed;
381 for(auto route_point : route_geometry_points){
382 lanelet::BasicPoint2d current_point = route_point;
383 double delta_d = lanelet::geometry::distance2d(prev_point, current_point);
384 total_dist_planned += delta_d;
385
386 //Find speed at dist covered
387 double speed_i;
388 if(total_dist_planned < dist_acc){
389 //Acceleration part
390 speed_i = sqrt(pow(starting_speed,2) + 2*a_acc*total_dist_planned);
391 }
392 else if(dist_cruise > 0 && total_dist_planned >= dist_acc && total_dist_planned <= (dist_acc + dist_cruise)){
393 //Cruising part
394 speed_i = prev_speed;
395 }
396 else{
397 //Deceleration part
398 speed_i = sqrt(std::max(pow(speed_before_decel,2) + 2*a_dec*(total_dist_planned - dist_acc - dist_cruise),0.0));//std::max to ensure negative value is not sqrt
399 }
400
402 if(speed_i < epsilon_){
403 p.point = prev_point;
404 p.speed = 0.0;
405 }
406 else{
407 p.point = route_point;
408 p.speed = std::min(speed_i,speed_before_decel);
409 prev_point = current_point; //Advance prev point if speed changes
410 }
411 points_and_target_speeds.push_back(p);
412
413 prev_speed = speed_i;
414 }
415
416 return points_and_target_speeds;
417
418}

References epsilon_, process_bag::first_point, GET_MANEUVER_PROPERTY, basic_autonomy::waypoint_generation::PointSpeedPair::point, and basic_autonomy::waypoint_generation::PointSpeedPair::speed.

Referenced by maneuvers_to_points().

Here is the caller graph for this function:

◆ FRIEND_TEST() [1/3]

stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::FRIEND_TEST ( StopControlledIntersectionTacticalPlugin  ,
TestSCIPlanning_case_one   
)
private

◆ FRIEND_TEST() [2/3]

stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::FRIEND_TEST ( StopControlledIntersectionTacticalPlugin  ,
TestSCIPlanning_case_three   
)
private

◆ FRIEND_TEST() [3/3]

stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::FRIEND_TEST ( StopControlledIntersectionTacticalPlugin  ,
TestSCIPlanning_case_two   
)
private

◆ get_availability()

bool stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::get_availability ( )
virtual

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 602 of file stop_controlled_intersection_tactical_plugin.cpp.

603{
604 return true;
605}

◆ get_version_id()

std::string stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::get_version_id ( )
virtual

Returns the version id of this plugin.

Returns
The version id represented as a string

Implements carma_guidance_plugins::PluginBaseNode.

Definition at line 607 of file stop_controlled_intersection_tactical_plugin.cpp.

608{
609 return "v1.0";
610}

◆ maneuvers_to_points()

std::vector< PointSpeedPair > stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::maneuvers_to_points ( const std::vector< carma_planning_msgs::msg::Maneuver > &  maneuvers,
const carma_wm::WorldModelConstPtr wm,
const carma_planning_msgs::msg::VehicleState &  state 
)

Converts a set of requested stop controlled intersection maneuvers to point speed limit pairs.

Parameters
maneuversThe list of maneuvers to convert
wmPointer to intialized world model for semantic map access
stateThe current state of the vehicle
Returns
List of centerline points paired with target speeds

Definition at line 170 of file stop_controlled_intersection_tactical_plugin.cpp.

172{
173 std::vector<PointSpeedPair> points_and_target_speeds;
174 std::unordered_set<lanelet::Id> visited_lanelets;
175
176 lanelet::BasicPoint2d veh_pos(state.x_pos_global, state.y_pos_global);
177 double max_starting_downtrack = wm_->routeTrackPos(veh_pos).downtrack; //The vehicle position
178 double starting_speed = state.longitudinal_vel;
179
180 bool first = true;
181 double starting_downtrack;
182 for (const auto& maneuver : maneuvers)
183 {
184 if(maneuver.type != carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING && maneuver.type != carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT && maneuver.type != carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN
185 && maneuver.type !=carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN ){
186 throw std::invalid_argument("Stop Controlled Intersection Tactical Plugin does not support this maneuver type");
187 }
188
189 if(first)
190 {
191 starting_downtrack = GET_MANEUVER_PROPERTY(maneuver, start_dist);
192 if (starting_downtrack > max_starting_downtrack)
193 {
194 starting_downtrack = max_starting_downtrack;
195 }
196 first = false;
197 }
198
199 // Sample the lanelet centerline at fixed increments.
200 // std::min call here is a guard against starting_downtrack being within 1m of the maneuver end_dist
201 // in this case the sampleRoutePoints method will return a single point allowing execution to continue
202 std::vector<lanelet::BasicPoint2d> route_points = wm->sampleRoutePoints(
203 std::min(starting_downtrack + config_.centerline_sampling_spacing, GET_MANEUVER_PROPERTY(maneuver,end_dist)),
205
206 route_points.insert(route_points.begin(), veh_pos);
207 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Route geometery points size: "<<route_points.size());
208 //get case num from maneuver parameters
209 if(GET_MANEUVER_PROPERTY(maneuver,parameters.int_valued_meta_data).empty()){
210 throw std::invalid_argument("No case number specified for stop controlled intersection maneuver");
211 }
212
213 int case_num = GET_MANEUVER_PROPERTY(maneuver,parameters.int_valued_meta_data[0]);
214 if(case_num == 1){
215 points_and_target_speeds = create_case_one_speed_profile(wm, maneuver, route_points, starting_speed, state);
216 }
217 else if(case_num == 2){
218 points_and_target_speeds = create_case_two_speed_profile(wm, maneuver, route_points, starting_speed);
219 }
220 else if(case_num == 3)
221 {
222 points_and_target_speeds = create_case_three_speed_profile(wm, maneuver, route_points, starting_speed);
223 }
224 else{
225 throw std::invalid_argument("The stop controlled intersection tactical plugin doesn't handle the case number requested");
226 }
227 }
228
229 return points_and_target_speeds;
230}
std::vector< PointSpeedPair > create_case_two_speed_profile(const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::Maneuver &maneuver, std::vector< lanelet::BasicPoint2d > &route_geometry_points, double starting_speed)
Creates a speed profile according to case two of the stop controlled intersection,...
std::vector< PointSpeedPair > create_case_one_speed_profile(const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::Maneuver &maneuver, std::vector< lanelet::BasicPoint2d > &route_geometry_points, double starting_speed, const carma_planning_msgs::msg::VehicleState &states)
Creates a speed profile according to case one of the stop controlled intersection,...
std::vector< PointSpeedPair > create_case_three_speed_profile(const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::Maneuver &maneuver, std::vector< lanelet::BasicPoint2d > &route_geometry_points, double starting_speed)
Creates a speed profile according to case three of the stop controlled intersection,...

References stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::centerline_sampling_spacing, config_, create_case_one_speed_profile(), create_case_three_speed_profile(), create_case_two_speed_profile(), GET_MANEUVER_PROPERTY, and wm_.

Referenced by plan_trajectory_callback().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ on_configure_plugin()

carma_ros2_utils::CallbackReturn stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::on_configure_plugin ( )
overridevirtual

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 86 of file stop_controlled_intersection_tactical_plugin.cpp.

87{
88 config_ = StopControlledIntersectionTacticalPluginConfig();
89
90 // Declare parameters
91 get_parameter<double>("trajectory_time_length", config_.trajectory_time_length);
92 get_parameter<double>("curve_resample_step_size", config_.curve_resample_step_size);
93 get_parameter<double>("centerline_sampling_spacing", config_.centerline_sampling_spacing);
94 get_parameter<int>("curvature_moving_average_window_size", config_.curvature_moving_average_window_size);
95 get_parameter<double>("lateral_accel_limit", config_.lateral_accel_limit);
96 get_parameter<int>("speed_moving_average_window_size", config_.speed_moving_average_window_size);
97 get_parameter<double>("back_distance", config_.back_distance);
98
99 // Register runtime parameter update callback
100 add_on_set_parameters_callback(std::bind(&StopControlledIntersectionTacticalPlugin::parameter_update_callback, this, std_ph::_1));
101
102 RCLCPP_INFO_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"),"Done loading parameters: " << config_);
103
104 // set world model pointer
106
107 // Return success if everything initialized successfully
108 return CallbackReturn::SUCCESS;
109}
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)

References stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::back_distance, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::centerline_sampling_spacing, config_, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::curvature_moving_average_window_size, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::curve_resample_step_size, carma_guidance_plugins::PluginBaseNode::get_world_model(), stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::lateral_accel_limit, parameter_update_callback(), stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::speed_moving_average_window_size, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::trajectory_time_length, and wm_.

Here is the call graph for this function:

◆ parameter_update_callback()

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

Definition at line 64 of file stop_controlled_intersection_tactical_plugin.cpp.

65{
66 auto error_double = update_params<double>({
67 {"trajectory_time_length", config_.trajectory_time_length},
68 {"curve_resample_step_size", config_.curve_resample_step_size},
69 {"centerline_sampling_spacing", config_.centerline_sampling_spacing},
70 {"lateral_accel_limit", config_.lateral_accel_limit},
71 {"back_distance", config_.back_distance}
72 }, parameters);
73
74 auto error_int = update_params<int>({
75 {"curvature_moving_average_window_size", config_.curvature_moving_average_window_size},
76 {"speed_moving_average_window_size", config_.speed_moving_average_window_size}
77 }, parameters);
78
79 rcl_interfaces::msg::SetParametersResult result;
80
81 result.successful = !error_double && !error_int;
82
83 return result;
84}

References stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::back_distance, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::centerline_sampling_spacing, config_, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::curvature_moving_average_window_size, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::curve_resample_step_size, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::lateral_accel_limit, stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::speed_moving_average_window_size, and stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPluginConfig::trajectory_time_length.

Referenced by on_configure_plugin().

Here is the caller graph for this function:

◆ plan_trajectory_callback()

void stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::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 111 of file stop_controlled_intersection_tactical_plugin.cpp.

115{
116 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Starting stop controlled intersection trajectory planning");
117
118 if(req->maneuver_index_to_plan >= req->maneuver_plan.maneuvers.size())
119 {
120 throw std::invalid_argument(
121 "Stop Control Intersection Plugin asked to plan invalid maneuver index: " + std::to_string(req->maneuver_index_to_plan) +
122 " for plan of size: " + std::to_string(req->maneuver_plan.maneuvers.size()));
123 }
124 std::vector<carma_planning_msgs::msg::Maneuver> maneuver_plan;
125 for(size_t i = req->maneuver_index_to_plan; i < req->maneuver_plan.maneuvers.size(); i++){
126
127 if((req->maneuver_plan.maneuvers[i].type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING || req->maneuver_plan.maneuvers[i].type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT
128 || req->maneuver_plan.maneuvers[i].type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN || req->maneuver_plan.maneuvers[i].type ==carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN)
129 && GET_MANEUVER_PROPERTY(req->maneuver_plan.maneuvers[i], parameters.string_valued_meta_data.front()) == stop_controlled_intersection_strategy_)
130 {
131 maneuver_plan.push_back(req->maneuver_plan.maneuvers[i]);
132 resp->related_maneuvers.push_back(req->maneuver_plan.maneuvers[i].type);
133 }
134 else
135 {
136 break;
137 }
138 }
139
140 lanelet::BasicPoint2d veh_pos(req->vehicle_state.x_pos_global, req->vehicle_state.y_pos_global);
141 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Planning state x:"<<req->vehicle_state.x_pos_global <<" , y: " << req->vehicle_state.y_pos_global);
142
143 double current_downtrack = wm_->routeTrackPos(veh_pos).downtrack;
144 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Current_downtrack"<< current_downtrack);
145
146 std::vector<PointSpeedPair> points_and_target_speeds = maneuvers_to_points( maneuver_plan, wm_, req->vehicle_state);
147 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Maneuver to points size:"<< points_and_target_speeds.size());
148 // RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_controlled_intersection_tactical_plugin"), "Printing points: ");
149 // TODO: add print logic
150 carma_planning_msgs::msg::TrajectoryPlan trajectory;
151 trajectory.header.frame_id = "map";
152 trajectory.header.stamp = req->header.stamp;
153 trajectory.trajectory_id = boost::uuids::to_string(boost::uuids::random_generator()());
154
155 //Add compose trajectory from centerline
156 trajectory.trajectory_points = compose_trajectory_from_centerline(points_and_target_speeds, req->vehicle_state, req->header.stamp);
157 trajectory.initial_longitudinal_velocity = req->vehicle_state.longitudinal_vel;
158
159 // Set the planning plugin field name
160 for (auto& p : trajectory.trajectory_points) {
161 p.planner_plugin_name = get_plugin_name();
162 // p.controller_plugin_name = "PurePursuit";
163 }
164
165 resp->trajectory_plan = trajectory;
166
167 resp->maneuver_status.push_back(carma_planning_msgs::srv::PlanTrajectory::Response::MANEUVER_IN_PROGRESS);
168}
std::string get_plugin_name() const
Return the name of this plugin.
std::vector< PointSpeedPair > maneuvers_to_points(const std::vector< carma_planning_msgs::msg::Maneuver > &maneuvers, const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::VehicleState &state)
Converts a set of requested stop controlled intersection maneuvers to point speed limit pairs.
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > compose_trajectory_from_centerline(const std::vector< PointSpeedPair > &points, const carma_planning_msgs::msg::VehicleState &state, const rclcpp::Time &state_time)
Method converts a list of lanelet centerline points and current vehicle state into a usable list of t...
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21

References compose_trajectory_from_centerline(), GET_MANEUVER_PROPERTY, carma_guidance_plugins::PluginBaseNode::get_plugin_name(), process_bag::i, maneuvers_to_points(), stop_controlled_intersection_strategy_, carma_cooperative_perception::to_string(), and wm_.

Here is the call graph for this function:

Member Data Documentation

◆ config_

StopControlledIntersectionTacticalPluginConfig stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::config_
private

◆ epsilon_

double stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::epsilon_ = 0.001
private

◆ stop_controlled_intersection_strategy_

std::string stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::stop_controlled_intersection_strategy_ = "Carma/stop_controlled_intersection"
private

Definition at line 160 of file stop_controlled_intersection_plugin.hpp.

Referenced by plan_trajectory_callback().

◆ wm_

carma_wm::WorldModelConstPtr stop_controlled_intersection_tactical_plugin::StopControlledIntersectionTacticalPlugin::wm_
private

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