Autoware.Auto
pid.hpp
Go to the documentation of this file.
1 // Copyright 2018-2021 Tier IV, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef TRAJECTORY_FOLLOWER__PID_HPP_
16 #define TRAJECTORY_FOLLOWER__PID_HPP_
17 
18 #include <vector>
19 
20 #include "common/types.hpp"
22 
23 namespace autoware
24 {
25 namespace motion
26 {
27 namespace control
28 {
29 namespace trajectory_follower
30 {
34 class TRAJECTORY_FOLLOWER_PUBLIC PIDController
35 {
36 public:
37  PIDController();
38 
48  float64_t calculate(
49  const float64_t error, const float64_t dt, const bool8_t is_integrated,
50  std::vector<float64_t> & pid_contributions);
57  void setGains(const float64_t kp, const float64_t ki, const float64_t kd);
69  void setLimits(
70  const float64_t max_ret, const float64_t min_ret, const float64_t max_ret_p,
71  const float64_t min_ret_p,
72  const float64_t max_ret_i, const float64_t min_ret_i, const float64_t max_ret_d,
73  const float64_t min_ret_d);
77  void reset();
78 
79 private:
80  // PID parameters
81  struct Params
82  {
83  float64_t kp;
84  float64_t ki;
85  float64_t kd;
86  float64_t max_ret_p;
87  float64_t min_ret_p;
88  float64_t max_ret_i;
89  float64_t min_ret_i;
90  float64_t max_ret_d;
91  float64_t min_ret_d;
92  float64_t max_ret;
93  float64_t min_ret;
94  };
95  Params m_params;
96 
97  // state variables
98  float64_t m_error_integral;
99  float64_t m_prev_error;
100  bool8_t m_is_first_time;
101  bool8_t m_is_gains_set;
102  bool8_t m_is_limits_set;
103 };
104 } // namespace trajectory_follower
105 } // namespace control
106 } // namespace motion
107 } // namespace autoware
108 
109 #endif // TRAJECTORY_FOLLOWER__PID_HPP_
visibility_control.hpp
autoware::motion::control::trajectory_follower::PIDController
implementation of a PID controller
Definition: pid.hpp:34
motion::motion_common::error
MOTION_COMMON_PUBLIC void error(const Point &state, const Point &ref, Diagnostic &out) noexcept
Diagnostic header stuff.
Definition: motion_common.cpp:135
types.hpp
This file includes common type definition.
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::motion::control::trajectory_follower
Definition: debug_values.hpp:29
motion
Definition: controller_base.hpp:31
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:47