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 Namespace Reference

Classes

struct  GetCollisionResult
 Convenience class for saving collision results. More...
 
struct  PointSpeedPair
 Convenience class for pairing 2d points with speeds. More...
 
class  YieldPlugin
 Class containing primary business logic for the In-Lane Cruising Plugin. More...
 
class  YieldPluginNode
 ROS node for the YieldPlugin. More...
 

Typedefs

using MobilityResponseCB = std::function< void(const carma_v2x_msgs::msg::MobilityResponse &)>
 
using LaneChangeStatusCB = std::function< void(const carma_planning_msgs::msg::LaneChangeStatus &)>
 

Functions

def generate_launch_description ()
 
double get_trajectory_end_time (const carma_planning_msgs::msg::TrajectoryPlan &trajectory)
 
double get_trajectory_start_time (const carma_planning_msgs::msg::TrajectoryPlan &trajectory)
 
double get_trajectory_duration (const carma_planning_msgs::msg::TrajectoryPlan &trajectory)
 
double get_trajectory_duration (const std::vector< carma_perception_msgs::msg::PredictedState > &trajectory)
 
double get_smallest_time_step_of_traj (const carma_planning_msgs::msg::TrajectoryPlan &original_tp)
 

Typedef Documentation

◆ LaneChangeStatusCB

using yield_plugin::LaneChangeStatusCB = typedef std::function<void(const carma_planning_msgs::msg::LaneChangeStatus&)>

Definition at line 52 of file yield_plugin.hpp.

◆ MobilityResponseCB

using yield_plugin::MobilityResponseCB = typedef std::function<void(const carma_v2x_msgs::msg::MobilityResponse&)>

Definition at line 51 of file yield_plugin.hpp.

Function Documentation

◆ generate_launch_description()

def yield_plugin.generate_launch_description ( )

Definition at line 31 of file yield_plugin.launch.py.

32
33 # Declare the log_level launch argument
34 log_level = LaunchConfiguration('log_level')
35 declare_log_level_arg = DeclareLaunchArgument(
36 name ='log_level', default_value='DEBUG')
37
38 # Get parameter file path
39 param_file_path = os.path.join(
40 get_package_share_directory('yield_plugin'), 'config/parameters.yaml')
41
42 # Launch node(s) in a carma container to allow logging to be configured
43 container = ComposableNodeContainer(
44 package='carma_ros2_utils',
45 name='yield_plugin_container',
46 namespace=GetCurrentNamespace(),
47 executable='carma_component_container_mt',
48 composable_node_descriptions=[
49
50 # Launch the core node(s)
51 ComposableNode(
52 package='yield_plugin',
53 plugin='yield_plugin::YieldPluginNode',
54 name='yield_plugin',
55 extra_arguments=[
56 {'use_intra_process_comms': True},
57 {'--log-level' : log_level }
58 ],
59 parameters=[ param_file_path ]
60 ),
61 ]
62 )
63
64 return LaunchDescription([
65 declare_log_level_arg,
66 container
67 ])
def generate_launch_description()

◆ get_smallest_time_step_of_traj()

double yield_plugin::get_smallest_time_step_of_traj ( const carma_planning_msgs::msg::TrajectoryPlan &  original_tp)

Definition at line 388 of file yield_plugin.cpp.

389 {
390 double smallest_time_step = std::numeric_limits<double>::infinity();
391 for (size_t i = 0; i < original_tp.trajectory_points.size() - 1; i ++)
392 {
393 smallest_time_step = std::min(smallest_time_step,
394 (rclcpp::Time(original_tp.trajectory_points.at(i + 1).target_time)
395 - rclcpp::Time(original_tp.trajectory_points.at(i).target_time)).seconds());
396 }
397 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("yield_plugin"),"smallest_time_step: " << smallest_time_step);
398
399 return smallest_time_step;
400 }

References process_bag::i.

Referenced by yield_plugin::YieldPlugin::generate_JMT_trajectory().

Here is the caller graph for this function:

◆ get_trajectory_duration() [1/2]

double yield_plugin::get_trajectory_duration ( const carma_planning_msgs::msg::TrajectoryPlan &  trajectory)

Definition at line 63 of file yield_plugin.cpp.

64 {
65 return fabs(get_trajectory_end_time(trajectory) - get_trajectory_start_time(trajectory));
66 }
double get_trajectory_start_time(const carma_planning_msgs::msg::TrajectoryPlan &trajectory)
double get_trajectory_end_time(const carma_planning_msgs::msg::TrajectoryPlan &trajectory)

References get_trajectory_end_time(), and get_trajectory_start_time().

Referenced by yield_plugin::YieldPlugin::get_collision().

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

◆ get_trajectory_duration() [2/2]

double yield_plugin::get_trajectory_duration ( const std::vector< carma_perception_msgs::msg::PredictedState > &  trajectory)

Definition at line 68 of file yield_plugin.cpp.

69 {
70 return (rclcpp::Time(trajectory.back().header.stamp) - rclcpp::Time(trajectory.front().header.stamp)).seconds();
71 }

◆ get_trajectory_end_time()

double yield_plugin::get_trajectory_end_time ( const carma_planning_msgs::msg::TrajectoryPlan &  trajectory)

Definition at line 53 of file yield_plugin.cpp.

54 {
55 return rclcpp::Time(trajectory.trajectory_points.back().target_time).seconds();
56 }

Referenced by yield_plugin::YieldPlugin::get_earliest_collision_object_and_time(), yield_plugin::YieldPlugin::get_predicted_velocity_at_time(), get_trajectory_duration(), yield_plugin::YieldPlugin::plan_trajectory_callback(), and yield_plugin::YieldPlugin::update_traj_for_cooperative_behavior().

Here is the caller graph for this function:

◆ get_trajectory_start_time()

double yield_plugin::get_trajectory_start_time ( const carma_planning_msgs::msg::TrajectoryPlan &  trajectory)

Definition at line 58 of file yield_plugin.cpp.

59 {
60 return rclcpp::Time(trajectory.trajectory_points.front().target_time).seconds();
61 }

Referenced by yield_plugin::YieldPlugin::get_collision_time(), and get_trajectory_duration().

Here is the caller graph for this function: