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.
yield_plugin::YieldPlugin Class Reference

Class containing primary business logic for the In-Lane Cruising Plugin. More...

#include <yield_plugin.hpp>

Collaboration diagram for yield_plugin::YieldPlugin:
Collaboration graph

Public Member Functions

 YieldPlugin (std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh, carma_wm::WorldModelConstPtr wm, YieldPluginConfig config, MobilityResponseCB mobility_response_publisher, LaneChangeStatusCB lc_status_publisher)
 Constructor. More...
 
void plan_trajectory_callback (carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp)
 Service callback for trajectory planning. More...
 
carma_planning_msgs::msg::TrajectoryPlan update_traj_for_object (const carma_planning_msgs::msg::TrajectoryPlan &original_tp, const std::vector< carma_perception_msgs::msg::ExternalObject > &external_objects, double initial_velocity)
 trajectory is modified to safely avoid obstacles on the road More...
 
double polynomial_calc (std::vector< double > coeff, double x) const
 calculate quintic polynomial equation for a given x More...
 
double polynomial_calc_d (std::vector< double > coeff, double x) const
 calculate derivative of quintic polynomial equation for a given x More...
 
double max_trajectory_speed (const std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > &trajectory_points, double timestamp_in_sec_to_search_until) const
 calculates the maximum speed in a set of tajectory points More...
 
std::vector< double > get_relative_downtracks (const carma_planning_msgs::msg::TrajectoryPlan &trajectory_plan) const
 calculates distance between trajectory points in a plan More...
 
void mobilityrequest_cb (const carma_v2x_msgs::msg::MobilityRequest::UniquePtr msg)
 callback for mobility request More...
 
void bsm_cb (const carma_v2x_msgs::msg::BSM::UniquePtr msg)
 callback for bsm message More...
 
std::vector< lanelet::BasicPoint2d > convert_eceftrajectory_to_mappoints (const carma_v2x_msgs::msg::Trajectory &ecef_trajectory) const
 convert a carma trajectory from ecef frame to map frame ecef trajectory consists of the point and a set of offsets with reference to the point More...
 
lanelet::BasicPoint2d ecef_to_map_point (const carma_v2x_msgs::msg::LocationECEF &ecef_point) const
 convert a point in ecef frame (in cm) into map frame (in meters) More...
 
carma_v2x_msgs::msg::MobilityResponse compose_mobility_response (const std::string &resp_recipient_id, const std::string &req_plan_id, bool response) const
 compose a mobility response message More...
 
carma_planning_msgs::msg::TrajectoryPlan generate_JMT_trajectory (const carma_planning_msgs::msg::TrajectoryPlan &original_tp, double initial_pos, double goal_pos, double initial_velocity, double goal_velocity, double planning_time, double original_max_speed)
 generate a Jerk Minimizing Trajectory(JMT) with the provided start and end conditions More...
 
carma_planning_msgs::msg::TrajectoryPlan update_traj_for_cooperative_behavior (const carma_planning_msgs::msg::TrajectoryPlan &original_tp, double current_speed)
 update trajectory for yielding to an incoming cooperative behavior More...
 
std::vector< std::pair< int, lanelet::BasicPoint2d > > detect_trajectories_intersection (std::vector< lanelet::BasicPoint2d > self_trajectory, std::vector< lanelet::BasicPoint2d > incoming_trajectory) const
 detect intersection point(s) of two trajectories More...
 
void set_incoming_request_info (std::vector< lanelet::BasicPoint2d > req_trajectory, double req_speed, double req_planning_time, double req_timestamp)
 set values for member variables related to cooperative behavior More...
 
void lookup_ecef_to_map_transform ()
 Looks up the transform between map and earth frames, and sets the member variable. More...
 
double check_traj_for_digital_min_gap (const carma_planning_msgs::msg::TrajectoryPlan &original_tp) const
 checks trajectory for minimum gap associated with it More...
 
void set_georeference_string (const std::string &georeference)
 Setter for map projection string to define lat/lon -> map conversion. More...
 
void set_external_objects (const std::vector< carma_perception_msgs::msg::ExternalObject > &object_list)
 Setter for external objects with predictions in the environment. More...
 
std::optional< GetCollisionResultget_collision (const carma_planning_msgs::msg::TrajectoryPlan &trajectory1, const std::vector< carma_perception_msgs::msg::PredictedState > &trajectory2, double collision_radius, double trajectory1_max_speed)
 Return naive collision time and locations based on collision radius given two trajectories with one being obstacle's predicted steps. More...
 
std::optional< rclcpp::Time > get_collision_time (const carma_planning_msgs::msg::TrajectoryPlan &original_tp, const carma_perception_msgs::msg::ExternalObject &curr_obstacle, double original_tp_max_speed)
 Return collision time given two trajectories with one being external object with predicted steps. More...
 
bool is_object_behind_vehicle (uint32_t object_id, const rclcpp::Time &collision_time, double vehicle_point, double object_downtrack)
 Check if object location is behind the vehicle using estimates of the vehicle's length and route downtracks. More...
 
std::optional< std::pair< carma_perception_msgs::msg::ExternalObject, double > > get_earliest_collision_object_and_time (const carma_planning_msgs::msg::TrajectoryPlan &original_tp, const std::vector< carma_perception_msgs::msg::ExternalObject > &external_objects)
 Return the earliest collision object and time of collision pair from the given trajectory and list of external objects with predicted states. Function first filters obstacles based on whether if their any of predicted state will be on the route. Only then, the logic compares trajectory and predicted states. More...
 
std::unordered_map< uint32_t, rclcpp::Time > get_collision_times_concurrently (const carma_planning_msgs::msg::TrajectoryPlan &original_tp, const std::vector< carma_perception_msgs::msg::ExternalObject > &external_objects, double original_tp_max_speed)
 Given the list of objects with predicted states, get all collision times concurrently using multi-threading. More...
 
double get_predicted_velocity_at_time (const geometry_msgs::msg::Twist &object_velocity_in_map_frame, const carma_planning_msgs::msg::TrajectoryPlan &original_tp, double timestamp_in_sec_to_predict)
 Given the object velocity in map frame with x,y components, this function returns the projected velocity along the trajectory at given time. More...
 

Private Member Functions

std::string bsmIDtoString (carma_v2x_msgs::msg::BSMCoreData bsm_core)
 

Private Attributes

carma_wm::WorldModelConstPtr wm_
 
YieldPluginConfig config_
 
MobilityResponseCB mobility_response_publisher_
 
LaneChangeStatusCB lc_status_publisher_
 
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh_
 
std::set< lanelet::Id > route_llt_ids_
 
lanelet::Id previous_llt_id_
 
std::vector< carma_perception_msgs::msg::ExternalObject > external_objects_
 
std::unordered_map< uint32_t, int > consecutive_clearance_count_for_obstacles_
 
bool cooperative_request_acceptable_ = false
 
std::vector< lanelet::BasicPoint2d > req_trajectory_points_
 
double req_target_speed_ = 0
 
double req_timestamp_ = 0
 
double req_target_plan_time_ = 0
 
int timesteps_since_last_req_ = 0
 
int clc_urgency_ = 0
 
double ecef_traj_timestep_ = 0.1
 
geometry_msgs::msg::Vector3 host_vehicle_size
 
double current_speed_
 
std::string host_bsm_id_
 
std::string georeference_ {""}
 
std::shared_ptr< lanelet::projection::LocalFrameProjector > map_projector_
 

Detailed Description

Class containing primary business logic for the In-Lane Cruising Plugin.

Definition at line 77 of file yield_plugin.hpp.

Constructor & Destructor Documentation

◆ YieldPlugin()

yield_plugin::YieldPlugin::YieldPlugin ( std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode >  nh,
carma_wm::WorldModelConstPtr  wm,
YieldPluginConfig  config,
MobilityResponseCB  mobility_response_publisher,
LaneChangeStatusCB  lc_status_publisher 
)

Constructor.

Parameters
wmPointer to intialized instance of the carma world model for accessing semantic map data
configThe configuration to be used for this object
mobility_response_publisherCallback which will publish the mobility response
lc_status_publisherCallback which will publish the cooperative lane change status

Definition at line 45 of file yield_plugin.cpp.

48 : nh_(nh), wm_(wm), config_(config),mobility_response_publisher_(mobility_response_publisher), lc_status_publisher_(lc_status_publisher)
49 {
50
51 }
LaneChangeStatusCB lc_status_publisher_
MobilityResponseCB mobility_response_publisher_
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh_
YieldPluginConfig config_
carma_wm::WorldModelConstPtr wm_

Member Function Documentation

◆ bsm_cb()

void yield_plugin::YieldPlugin::bsm_cb ( const carma_v2x_msgs::msg::BSM::UniquePtr  msg)

callback for bsm message

Parameters
msgmobility bsm message

Definition at line 246 of file yield_plugin.cpp.

247 {
248 carma_v2x_msgs::msg::BSMCoreData bsm_core_ = msg->core_data;
249 host_bsm_id_ = bsmIDtoString(bsm_core_);
250 }
std::string bsmIDtoString(carma_v2x_msgs::msg::BSMCoreData bsm_core)

References bsmIDtoString(), and host_bsm_id_.

Referenced by yield_plugin::YieldPluginNode::on_configure_plugin().

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

◆ bsmIDtoString()

std::string yield_plugin::YieldPlugin::bsmIDtoString ( carma_v2x_msgs::msg::BSMCoreData  bsm_core)
inlineprivate

Definition at line 342 of file yield_plugin.hpp.

343 {
344 std::string res = "";
345 for (size_t i=0; i<bsm_core.id.size(); i++)
346 {
347 res+=std::to_string(bsm_core.id[i]);
348 }
349 return res;
350 }
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21

References process_bag::i, and carma_cooperative_perception::to_string().

Referenced by bsm_cb().

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

◆ check_traj_for_digital_min_gap()

double yield_plugin::YieldPlugin::check_traj_for_digital_min_gap ( const carma_planning_msgs::msg::TrajectoryPlan &  original_tp) const

checks trajectory for minimum gap associated with it

Parameters
original_tporiginal trajectory plan
Returns
minumum required

Definition at line 1036 of file yield_plugin.cpp.

