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.
YieldPluginConfig Struct Reference

Stuct containing the algorithm configuration values for the YieldPluginConfig. More...

#include <yield_config.hpp>

Collaboration diagram for YieldPluginConfig:
Collaboration graph

Public Attributes

double acceleration_adjustment_factor = 4.0
 
double on_route_vehicle_collision_horizon_in_s = 10.0
 
double obstacle_zero_speed_threshold_in_ms = 0.25
 
double min_obj_avoidance_plan_time_in_s = 2.0
 
double yield_max_deceleration_in_ms2 = 3.0
 
double minimum_safety_gap_in_meters = 2.0
 
double vehicle_length = 5.0
 
double vehicle_height = 3.0
 
double vehicle_width = 2.5
 
double max_stop_speed_in_ms = 1.0
 
bool enable_cooperative_behavior = true
 
bool always_accept_mobility_request = true
 
std::string vehicle_id = "DEFAULT_VEHICLE_ID"
 
int acceptable_passed_timesteps = 10
 
double intervehicle_collision_distance_in_m = 10.0
 
int consecutive_clearance_count_for_obstacles_threshold = 5
 
double safety_collision_time_gap_in_s = 2.0
 
bool enable_adjustable_gap = true
 
int acceptable_urgency = 5
 
double speed_moving_average_window_size = 3.0
 
double collision_check_radius_in_m = 150.0
 

Friends

std::ostream & operator<< (std::ostream &output, const YieldPluginConfig &c)
 

Detailed Description

Stuct containing the algorithm configuration values for the YieldPluginConfig.

Definition at line 24 of file yield_config.hpp.

Friends And Related Function Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream &  output,
const YieldPluginConfig c 
)
friend

Definition at line 48 of file yield_config.hpp.

49 {
50 output << "YieldPluginConfig { " << std::endl
51 << "acceleration_adjustment_factor: " << c.acceleration_adjustment_factor << std::endl
52 << "on_route_vehicle_collision_horizon_in_s: " << c.on_route_vehicle_collision_horizon_in_s << std::endl
53 << "obstacle_zero_speed_threshold_in_ms: " << c.obstacle_zero_speed_threshold_in_ms << std::endl
54 << "yield_max_deceleration_in_ms2: " << c.yield_max_deceleration_in_ms2 << std::endl
55 << "minimum_safety_gap_in_meters: " << c.minimum_safety_gap_in_meters << std::endl
56 << "vehicle_length: " << c.vehicle_length << std::endl
57 << "vehicle_height: " << c.vehicle_height << std::endl
58 << "vehicle_width: " << c.vehicle_width << std::endl
59 << "max_stop_speed_in_ms: " << c.max_stop_speed_in_ms << std::endl
60 << "enable_cooperative_behavior: " << c.enable_cooperative_behavior << std::endl
61 << "always_accept_mobility_request: " << c.always_accept_mobility_request << std::endl
62 << "vehicle_id: " << c.vehicle_id << std::endl
63 << "acceptable_passed_timesteps: " << c.acceptable_passed_timesteps << std::endl
64 << "intervehicle_collision_distance_in_m: " << c.intervehicle_collision_distance_in_m << std::endl
65 << "consecutive_clearance_count_for_obstacles_threshold: " << c.consecutive_clearance_count_for_obstacles_threshold << std::endl
66 << "safety_collision_time_gap_in_s: " << c.safety_collision_time_gap_in_s << std::endl
67 << "enable_adjustable_gap: " << c.enable_adjustable_gap << std::endl
68 << "acceptable_urgency: " << c.acceptable_urgency << std::endl
69 << "speed_moving_average_window_size: " << c.speed_moving_average_window_size << std::endl
70 << "collision_check_radius_in_m: " << c.collision_check_radius_in_m << std::endl
71 << "}" << std::endl;
72 return output;
73 }

Member Data Documentation

◆ acceleration_adjustment_factor

double YieldPluginConfig::acceleration_adjustment_factor = 4.0

◆ acceptable_passed_timesteps

◆ acceptable_urgency

◆ always_accept_mobility_request

bool YieldPluginConfig::always_accept_mobility_request = true

◆ collision_check_radius_in_m

double YieldPluginConfig::collision_check_radius_in_m = 150.0

◆ consecutive_clearance_count_for_obstacles_threshold

int YieldPluginConfig::consecutive_clearance_count_for_obstacles_threshold = 5

◆ enable_adjustable_gap

◆ enable_cooperative_behavior

bool YieldPluginConfig::enable_cooperative_behavior = true

◆ intervehicle_collision_distance_in_m

◆ max_stop_speed_in_ms

◆ min_obj_avoidance_plan_time_in_s

◆ minimum_safety_gap_in_meters

◆ obstacle_zero_speed_threshold_in_ms

◆ on_route_vehicle_collision_horizon_in_s

double YieldPluginConfig::on_route_vehicle_collision_horizon_in_s = 10.0

◆ safety_collision_time_gap_in_s

◆ speed_moving_average_window_size

double YieldPluginConfig::speed_moving_average_window_size = 3.0

◆ vehicle_height

double YieldPluginConfig::vehicle_height = 3.0

◆ vehicle_id

◆ vehicle_length

◆ vehicle_width

double YieldPluginConfig::vehicle_width = 2.5

◆ yield_max_deceleration_in_ms2


The documentation for this struct was generated from the following file: