Apollo  6.0
Open source self driving car software
mpc_controller.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2017 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 
22 #pragma once
23 
24 #include <fstream>
25 #include <memory>
26 #include <string>
27 
28 #include "Eigen/Core"
29 #include "modules/common/configs/proto/vehicle_config.pb.h"
38 
43 namespace apollo {
44 namespace control {
45 
51 class MPCController : public Controller {
52  public:
56  MPCController();
57 
61  virtual ~MPCController();
62 
68  common::Status Init(std::shared_ptr<DependencyInjector> injector,
69  const ControlConf *control_conf) override;
70 
81  const localization::LocalizationEstimate *localization,
82  const canbus::Chassis *chassis, const planning::ADCTrajectory *trajectory,
83  ControlCommand *cmd) override;
84 
89  common::Status Reset() override;
90 
94  void Stop() override;
95 
100  std::string Name() const override;
101 
102  protected:
103  void UpdateState(SimpleMPCDebug *debug);
104 
105  void UpdateMatrix(SimpleMPCDebug *debug);
106 
107  void FeedforwardUpdate(SimpleMPCDebug *debug);
108 
109  void ComputeLateralErrors(const double x, const double y, const double theta,
110  const double linear_v, const double angular_v,
111  const double linear_a,
112  const TrajectoryAnalyzer &trajectory_analyzer,
113  SimpleMPCDebug *debug);
114 
115  void ComputeLongitudinalErrors(const TrajectoryAnalyzer *trajectory,
116  SimpleMPCDebug *debug);
117 
118  bool LoadControlConf(const ControlConf *control_conf);
119 
120  void InitializeFilters(const ControlConf *control_conf);
121 
122  void LogInitParameters();
123 
124  void ProcessLogs(const SimpleMPCDebug *debug, const canbus::Chassis *chassis);
125 
126  void CloseLogFile();
127 
128  double Wheel2SteerPct(const double wheel_angle);
129 
130  // vehicle parameter
131  common::VehicleParam vehicle_param_;
132 
133  // a proxy to analyze the planning trajectory
135 
137  const MPCControllerConf &mpc_controller_conf);
138 
139  void LoadMPCGainScheduler(const MPCControllerConf &mpc_controller_conf);
140 
141  std::unique_ptr<Interpolation2D> control_interpolation_;
142 
143  // the following parameters are vehicle physics related.
144  // control time interval
145  double ts_ = 0.0;
146  // corner stiffness; front
147  double cf_ = 0.0;
148  // corner stiffness; rear
149  double cr_ = 0.0;
150  // distance between front and rear wheel center
151  double wheelbase_ = 0.0;
152  // mass of the vehicle
153  double mass_ = 0.0;
154  // distance from front wheel center to COM
155  double lf_ = 0.0;
156  // distance from rear wheel center to COM
157  double lr_ = 0.0;
158  // rotational inertia
159  double iz_ = 0.0;
160  // the ratio between the turn of the steering wheel and the turn of the wheels
161  double steer_ratio_ = 0.0;
162  // the maximum turn of steer
164  // the maximum turn of vehicle wheel
166 
167  // limit steering to maximum theoretical lateral acceleration
168  double max_lat_acc_ = 0.0;
169 
170  // number of states, includes
171  // lateral error, lateral error rate, heading error, heading error rate,
172  // station error, velocity error,
173  const int basic_state_size_ = 6;
174 
175  const int controls_ = 2;
176 
177  const int horizon_ = 10;
178  // vehicle state matrix
179  Eigen::MatrixXd matrix_a_;
180  // vehicle state matrix (discrete-time)
181  Eigen::MatrixXd matrix_ad_;
182 
183  // control matrix
184  Eigen::MatrixXd matrix_b_;
185  // control matrix (discrete-time)
186  Eigen::MatrixXd matrix_bd_;
187 
188  // offset matrix
189  Eigen::MatrixXd matrix_c_;
190  // offset matrix (discrete-time)
191  Eigen::MatrixXd matrix_cd_;
192 
193  // gain matrix
194  Eigen::MatrixXd matrix_k_;
195  // control authority weighting matrix
196  Eigen::MatrixXd matrix_r_;
197  // updated control authority weighting matrix
198  Eigen::MatrixXd matrix_r_updated_;
199  // state weighting matrix
200  Eigen::MatrixXd matrix_q_;
201  // updated state weighting matrix
202  Eigen::MatrixXd matrix_q_updated_;
203  // vehicle state matrix coefficients
204  Eigen::MatrixXd matrix_a_coeff_;
205  // 4 by 1 matrix; state matrix
206  Eigen::MatrixXd matrix_state_;
207 
208  // heading error of last control cycle
210  // lateral distance to reference trajectory of last control cycle
212 
213  // lateral dynamic variables for computing the differential valute to
214  // estimate acceleration and jerk
216 
219 
222 
223  // longitudinal dynamic variables for computing the differential valute to
224  // estimate acceleration and jerk
227 
228  // parameters for mpc solver; number of iterations
230  // parameters for mpc solver; threshold for computation
231  double mpc_eps_ = 0.0;
232 
234 
235  std::unique_ptr<Interpolation1D> lat_err_interpolation_;
236 
237  std::unique_ptr<Interpolation1D> heading_err_interpolation_;
238 
239  std::unique_ptr<Interpolation1D> feedforwardterm_interpolation_;
240 
241  std::unique_ptr<Interpolation1D> steer_weight_interpolation_;
242 
243  // for logging purpose
244  std::ofstream mpc_log_file_;
245 
246  const std::string name_;
247 
249 
251 
253 
254  double throttle_lowerbound_ = 0.0;
255 
256  double brake_lowerbound_ = 0.0;
257 
259 
261 
262  double max_acceleration_ = 0.0;
263 
264  double max_deceleration_ = 0.0;
265 
266  // MeanFilter heading_error_filter_;
268 
269  // MeanFilter lateral_error_filter;
271 
273 
274  // Enable the feedback-gain-related compensation components in the feedfoward
275  // term for steering control
277 
278  // Limitation for judging if the unconstrained analytical control is close
279  // enough to the solver's output with constraint
281 
282  std::shared_ptr<DependencyInjector> injector_;
283 };
284 
285 } // namespace control
286 } // namespace apollo
const std::string name_
Definition: mpc_controller.h:246
double lf_
Definition: mpc_controller.h:155
double standstill_acceleration_
Definition: mpc_controller.h:252
double previous_lateral_error_
Definition: mpc_controller.h:211
common::MeanFilter lateral_error_filter_
Definition: mpc_controller.h:267
double previous_ref_heading_rate_
Definition: mpc_controller.h:218
double ts_
Definition: mpc_controller.h:145
Eigen::MatrixXd matrix_a_coeff_
Definition: mpc_controller.h:204
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 ...
double previous_ref_heading_acceleration_
Definition: mpc_controller.h:221
void InitializeFilters(const ControlConf *control_conf)
Eigen::MatrixXd matrix_cd_
Definition: mpc_controller.h:191
MPCController, combined lateral and longitudinal controllers.
Definition: mpc_controller.h:51
common::DigitalFilter digital_filter_
Definition: mpc_controller.h:233
bool enable_mpc_feedforward_compensation_
Definition: mpc_controller.h:276
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
void Stop() override
stop MPC controller
double max_lat_acc_
Definition: mpc_controller.h:168
The MeanFilter class is used to smoothen a series of noisy numbers, such as sensor data or the output...
Definition: mean_filter.h:45
void LoadControlCalibrationTable(const MPCControllerConf &mpc_controller_conf)
std::shared_ptr< DependencyInjector > injector_
Definition: mpc_controller.h:282
void UpdateMatrix(SimpleMPCDebug *debug)
double steer_angle_feedforwardterm_
Definition: mpc_controller.h:258
double max_abs_speed_when_stopped_
Definition: mpc_controller.h:250
Eigen::MatrixXd matrix_r_
Definition: mpc_controller.h:196
double minimum_speed_protection_
Definition: mpc_controller.h:272
Eigen::MatrixXd matrix_a_
Definition: mpc_controller.h:179
void ComputeLongitudinalErrors(const TrajectoryAnalyzer *trajectory, SimpleMPCDebug *debug)
Defines the MeanFilter class.
double steer_ratio_
Definition: mpc_controller.h:161
Eigen::MatrixXd matrix_state_
Definition: mpc_controller.h:206
std::unique_ptr< Interpolation2D > control_interpolation_
Definition: mpc_controller.h:141
base class for all controllers.
Definition: controller.h:46
Eigen::MatrixXd matrix_ad_
Definition: mpc_controller.h:181
Eigen::MatrixXd matrix_q_
Definition: mpc_controller.h:200
Eigen::MatrixXd matrix_k_
Definition: mpc_controller.h:194
double lr_
Definition: mpc_controller.h:157
double previous_heading_rate_
Definition: mpc_controller.h:217
Eigen::MatrixXd matrix_r_updated_
Definition: mpc_controller.h:198
void UpdateState(SimpleMPCDebug *debug)
Eigen::MatrixXd matrix_bd_
Definition: mpc_controller.h:186
void LoadMPCGainScheduler(const MPCControllerConf &mpc_controller_conf)
process point query and conversion related to trajectory
Definition: trajectory_analyzer.h:44
double steer_single_direction_max_degree_
Definition: mpc_controller.h:163
Defines the DigitalFilter class.
double cf_
Definition: mpc_controller.h:147
double wheel_single_direction_max_degree_
Definition: mpc_controller.h:165
double wheelbase_
Definition: mpc_controller.h:151
std::unique_ptr< Interpolation1D > feedforwardterm_interpolation_
Definition: mpc_controller.h:239
double steer_angle_feedforwardterm_updated_
Definition: mpc_controller.h:260
double mpc_eps_
Definition: mpc_controller.h:231
Defines the Controller base class.
double max_deceleration_
Definition: mpc_controller.h:264
double brake_lowerbound_
Definition: mpc_controller.h:256
Eigen::MatrixXd matrix_c_
Definition: mpc_controller.h:189
TrajectoryAnalyzer trajectory_analyzer_
Definition: mpc_controller.h:134
std::string Name() const override
MPC controller name.
Functions to generate coefficients for digital filter.
void ProcessLogs(const SimpleMPCDebug *debug, const canbus::Chassis *chassis)
double previous_acceleration_
Definition: mpc_controller.h:225
Eigen::MatrixXd matrix_b_
Definition: mpc_controller.h:184
const int horizon_
Definition: mpc_controller.h:177
double Wheel2SteerPct(const double wheel_angle)
double iz_
Definition: mpc_controller.h:159
common::Status Init(std::shared_ptr< DependencyInjector > injector, const ControlConf *control_conf) override
initialize MPC Controller
double max_acceleration_when_stopped_
Definition: mpc_controller.h:248
bool LoadControlConf(const ControlConf *control_conf)
const int basic_state_size_
Definition: mpc_controller.h:173
common::MeanFilter heading_error_filter_
Definition: mpc_controller.h:270
const int controls_
Definition: mpc_controller.h:175
double previous_lateral_acceleration_
Definition: mpc_controller.h:215
The DigitalFilter class is used to pass signals with a frequency lower than a certain cutoff frequenc...
Definition: digital_filter.h:40
double previous_heading_error_
Definition: mpc_controller.h:209
A general class to denote the return status of an API call. It can either be an OK status for success...
Definition: status.h:43
double previous_heading_acceleration_
Definition: mpc_controller.h:220
std::unique_ptr< Interpolation1D > steer_weight_interpolation_
Definition: mpc_controller.h:241
double cr_
Definition: mpc_controller.h:149
double throttle_lowerbound_
Definition: mpc_controller.h:254
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)
common::Status Reset() override
reset MPC Controller
void FeedforwardUpdate(SimpleMPCDebug *debug)
double unconstrained_control_diff_limit_
Definition: mpc_controller.h:280
std::ofstream mpc_log_file_
Definition: mpc_controller.h:244
virtual ~MPCController()
destructor
std::unique_ptr< Interpolation1D > lat_err_interpolation_
Definition: mpc_controller.h:235
common::VehicleParam vehicle_param_
Definition: mpc_controller.h:131
double previous_acceleration_reference_
Definition: mpc_controller.h:226
std::unique_ptr< Interpolation1D > heading_err_interpolation_
Definition: mpc_controller.h:237
Eigen::MatrixXd matrix_q_updated_
Definition: mpc_controller.h:202
double mass_
Definition: mpc_controller.h:153
double max_acceleration_
Definition: mpc_controller.h:262
int mpc_max_iteration_
Definition: mpc_controller.h:229
Defines the TrajectoryAnalyzer class.