1037 {
1038 double desired_gap = 0;
1039
1040 for (size_t i = 0; i < original_tp.trajectory_points.size(); i++)
1041 {
1042 lanelet::BasicPoint2d veh_pos(original_tp.trajectory_points.at(i).x, original_tp.trajectory_points.at(i).y);
1043 auto llts = wm_->getLaneletsFromPoint(veh_pos, 1);
1044 if (llts.empty())
1045 {
1046 RCLCPP_WARN_STREAM(nh_->get_logger(),"Trajectory point: x= " << original_tp.trajectory_points.at(i).x << "y="<< original_tp.trajectory_points.at(i).y);
1047
1048 throw std::invalid_argument("Trajectory Point is not on a valid lanelet.");
1049 }
1050 auto digital_min_gap = llts[0].regulatoryElementsAs<lanelet::DigitalMinimumGap>(); //Returns a list of these elements)
1051 if (!digital_min_gap.empty())
1052 {
1053 double digital_gap = digital_min_gap[0]->getMinimumGap(); // Provided gap is in meters
1054 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"Digital Gap found with value: " << digital_gap);
1055 desired_gap = std::max(desired_gap, digital_gap);
1056 }
1057 }
1058 return desired_gap;
1059 }

References process_bag::i, nh_, and wm_.

Referenced by update_traj_for_cooperative_behavior(), and update_traj_for_object().

Here is the caller graph for this function:

◆ compose_mobility_response()

carma_v2x_msgs::msg::MobilityResponse yield_plugin::YieldPlugin::compose_mobility_response ( const std::string &  resp_recipient_id,
const std::string &  req_plan_id,
bool  response 
) const

compose a mobility response message

Parameters
resp_recipient_idvehicle id of the recipient of the message
req_plan_idplan id from the requested message
responseaccept/reject to the response based on conditions
Returns
filled mobility response

Definition at line 133 of file yield_plugin.cpp.

134 {
135 carma_v2x_msgs::msg::MobilityResponse out_mobility_response;
136 out_mobility_response.m_header.sender_id = config_.vehicle_id;
137 out_mobility_response.m_header.recipient_id = resp_recipient_id;
138 out_mobility_response.m_header.sender_bsm_id = host_bsm_id_;
139 out_mobility_response.m_header.plan_id = req_plan_id;
140 out_mobility_response.m_header.timestamp = nh_->now().seconds()*1000;
141
142
144 {
145 out_mobility_response.is_accepted = true;
146 }
147 else out_mobility_response.is_accepted = false;
148
149 return out_mobility_response;
150 }
bool always_accept_mobility_request
std::string vehicle_id

References YieldPluginConfig::always_accept_mobility_request, config_, host_bsm_id_, nh_, and YieldPluginConfig::vehicle_id.

Referenced by mobilityrequest_cb().

Here is the caller graph for this function:

◆ convert_eceftrajectory_to_mappoints()

std::vector< lanelet::BasicPoint2d > yield_plugin::YieldPlugin::convert_eceftrajectory_to_mappoints ( const carma_v2x_msgs::msg::Trajectory &  ecef_trajectory) const

convert a carma trajectory from ecef frame to map frame ecef trajectory consists of the point and a set of offsets with reference to the point

Parameters
ecef_trajectorycarma trajectory (ecef frame)
Returns
vector of 2d points in map frame

Definition at line 94 of file yield_plugin.cpp.

95 {
96 carma_planning_msgs::msg::TrajectoryPlan trajectory_plan;
97 std::vector<lanelet::BasicPoint2d> map_points;
98
99 lanelet::BasicPoint2d first_point = ecef_to_map_point(ecef_trajectory.location);
100
101 map_points.push_back(first_point);
102 auto curr_point = ecef_trajectory.location;
103
104 for (size_t i = 0; i<ecef_trajectory.offsets.size(); i++)
105 {
106 lanelet::BasicPoint2d offset_point;
107 curr_point.ecef_x += ecef_trajectory.offsets.at(i).offset_x;
108 curr_point.ecef_y += ecef_trajectory.offsets.at(i).offset_y;
109 curr_point.ecef_z += ecef_trajectory.offsets.at(i).offset_z;
110
111 offset_point = ecef_to_map_point(curr_point);
112
113 map_points.push_back(offset_point);
114 }
115
116 return map_points;
117 }
lanelet::BasicPoint2d ecef_to_map_point(const carma_v2x_msgs::msg::LocationECEF &ecef_point) const
convert a point in ecef frame (in cm) into map frame (in meters)
list first_point
Definition: process_bag.py:52

References ecef_to_map_point(), process_bag::first_point, and process_bag::i.

Referenced by mobilityrequest_cb().

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

◆ detect_trajectories_intersection()

std::vector< std::pair< int, lanelet::BasicPoint2d > > yield_plugin::YieldPlugin::detect_trajectories_intersection ( std::vector< lanelet::BasicPoint2d >  self_trajectory,
std::vector< lanelet::BasicPoint2d >  incoming_trajectory 
) const

detect intersection point(s) of two trajectories

Parameters
trajectory1vector of 2d trajectory points
trajectory2vector of 2d trajectory points
Returns
vector of pairs of 2d intersection points and index of the point in trajectory array

Definition at line 73 of file yield_plugin.cpp.

74 {
75 std::vector<std::pair<int, lanelet::BasicPoint2d>> intersection_points;
76 boost::geometry::model::linestring<lanelet::BasicPoint2d> self_traj;
77 for (auto tpp:self_trajectory)
78 {
79 boost::geometry::append(self_traj, tpp);
80 }
81 // distance to consider trajectories colliding (chosen based on lane width and vehicle size)
82 for (size_t i=0; i<incoming_trajectory.size(); i++)
83 {
84 double res = boost::geometry::distance(incoming_trajectory.at(i), self_traj);
85
87 {
88 intersection_points.push_back(std::make_pair(i, incoming_trajectory.at(i)));
89 }
90 }
91 return intersection_points;
92 }
double intervehicle_collision_distance_in_m

References config_, process_bag::i, and YieldPluginConfig::intervehicle_collision_distance_in_m.

Referenced by update_traj_for_cooperative_behavior().

Here is the caller graph for this function:

◆ ecef_to_map_point()

lanelet::BasicPoint2d yield_plugin::YieldPlugin::ecef_to_map_point ( const carma_v2x_msgs::msg::LocationECEF &  ecef_point) const

convert a point in ecef frame (in cm) into map frame (in meters)

Parameters
ecef_pointcarma point ecef frame in cm
map_in_earthtranslate frame
Returns
2d point in map frame

Definition at line 119 of file yield_plugin.cpp.

120 {
121
122 if (!map_projector_) {
123 throw std::invalid_argument("No map projector available for ecef conversion");
124 }
125
126 lanelet::BasicPoint3d map_point = map_projector_->projectECEF( { static_cast<double>(ecef_point.ecef_x)/100.0, static_cast<double>(ecef_point.ecef_y)/100.0, static_cast<double>(ecef_point.ecef_z)/100.0 } , 1);
127
128 return lanelet::traits::to2D(map_point);
129 }
std::shared_ptr< lanelet::projection::LocalFrameProjector > map_projector_

References map_projector_.

Referenced by convert_eceftrajectory_to_mappoints().

Here is the caller graph for this function:

◆ generate_JMT_trajectory()

carma_planning_msgs::msg::TrajectoryPlan yield_plugin::YieldPlugin::generate_JMT_trajectory ( const carma_planning_msgs::msg::TrajectoryPlan &  original_tp,
double  initial_pos,
double  goal_pos,
double  initial_velocity,
double  goal_velocity,
double  planning_time,
double  original_max_speed 
)

generate a Jerk Minimizing Trajectory(JMT) with the provided start and end conditions

Parameters
original_tporiginal trajectory plan
intial_posstart position
goal_posfinal position
initial_velocitystart velocity
goal_velocityend velocity
planning_timetime duration of the planning
originaloriginal_max_speed from original_tp up until the goal_pos portion NOTE: the function would generate trajectory duration arbitrarily high if stopping motion is needed. This is to keep the original trajectory's shape in terms of location so that the vehicle steers toward the direction of travel even when stopping.
Returns
updated JMT trajectory

Definition at line 402 of file yield_plugin.cpp.

