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
Struct to store the configuration settings for the LCIStrategicPlugin class.
std::string intersection_transit_plugin_name
bool enable_carma_streets_connection
Bool: Enable carma streets connection.
std::string vehicle_id
License plate of the vehicle.
double trajectory_smoothing_activation_distance
Downtrack distance until nearest intersection where the Trajectory Smoothing algorithm should activat...
double algo_minimum_speed
Minimum allowable speed TS algorithm in m/s.
double vehicle_accel_limit_multiplier
A multiplier to apply to the maximum allowable vehicle acceleration limit so we plan under our capabi...
double min_maneuver_planning_period
The minimum period in seconds which a maneuver plan must cover if the plugin wishes to control the wh...
double green_light_time_buffer
A buffer in seconds around the green phase which will reduce the phase length such that vehicle still...
std::string stop_and_wait_plugin_name
The name of the plugin to use for stop and wait trajectory planning.
double stopping_location_buffer
A buffer infront of the stopping location which will still be considered a valid stop....
double reaction_time
Double: Vehicle reaction time to a received schedule in seconds (approximate value,...
std::string lane_following_plugin_name
double vehicle_decel_limit
The maximum allowable vehicle deceleration limit in m/s.
double vehicle_decel_limit_multiplier
A multiplier to apply to the maximum allowable vehicle deceleration limit so we plan under our capabi...
double min_approach_distance
The minimum distance in meters that the vehicle can be at before requiring a transition to the APPROA...
double vehicle_accel_limit
The maximum allowable vehicle acceleration limit in m/s.
std::string strategic_plugin_name
The name to use for this plugin during comminications with the arbitrator.
double deceleration_fraction
friend std::ostream & operator<<(std::ostream &output, const LCIStrategicPluginConfig &c)
double mobility_rate
Double: Mobility operation rate.
double desired_distance_to_stop_buffer
Double: Desired distance to stop buffer in meters.
double min_gap
Double: Minimum inter-vehicle gap.