69 {
70 output << "motion_computation::Config { " << std::endl
71 <<
"prediction_time_step: " <<
c.prediction_time_step << std::endl
72 <<
"mobility_path_time_step: " <<
c.mobility_path_time_step << std::endl
73 <<
"prediction_period: " <<
c.prediction_period << std::endl
74 <<
"cv_x_accel_noise: " <<
c.cv_x_accel_noise << std::endl
75 <<
"cv_y_accel_noise: " <<
c.cv_y_accel_noise << std::endl
76 <<
"prediction_process_noise_max: " <<
c.prediction_process_noise_max << std::endl
77 <<
"prediction_confidence_drop_rate: " <<
c.prediction_confidence_drop_rate << std::endl
78 <<
"enable_bsm_processing: " <<
c.enable_bsm_processing << std::endl
79 <<
"enable_psm_processing: " <<
c.enable_psm_processing << std::endl
80 <<
"enable_mobility_path_processing: " <<
c.enable_mobility_path_processing << std::endl
81 <<
"enable_sensor_processing: " <<
c.enable_sensor_processing << std::endl
82 <<
"enable_ctrv_for_unknown_obj: " <<
c.enable_ctrv_for_unknown_obj << std::endl
83 <<
"enable_ctrv_for_motorcycle_obj: " <<
c.enable_ctrv_for_motorcycle_obj << std::endl
84 <<
"enable_ctrv_for_small_vehicle_obj: " <<
c.enable_ctrv_for_small_vehicle_obj
85 << std::endl
86 <<
"enable_ctrv_for_large_vehicle_obj: " <<
c.enable_ctrv_for_large_vehicle_obj
87 << std::endl
88 <<
"enable_ctrv_for_pedestrian_obj: " <<
c.enable_ctrv_for_pedestrian_obj << std::endl
89 << "}" << std::endl;
90 return output;
91 }