404 {
405 carma_planning_msgs::msg::TrajectoryPlan jmt_trajectory;
406 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> jmt_trajectory_points;
407 jmt_trajectory_points.push_back(original_tp.trajectory_points[0]);
408
409 std::vector<double> original_traj_relative_downtracks = get_relative_downtracks(original_tp);
410 std::vector<double> calculated_speeds = {};
411 std::vector<double> new_relative_downtracks = {};
412 new_relative_downtracks.push_back(0.0);
413 calculated_speeds.push_back(initial_velocity);
414 double new_traj_accumulated_downtrack = 0.0;
415 double original_traj_accumulated_downtrack = original_traj_relative_downtracks.at(1);
416
417 // Up until goal_pos (which also can be until end of the entire original trajectory), generate new speeds at
418 // or near original trajectory points by generating them at a fixed time interval using the JMT polynomial equation
419 const double initial_time = 0;
420 const double initial_accel = 0;
421 const double goal_accel = 0;
422 int new_traj_idx = 1;
423 int original_traj_idx = 1;
424 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"Following parameters used for JMT: "
425 "\ninitial_pos: " << initial_pos <<
426 "\ngoal_pos: " << goal_pos <<
427 "\ninitial_velocity: " << initial_velocity <<
428 "\ngoal_velocity: " << goal_velocity <<
429 "\ninitial_accel: " << initial_accel <<
430 "\ngoal_accel: " << goal_accel <<
431 "\nplanning_time: " << planning_time <<
432 "\noriginal_max_speed: " << original_max_speed);
433
434 // Get the polynomial solutions used to generate the trajectory
435 std::vector<double> polynomial_coefficients = quintic_coefficient_calculator::quintic_coefficient_calculator(initial_pos,
436 goal_pos,
437 initial_velocity,
438 goal_velocity,
439 initial_accel,
440 goal_accel,
441 initial_time,
442 planning_time);
443 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"Used original_max_speed: " << original_max_speed);
444 const auto smallest_time_step = get_smallest_time_step_of_traj(original_tp);
445 while (new_traj_accumulated_downtrack < goal_pos - EPSILON && original_traj_idx < original_traj_relative_downtracks.size())
446 {
447 const double target_time = new_traj_idx * smallest_time_step;
448 const double downtrack_at_target_time = polynomial_calc(polynomial_coefficients, target_time);
449 double velocity_at_target_time = polynomial_calc_d(polynomial_coefficients, target_time);
450
451 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "Calculated speed velocity_at_target_time: " << velocity_at_target_time
452 << ", downtrack_at_target_time: "<< downtrack_at_target_time << ", target_time: " << target_time);
453
454 // if the speed becomes negative, the downtrack starts reversing to negative as well
455 // which will never reach the goal_pos, so break here.
456 if (velocity_at_target_time < 0.0)
457 {
458 break;
459 }
460
461 // Cannot have a negative speed or have a higher speed than that of the original trajectory
462 velocity_at_target_time = std::clamp(velocity_at_target_time, 0.0, original_max_speed);
463
464 // Pick the speed if it matches with the original downtracks
465 if (downtrack_at_target_time >= original_traj_accumulated_downtrack)
466 {
467 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "Picked calculated speed velocity_at_target_time: " << velocity_at_target_time
468 << ", downtrack_at_target_time: "<< downtrack_at_target_time << ", target_time: " << target_time);
469 // velocity_at_target_time doesn't exactly correspond to original_traj_accumulated_downtrack but does for new_traj_accumulated_downtrack.
470 // however, the logic is assuming they are close enough that the speed is usable
471 calculated_speeds.push_back(velocity_at_target_time);
472 original_traj_accumulated_downtrack += original_traj_relative_downtracks.at(original_traj_idx);
473 original_traj_idx ++;
474 }
475 new_traj_accumulated_downtrack = downtrack_at_target_time;
476 new_traj_idx++;
477
478 }
479
480 // if the loop above finished prematurely due to negative speed, fill with 0.0 speeds
481 // since the speed crossed 0.0 and algorithm indicates stopping
482 std::fill_n(std::back_inserter(calculated_speeds),
483 std::size(original_traj_relative_downtracks) - std::size(calculated_speeds),
484 0.0);
485
486 // Moving average filter to smoothen the speeds
487 std::vector<double> filtered_speeds = basic_autonomy::smoothing::moving_average_filter(calculated_speeds, config_.speed_moving_average_window_size);
488 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "filtered_speeds size: " << filtered_speeds.size());
489
490 // Replace the original trajectory's associated timestamps based on the newly calculated speeds
491 double prev_speed = filtered_speeds.at(0);
492 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "start speed: " << prev_speed << ", target_time: " << std::to_string(rclcpp::Time(original_tp.trajectory_points[0].target_time).seconds()));
493
494 for(size_t i = 1; i < original_tp.trajectory_points.size(); i++)
495 {
496 carma_planning_msgs::msg::TrajectoryPlanPoint jmt_tpp = original_tp.trajectory_points.at(i);
497
498 // In case only subset of original trajectory needs modification,
499 // the rest of the points should keep the last speed to cruise
500 double current_speed = goal_velocity;
501
502 if (i < filtered_speeds.size())
503 {
504 current_speed = filtered_speeds.at(i);
505 }
506
507 //Force the speed to 0 if below configured value for more control over stopping behavior
508 if (current_speed < config_.max_stop_speed_in_ms)
509 {
510 current_speed = 0;
511 }
512
513 // Derived from constant accelaration kinematic equation: (vi + vf) / 2 * dt = d_dist
514 // This also handles a case correctly when current_speed is 0, but prev_speed is not 0 yet
515 const double dt = (2 * original_traj_relative_downtracks.at(i)) / (current_speed + prev_speed);
516 jmt_tpp.target_time = rclcpp::Time(jmt_trajectory_points.back().target_time) + rclcpp::Duration(dt*1e9);
517
518 if (prev_speed < EPSILON) // Handle a special case if prev_speed (thus current_speed too) is 0
519 {
520 // NOTE: Assigning arbitrary 100 mins dt between points where normally dt is only 1 sec to model a stopping behavior.
521 // Another way to model it is to keep the trajectory point at a same location and increment time slightly. However,
522 // if the vehicle goes past the point, it may cruise toward undesirable location (for example into the intersection).
523 // Keeping the points help the controller steer the vehicle toward direction of travel even when stopping.
524 // Only downside is the trajectory plan is huge where only 15 sec is expected, but since this is stopping case, it shouldn't matter.
525 jmt_tpp.target_time = rclcpp::Time(jmt_trajectory_points.back().target_time) + rclcpp::Duration(6000 * 1e9);
526 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "Zero speed = x: " << jmt_tpp.x << ", y:" << jmt_tpp.y
527 << ", t:" << std::to_string(rclcpp::Time(jmt_tpp.target_time).seconds())
528 << ", prev_speed: " << prev_speed << ", current_speed: " << current_speed);
529 }
530 else
531 {
532 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "Non-zero speed = x: " << jmt_tpp.x << ", y:" << jmt_tpp.y
533 << ", t:" << std::to_string(rclcpp::Time(jmt_tpp.target_time).seconds())
534 << ", prev_speed: " << prev_speed << ", current_speed: " << current_speed);
535 }
536
537 jmt_trajectory_points.push_back(jmt_tpp);
538 double insta_decel = (current_speed - prev_speed) / (rclcpp::Time(jmt_trajectory_points.at(i).target_time).seconds() - rclcpp::Time(jmt_trajectory_points.at(i - 1).target_time).seconds());
539 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "insta_decel: " << insta_decel );
540 prev_speed = current_speed;
541 }
542
543 jmt_trajectory.header = original_tp.header;
544 jmt_trajectory.trajectory_id = original_tp.trajectory_id;
545 jmt_trajectory.trajectory_points = jmt_trajectory_points;
546 jmt_trajectory.initial_longitudinal_velocity = initial_velocity;
547 return jmt_trajectory;
548 }
std::vector< double > get_relative_downtracks(const carma_planning_msgs::msg::TrajectoryPlan &trajectory_plan) const
calculates distance between trajectory points in a plan
double polynomial_calc(std::vector< double > coeff, double x) const
calculate quintic polynomial equation for a given x
double polynomial_calc_d(std::vector< double > coeff, double x) const
calculate derivative of quintic polynomial equation for a given x
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
double get_smallest_time_step_of_traj(const carma_planning_msgs::msg::TrajectoryPlan &original_tp)
double max_stop_speed_in_ms
double speed_moving_average_window_size
constexpr auto EPSILON

References config_, EPSILON, get_relative_downtracks(), yield_plugin::get_smallest_time_step_of_traj(), process_bag::i, YieldPluginConfig::max_stop_speed_in_ms, basic_autonomy::smoothing::moving_average_filter(), nh_, polynomial_calc(), polynomial_calc_d(), YieldPluginConfig::speed_moving_average_window_size, and carma_cooperative_perception::to_string().

Referenced by update_traj_for_cooperative_behavior(), and update_traj_for_object().

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

◆ get_collision()

std::optional< GetCollisionResult > yield_plugin::YieldPlugin::get_collision ( const carma_planning_msgs::msg::TrajectoryPlan &  trajectory1,
const std::vector< carma_perception_msgs::msg::PredictedState > &  trajectory2,
double  collision_radius,
double  trajectory1_max_speed 
)

Return naive collision time and locations based on collision radius given two trajectories with one being obstacle's predicted steps.

Parameters
trajectory1trajectory of the ego vehicle
trajectory2trajectory of predicted steps
collision_radiusa distance to check between two trajectory points at a same timestamp that is considered a collision
trajectory1_max_speedmax speed of the trajectory1 to efficiently traverse through possible collision combination of the two trajectories NOTE: Currently Traj2 is assumed to be a simple cv model to save computational performance NOTE: Collisions are based on only collision radius at the same predicted time even if ego vehicle maybe past the obstacle. To filter these cases, see is_object_behind_vehicle()
Returns
data of time of collision if detected, otherwise, std::nullopt

Definition at line 550 of file yield_plugin.cpp.

