PidControl.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015-2018, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef PIDCONTROL_H
36 #define PIDCONTROL_H
37 
38 #include <math.h>
39 
40 namespace dbw_mkz_twist_controller {
41 
42 class PidControl {
43 public:
45  last_error_ = 0.0; int_val_ = 0.0; last_int_val_ = 0.0;
46  kp_ = 0.0; ki_ = 0.0; kd_ = 0.0; min_ = -INFINITY; max_ = INFINITY;
47  }
48  PidControl(double kp, double ki, double kd, double min, double max) {
49  last_error_ = 0.0; int_val_ = 0.0; last_int_val_ = 0.0;
50  kp_ = kp; ki_ = ki; kd_ = kd; min_ = std::min(min,max); max_ = std::max(min,max);
51  }
52 
53  void setGains(double kp, double ki, double kd) { kp_ = kp; ki_ = ki; kd_ = kd; }
54  void setRange(double min, double max) { min_ = std::min(min,max); max_ = std::max(min,max); }
55  void setParams(double kp, double ki, double kd, double min, double max) { setGains(kp,ki,kd); setRange(min,max); }
56  void resetIntegrator() { int_val_ = 0.0; last_int_val_ = 0.0; }
58 
59  double step(double error, double sample_time) {
61 
62  double integral = int_val_ + error * sample_time;
63  double derivative = (error - last_error_) / sample_time;
64 
65  double y = kp_ * error + ki_ * int_val_ + kd_ * derivative;
66  if (y > max_) {
67  y = max_;
68  } else if (y < min_) {
69  y = min_;
70  } else {
71  int_val_ = integral;
72  }
73  last_error_ = error;
74  return y;
75  }
76 
77 private:
78  double last_error_;
80  double kp_, ki_, kd_;
81  double min_, max_;
82 };
83 
84 }
85 
86 #endif // PIDCONTROL_H
87 
void setRange(double min, double max)
Definition: PidControl.h:54
void setParams(double kp, double ki, double kd, double min, double max)
Definition: PidControl.h:55
PidControl(double kp, double ki, double kd, double min, double max)
Definition: PidControl.h:48
void setGains(double kp, double ki, double kd)
Definition: PidControl.h:53
double step(double error, double sample_time)
Definition: PidControl.h:59


dbw_mkz_twist_controller
Author(s): Micho Radovnikovich , Kevin Hallenbeck
autogenerated on Thu Nov 14 2019 03:46:10