Apollo 10.0
自动驾驶开放平台
pid_controller.h
浏览该文件的文档.
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 "modules/control/control_component/proto/pid_conf.pb.h"
25
30namespace apollo {
31namespace control {
32
39 public:
44 void Init(const PidConf &pid_conf);
45
51 void SetPID(const PidConf &pid_conf);
52
56 void Reset();
57
61 void Reset_integral();
62
70 virtual double Control(const double error, const double dt);
71
72 virtual ~PIDController() = default;
73
79
84 bool IntegratorHold() const;
85
90 void SetIntegratorHold(bool hold);
91
92 protected:
93 double kp_ = 0.0;
94 double ki_ = 0.0;
95 double kd_ = 0.0;
96 double kaw_ = 0.0;
97 double previous_error_ = 0.0;
98 double previous_output_ = 0.0;
99 double integral_ = 0.0;
102 bool first_hit_ = false;
104 bool integrator_hold_ = false;
106 // Only used for pid_BC_controller and pid_IC_controller
110};
111
112} // namespace control
113} // namespace apollo
control module main class, it processes localization, chassis, and pad data to compute throttle,...
A proportional-integral-derivative controller for speed and steering using defualt integral hold
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
int IntegratorSaturationStatus() const
get saturation status
void SetIntegratorHold(bool hold)
set whether to hold integrator component at its current value.
virtual ~PIDController()=default
class register implement
Definition arena_queue.h:37