552 {
553
554 // Iterate through each pair of consecutive points in the trajectories
555 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "Starting a new collision detection, trajectory size: "
556 << trajectory1.trajectory_points.size() << ". prediction size: " << trajectory2.size());
557
558 // Iterate through the object to check if it's on the route
559 bool on_route = false;
560 int on_route_idx = 0;
561
562 // A flag to stop searching more than one lanelet if the object has no velocity
563 const auto traj2_speed{std::hypot(trajectory2.front().predicted_velocity.linear.x,
564 trajectory2.front().predicted_velocity.linear.y)};
565 bool traj2_has_zero_speed = traj2_speed < config_.obstacle_zero_speed_threshold_in_ms;
566
567 if (trajectory2.size() < 2)
568 {
569 throw std::invalid_argument("Object on ther road doesn't have enough predicted states! Please check motion_computation is correctly applying predicted states");
570 }
571 const double predict_step_duration = (rclcpp::Time(trajectory2.at(1).header.stamp) - rclcpp::Time(trajectory2.front().header.stamp)).seconds();
572 const double predict_total_duration = get_trajectory_duration(trajectory2);
573
574 if (predict_step_duration < 0.0)
575 {
576 throw std::invalid_argument("Predicted states of the object is malformed. Detected trajectory going backwards in time!");
577 }
578
579 // In order to optimize the for loops for comparing two trajectories, following logic skips every iteration_stride-th points of the traj2.
580 // Since skipping number of points from the traj2 may result in ignoring potential collisions, its value is dependent on two
581 // trajectories' speeds and intervehicle_collision_distance_in_m radius.
582 // Therefore, the derivation first calculates the max time, t, that both actors can move while still being in collision radius:
583 // sqrt( (v1 * t / 2)^2 + (v2 * t / 2)^2 ) = collision_radius. Here v1 and v2 are assumed to be perpendicular to each other and
584 // intersecting at t/2 to get max possible collision_radius. Solving for t gives following:
585 double iteration_stride_max_time_s = 2 * config_.intervehicle_collision_distance_in_m / sqrt(pow(traj2_speed, 2) + pow(trajectory1_max_speed, 2));
586 int iteration_stride = std::max(1, static_cast<int>(iteration_stride_max_time_s / predict_step_duration));
587
588 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "Determined iteration_stride: " << iteration_stride
589 << ", with traj2_speed: " << traj2_speed
590 << ", with trajectory1_max_speed: " << trajectory1_max_speed
591 << ", with predict_step_duration: " << predict_step_duration
592 << ", iteration_stride_max_time_s: " << iteration_stride_max_time_s);
593
594 for (size_t j = 0; j < trajectory2.size(); j += iteration_stride) // Saving computation time aiming for 1.5 meter interval
595 {
596 lanelet::BasicPoint2d curr_point;
597 curr_point.x() = trajectory2.at(j).predicted_position.position.x;
598 curr_point.y() = trajectory2.at(j).predicted_position.position.y;
599
600 auto corresponding_lanelets = wm_->getLaneletsFromPoint(curr_point, 8); // some intersection can have 8 overlapping lanelets
601
602 for (const auto& llt: corresponding_lanelets)
603 {
604 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "Checking llt: " << llt.id());
605
606 if (route_llt_ids_.find(llt.id()) != route_llt_ids_.end())
607 {
608 on_route = true;
609 on_route_idx = j;
610 break;
611 }
612 }
613 if (on_route || traj2_has_zero_speed)
614 break;
615 }
616
617 if (!on_route)
618 {
619 RCLCPP_DEBUG(nh_->get_logger(), "Predicted states are not on the route! ignoring");
620 return std::nullopt;
621 }
622
623 double smallest_dist = std::numeric_limits<double>::infinity();
624 for (size_t i = 0; i < trajectory1.trajectory_points.size() - 1; ++i)
625 {
626 auto p1a = trajectory1.trajectory_points.at(i);
627 auto p1b = trajectory1.trajectory_points.at(i + 1);
628 double previous_distance_between_predictions = std::numeric_limits<double>::infinity();
629 for (size_t j = on_route_idx; j < trajectory2.size() - 1; j += iteration_stride)
630 {
631 auto p2a = trajectory2.at(j);
632 auto p2b = trajectory2.at(j + 1);
633 double p1a_t = rclcpp::Time(p1a.target_time).seconds();
634 double p1b_t = rclcpp::Time(p1b.target_time).seconds();
635 double p2a_t = rclcpp::Time(p2a.header.stamp).seconds();
636 double p2b_t = rclcpp::Time(p2b.header.stamp).seconds();
637
638 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "p1a.target_time: " << std::to_string(p1a_t) << ", p1b.target_time: " << std::to_string(p1b_t));
639 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "p2a.target_time: " << std::to_string(p2a_t) << ", p2b.target_time: " << std::to_string(p2b_t));
640 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "p1a.x: " << p1a.x << ", p1a.y: " << p1a.y);
641 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "p1b.x: " << p1b.x << ", p1b.y: " << p1b.y);
642
643 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "p2a.x: " << p2a.predicted_position.position.x << ", p2a.y: " << p2a.predicted_position.position.y);
644 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "p2b.x: " << p2b.predicted_position.position.x << ", p2b.y: " << p2b.predicted_position.position.y);
645
646 // Linearly interpolate positions at a common timestamp for both trajectories
647 double dt = (p2a_t - p1a_t) / (p1b_t - p1a_t);
648 double x1 = p1a.x + dt * (p1b.x - p1a.x);
649 double y1 = p1a.y + dt * (p1b.y - p1a.y);
650 double x2 = p2a.predicted_position.position.x;
651 double y2 = p2a.predicted_position.position.y;
652
653 // Calculate the distance between the two interpolated points
654 const auto distance{std::hypot(x1 - x2, y1 - y2)};
655
656 smallest_dist = std::min(distance, smallest_dist);
657 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "Smallest_dist: " << smallest_dist << ", distance: " << distance << ", dt: " << dt
658 << ", x1: " << x1 << ", y1: " << y1
659 << ", x2: " << x2 << ", y2: " << y2
660 << ", p2a_t:" << std::to_string(p2a_t));
661
662 // Following "if logic" assumes the traj2 is a simple cv model, aka, traj2 point is a straight line over time.
663 // And current traj1 point is fixed in this iteration.
664 // Then once the distance between the two start to increase over traj2 iteration,
665 // the distance will always increase and it's unnecessary to continue the logic to find the smallest_dist
666 if (previous_distance_between_predictions < distance)
667 {
668 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "Stopping search here because the distance between predictions started to increase");
669 break;
670 }
671 previous_distance_between_predictions = distance;
672
673 if (i == 0 && j == 0 && distance > config_.collision_check_radius_in_m)
674 {
675 RCLCPP_DEBUG(nh_->get_logger(), "Too far away" );
676 return std::nullopt;
677 }
678
679 if (distance > collision_radius)
680 {
681 // continue searching for collision
682 continue;
683 }
684
685 GetCollisionResult collision_result;
686 collision_result.point1 = lanelet::BasicPoint2d(x1,y1);
687 collision_result.point2 = lanelet::BasicPoint2d(x2,y2);
688 collision_result.collision_time = rclcpp::Time(p2a.header.stamp);
689 return collision_result;
690 }
691 }
692
693 // No collision detected
694 return std::nullopt;
695 }
std::set< lanelet::Id > route_llt_ids_
double get_trajectory_duration(const carma_planning_msgs::msg::TrajectoryPlan &trajectory)
double collision_check_radius_in_m
double obstacle_zero_speed_threshold_in_ms

References YieldPluginConfig::collision_check_radius_in_m, yield_plugin::GetCollisionResult::collision_time, config_, yield_plugin::get_trajectory_duration(), process_bag::i, YieldPluginConfig::intervehicle_collision_distance_in_m, nh_, YieldPluginConfig::obstacle_zero_speed_threshold_in_ms, yield_plugin::GetCollisionResult::point1, yield_plugin::GetCollisionResult::point2, route_llt_ids_, carma_cooperative_perception::to_string(), and wm_.

Referenced by get_collision_time().

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

◆ get_collision_time()

std::optional< rclcpp::Time > yield_plugin::YieldPlugin::get_collision_time ( const carma_planning_msgs::msg::TrajectoryPlan &  original_tp,
const carma_perception_msgs::msg::ExternalObject &  curr_obstacle,
double  original_tp_max_speed 
)

Return collision time given two trajectories with one being external object with predicted steps.

Parameters
trajectory1trajectory of the ego vehicle
trajectory2trajectory of the obstacle
original_tp_max_speedmax speed of the original_tp to efficiently traverse through possible collision combination of the two trajectories NOTE: Currently curr_obstacle is assumed to be using a simple cv model to save computational performance
Returns
time_of_collision if collision detected, otherwise, std::nullopt

Definition at line 723 of file yield_plugin.cpp.

725 {
726 auto plan_start_time = get_trajectory_start_time(original_tp);
727
728 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "Object's back time: " << std::to_string(rclcpp::Time(curr_obstacle.predictions.back().header.stamp).seconds())
729 << ", plan_start_time: " << std::to_string(plan_start_time));
730
731 // do not process outdated objects
732 if (rclcpp::Time(curr_obstacle.predictions.back().header.stamp).seconds() <= plan_start_time)
733 {
734 return std::nullopt;
735 }
736
737 std::vector<carma_perception_msgs::msg::PredictedState> new_list;
738 carma_perception_msgs::msg::PredictedState curr_state;
739 // artificially include current position as one of the predicted states
740 curr_state.header.stamp = curr_obstacle.header.stamp;
741 curr_state.predicted_position.position.x = curr_obstacle.pose.pose.position.x;
742 curr_state.predicted_position.position.y = curr_obstacle.pose.pose.position.y;
743 // NOTE: predicted_velocity is not used for collision calculation, but timestamps
744 curr_state.predicted_velocity.linear.x = curr_obstacle.velocity.twist.linear.x;
745 curr_state.predicted_velocity.linear.y = curr_obstacle.velocity.twist.linear.y;
746 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "Object: " << curr_obstacle.id <<", type: " << static_cast<int>(curr_obstacle.object_type)
747 << ", speed_x: " << curr_obstacle.velocity.twist.linear.x << ", speed_y: " << curr_obstacle.velocity.twist.linear.y);
748 new_list.push_back(curr_state);
749 new_list.insert(new_list.end(), curr_obstacle.predictions.cbegin(), curr_obstacle.predictions.cend());
750
751 const auto collision_result = get_collision(original_tp, new_list, config_.intervehicle_collision_distance_in_m, original_tp_max_speed);
752
753 if (!collision_result)
754 {
755 // reset the consecutive clearance counter because no collision was detected at this iteration
756 consecutive_clearance_count_for_obstacles_[curr_obstacle.id] = 0;
757 return std::nullopt;
758 }
759
760 // if within collision radius, it is not a collision if obstacle is behind the vehicle despite being in collision radius
761 const double vehicle_downtrack = wm_->routeTrackPos(collision_result.value().point1).downtrack;
762 const double object_downtrack = wm_->routeTrackPos(collision_result.value().point2).downtrack;
763
764 if (is_object_behind_vehicle(curr_obstacle.id, collision_result.value().collision_time, vehicle_downtrack, object_downtrack))
765 {
766 RCLCPP_INFO_STREAM(nh_->get_logger(), "Confirmed that the object: " << curr_obstacle.id << " is behind the vehicle at timestamp " << std::to_string(collision_result.value().collision_time.seconds()));
767 return std::nullopt;
768 }
769
770 const auto distance{std::hypot(
771 collision_result.value().point1.x() - collision_result.value().point2.x(),
772 collision_result.value().point1.y() - collision_result.value().point2.y()
773 )}; //for debug
774
775 RCLCPP_WARN_STREAM(nh_->get_logger(), "Collision detected for object: " << curr_obstacle.id << ", at timestamp " << std::to_string(collision_result.value().collision_time.seconds()) <<
776 ", x: " << collision_result.value().point1.x() << ", y: " << collision_result.value().point1.y() <<
777 ", within actual downtrack distance: " << object_downtrack - vehicle_downtrack <<
778 ", and collision distance: " << distance);
779
780 return collision_result.value().collision_time;
781 }
std::optional< GetCollisionResult > get_collision(const carma_planning_msgs::msg::TrajectoryPlan &trajectory1, const std::vector< carma_perception_msgs::msg::PredictedState > &trajectory2, double collision_radius, double trajectory1_max_speed)
Return naive collision time and locations based on collision radius given two trajectories with one b...
std::unordered_map< uint32_t, int > consecutive_clearance_count_for_obstacles_
bool is_object_behind_vehicle(uint32_t object_id, const rclcpp::Time &collision_time, double vehicle_point, double object_downtrack)
Check if object location is behind the vehicle using estimates of the vehicle's length and route down...
double get_trajectory_start_time(const carma_planning_msgs::msg::TrajectoryPlan &trajectory)

References config_, consecutive_clearance_count_for_obstacles_, get_collision(), yield_plugin::get_trajectory_start_time(), YieldPluginConfig::intervehicle_collision_distance_in_m, is_object_behind_vehicle(), nh_, carma_cooperative_perception::to_string(), and wm_.

Referenced by get_collision_times_concurrently().

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

◆ get_collision_times_concurrently()

std::unordered_map< uint32_t, rclcpp::Time > yield_plugin::YieldPlugin::get_collision_times_concurrently ( const carma_planning_msgs::msg::TrajectoryPlan &  original_tp,
const std::vector< carma_perception_msgs::msg::ExternalObject > &  external_objects,
double  original_tp_max_speed 
)

Given the list of objects with predicted states, get all collision times concurrently using multi-threading.

Parameters
original_tptrajectory of the ego vehicle
external_objectslist of external objects with predicted states
original_tp_max_speedmax speed of the original_tp to efficiently traverse through possible collision combination of the two trajectories
Returns
mapping of objects' ids and their corresponding collision times (non-colliding objects are omitted)

