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.
platooning_control::PlatooningControlPluginConfig Struct Reference

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

#include <platooning_control_config.hpp>

Collaboration diagram for platooning_control::PlatooningControlPluginConfig:
Collaboration graph

Public Attributes

double stand_still_headway_m = 12.0
 
double max_accel_mps2 = 2.5
 
double kp = 0.5
 
double kd = -0.5
 
double ki = 0.0
 
double max_delta_speed_per_timestep = 2
 
double min_delta_speed_per_timestep = -10
 
double adjustment_cap_mps = 10
 
int cmd_timestamp_ms = 100
 
double integrator_max = 100
 
double integrator_min = -100
 
std::string vehicle_id = "DEFAULT_VEHICLE_ID"
 
int shutdown_timeout = 200
 
int ignore_initial_inputs = 0
 
double vehicle_response_lag = 0.2
 
double max_lookahead_dist = 100.0
 
double min_lookahead_dist = 6.0
 
double speed_to_lookahead_ratio = 2.0
 
bool is_interpolate_lookahead_point = true
 
bool is_delay_compensation = true
 
double emergency_stop_distance = 0.1
 
double speed_thres_traveling_direction = 0.3
 
double dist_front_rear_wheels = 3.5
 
double dt = 0.1
 
double integrator_max_pp = 0.0
 
double integrator_min_pp = 0.0
 
double ki_pp = 0.0
 
bool is_integrator_enabled = false
 
bool enable_max_adjustment_filter = true
 
bool enable_max_accel_filter = true
 

Friends

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

Detailed Description

Stuct containing the algorithm configuration values for the PlatooningControlPlugin.

Definition at line 28 of file platooning_control_config.hpp.

Friends And Related Function Documentation

◆ operator<<

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

Definition at line 68 of file platooning_control_config.hpp.

69 {
70 output << "PlatooningControlPluginConfig { " << std::endl
71 << "stand_still_headway_m: " << c.stand_still_headway_m << std::endl
72 << "max_accel_mps2: " << c.max_accel_mps2 << std::endl
73 << "kp: " << c.kp << std::endl
74 << "kd: " << c.kd << std::endl
75 << "ki: " << c.ki << std::endl
76 << "max_delta_speed_per_timestep: " << c.max_delta_speed_per_timestep << std::endl
77 << "min_delta_speed_per_timestep_: " << c.min_delta_speed_per_timestep << std::endl
78 << "adjustment_cap_mps: " << c.adjustment_cap_mps << std::endl
79 << "cmd_timestamp_ms: " << c.cmd_timestamp_ms << std::endl
80 << "integrator_max: " << c.integrator_max << std::endl
81 << "integrator_min: " << c.integrator_min << std::endl
82 << "vehicle_id: " << c.vehicle_id << std::endl
83 << "shutdown_timeout: " << c.shutdown_timeout << std::endl
84 << "ignore_initial_inputs: " << c.ignore_initial_inputs << std::endl
85 //Pure Pursuit configs
86 << "vehicle_response_lag" << c.vehicle_response_lag << std::endl
87 << "max_lookahead_dist: " << c.max_lookahead_dist << std::endl
88 << "min_lookahead_dist: " << c.min_lookahead_dist << std::endl
89 << "speed_to_lookahead_ratio: " << c.speed_to_lookahead_ratio << std::endl
90 << "is_interpolate_lookahead_point: " << c.is_interpolate_lookahead_point << std::endl
91 << "is_delay_compensation: " << c.is_delay_compensation << std::endl
92 << "emergency_stop_distance: " << c.emergency_stop_distance << std::endl
93 << "speed_thres_traveling_direction: "<< c.speed_thres_traveling_direction << std::endl
94 << "dist_front_rear_wheels: " << c.dist_front_rear_wheels << std::endl
95 << "dt: " << c.dt << std::endl
96 << "integrator_max_pp: " << c.integrator_max_pp << std::endl
97 << "integrator_min_pp: " << c.integrator_min_pp << std::endl
98 << "ki_pp_: " << c.ki_pp << std::endl
99 << "is_integrator_enabled" << c.is_integrator_enabled <<std::endl
100 << "enable_max_adjustment_filter" << c.enable_max_adjustment_filter << std::endl
101 << "enable_max_accel_filter" << c.enable_max_accel_filter << std::endl
102 << "}" << std::endl;
103 return output;
104 }

Member Data Documentation

◆ adjustment_cap_mps

◆ cmd_timestamp_ms

◆ dist_front_rear_wheels

◆ dt

◆ emergency_stop_distance

◆ enable_max_accel_filter

◆ enable_max_adjustment_filter

◆ ignore_initial_inputs

◆ integrator_max

◆ integrator_max_pp

◆ integrator_min

◆ integrator_min_pp

◆ is_delay_compensation

◆ is_integrator_enabled

◆ is_interpolate_lookahead_point

◆ kd

◆ ki

◆ ki_pp

◆ kp

◆ max_accel_mps2

◆ max_delta_speed_per_timestep

◆ max_lookahead_dist

◆ min_delta_speed_per_timestep

◆ min_lookahead_dist

◆ shutdown_timeout

◆ speed_thres_traveling_direction

◆ speed_to_lookahead_ratio

◆ stand_still_headway_m

◆ vehicle_id

std::string platooning_control::PlatooningControlPluginConfig::vehicle_id = "DEFAULT_VEHICLE_ID"

◆ vehicle_response_lag


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