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
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
Stuct containing the algorithm configuration values for the PlatooningControlPlugin.
double emergency_stop_distance
bool is_interpolate_lookahead_point
double speed_thres_traveling_direction
double min_delta_speed_per_timestep
double max_lookahead_dist
double stand_still_headway_m
double adjustment_cap_mps
double max_delta_speed_per_timestep
int ignore_initial_inputs
double dist_front_rear_wheels
bool is_integrator_enabled
double vehicle_response_lag
friend std::ostream & operator<<(std::ostream &output, const PlatooningControlPluginConfig &c)
double min_lookahead_dist
bool is_delay_compensation
double speed_to_lookahead_ratio
bool enable_max_accel_filter
bool enable_max_adjustment_filter