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.
lci_strategic_plugin::LCIStrategicPluginConfig Struct Reference

Struct to store the configuration settings for the LCIStrategicPlugin class. More...

#include <lci_strategic_plugin_config.hpp>

Collaboration diagram for lci_strategic_plugin::LCIStrategicPluginConfig:
Collaboration graph

Public Attributes

double vehicle_decel_limit = 2.0
 The maximum allowable vehicle deceleration limit in m/s. More...
 
double vehicle_decel_limit_multiplier = 0.75
 A multiplier to apply to the maximum allowable vehicle deceleration limit so we plan under our capabilities. More...
 
double vehicle_accel_limit = 2.0
 The maximum allowable vehicle acceleration limit in m/s. More...
 
double vehicle_accel_limit_multiplier = 0.75
 A multiplier to apply to the maximum allowable vehicle acceleration limit so we plan under our capabilities. More...
 
double min_approach_distance = 30.0
 The minimum distance in meters that the vehicle can be at before requiring a transition to the APPROACH state. More...
 
double trajectory_smoothing_activation_distance = 200.0
 Downtrack distance until nearest intersection where the Trajectory Smoothing algorithm should activate. More...
 
double stopping_location_buffer = 3.0
 A buffer infront of the stopping location which will still be considered a valid stop. Units in meters. More...
 
double green_light_time_buffer = 0.0
 A buffer in seconds around the green phase which will reduce the phase length such that vehicle still considers it non-green. More...
 
double algo_minimum_speed = 2.2352
 Minimum allowable speed TS algorithm in m/s. More...
 
double deceleration_fraction = 0.8
 
double desired_distance_to_stop_buffer = 10.0
 Double: Desired distance to stop buffer in meters. More...
 
double min_maneuver_planning_period = 15.1
 The minimum period in seconds which a maneuver plan must cover if the plugin wishes to control the whole plan. More...
 
double reaction_time = 2.0
 Double: Vehicle reaction time to a received schedule in seconds (approximate value, only used for communication with the schedule) More...
 
double min_gap = 10.0
 Double: Minimum inter-vehicle gap. More...
 
bool enable_carma_streets_connection = false
 Bool: Enable carma streets connection. More...
 
double mobility_rate = 10.0
 Double: Mobility operation rate. More...
 
std::string vehicle_id = "default_id"
 License plate of the vehicle. More...
 
std::string strategic_plugin_name = "lci_strategic_plugin"
 The name to use for this plugin during comminications with the arbitrator. More...
 
std::string lane_following_plugin_name = "light_controlled_intersection_tactical_plugin"
 
std::string stop_and_wait_plugin_name = "stop_and_wait_plugin"
 The name of the plugin to use for stop and wait trajectory planning. More...
 
std::string intersection_transit_plugin_name = "intersection_transit_maneuvering"
 

Friends

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

Detailed Description

Struct to store the configuration settings for the LCIStrategicPlugin class.

Definition at line 23 of file lci_strategic_plugin_config.hpp.

Friends And Related Function Documentation

◆ operator<<

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

Definition at line 92 of file lci_strategic_plugin_config.hpp.

93 {
94 output << "LCIStrategicPluginConfig { " << std::endl
95 << "vehicle_decel_limit: " << c.vehicle_decel_limit << std::endl
96 << "vehicle_decel_limit_multiplier: " << c.vehicle_decel_limit_multiplier << std::endl
97 << "vehicle_accel_limit: " << c.vehicle_accel_limit << std::endl
98 << "vehicle_accel_limit_multiplier: " << c.vehicle_accel_limit_multiplier << std::endl
99 << "min_approach_distance: " << c.min_approach_distance << std::endl
100 << "trajectory_smoothing_activation_distance: " << c.trajectory_smoothing_activation_distance << std::endl
101 << "stopping_location_buffer: " << c.stopping_location_buffer << std::endl
102 << "green_light_time_buffer: " << c.green_light_time_buffer << std::endl
103 << "algo_minimum_speed: " << c.algo_minimum_speed << std::endl
104 << "deceleration_fraction: " << c.deceleration_fraction << std::endl
105 << "desired_distance_to_stop_buffer: " << c.desired_distance_to_stop_buffer << std::endl
106 << "min_maneuver_planning_period: " << c.min_maneuver_planning_period << std::endl
107 << "reaction_time: " << c.reaction_time << std::endl
108 << "min_gap: " << c.min_gap << std::endl
109 << "enable_carma_streets_connection: " << c.enable_carma_streets_connection << std::endl
110 << "mobility_rate: " << c.mobility_rate << std::endl
111 << "vehicle_id: " << c.vehicle_id << std::endl
112 << "strategic_plugin_name: " << c.strategic_plugin_name << std::endl
113 << "lane_following_plugin_name: " << c.lane_following_plugin_name << std::endl
114 << "stop_and_wait_plugin_name: " << c.stop_and_wait_plugin_name << std::endl
115 << "intersection_transit_plugin_name: " << c.intersection_transit_plugin_name << std::endl
116 << "}" << std::endl;
117 return output;
118 }

