Apollo 10.0
自动驾驶开放平台
pid_controller.cc
浏览该文件的文档.
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
18
19#include <cmath>
20
21#include "cyber/common/log.h"
22
23namespace apollo {
24namespace control {
25
26double PIDController::Control(const double error, const double dt) {
27 if (dt <= 0) {
28 AWARN << "dt <= 0, will use the last output, dt: " << dt;
29 return previous_output_;
30 }
31 double diff = 0;
32 double output = 0;
33
34 if (first_hit_) {
35 first_hit_ = false;
36 } else {
37 diff = (error - previous_error_) / dt;
38 }
39 // integral hold
41 integral_ = 0;
42 } else if (!integrator_hold_) {
43 integral_ += error * dt * ki_;
44 // apply Ki before integrating to avoid steps when change Ki at steady state
51 } else {
53 }
54 }
55 previous_error_ = error;
56 output = error * kp_ + integral_ + diff * kd_; // Ki already applied
57 previous_output_ = output;
58 return output;
59}
60
65
74
75void PIDController::Init(const PidConf &pid_conf) {
76 previous_error_ = 0.0;
77 previous_output_ = 0.0;
78 integral_ = 0.0;
79 first_hit_ = true;
82 std::fabs(pid_conf.integrator_saturation_level());
84 -std::fabs(pid_conf.integrator_saturation_level());
86 integrator_hold_ = false;
88 output_saturation_low_ = -std::fabs(pid_conf.output_saturation_level());
90 SetPID(pid_conf);
91}
92
93void PIDController::SetPID(const PidConf &pid_conf) {
94 kp_ = pid_conf.kp();
95 ki_ = pid_conf.ki();
96 kd_ = pid_conf.kd();
97 kaw_ = pid_conf.kaw();
98}
99
103
105
107
108} // namespace control
109} // namespace apollo
void Init(const PidConf &pid_conf)
initialize pid controller
bool IntegratorHold() const
get status that if integrator is hold
void Reset_integral()
reset integral for pid controller
void Reset()
reset variables for 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
int IntegratorSaturationStatus() const
get saturation status
void SetIntegratorHold(bool hold)
set whether to hold integrator component at its current value.
#define AWARN
Definition log.h:43
class register implement
Definition arena_queue.h:37
Defines the PIDBCController class.
optional double output_saturation_level
optional bool integrator_enable
Definition pid_conf.proto:6
optional double integrator_saturation_level
Definition pid_conf.proto:7