Definition at line 783 of file yield_plugin.cpp.

785 {
786
787 std::unordered_map<uint32_t, std::future<std::optional<rclcpp::Time>>> futures;
788 std::unordered_map<uint32_t, rclcpp::Time> collision_times;
789
790 // Launch asynchronous tasks to check for collision times
791 for (const auto& object : external_objects) {
792 futures[object.id] = std::async(std::launch::async,[this, &original_tp, &object, &original_tp_max_speed]{
793 return get_collision_time(original_tp, object, original_tp_max_speed);
794 });
795 }
796
797 // Collect results from futures and update collision_times
798 for (const auto& object : external_objects) {
799 if (const auto collision_time{futures.at(object.id).get()}) {
800 collision_times[object.id] = collision_time.value();
801 }
802 }
803
804 return collision_times;
805 }
std::optional< rclcpp::Time > get_collision_time(const carma_planning_msgs::msg::TrajectoryPlan &original_tp, const carma_perception_msgs::msg::ExternalObject &curr_obstacle, double original_tp_max_speed)
Return collision time given two trajectories with one being external object with predicted steps.

References get_collision_time().

Referenced by get_earliest_collision_object_and_time().

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

◆ get_earliest_collision_object_and_time()

std::optional< std::pair< carma_perception_msgs::msg::ExternalObject, double > > yield_plugin::YieldPlugin::get_earliest_collision_object_and_time ( const carma_planning_msgs::msg::TrajectoryPlan &  original_tp,
const std::vector< carma_perception_msgs::msg::ExternalObject > &  external_objects 
)

Return the earliest collision object and time of collision pair from the given trajectory and list of external objects with predicted states. Function first filters obstacles based on whether if their any of predicted state will be on the route. Only then, the logic compares trajectory and predicted states.

Parameters
original_tptrajectory of the ego vehicle
external_objectslist of external objects with predicted states
Returns
earliest collision object and its collision time if collision detected. std::nullopt if no collision is detected or if route is not available.

Definition at line 807 of file yield_plugin.cpp.

809 {
810 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "ExternalObjects size: " << external_objects.size());
811
812 if (!wm_->getRoute())
813 {
814 RCLCPP_WARN(nh_->get_logger(), "Yield plugin was not able to analyze collision since route is not available! Please check if route is set");
815 return std::nullopt;
816 }
817
818 // save route Ids for faster access
819 for (const auto& llt: wm_->getRoute()->shortestPath())
820 {
821 // TODO: Enhancement https://github.com/usdot-fhwa-stol/carma-platform/issues/2316
822 route_llt_ids_.insert(llt.id());
823 }
824
825 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"External Object List (external_objects) size: " << external_objects.size());
826 const double original_max_speed = max_trajectory_speed(original_tp.trajectory_points, get_trajectory_end_time(original_tp));
827 std::unordered_map<uint32_t, rclcpp::Time> collision_times = get_collision_times_concurrently(original_tp,external_objects, original_max_speed);
828
829 if (collision_times.empty()) { return std::nullopt; }
830
831 const auto earliest_colliding_object_id{std::min_element(
832 std::cbegin(collision_times), std::cend(collision_times),
833 [](const auto & a, const auto & b){ return a.second < b.second; })->first};
834
835 const auto earliest_colliding_object{std::find_if(
836 std::cbegin(external_objects), std::cend(external_objects),
837 [&earliest_colliding_object_id](const auto & object) { return object.id == earliest_colliding_object_id; })};
838
839 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"earliest object x: " << earliest_colliding_object->velocity.twist.linear.x
840 << ", y: " << earliest_colliding_object->velocity.twist.linear.y);
841 return std::make_pair(*earliest_colliding_object, collision_times.at(earliest_colliding_object_id).seconds());
842
843 }
std::unordered_map< uint32_t, rclcpp::Time > get_collision_times_concurrently(const carma_planning_msgs::msg::TrajectoryPlan &original_tp, const std::vector< carma_perception_msgs::msg::ExternalObject > &external_objects, double original_tp_max_speed)
Given the list of objects with predicted states, get all collision times concurrently using multi-thr...
double max_trajectory_speed(const std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > &trajectory_points, double timestamp_in_sec_to_search_until) const
calculates the maximum speed in a set of tajectory points
double get_trajectory_end_time(const carma_planning_msgs::msg::TrajectoryPlan &trajectory)

References get_collision_times_concurrently(), yield_plugin::get_trajectory_end_time(), max_trajectory_speed(), nh_, route_llt_ids_, and wm_.

Referenced by update_traj_for_object().

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

◆ get_predicted_velocity_at_time()

double yield_plugin::YieldPlugin::get_predicted_velocity_at_time ( const geometry_msgs::msg::Twist &  object_velocity_in_map_frame,
const carma_planning_msgs::msg::TrajectoryPlan &  original_tp,
double  timestamp_in_sec_to_predict 
)

Given the object velocity in map frame with x,y components, this function returns the projected velocity along the trajectory at given time.

Parameters
object_velocity_in_map_frametrajectory of the ego vehicle
original_tptrajectory of the ego vehicle
timestamp_in_sec_to_predicttimestamp in seconds along the trajectory to return the projected velocity NOTE: returns the last point's speed if the specified time is past the trajectory's planning time
Returns
get_predicted_velocity_at_time

Definition at line 845 of file yield_plugin.cpp.

847 {
848 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "timestamp_in_sec_to_predict: " << std::to_string(timestamp_in_sec_to_predict) <<
849 ", trajectory_end_time: " << std::to_string(get_trajectory_end_time(original_tp)));
850
851 double point_b_time = 0.0;
852 carma_planning_msgs::msg::TrajectoryPlanPoint point_a;
853 carma_planning_msgs::msg::TrajectoryPlanPoint point_b;
854
855 // trajectory points' time is guaranteed to be increasing
856 // then find the corresponding point at timestamp_in_sec_to_predict
857 for (size_t i = 0; i < original_tp.trajectory_points.size() - 1; ++i)
858 {
859 point_a = original_tp.trajectory_points.at(i);
860 point_b = original_tp.trajectory_points.at(i + 1);
861 point_b_time = rclcpp::Time(point_b.target_time).seconds();
862 if (point_b_time >= timestamp_in_sec_to_predict)
863 {
864 break;
865 }
866 }
867
868 auto dx = point_b.x - point_a.x;
869 auto dy = point_b.y - point_a.y;
870 const tf2::Vector3 trajectory_direction(dx, dy, 0);
871
872 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "timestamp_in_sec_to_predict: " << std::to_string(timestamp_in_sec_to_predict)
873 << ", point_b_time: " << std::to_string(point_b_time)
874 << ", dx: " << dx << ", dy: " << dy << ", "
875 << ", object_velocity_in_map_frame.x: " << object_velocity_in_map_frame.linear.x
876 << ", object_velocity_in_map_frame.y: " << object_velocity_in_map_frame.linear.y);
877
878 if (trajectory_direction.length() < 0.001) //EPSILON
879 {
880 return 0.0;
881 }
882
883 const tf2::Vector3 object_direction(object_velocity_in_map_frame.linear.x, object_velocity_in_map_frame.linear.y, 0);
884
885 return tf2::tf2Dot(object_direction, trajectory_direction) / trajectory_direction.length();
886 }

References yield_plugin::get_trajectory_end_time(), process_bag::i, nh_, and carma_cooperative_perception::to_string().

Referenced by update_traj_for_object().

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

◆ get_relative_downtracks()

std::vector< double > yield_plugin::YieldPlugin::get_relative_downtracks ( const carma_planning_msgs::msg::TrajectoryPlan &  trajectory_plan) const

calculates distance between trajectory points in a plan

Parameters
trajectory_planinput trajectory plan
Returns
vector of relative distances between trajectory points

Definition at line 976 of file yield_plugin.cpp.

977 {
978 std::vector<double> downtracks;
979 downtracks.reserve(trajectory_plan.trajectory_points.size());
980 // relative downtrack distance of the fist Point is 0.0
981 downtracks.push_back(0.0);
982 for (size_t i=1; i < trajectory_plan.trajectory_points.size(); i++){
983
984 double dx = trajectory_plan.trajectory_points.at(i).x - trajectory_plan.trajectory_points.at(i-1).x;
985 double dy = trajectory_plan.trajectory_points.at(i).y - trajectory_plan.trajectory_points.at(i-1).y;
986 downtracks.push_back(sqrt(dx*dx + dy*dy));
987 }
988 return downtracks;
989 }

References process_bag::i.

Referenced by generate_JMT_trajectory().

Here is the caller graph for this function:

◆ is_object_behind_vehicle()

bool yield_plugin::YieldPlugin::is_object_behind_vehicle ( uint32_t  object_id,
const rclcpp::Time &  collision_time,
double  vehicle_point,
double  object_downtrack 
)

Check if object location is behind the vehicle using estimates of the vehicle's length and route downtracks.

Parameters
object_idobject id to use for the consecutive_clearance_count_for_obstacles_
collision_timepredicted time of collision
vehicle_downtrackat the time of collision
object_downtrackat the time of collision NOTE: Uses internal counter low pass filter to confirm the object is behind only if it counted continuously above config_.consecutive_clearance_count_for_obstacles_threshold
Returns
return true if object is behind the vehicle

Definition at line 697 of file yield_plugin.cpp.

698 {
699 const auto previous_clearance_count = consecutive_clearance_count_for_obstacles_[object_id];
700 // if the object's location is half a length of the vehicle past its rear-axle, it is considered behind
701 // half a length of the vehicle to conservatively estimate the rear axle to rear bumper length
702 if (object_downtrack < vehicle_downtrack - config_.vehicle_length / 2)
703 {
705 RCLCPP_INFO_STREAM(nh_->get_logger(), "Detected an object nearby might be behind the vehicle at timestamp: " << std::to_string(collision_time.seconds()) <<
706 ", and consecutive_clearance_count_for obstacle: " << object_id << ", is: " << consecutive_clearance_count_for_obstacles_[object_id]);
707 }
708 // confirmed false positive for a collision
710 {
711 return true;
712 }
713 // if the clearance counter didn't increase by this point, true collision was detected
714 // therefore reset the consecutive clearance counter as it is no longer consecutive
715 if (consecutive_clearance_count_for_obstacles_[object_id] == previous_clearance_count)
716 {
718 }
719
720 return false;
721 }
int consecutive_clearance_count_for_obstacles_threshold

References config_, consecutive_clearance_count_for_obstacles_, YieldPluginConfig::consecutive_clearance_count_for_obstacles_threshold, nh_, carma_cooperative_perception::to_string(), and YieldPluginConfig::vehicle_length.