Member Data Documentation

◆ algo_minimum_speed

◆ deceleration_fraction

double lci_strategic_plugin::LCIStrategicPluginConfig::deceleration_fraction = 0.8

Double: Safety multiplier of planned allowable vehicle deceleration to use when stopping. This new deceleration makes vehicle decelerate earlier distance. NOTE: Stacks on vehicle_decel_limit_multiplier and stopping uses max_decel; this distance is only used for calculating earlier downtrack

Definition at line 54 of file lci_strategic_plugin_config.hpp.

Referenced by lci_strategic_plugin::LCIStrategicPlugin::LCIStrategicPlugin(), lci_strategic_plugin::LCIStrategicPlugin::on_configure_plugin(), lci_strategic_plugin::LCIStrategicPlugin::parameter_update_callback(), and lci_strategic_plugin::LCIStrategicPlugin::planWhenAPPROACHING().

◆ desired_distance_to_stop_buffer

double lci_strategic_plugin::LCIStrategicPluginConfig::desired_distance_to_stop_buffer = 10.0

◆ enable_carma_streets_connection

◆ green_light_time_buffer

double lci_strategic_plugin::LCIStrategicPluginConfig::green_light_time_buffer = 0.0

◆ intersection_transit_plugin_name

std::string lci_strategic_plugin::LCIStrategicPluginConfig::intersection_transit_plugin_name = "intersection_transit_maneuvering"

The name of the plugin to use for intersection transit trajectory planning This plugin is used to travel INSIDE the intersection where there is no trajectory smoothing algorithm active

Definition at line 89 of file lci_strategic_plugin_config.hpp.

Referenced by lci_strategic_plugin::LCIStrategicPlugin::LCIStrategicPlugin(), lci_strategic_plugin::LCIStrategicPlugin::composeIntersectionTransitMessage(), and lci_strategic_plugin::LCIStrategicPlugin::on_configure_plugin().

◆ lane_following_plugin_name

std::string lci_strategic_plugin::LCIStrategicPluginConfig::lane_following_plugin_name = "light_controlled_intersection_tactical_plugin"

The name of the tactical plugin to use for Lane Following trajectory planning This plugin is used to apply trajectory smoothing algorithm BEFORE entering the intersection if within activation distance

Definition at line 82 of file lci_strategic_plugin_config.hpp.

Referenced by lci_strategic_plugin::LCIStrategicPlugin::LCIStrategicPlugin(), lci_strategic_plugin::LCIStrategicPlugin::composeTrajectorySmoothingManeuverMessage(), and lci_strategic_plugin::LCIStrategicPlugin::on_configure_plugin().

◆ min_approach_distance

double lci_strategic_plugin::LCIStrategicPluginConfig::min_approach_distance = 30.0

◆ min_gap

double lci_strategic_plugin::LCIStrategicPluginConfig::min_gap = 10.0

Double: Minimum inter-vehicle gap.

Definition at line 66 of file lci_strategic_plugin_config.hpp.

Referenced by lci_strategic_plugin::LCIStrategicPlugin::generateMobilityOperation().

◆ min_maneuver_planning_period

◆ mobility_rate

◆ reaction_time

double lci_strategic_plugin::LCIStrategicPluginConfig::reaction_time = 2.0

Double: Vehicle reaction time to a received schedule in seconds (approximate value, only used for communication with the schedule)

Definition at line 63 of file lci_strategic_plugin_config.hpp.

Referenced by lci_strategic_plugin::LCIStrategicPlugin::generateMobilityOperation().

◆ stop_and_wait_plugin_name

std::string lci_strategic_plugin::LCIStrategicPluginConfig::stop_and_wait_plugin_name = "stop_and_wait_plugin"

◆ stopping_location_buffer

double lci_strategic_plugin::LCIStrategicPluginConfig::stopping_location_buffer = 3.0

◆ strategic_plugin_name

◆ trajectory_smoothing_activation_distance

double lci_strategic_plugin::LCIStrategicPluginConfig::trajectory_smoothing_activation_distance = 200.0

◆ vehicle_accel_limit

◆ vehicle_accel_limit_multiplier

double lci_strategic_plugin::LCIStrategicPluginConfig::vehicle_accel_limit_multiplier = 0.75

◆ vehicle_decel_limit

◆ vehicle_decel_limit_multiplier

◆ vehicle_id


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