26#include "absl/strings/str_cat.h"
43using Matrix = Eigen::MatrixXd;
50std::string GetLogFileName() {
56 localtime_r(&raw_time, &time_tm);
57 strftime(name_buffer,
sizeof(name_buffer),
58 "/tmp/mpc_controller_%F_%H%M%S.csv", &time_tm);
59 return std::string(name_buffer);
62void WriteHeaders(std::ofstream &file_stream) {}
66 if (FLAGS_enable_csv_debug) {
78 vehicle_param_ = VehicleConfigHelper::Instance()->GetConfig().vehicle_param();
82 AERROR <<
"[MPCController] Invalid control update interval.";
95 static constexpr double kEpsilon = 1e-6;
97 AERROR <<
"[MPCController] steer_ratio = 0";
109 const double mass_front = mass_fl + mass_fr;
110 const double mass_rear = mass_rl + mass_rr;
111 mass_ = mass_front + mass_rear;
162 ADEBUG <<
"MPC conf loaded";
173 AINFO <<
"[MPCController parameters]"
174 <<
" mass_: " <<
mass_ <<
","
175 <<
" iz_: " <<
iz_ <<
","
176 <<
" lf_: " <<
lf_ <<
","
182 std::vector<double> den(3, 0.0);
183 std::vector<double> num(3, 0.0);
191 static_cast<std::uint_fast8_t
>(
control_conf_.mean_filter_window_size()));
193 static_cast<std::uint_fast8_t
>(
control_conf_.mean_filter_window_size()));
197 if (!ControlTask::LoadConfig<MPCControllerConf>(&
control_conf_)) {
198 AERROR <<
"failed to load control conf";
199 return Status(ErrorCode::CONTROL_INIT_ERROR,
200 "failed to load mpc control_conf");
204 AERROR <<
"failed to load calibration table";
205 return Status(ErrorCode::CONTROL_INIT_ERROR,
206 "mpc failed to load calibration table");
210 AERROR <<
"failed to load control conf";
211 return Status(ErrorCode::CONTROL_COMPUTE_ERROR,
212 "failed to load control_conf");
253 for (
int i = 0; i < r_param_size; ++i) {
259 const auto error_msg =
260 absl::StrCat(
"MPC controller error: matrix_q size: ", q_param_size,
261 " in parameter file not equal to basic_state_size_: ",
264 return Status(ErrorCode::CONTROL_COMPUTE_ERROR, error_msg);
266 for (
int i = 0; i < q_param_size; ++i) {
279 ADEBUG <<
"[MPCController] init done!";
298 const auto &lat_err_gain_scheduler =
control_conf_.lat_err_gain_scheduler();
299 const auto &heading_err_gain_scheduler =
301 const auto &feedforwardterm_gain_scheduler =
303 const auto &steer_weight_gain_scheduler =
305 ADEBUG <<
"MPC control gain scheduler loaded";
307 for (
const auto &scheduler : lat_err_gain_scheduler.scheduler()) {
308 xy1.push_back(std::make_pair(scheduler.speed(), scheduler.ratio()));
310 for (
const auto &scheduler : heading_err_gain_scheduler.scheduler()) {
311 xy2.push_back(std::make_pair(scheduler.speed(), scheduler.ratio()));
313 for (
const auto &scheduler : feedforwardterm_gain_scheduler.scheduler()) {
314 xy3.push_back(std::make_pair(scheduler.speed(), scheduler.ratio()));
316 for (
const auto &scheduler : steer_weight_gain_scheduler.scheduler()) {
317 xy4.push_back(std::make_pair(scheduler.speed(), scheduler.ratio()));
322 <<
"Fail to load lateral error gain scheduler for MPC controller";
326 <<
"Fail to load heading error gain scheduler for MPC controller";
330 <<
"Fail to load feed forward term gain scheduler for MPC controller";
334 <<
"Fail to load steer weight gain scheduler for MPC controller";
344 auto vehicle_state =
injector_->vehicle_state();
388 SimpleMPCDebug *debug = cmd->mutable_debug()->mutable_simple_mpc_debug();
405 if (FLAGS_enable_gain_scheduler) {
411 vehicle_state->linear_velocity());
415 vehicle_state->linear_velocity());
418 vehicle_state->linear_velocity());
434 std::vector<Matrix> control(
horizon_, control_matrix);
437 std::vector<Matrix> control_gain(
horizon_, control_gain_matrix);
440 std::vector<Matrix> addition_gain(
horizon_, addition_gain_matrix);
443 std::vector<Matrix> reference(
horizon_, reference_state);
451 const double max = std::numeric_limits<double>::max();
457 lower_state_bound << -1.0 * max, -1.0 * max, -1.0 * M_PI, -1.0 * max,
458 -1.0 * max, -1.0 * max;
459 upper_state_bound << max, max, M_PI, max, max, max;
462 double steer_angle_feedback = 0.0;
463 double acc_feedback = 0.0;
464 double steer_angle_ff_compensation = 0.0;
465 double unconstrained_control_diff = 0.0;
466 double control_gain_truncation_ratio = 0.0;
467 double unconstrained_control = 0.0;
468 double steer_angle_feedback_augment = 0.0;
469 const double v =
injector_->vehicle_state()->linear_velocity();
471 std::vector<double> control_cmd(
controls_, 0);
478 if (!mpc_osqp.
Solve(&control_cmd)) {
479 AERROR <<
"MPC OSQP solver failed";
481 ADEBUG <<
"MPC OSQP problem solved! ";
482 control[0](0, 0) = control_cmd.at(0);
483 control[0](1, 0) = control_cmd.at(1);
487 acc_feedback = control[0](1, 0);
489 unconstrained_control += control_gain[0](0, i) *
matrix_state_(i, 0);
491 unconstrained_control += addition_gain[0](0, 0) * v * debug->
curvature();
493 unconstrained_control_diff =
496 steer_angle_ff_compensation =
498 (control_gain[0](0, 2) *
500 addition_gain[0](0, 0) * v));
502 control_gain_truncation_ratio = control[0](0, 0) / unconstrained_control;
503 steer_angle_ff_compensation =
505 (control_gain[0](0, 2) *
507 addition_gain[0](0, 0) * v) *
508 control_gain_truncation_ratio);
510 if (std::isnan(steer_angle_ff_compensation)) {
511 ADEBUG <<
"steer_angle_ff_compensation is nan";
512 steer_angle_ff_compensation = 0.0;
515 steer_angle_ff_compensation = 0.0;
520 ADEBUG <<
"MPC core algorithm: calculation time is: "
521 << (mpc_end_timestamp - mpc_start_timestamp) * 1000 <<
" ms.";
526 steer_angle_feedback_augment =
529 if (std::fabs(vehicle_state->linear_velocity()) >
543 steer_angle_ff_compensation + steer_angle_feedback_augment;
545 if (FLAGS_set_steer_limit) {
547 (vehicle_state->linear_velocity() *
548 vehicle_state->linear_velocity())) *
553 double steer_angle_limited =
556 steer_angle = steer_angle_limited;
557 debug->set_steer_angle_limited(steer_angle_limited);
562 cmd->set_steering_target(steer_angle);
564 debug->set_acceleration_cmd_closeloop(acc_feedback);
566 double vehicle_pitch = 0.0;
571 vehicle_pitch =
injector_->vehicle_state()->pitch();
574 if (std::isnan(vehicle_pitch)) {
575 AINFO <<
"pitch angle is nan.";
578 debug->set_vehicle_pitch(vehicle_pitch);
580 double slope_offset_compensation =
GRA_ACC * std::sin(vehicle_pitch);
581 if (std::isnan(slope_offset_compensation)) {
582 slope_offset_compensation = 0;
584 debug->set_slope_offset_compensation(slope_offset_compensation);
586 double acceleration_cmd =
603 FLAGS_max_acceleration_when_stopped) &&
606 debug->set_is_full_stop(
true);
607 ADEBUG <<
"Into full stop within preview acc and reference speed, "
610 if (std::abs(debug->
path_remain()) < FLAGS_max_acceleration_when_stopped) {
611 debug->set_is_full_stop(
true);
612 ADEBUG <<
"Into full stop within path remain, "
625 debug->set_acceleration_cmd(acceleration_cmd);
630 double acceleration_lookup_error =
632 double acceleration_lookup_offset = 0.0;
636 acceleration_lookup_error,
ts_);
638 acceleration_lookup_offset = 0.0;
641 double acceleration_lookup = acceleration_lookup_offset + acceleration_cmd;
643 debug->set_acceleration_lookup_offset(acceleration_lookup_offset);
645 debug->set_acceleration_lookup(acceleration_lookup);
647 double calibration_value = 0.0;
648 if (FLAGS_use_preview_speed_for_table) {
653 injector_->vehicle_state()->linear_velocity(), acceleration_lookup));
656 debug->set_calibration_value(calibration_value);
658 double throttle_cmd = 0.0;
659 double brake_cmd = 0.0;
660 if (acceleration_cmd >= 0) {
661 if (calibration_value >= 0) {
669 if (calibration_value >= 0) {
676 cmd->set_steering_rate(FLAGS_steer_angle_rate);
678 cmd->set_throttle(throttle_cmd);
679 cmd->set_brake(brake_cmd);
680 cmd->set_acceleration(acceleration_cmd);
682 debug->set_heading(vehicle_state->heading());
684 debug->set_steer_angle(steer_angle);
686 debug->set_steer_angle_feedforward_compensation(steer_angle_ff_compensation);
687 debug->set_steer_unconstrained_control_diff(unconstrained_control_diff);
688 debug->set_steer_angle_feedback(steer_angle_feedback);
690 debug->set_steer_angle_feedback_augment(steer_angle_feedback_augment);
692 if (std::fabs(vehicle_state->linear_velocity()) <=
695 cmd->set_gear_location(planning_published_trajectory->
gear());
711 ADEBUG <<
"Control calibration table size is "
715 xyz.push_back(std::make_tuple(calibration.speed(),
716 calibration.acceleration(),
717 calibration.command()));
721 <<
"Fail to init control calibration table";
725 const auto &com =
injector_->vehicle_state()->ComputeCOMPosition(
lr_);
727 injector_->vehicle_state()->linear_velocity(),
728 injector_->vehicle_state()->angular_velocity(),
729 injector_->vehicle_state()->linear_acceleration(),
751 const double v = std::max(
injector_->vehicle_state()->linear_velocity(),
768 const double v =
injector_->vehicle_state()->linear_velocity();
783 const double x,
const double y,
const double theta,
const double linear_v,
784 const double angular_v,
const double linear_a,
786 const auto matched_point =
789 const double dx = x - matched_point.
path_point().
x();
790 const double dy = y - matched_point.path_point().y();
792 const double cos_matched_theta = std::cos(matched_point.path_point().theta());
793 const double sin_matched_theta = std::sin(matched_point.path_point().theta());
795 double lateral_error = cos_matched_theta * dy - sin_matched_theta * dx;
799 debug->set_lateral_error(lateral_error);
802 debug->set_ref_heading(matched_point.path_point().theta());
808 debug->set_heading_error(delta_theta);
813 double lookahead_station = 0.0;
814 double lookback_station = 0.0;
835 auto lookahead_point =
837 matched_point.relative_time() +
839 (std::max(std::fabs(linear_v), 0.1) * std::cos(delta_theta)));
841 delta_theta + matched_point.path_point().theta() -
842 lookahead_point.path_point().theta());
849 lateral_error - lookback_station * std::sin(delta_theta);
852 lateral_error + lookahead_station * std::sin(delta_theta);
857 const double sin_delta_theta = std::sin(delta_theta);
859 double lateral_error_dot = linear_v * sin_delta_theta;
860 double lateral_error_dot_dot = linear_a * sin_delta_theta;
861 if (FLAGS_reverse_heading_control) {
863 lateral_error_dot = -lateral_error_dot;
864 lateral_error_dot_dot = -lateral_error_dot_dot;
868 debug->set_lateral_error_rate(lateral_error_dot);
869 debug->set_lateral_acceleration(lateral_error_dot_dot);
870 debug->set_lateral_jerk(
875 debug->set_curvature(matched_point.path_point().kappa());
877 debug->set_heading_error(delta_theta);
882 debug->set_heading_rate(-angular_v);
884 debug->set_heading_rate(angular_v);
886 debug->set_ref_heading_rate(debug->
curvature() * matched_point.v());
890 debug->set_heading_acceleration(
892 debug->set_ref_heading_acceleration(
899 debug->set_heading_jerk(
901 debug->set_ref_heading_jerk(
917 double s_matched = 0.0;
918 double s_dot_matched = 0.0;
919 double d_matched = 0.0;
920 double d_dot_matched = 0.0;
928 injector_->vehicle_state()->linear_velocity(), matched_point, &s_matched,
929 &s_dot_matched, &d_matched, &d_dot_matched);
935 current_control_time);
937 ADEBUG <<
"matched point:" << matched_point.DebugString();
938 ADEBUG <<
"reference point:" << reference_point.DebugString();
940 const double linear_v =
injector_->vehicle_state()->linear_velocity();
941 const double linear_a =
injector_->vehicle_state()->linear_acceleration();
943 injector_->vehicle_state()->heading() - matched_point.theta());
944 double lon_speed = linear_v * std::cos(heading_error);
945 double lon_acceleration = linear_a * std::cos(heading_error);
946 double one_minus_kappa_lat_error = 1 - reference_point.
path_point().
kappa() *
947 linear_v * std::sin(heading_error);
949 debug->set_station_reference(reference_point.
path_point().
s());
950 debug->set_station_feedback(s_matched);
951 debug->set_station_error(reference_point.
path_point().
s() - s_matched);
952 debug->set_speed_reference(reference_point.
v());
953 debug->set_speed_feedback(lon_speed);
954 debug->set_speed_error(reference_point.
v() - s_dot_matched);
955 debug->set_acceleration_reference(reference_point.
a());
956 debug->set_acceleration_feedback(lon_acceleration);
957 debug->set_acceleration_error(reference_point.
a() -
958 lon_acceleration / one_minus_kappa_lat_error);
959 double jerk_reference =
964 debug->set_jerk_reference(jerk_reference);
965 debug->set_jerk_feedback(lon_jerk);
966 debug->set_jerk_error(jerk_reference - lon_jerk / one_minus_kappa_lat_error);
979 double s_matched = 0.0;
980 double s_dot_matched = 0.0;
981 double d_matched = 0.0;
982 double d_dot_matched = 0.0;
984 auto vehicle_state =
injector_->vehicle_state();
986 vehicle_state->x(), vehicle_state->y());
989 vehicle_state->x(), vehicle_state->y(), vehicle_state->heading(),
990 vehicle_state->linear_velocity(), matched_point, &s_matched,
991 &s_dot_matched, &d_matched, &d_dot_matched);
995 double preview_control_time = current_control_time + preview_time;
999 current_control_time);
1002 preview_control_time);
1004 debug->mutable_current_matched_point()->mutable_path_point()->set_x(
1006 debug->mutable_current_matched_point()->mutable_path_point()->set_y(
1008 debug->mutable_current_reference_point()->mutable_path_point()->set_x(
1010 debug->mutable_current_reference_point()->mutable_path_point()->set_y(
1012 debug->mutable_preview_reference_point()->mutable_path_point()->set_x(
1014 debug->mutable_preview_reference_point()->mutable_path_point()->set_y(
1017 ADEBUG <<
"matched point:" << matched_point.DebugString();
1018 ADEBUG <<
"reference point:" << reference_point.DebugString();
1019 ADEBUG <<
"preview point:" << preview_point.DebugString();
1022 matched_point.theta());
1023 double lon_speed = vehicle_state->linear_velocity() * std::cos(heading_error);
1024 double lon_acceleration =
1025 vehicle_state->linear_acceleration() * std::cos(heading_error);
1026 double one_minus_kappa_lat_error = 1 - reference_point.
path_point().
kappa() *
1027 vehicle_state->linear_velocity() *
1028 std::sin(heading_error);
1030 debug->set_station_reference(reference_point.
path_point().
s());
1031 debug->set_station_feedback(s_matched);
1032 debug->set_station_error(reference_point.
path_point().
s() - s_matched);
1033 debug->set_speed_reference(reference_point.
v());
1034 debug->set_speed_feedback(lon_speed);
1035 debug->set_speed_error(reference_point.
v() - s_dot_matched);
1036 debug->set_acceleration_reference(reference_point.
a());
1037 debug->set_acceleration_feedback(lon_acceleration);
1038 debug->set_acceleration_vrf(vehicle_state->linear_acceleration());
1039 debug->set_acceleration_error(reference_point.
a() -
1040 lon_acceleration / one_minus_kappa_lat_error);
1041 double jerk_reference =
1045 debug->set_jerk_reference(jerk_reference);
1046 debug->set_jerk_feedback(lon_jerk);
1047 debug->set_jerk_error(jerk_reference - lon_jerk / one_minus_kappa_lat_error);
1052 debug->set_preview_station_error(preview_point.
path_point().
s() - s_matched);
1053 debug->set_preview_speed_error(preview_point.
v() - s_dot_matched);
1054 debug->set_preview_speed_reference(preview_point.
v());
1055 debug->set_preview_acceleration_reference(preview_point.
a());
1063 static constexpr double kSpeedThreshold = 1e-3;
1064 static constexpr double kForwardAccThreshold = -1e-2;
1065 static constexpr double kBackwardAccThreshold = 1e-1;
1066 static constexpr double kParkingSpeed = 0.1;
1070 planning_published_trajectory->trajectory_point_size()) {
1071 auto ¤t_trajectory_point =
1073 if (fabs(current_trajectory_point.v()) < kSpeedThreshold &&
1074 current_trajectory_point.a() > kForwardAccThreshold &&
1075 current_trajectory_point.a() < 0.0) {
1082 planning_published_trajectory->trajectory_point_size()) {
1083 auto ¤t_trajectory_point =
1085 if (current_trajectory_point.v() > -kSpeedThreshold &&
1086 current_trajectory_point.a() < kBackwardAccThreshold &&
1087 current_trajectory_point.a() > 0.0) {
1093 ADEBUG <<
"stop_index is, " << stop_index;
1094 if (stop_index == planning_published_trajectory->trajectory_point_size()) {
1098 ADEBUG <<
"the last point is selected as parking point";
1100 ADEBUG <<
"the last point found in path and speed > speed_deadzone";
1103 debug->set_path_remain(
void set_coefficients(const std::vector< double > &denominators, const std::vector< double > &numerators)
set denominators and numerators
double Filter(const double x_insert)
Processes a new measurement with the filter.
The MeanFilter class is used to smoothen a series of noisy numbers, such as sensor data or the output...
double Update(const double measurement)
Processes a new measurement in amortized constant time.
A general class to denote the return status of an API call.
static Status OK()
generate a success status.
@Brief This is a helper class that can load vehicle configurations.
The class of vehicle state.
bool Solve(std::vector< double > *control_cmd)
bool LoadCalibrationTable(calibration_table *calibration_table_conf)
std::vector< std::pair< double, double > > DataType
linear interpolation from key (double, double) to one double value.
std::vector< std::tuple< double, double, double > > DataType
void Init(const LeadlagConf &leadlag_conf, const double dt)
initialize lead/lag controller
virtual double Control(const double error, const double dt)
compute control value based on the error
PIDController acceleration_lookup_pid_controller_
TrajectoryAnalyzer trajectory_analyzer_
void FeedforwardUpdate(SimpleMPCDebug *debug)
common::Status ComputeControlCommand(const localization::LocalizationEstimate *localization, const canbus::Chassis *chassis, const planning::ADCTrajectory *trajectory, ControlCommand *cmd) override
compute steering target and throttle/ brake based on current vehicle status and target trajectory
Eigen::MatrixXd matrix_state_
void LoadMPCGainScheduler()
Eigen::MatrixXd matrix_bd_
double max_acceleration_when_stopped_
void GetPathRemain(const planning::ADCTrajectory *planning_published_trajectory, SimpleMPCDebug *debug)
double lookback_station_high_speed_
double max_abs_speed_when_stopped_
MPCController()
constructor
Eigen::MatrixXd matrix_b_
void ProcessLogs(const SimpleMPCDebug *debug, const canbus::Chassis *chassis)
double standstill_acceleration_
void ComputeLateralErrors(const double x, const double y, const double theta, const double linear_v, const double angular_v, const double linear_a, const TrajectoryAnalyzer &trajectory_analyzer, SimpleMPCDebug *debug)
void UpdateMatrix(SimpleMPCDebug *debug)
bool enable_look_ahead_back_control_
MPCControllerConf control_conf_
std::unique_ptr< Interpolation1D > heading_err_interpolation_
double previous_ref_heading_acceleration_
double previous_heading_error_
Eigen::MatrixXd matrix_q_
LeadlagController leadlag_controller_
common::MeanFilter lateral_error_filter_
void InitControlCalibrationTable()
double previous_heading_acceleration_
std::unique_ptr< Interpolation1D > feedforwardterm_interpolation_
double lookback_station_low_speed_
Eigen::MatrixXd matrix_ad_
double previous_acceleration_vrf_
double lateral_error_feedback
std::unique_ptr< Interpolation2D > control_interpolation_
Eigen::MatrixXd matrix_r_updated_
void Stop() override
stop MPC controller
std::unique_ptr< Interpolation1D > lat_err_interpolation_
double previous_lateral_error_
double previous_lateral_acceleration_
common::DigitalFilter digital_filter_pitch_angle_
Eigen::MatrixXd matrix_cd_
bool enable_mpc_feedforward_compensation_
std::ofstream mpc_log_file_
double minimum_speed_protection_
double previous_heading_rate_
const int basic_state_size_
std::unique_ptr< Interpolation1D > steer_weight_interpolation_
double previous_acceleration_
double lookahead_station_high_speed_
calibration_table calibration_table_
double lookahead_station_low_speed_
bool use_pitch_angle_filter_
double Wheel2SteerPct(const double wheel_angle)
Eigen::MatrixXd matrix_r_
double steer_angle_feedforwardterm_updated_
double wheel_single_direction_max_degree_
bool use_lqr_curvature_feedforward_
common::VehicleParam vehicle_param_
Eigen::MatrixXd matrix_k_
common::MeanFilter heading_error_filter_
common::Status Reset() override
reset MPC Controller
double heading_error_feedback
double throttle_lowerbound_
Eigen::MatrixXd matrix_a_
double previous_acceleration_reference_
std::shared_ptr< DependencyInjector > injector_
std::string Name() const override
MPC controller name
double previous_ref_heading_rate_
double steer_single_direction_max_degree_
virtual ~MPCController()
destructor
double steer_angle_feedforwardterm_
Eigen::MatrixXd matrix_c_
common::Status Init(std::shared_ptr< DependencyInjector > injector) override
initialize MPC Controller
common::DigitalFilter digital_filter_
Eigen::MatrixXd matrix_q_updated_
Eigen::MatrixXd matrix_a_coeff_
double unconstrained_control_diff_limit_
void UpdateState(SimpleMPCDebug *debug)
void ComputeLongitudinalErrors(const TrajectoryAnalyzer *trajectory, SimpleMPCDebug *debug)
void Init(const PidConf &pid_conf)
initialize pid controller
void SetPID(const PidConf &pid_conf)
set pid controller coefficients for the proportional, integral, and derivative
virtual double Control(const double error, const double dt)
compute control value based on the error
process point query and conversion related to trajectory
common::TrajectoryPoint QueryNearestPointByPosition(const double x, const double y) const
query a point of trajectory that its position is closest to the given position.
void TrajectoryTransformToCOM(const double rear_to_com_distance)
Transform the current trajectory points to the center of mass(COM) of the vehicle,...
common::PathPoint QueryMatchedPathPoint(const double x, const double y) const
query a point on trajectory that its position is closest to the given position.
common::TrajectoryPoint QueryNearestPointByAbsoluteTime(const double t) const
query a point of trajectory that its absolute time is closest to the give time.
void ToTrajectoryFrame(const double x, const double y, const double theta, const double v, const common::PathPoint &matched_point, double *ptr_s, double *ptr_s_dot, double *ptr_d, double *ptr_d_dot) const
convert a position with theta and speed to trajectory frame,
common::TrajectoryPoint QueryNearestPointByRelativeTime(const double t) const
query a point of trajectory that its relative time is closest to the give time.
a singleton clock that can be used to get the current timestamp.
static double NowInSeconds()
gets the current time in second.
Linear interpolation functions.
Math-related util functions.
Defines the MPCController class.
T lerp(const T &x0, const double t0, const T &x1, const double t1, const double t)
Linear interpolation between two points of type T.
T Clamp(const T value, T bound1, T bound2)
Clamp a value between two bounds.
double NormalizeAngle(const double angle)
Normalize angle to [-PI, PI).
void LpfCoefficients(const double ts, const double cutoff_freq, std::vector< double > *denominators, std::vector< double > *numerators)
Get low-pass coefficients for digital filter.
optional GearPosition gear_location
optional float steering_percentage
optional PathPoint path_point
optional double throttle_deadzone
optional double max_steer_angle
optional double max_deceleration
optional double max_acceleration
optional double steer_ratio
optional float max_abs_speed_when_stopped
optional double wheel_base
optional double brake_deadzone
optional double curvature
optional double heading_acceleration
optional double lateral_error
optional double acceleration_feedback
optional double heading_jerk
optional double preview_acceleration_reference
optional double lateral_acceleration
optional bool is_full_stop
optional double speed_error
optional double station_feedback
optional double acceleration_vrf
optional double ref_heading_rate
optional double heading_error_rate
optional double lateral_error_rate
optional double slope_offset_compensation
optional double heading_error
optional double acceleration_reference
optional double station_error
optional double path_remain
optional double lateral_error_feedback
optional double ref_heading
optional double preview_speed_reference
optional double ref_heading_acceleration
optional double ref_heading_jerk
optional double heading_error_feedback
optional double heading_rate
repeated ControlCalibrationInfo calibration
repeated apollo::common::TrajectoryPoint trajectory_point
optional TrajectoryType trajectory_type
optional apollo::canbus::Chassis::GearPosition gear