Referenced by get_collision_time().

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

◆ lookup_ecef_to_map_transform()

void yield_plugin::YieldPlugin::lookup_ecef_to_map_transform ( )

Looks up the transform between map and earth frames, and sets the member variable.

◆ max_trajectory_speed()

double yield_plugin::YieldPlugin::max_trajectory_speed ( const std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > &  trajectory_points,
double  timestamp_in_sec_to_search_until 
) const

calculates the maximum speed in a set of tajectory points

Parameters
trajectory_pointstrajectory points

\param timestamp_in_sec_to_search_until before which to look for max trajectory speed

Returns
maximum speed

Definition at line 1013 of file yield_plugin.cpp.

1014 {
1015 double max_speed = 0;
1016 for(size_t i = 0; i < trajectory_points.size() - 2; i++ )
1017 {
1018 double dx = trajectory_points.at(i + 1).x - trajectory_points.at(i).x;
1019 double dy = trajectory_points.at(i + 1).y - trajectory_points.at(i).y;
1020 double d = sqrt(dx*dx + dy*dy);
1021 double t = (rclcpp::Time(trajectory_points.at(i + 1).target_time).seconds() - rclcpp::Time(trajectory_points.at(i).target_time).seconds());
1022 double v = d/t;
1023 if(v > max_speed)
1024 {
1025 max_speed = v;
1026 }
1027 if (rclcpp::Time(trajectory_points.at(i + 1).target_time).seconds() >= timestamp_in_sec_to_search_until)
1028 {
1029 break;
1030 }
1031
1032 }
1033 return max_speed;
1034 }

References process_bag::i.

Referenced by get_earliest_collision_object_and_time(), update_traj_for_cooperative_behavior(), and update_traj_for_object().

Here is the caller graph for this function:

◆ mobilityrequest_cb()

void yield_plugin::YieldPlugin::mobilityrequest_cb ( const carma_v2x_msgs::msg::MobilityRequest::UniquePtr  msg)

callback for mobility request

Parameters
msgmobility request message

Definition at line 153 of file yield_plugin.cpp.

154 {
155 carma_v2x_msgs::msg::MobilityRequest incoming_request = *msg;
156 carma_planning_msgs::msg::LaneChangeStatus lc_status_msg;
157 if (incoming_request.strategy == "carma/cooperative-lane-change")
158 {
159 if (!map_projector_) {
160 RCLCPP_ERROR(nh_->get_logger(),"Cannot process mobility request as map projection is not yet set!");
161 return;
162 }
163 if (incoming_request.plan_type.type == carma_v2x_msgs::msg::PlanType::CHANGE_LANE_LEFT || incoming_request.plan_type.type == carma_v2x_msgs::msg::PlanType::CHANGE_LANE_RIGHT)
164 {
165 RCLCPP_DEBUG(nh_->get_logger(),"Cooperative Lane Change Request Received");
166 lc_status_msg.status = carma_planning_msgs::msg::LaneChangeStatus::REQUEST_RECEIVED;
167 lc_status_msg.description = "Received lane merge request";
168
169 if (incoming_request.m_header.recipient_id == config_.vehicle_id)
170 {
171 RCLCPP_DEBUG(nh_->get_logger(),"CLC Request correctly received");
172 }
173
174 // extract mobility header
175 std::string req_sender_id = incoming_request.m_header.sender_id;
176 std::string req_plan_id = incoming_request.m_header.plan_id;
177 // extract mobility request
178 carma_v2x_msgs::msg::LocationECEF ecef_location = incoming_request.location;
179 carma_v2x_msgs::msg::Trajectory incoming_trajectory = incoming_request.trajectory;
180 std::string req_strategy_params = incoming_request.strategy_params;
181 clc_urgency_ = incoming_request.urgency;
182 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"received urgency: " << clc_urgency_);
183
184 // Parse strategy parameters
185 using boost::property_tree::ptree;
186 ptree pt;
187 std::istringstream strstream(req_strategy_params);
188 boost::property_tree::json_parser::read_json(strstream, pt);
189 int req_traj_speed_full = pt.get<int>("s");
190 int req_traj_fractional = pt.get<int>("f");
191 int start_lanelet_id = pt.get<int>("sl");
192 int end_lanelet_id = pt.get<int>("el");
193 double req_traj_speed = static_cast<double>(req_traj_speed_full) + static_cast<double>(req_traj_fractional)/10.0;
194 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"req_traj_speed" << req_traj_speed);
195 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"start_lanelet_id" << start_lanelet_id);
196 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"end_lanelet_id" << end_lanelet_id);
197
198 std::vector<lanelet::BasicPoint2d> req_traj_plan = {};
199
200 req_traj_plan = convert_eceftrajectory_to_mappoints(incoming_trajectory);
201
202 double req_expiration_sec = static_cast<double>(incoming_request.expiration);
203 double current_time_sec = nh_->now().seconds();
204
205 bool response_to_clc_req = false;
206 // ensure there is enough time for the yield
207 double req_plan_time = req_expiration_sec - current_time_sec;
208 double req_timestamp = static_cast<double>(incoming_request.m_header.timestamp) / 1000.0 - current_time_sec;
209 set_incoming_request_info(req_traj_plan, req_traj_speed, req_plan_time, req_timestamp);
210
211
212 if (req_expiration_sec - current_time_sec >= config_.min_obj_avoidance_plan_time_in_s && cooperative_request_acceptable_)
213 {
215 lc_status_msg.status = carma_planning_msgs::msg::LaneChangeStatus::REQUEST_ACCEPTED;
216 lc_status_msg.description = "Accepted lane merge request";
217 response_to_clc_req = true;
218 RCLCPP_DEBUG(nh_->get_logger(),"CLC accepted");
219 }
220 else
221 {
222 lc_status_msg.status = carma_planning_msgs::msg::LaneChangeStatus::REQUEST_REJECTED;
223 lc_status_msg.description = "Rejected lane merge request";
224 response_to_clc_req = false;
225 RCLCPP_DEBUG(nh_->get_logger(),"CLC rejected");
226 }
227 carma_v2x_msgs::msg::MobilityResponse outgoing_response = compose_mobility_response(req_sender_id, req_plan_id, response_to_clc_req);
228 mobility_response_publisher_(outgoing_response);
229 lc_status_msg.status = carma_planning_msgs::msg::LaneChangeStatus::RESPONSE_SENT;
230 RCLCPP_DEBUG(nh_->get_logger(),"response sent");
231 }
232 }
233 lc_status_publisher_(lc_status_msg);
234
235 }
void set_incoming_request_info(std::vector< lanelet::BasicPoint2d > req_trajectory, double req_speed, double req_planning_time, double req_timestamp)
set values for member variables related to cooperative behavior
std::vector< lanelet::BasicPoint2d > convert_eceftrajectory_to_mappoints(const carma_v2x_msgs::msg::Trajectory &ecef_trajectory) const
convert a carma trajectory from ecef frame to map frame ecef trajectory consists of the point and a s...
carma_v2x_msgs::msg::MobilityResponse compose_mobility_response(const std::string &resp_recipient_id, const std::string &req_plan_id, bool response) const
compose a mobility response message
double min_obj_avoidance_plan_time_in_s

References clc_urgency_, compose_mobility_response(), config_, convert_eceftrajectory_to_mappoints(), cooperative_request_acceptable_, lc_status_publisher_, map_projector_, YieldPluginConfig::min_obj_avoidance_plan_time_in_s, mobility_response_publisher_, nh_, set_incoming_request_info(), timesteps_since_last_req_, and YieldPluginConfig::vehicle_id.

Referenced by yield_plugin::YieldPluginNode::on_configure_plugin().

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

◆ plan_trajectory_callback()

void yield_plugin::YieldPlugin::plan_trajectory_callback ( carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr  req,
carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr  resp 
)

Service callback for trajectory planning.

Parameters
srv_headerheader
reqThe service request
respThe service response

Definition at line 252 of file yield_plugin.cpp.

255{
256 RCLCPP_DEBUG(nh_->get_logger(),"Yield_plugin was called!");
257 if (req->initial_trajectory_plan.trajectory_points.size() < 2){
258 throw std::invalid_argument("Empty Trajectory received by Yield");
259 }
260 rclcpp::Clock system_clock(RCL_SYSTEM_TIME);
261 rclcpp::Time start_time = system_clock.now(); // Start timing the execution time for planning so it can be logged
262
263 carma_planning_msgs::msg::TrajectoryPlan original_trajectory = req->initial_trajectory_plan;
264 carma_planning_msgs::msg::TrajectoryPlan yield_trajectory;
265
266
267 double initial_velocity = req->vehicle_state.longitudinal_vel;
268 // If vehicle_state is stopped, non-zero velocity from the trajectory
269 // should be used. Otherwise, vehicle will not move.
270 if (initial_velocity < EPSILON)
271 {
272 initial_velocity = original_trajectory.initial_longitudinal_velocity;
273 }
274
275 // seperating cooperative yield with regular object detection for better performance.
277 {
278 RCLCPP_DEBUG(nh_->get_logger(),"Only consider high urgency clc");
280 {
281 RCLCPP_DEBUG(nh_->get_logger(),"Yield for CLC. We haven't received an updated negotiation this timestep");
282 yield_trajectory = update_traj_for_cooperative_behavior(original_trajectory, initial_velocity);
284 }
285 else
286 {
287 RCLCPP_DEBUG(nh_->get_logger(),"unreliable CLC communication, switching to object avoidance");
288 yield_trajectory = update_traj_for_object(original_trajectory, external_objects_, initial_velocity); // Compute the trajectory
289 }
290 }
291 else
292 {
293 RCLCPP_DEBUG(nh_->get_logger(),"Yield for object avoidance");
294 yield_trajectory = update_traj_for_object(original_trajectory, external_objects_, initial_velocity); // Compute the trajectory
295 }
296
297 // return original trajectory if no difference in trajectory points a.k.a no collision
298 if (fabs(get_trajectory_end_time(original_trajectory) - get_trajectory_end_time(yield_trajectory)) < EPSILON)
299 {
300 resp->trajectory_plan = original_trajectory;
301 }
302 else
303 {
304 yield_trajectory.header.frame_id = "map";
305 yield_trajectory.header.stamp = nh_->now();
306 yield_trajectory.trajectory_id = original_trajectory.trajectory_id;
307 resp->trajectory_plan = yield_trajectory;
308 }
309
310 rclcpp::Time end_time = system_clock.now(); // Planning complete
311
312 auto duration = end_time - start_time;
313 RCLCPP_DEBUG_STREAM(nh_->get_logger(), "ExecutionTime: " << std::to_string(duration.seconds()));
314
315 }
carma_planning_msgs::msg::TrajectoryPlan update_traj_for_object(const carma_planning_msgs::msg::TrajectoryPlan &original_tp, const std::vector< carma_perception_msgs::msg::ExternalObject > &external_objects, double initial_velocity)
trajectory is modified to safely avoid obstacles on the road
carma_planning_msgs::msg::TrajectoryPlan update_traj_for_cooperative_behavior(const carma_planning_msgs::msg::TrajectoryPlan &original_tp, double current_speed)
update trajectory for yielding to an incoming cooperative behavior
std::vector< carma_perception_msgs::msg::ExternalObject > external_objects_
bool enable_cooperative_behavior

