PIDController.h
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5  *
6  * ArmarX is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License version 2 as
8  * published by the Free Software Foundation.
9  *
10  * ArmarX is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  *
18  * @package RobotAPI::core::PIDController
19  * @author Mirko Waechter ( mirko dot waechter at kit dot edu )
20  * @date 2014
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 
25 #pragma once
26 
27 #include "MultiDimPIDController.h"
28 
30 
31 #include <Eigen/Core>
32 
33 #include <memory>
34 #include <mutex>
35 
36 namespace armarx
37 {
38  namespace rtfilters
39  {
40  class RTFilterBase;
41  }
42 
43  class PIDController :
44  public Logging
45  {
46  public:
47  PIDController() = default;
49  PIDController(const PIDController& o);
52 
53  PIDController(float Kp,
54  float Ki,
55  float Kd,
58  bool limitless = false, bool threadSafe = true);
59  void update(double deltaSec, double measuredValue, double targetValue);
60  void update(double measuredValue, double targetValue);
61  void update(double measuredValue);
62  void setTarget(double newTarget);
63  void setMaxControlValue(double newMax);
64  double getControlValue() const;
65 
66  void reset();
67  // protected:
68  float Kp, Ki, Kd;
69  double integral;
72  double derivative;
73  double previousError;
74  double processValue;
75  double target;
77  double controlValue;
80  double maxDerivation;
81  bool firstRun;
82  bool limitless;
83  bool threadSafe = true;
84  std::shared_ptr<rtfilters::RTFilterBase> differentialFilter;
85  std::shared_ptr<rtfilters::RTFilterBase> pdOutputFilter;
86  private:
87  using ScopedRecursiveLock = std::unique_lock<std::recursive_mutex>;
88  using ScopedRecursiveLockPtr = std::unique_ptr<ScopedRecursiveLock>;
89  ScopedRecursiveLockPtr getLock() const;
90  mutable std::recursive_mutex mutex;
91  };
92  using PIDControllerPtr = std::shared_ptr<PIDController>;
93 
94 
95 }
96 
armarx::PIDController::maxControlValue
double maxControlValue
Definition: PIDController.h:79
armarx::PIDController::processValue
double processValue
Definition: PIDController.h:74
armarx::PIDController::conditionalIntegralErrorTreshold
double conditionalIntegralErrorTreshold
Definition: PIDController.h:71
armarx::PIDController::Kp
float Kp
Definition: PIDController.h:68
armarx::PIDController::operator=
PIDController & operator=(PIDController &&o)
Definition: PIDController.cpp:80
armarx::PIDControllerPtr
std::shared_ptr< PIDController > PIDControllerPtr
Definition: PIDController.h:92
armarx::PIDController::Ki
float Ki
Definition: PIDController.h:68
armarx::PIDController::Kd
float Kd
Definition: PIDController.h:68
armarx::PIDController::getControlValue
double getControlValue() const
Definition: PIDController.cpp:273
armarx::PIDController::setTarget
void setTarget(double newTarget)
Definition: PIDController.cpp:199
armarx::PIDController::update
void update(double deltaSec, double measuredValue, double targetValue)
Definition: PIDController.cpp:211
armarx::PIDController::reset
void reset()
Definition: PIDController.cpp:148
MultiDimPIDController.h
armarx::PIDController::PIDController
PIDController()=default
armarx::PIDController
Definition: PIDController.h:43
armarx::PIDController::limitless
bool limitless
Definition: PIDController.h:82
max
T max(T t1, T t2)
Definition: gdiam.h:48
armarx::PIDController::previousError
double previousError
Definition: PIDController.h:73
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::PIDController::controlValueDerivation
double controlValueDerivation
Definition: PIDController.h:78
armarx::PIDController::threadSafe
bool threadSafe
Definition: PIDController.h:83
armarx::PIDController::integral
double integral
Definition: PIDController.h:69
armarx::PIDController::controlValue
double controlValue
Definition: PIDController.h:77
armarx::Logging
Base Class for all Logging classes.
Definition: Logging.h:232
armarx::PIDController::maxIntegral
double maxIntegral
Definition: PIDController.h:70
armarx::PIDController::target
double target
Definition: PIDController.h:75
Logging.h
armarx::PIDController::derivative
double derivative
Definition: PIDController.h:72
armarx::PIDController::lastUpdateTime
IceUtil::Time lastUpdateTime
Definition: PIDController.h:76
armarx::PIDController::maxDerivation
double maxDerivation
Definition: PIDController.h:80
armarx::PIDController::pdOutputFilter
std::shared_ptr< rtfilters::RTFilterBase > pdOutputFilter
Definition: PIDController.h:85
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
armarx::PIDController::firstRun
bool firstRun
Definition: PIDController.h:81
armarx::PIDController::differentialFilter
std::shared_ptr< rtfilters::RTFilterBase > differentialFilter
Definition: PIDController.h:84
armarx::PIDController::setMaxControlValue
void setMaxControlValue(double newMax)
Definition: PIDController.cpp:205