Apollo  6.0
Open source self driving car software
pid_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 "modules/control/proto/pid_conf.pb.h"
25 
30 namespace apollo {
31 namespace control {
32 
39  public:
44  void Init(const PidConf &pid_conf);
45 
51  void SetPID(const PidConf &pid_conf);
52 
56  void Reset();
57 
65  virtual double Control(const double error, const double dt);
66 
67  virtual ~PIDController() = default;
68 
73  int IntegratorSaturationStatus() const;
74 
79  bool IntegratorHold() const;
80 
85  void SetIntegratorHold(bool hold);
86 
87  protected:
88  double kp_ = 0.0;
89  double ki_ = 0.0;
90  double kd_ = 0.0;
91  double kaw_ = 0.0;
92  double previous_error_ = 0.0;
93  double previous_output_ = 0.0;
94  double integral_ = 0.0;
97  bool first_hit_ = false;
98  bool integrator_enabled_ = false;
99  bool integrator_hold_ = false;
101  // Only used for pid_BC_controller and pid_IC_controller
105 };
106 
107 } // namespace control
108 } // namespace apollo
double previous_error_
Definition: pid_controller.h:92
void SetPID(const PidConf &pid_conf)
set pid controller coefficients for the proportional, integral, and derivative
bool first_hit_
Definition: pid_controller.h:97
void Reset()
reset variables for pid controller
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
bool integrator_enabled_
Definition: pid_controller.h:98
double integrator_saturation_low_
Definition: pid_controller.h:96
int IntegratorSaturationStatus() const
get saturation status
virtual double Control(const double error, const double dt)
compute control value based on the error
double previous_output_
Definition: pid_controller.h:93
double integrator_saturation_high_
Definition: pid_controller.h:95
double ki_
Definition: pid_controller.h:89
virtual ~PIDController()=default
double kp_
Definition: pid_controller.h:88
bool integrator_hold_
Definition: pid_controller.h:99
double kaw_
Definition: pid_controller.h:91
void Init(const PidConf &pid_conf)
initialize pid controller
int integrator_saturation_status_
Definition: pid_controller.h:100
double integral_
Definition: pid_controller.h:94
void SetIntegratorHold(bool hold)
set whether to hold integrator component at its current value.
double output_saturation_low_
Definition: pid_controller.h:103
int output_saturation_status_
Definition: pid_controller.h:104
double kd_
Definition: pid_controller.h:90
bool IntegratorHold() const
get status that if integrator is hold
double output_saturation_high_
Definition: pid_controller.h:102
A proportional-integral-derivative controller for speed and steering using defualt integral hold...
Definition: pid_controller.h:38