References YieldPluginConfig::acceptable_passed_timesteps, YieldPluginConfig::acceptable_urgency, clc_urgency_, config_, YieldPluginConfig::enable_cooperative_behavior, EPSILON, external_objects_, yield_plugin::get_trajectory_end_time(), nh_, timesteps_since_last_req_, carma_cooperative_perception::to_string(), update_traj_for_cooperative_behavior(), and update_traj_for_object().

Here is the call graph for this function:

◆ polynomial_calc()

double yield_plugin::YieldPlugin::polynomial_calc ( std::vector< double >  coeff,
double  x 
) const

calculate quintic polynomial equation for a given x

Parameters
coeffvector including polynomial coefficiencrs
xinput variable to the polynomial
Returns
value of polynomial for given input

Definition at line 991 of file yield_plugin.cpp.

992 {
993 double result = 0;
994 for (size_t i = 0; i < coeff.size(); i++)
995 {
996 double value = coeff.at(i) * pow(x, static_cast<int>(coeff.size() - 1 - i));
997 result = result + value;
998 }
999 return result;
1000 }

References process_bag::i, and process_traj_logs::x.

Referenced by generate_JMT_trajectory().

Here is the caller graph for this function:

◆ polynomial_calc_d()

double yield_plugin::YieldPlugin::polynomial_calc_d ( std::vector< double >  coeff,
double  x 
) const

calculate derivative of quintic polynomial equation for a given x

Parameters
coeffvector including polynomial coefficiencrs
xinput variable to the polynomial
Returns
value of derivative polynomial for given input

Definition at line 1002 of file yield_plugin.cpp.

1003 {
1004 double result = 0;
1005 for (size_t i = 0; i < coeff.size()-1; i++)
1006 {
1007 double value = static_cast<int>(coeff.size() - 1 - i) * coeff.at(i) * pow(x, static_cast<int>(coeff.size() - 2 - i));
1008 result = result + value;
1009 }
1010 return result;
1011 }

References process_bag::i, and process_traj_logs::x.

Referenced by generate_JMT_trajectory().

Here is the caller graph for this function:

◆ set_external_objects()

void yield_plugin::YieldPlugin::set_external_objects ( const std::vector< carma_perception_msgs::msg::ExternalObject > &  object_list)

Setter for external objects with predictions in the environment.

Parameters
object_listThe object list.

Definition at line 1070 of file yield_plugin.cpp.

1071 {
1072 external_objects_ = object_list;
1073 }

References external_objects_.

◆ set_georeference_string()

void yield_plugin::YieldPlugin::set_georeference_string ( const std::string &  georeference)

Setter for map projection string to define lat/lon -> map conversion.

Parameters
georeferenceThe proj string defining the projection.

Definition at line 1061 of file yield_plugin.cpp.

1062 {
1063 if (georeference_ != georeference)
1064 {
1065 georeference_ = georeference;
1066 map_projector_ = std::make_shared<lanelet::projection::LocalFrameProjector>(georeference.c_str()); // Build projector from proj string
1067 }
1068 }

References georeference_, and map_projector_.

◆ set_incoming_request_info()

void yield_plugin::YieldPlugin::set_incoming_request_info ( std::vector< lanelet::BasicPoint2d >  req_trajectory,
double  req_speed,
double  req_planning_time,
double  req_timestamp 
)

set values for member variables related to cooperative behavior

Parameters
req_trajectoryrequested trajectory
req_speedspeed of requested cooperative behavior
req_planning_timeplanning time for the requested cooperative behavior
req_timestampthe mobility request time stamp

Definition at line 237 of file yield_plugin.cpp.

238 {
239 req_trajectory_points_ = req_trajectory;
240 req_target_speed_ = req_speed;
241 req_target_plan_time_ = req_planning_time;
242 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"req_target_plan_time_" << req_target_plan_time_);
243 req_timestamp_ = req_timestamp;
244 }
std::vector< lanelet::BasicPoint2d > req_trajectory_points_

References nh_, req_target_plan_time_, req_target_speed_, req_timestamp_, and req_trajectory_points_.

Referenced by mobilityrequest_cb().

Here is the caller graph for this function:

◆ update_traj_for_cooperative_behavior()

carma_planning_msgs::msg::TrajectoryPlan yield_plugin::YieldPlugin::update_traj_for_cooperative_behavior ( const carma_planning_msgs::msg::TrajectoryPlan &  original_tp,
double  current_speed 
)

update trajectory for yielding to an incoming cooperative behavior

Parameters
original_tporiginal trajectory plan
current_speedcurrent speed of the vehicle
Returns
updated trajectory for cooperative behavior

Definition at line 317 of file yield_plugin.cpp.

318 {
319 carma_planning_msgs::msg::TrajectoryPlan cooperative_trajectory;
320
321 double initial_pos = 0;
322 double goal_pos;
323 double initial_velocity = current_speed;
324 double goal_velocity = req_target_speed_;
325 double planning_time = req_target_plan_time_;
326
327 std::vector<lanelet::BasicPoint2d> host_traj_points = {};
328 for (size_t i=0; i<original_tp.trajectory_points.size(); i++)
329 {
330 lanelet::BasicPoint2d traj_point;
331 traj_point.x() = original_tp.trajectory_points.at(i).x;
332 traj_point.y() = original_tp.trajectory_points.at(i).y;
333 host_traj_points.push_back(traj_point);
334 }
335
336 std::vector<std::pair<int, lanelet::BasicPoint2d>> intersection_points = detect_trajectories_intersection(host_traj_points, req_trajectory_points_);
337 if (!intersection_points.empty())
338 {
339 lanelet::BasicPoint2d intersection_point = intersection_points[0].second;
340 double dx = original_tp.trajectory_points[0].x - intersection_point.x();
341 double dy = original_tp.trajectory_points[0].y - intersection_point.y();
342 // check if a digital_gap is available
343 double digital_gap = check_traj_for_digital_min_gap(original_tp);
344 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"digital_gap: " << digital_gap);
345 goal_pos = sqrt(dx*dx + dy*dy) - config_.minimum_safety_gap_in_meters;
346 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"Goal position (goal_pos): " << goal_pos);
347 double collision_time = req_timestamp_ + (intersection_points[0].first * ecef_traj_timestep_) - config_.safety_collision_time_gap_in_s;
348 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"req time stamp: " << req_timestamp_);
349 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"Collision time: " << collision_time);
350 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"intersection num: " << intersection_points[0].first);
351 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"Planning time: " << planning_time);
352 // calculate distance traveled from beginning of trajectory to collision point
353 double dx2 = intersection_point.x() - req_trajectory_points_[0].x();
354 double dy2 = intersection_point.y() - req_trajectory_points_[0].y();
355 // calculate incoming trajectory speed from time and distance between trajectory points
356 double incoming_trajectory_speed = sqrt(dx2*dx2 + dy2*dy2)/(intersection_points[0].first * ecef_traj_timestep_);
357 // calculate goal velocity from request trajectory
358 goal_velocity = std::min(goal_velocity, incoming_trajectory_speed);
359 double min_time = (initial_velocity - goal_velocity)/config_.yield_max_deceleration_in_ms2;
360
361 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"goal_velocity: " << goal_velocity);
362 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"incoming_trajectory_speed: " << incoming_trajectory_speed);
363
364 if (planning_time > min_time)
365 {
367 double original_max_speed = max_trajectory_speed(original_tp.trajectory_points, get_trajectory_end_time(original_tp));
368 cooperative_trajectory = generate_JMT_trajectory(original_tp, initial_pos, goal_pos, initial_velocity, goal_velocity, planning_time, original_max_speed);
369 }
370 else
371 {
373 RCLCPP_DEBUG(nh_->get_logger(),"The incoming requested trajectory is rejected, due to insufficient gap");
374 cooperative_trajectory = original_tp;
375 }
376
377 }
378 else
379 {
381 RCLCPP_DEBUG(nh_->get_logger(),"The incoming requested trajectory does not overlap with host vehicle's trajectory");
382 cooperative_trajectory = original_tp;
383 }
384
385 return cooperative_trajectory;
386 }
double check_traj_for_digital_min_gap(const carma_planning_msgs::msg::TrajectoryPlan &original_tp) const
checks trajectory for minimum gap associated with it
std::vector< std::pair< int, lanelet::BasicPoint2d > > detect_trajectories_intersection(std::vector< lanelet::BasicPoint2d > self_trajectory, std::vector< lanelet::BasicPoint2d > incoming_trajectory) const
detect intersection point(s) of two trajectories
carma_planning_msgs::msg::TrajectoryPlan generate_JMT_trajectory(const carma_planning_msgs::msg::TrajectoryPlan &original_tp, double initial_pos, double goal_pos, double initial_velocity, double goal_velocity, double planning_time, double original_max_speed)
generate a Jerk Minimizing Trajectory(JMT) with the provided start and end conditions
double yield_max_deceleration_in_ms2
double minimum_safety_gap_in_meters
double safety_collision_time_gap_in_s

References check_traj_for_digital_min_gap(), config_, cooperative_request_acceptable_, detect_trajectories_intersection(), ecef_traj_timestep_, generate_JMT_trajectory(), yield_plugin::get_trajectory_end_time(), process_bag::i, max_trajectory_speed(), YieldPluginConfig::minimum_safety_gap_in_meters, nh_, req_target_plan_time_, req_target_speed_, req_timestamp_, req_trajectory_points_, YieldPluginConfig::safety_collision_time_gap_in_s, and YieldPluginConfig::yield_max_deceleration_in_ms2.

Referenced by plan_trajectory_callback().

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

◆ update_traj_for_object()

carma_planning_msgs::msg::TrajectoryPlan yield_plugin::YieldPlugin::update_traj_for_object ( const carma_planning_msgs::msg::TrajectoryPlan &  original_tp,
const std::vector< carma_perception_msgs::msg::ExternalObject > &  external_objects,
double  initial_velocity 
)

trajectory is modified to safely avoid obstacles on the road

Parameters
original_tporiginal trajectory plan without object avoidance
current_speed_current speed of the vehicle

return modified trajectory plan

Definition at line 888 of file yield_plugin.cpp.

890 {
891 if (original_tp.trajectory_points.size() < 2)
892 {
893 RCLCPP_WARN(nh_->get_logger(), "Yield plugin received less than 2 points in update_traj_for_object, returning unchanged...");
894 return original_tp;
895 }
896
897 // Get earliest collision object
898 const auto earliest_collision_obj_pair = get_earliest_collision_object_and_time(original_tp, external_objects);
899
900 if (!earliest_collision_obj_pair)
901 {
902 RCLCPP_DEBUG(nh_->get_logger(),"No collision detected, so trajectory not modified.");
903 return original_tp;
904 }
905
906 carma_perception_msgs::msg::ExternalObject earliest_collision_obj = earliest_collision_obj_pair.value().first;
907 double earliest_collision_time_in_seconds = earliest_collision_obj_pair.value().second;
908
909 // Issue (https://github.com/usdot-fhwa-stol/carma-platform/issues/2155): If the yield_plugin can detect if the roadway object is moving along the route,
910 // it is able to plan yielding much earlier and smoother using on_route_vehicle_collision_horizon_in_s.
911
912 const lanelet::BasicPoint2d vehicle_point(original_tp.trajectory_points[0].x,original_tp.trajectory_points[0].y);
913 const double vehicle_downtrack = wm_->routeTrackPos(vehicle_point).downtrack;
914
915 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"vehicle_downtrack: " << vehicle_downtrack);
916
917 RCLCPP_WARN_STREAM(nh_->get_logger(),"Collision Detected!");
918
919 const lanelet::BasicPoint2d object_point(earliest_collision_obj.pose.pose.position.x, earliest_collision_obj.pose.pose.position.y);
920 const double object_downtrack = wm_->routeTrackPos(object_point).downtrack;
921
922 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"object_downtrack: " << object_downtrack);
923
924 const double object_downtrack_lead = std::max(0.0, object_downtrack - vehicle_downtrack);
925 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"object_downtrack_lead: " << object_downtrack_lead);
926
927 // The vehicle's goal velocity of the yielding behavior is to match the velocity of the object along the trajectory.
928 double goal_velocity = get_predicted_velocity_at_time(earliest_collision_obj.velocity.twist, original_tp, earliest_collision_time_in_seconds);
929 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"object's speed along trajectory at collision: " << goal_velocity);
930
931 // roadway object position
932 const double gap_time_until_min_gap_distance = std::max(0.0, object_downtrack_lead - config_.minimum_safety_gap_in_meters)/initial_velocity;
933
934 if (goal_velocity <= config_.obstacle_zero_speed_threshold_in_ms){
935 RCLCPP_WARN_STREAM(nh_->get_logger(),"The obstacle is not moving, goal velocity is set to 0 from: " << goal_velocity);
936 goal_velocity = 0.0;
937 }
938
939 // determine the safety inter-vehicle gap based on speed
940 double safety_gap = std::max(goal_velocity * gap_time_until_min_gap_distance, config_.minimum_safety_gap_in_meters);
941 if (!std::isnormal(safety_gap))
942 {
943 RCLCPP_WARN_STREAM(rclcpp::get_logger("yield_plugin"),"Detected non-normal (nan, inf, etc.) safety_gap."
944 "Making it desired safety gap configured at config_.minimum_safety_gap_in_meters: " << config_.minimum_safety_gap_in_meters);
946 }
948 {
949 // externally_commanded_safety_gap is desired distance gap commanded from external sources
950 // such as different plugin, map, or infrastructure depending on the use case
951 double externally_commanded_safety_gap = check_traj_for_digital_min_gap(original_tp);
952 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"externally_commanded_safety_gap: " << externally_commanded_safety_gap);
953 // if a digital gap is available, it is replaced as safety gap
954 safety_gap = std::max(safety_gap, externally_commanded_safety_gap);
955 }
956
957 const double goal_pos = std::max(0.0, object_downtrack_lead - safety_gap - config_.vehicle_length);
958 const double initial_pos = 0.0; //relative initial position (first trajectory point)
959 const double original_max_speed = max_trajectory_speed(original_tp.trajectory_points, earliest_collision_time_in_seconds);
960 const double delta_v_max = fabs(goal_velocity - original_max_speed);
961 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"delta_v_max: " << delta_v_max << ", safety_gap: " << safety_gap);
962
963 const double time_required_for_comfortable_decel_in_s = config_.acceleration_adjustment_factor * 2 * goal_pos / delta_v_max;
964 const double min_time_required_for_comfortable_decel_in_s = delta_v_max / config_.yield_max_deceleration_in_ms2;
965
966 // planning time for object avoidance
967 double planning_time_in_s = std::max({config_.min_obj_avoidance_plan_time_in_s, time_required_for_comfortable_decel_in_s, min_time_required_for_comfortable_decel_in_s});
968 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"time_required_for_comfortable_decel_in_s: " << time_required_for_comfortable_decel_in_s << ", min_time_required_for_comfortable_decel_in_s: " << min_time_required_for_comfortable_decel_in_s);
969
970 RCLCPP_DEBUG_STREAM(nh_->get_logger(),"Object avoidance planning time: " << planning_time_in_s);
971
972 return generate_JMT_trajectory(original_tp, initial_pos, goal_pos, initial_velocity, goal_velocity, planning_time_in_s, original_max_speed);
973 }
double get_predicted_velocity_at_time(const geometry_msgs::msg::Twist &object_velocity_in_map_frame, const carma_planning_msgs::msg::TrajectoryPlan &original_tp, double timestamp_in_sec_to_predict)
Given the object velocity in map frame with x,y components, this function returns the projected veloc...
std::optional< std::pair< carma_perception_msgs::msg::ExternalObject, double > > get_earliest_collision_object_and_time(const carma_planning_msgs::msg::TrajectoryPlan &original_tp, const std::vector< carma_perception_msgs::msg::ExternalObject > &external_objects)
Return the earliest collision object and time of collision pair from the given trajectory and list of...
double acceleration_adjustment_factor

References YieldPluginConfig::acceleration_adjustment_factor, check_traj_for_digital_min_gap(), config_, YieldPluginConfig::enable_adjustable_gap, generate_JMT_trajectory(), get_earliest_collision_object_and_time(), get_predicted_velocity_at_time(), max_trajectory_speed(), YieldPluginConfig::min_obj_avoidance_plan_time_in_s, YieldPluginConfig::minimum_safety_gap_in_meters, nh_, YieldPluginConfig::obstacle_zero_speed_threshold_in_ms, YieldPluginConfig::vehicle_length, wm_, and YieldPluginConfig::yield_max_deceleration_in_ms2.

Referenced by plan_trajectory_callback().

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

Member Data Documentation

◆ clc_urgency_

int yield_plugin::YieldPlugin::clc_urgency_ = 0
private

Definition at line 329 of file yield_plugin.hpp.

Referenced by mobilityrequest_cb(), and plan_trajectory_callback().

◆ config_

◆ consecutive_clearance_count_for_obstacles_

std::unordered_map<uint32_t, int> yield_plugin::YieldPlugin::consecutive_clearance_count_for_obstacles_
private

Definition at line 319 of file yield_plugin.hpp.

Referenced by get_collision_time(), and is_object_behind_vehicle().

◆ cooperative_request_acceptable_

bool yield_plugin::YieldPlugin::cooperative_request_acceptable_ = false
private

Definition at line 321 of file yield_plugin.hpp.

Referenced by mobilityrequest_cb(), and update_traj_for_cooperative_behavior().

◆ current_speed_

double yield_plugin::YieldPlugin::current_speed_
private

Definition at line 335 of file yield_plugin.hpp.

◆ ecef_traj_timestep_

double yield_plugin::YieldPlugin::ecef_traj_timestep_ = 0.1
private

Definition at line 332 of file yield_plugin.hpp.

Referenced by update_traj_for_cooperative_behavior().

◆ external_objects_

std::vector<carma_perception_msgs::msg::ExternalObject> yield_plugin::YieldPlugin::external_objects_
private

Definition at line 318 of file yield_plugin.hpp.

Referenced by plan_trajectory_callback(), and set_external_objects().

◆ georeference_

std::string yield_plugin::YieldPlugin::georeference_ {""}
private

Definition at line 339 of file yield_plugin.hpp.

Referenced by set_georeference_string().

◆ host_bsm_id_

std::string yield_plugin::YieldPlugin::host_bsm_id_
private

Definition at line 337 of file yield_plugin.hpp.

Referenced by bsm_cb(), and compose_mobility_response().

◆ host_vehicle_size

geometry_msgs::msg::Vector3 yield_plugin::YieldPlugin::host_vehicle_size
private

Definition at line 334 of file yield_plugin.hpp.

◆ lc_status_publisher_

LaneChangeStatusCB yield_plugin::YieldPlugin::lc_status_publisher_
private

Definition at line 314 of file yield_plugin.hpp.

Referenced by mobilityrequest_cb().

◆ map_projector_

std::shared_ptr<lanelet::projection::LocalFrameProjector> yield_plugin::YieldPlugin::map_projector_
private

◆ mobility_response_publisher_

MobilityResponseCB yield_plugin::YieldPlugin::mobility_response_publisher_
private

Definition at line 313 of file yield_plugin.hpp.

Referenced by mobilityrequest_cb().

◆ nh_

◆ previous_llt_id_

lanelet::Id yield_plugin::YieldPlugin::previous_llt_id_
private

Definition at line 317 of file yield_plugin.hpp.

◆ req_target_plan_time_

double yield_plugin::YieldPlugin::req_target_plan_time_ = 0
private

◆ req_target_speed_

double yield_plugin::YieldPlugin::req_target_speed_ = 0
private

◆ req_timestamp_

double yield_plugin::YieldPlugin::req_timestamp_ = 0
private

◆ req_trajectory_points_

std::vector<lanelet::BasicPoint2d> yield_plugin::YieldPlugin::req_trajectory_points_
private

◆ route_llt_ids_

std::set<lanelet::Id> yield_plugin::YieldPlugin::route_llt_ids_
private

Definition at line 316 of file yield_plugin.hpp.

Referenced by get_collision(), and get_earliest_collision_object_and_time().

◆ timesteps_since_last_req_

int yield_plugin::YieldPlugin::timesteps_since_last_req_ = 0
private

Definition at line 328 of file yield_plugin.hpp.

Referenced by mobilityrequest_cb(), and plan_trajectory_callback().

◆ wm_


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