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 <memory>
28#include <mutex>
29
30#include <Eigen/Core>
31
33
35
36namespace armarx
37{
38 namespace rtfilters
39 {
40 class RTFilterBase;
41 }
42
43 class PIDController : public Logging
44 {
45 public:
46 PIDController() = default;
51
52 PIDController(float Kp,
53 float Ki,
54 float Kd,
55 double maxControlValue = std::numeric_limits<double>::max(),
56 double maxDerivation = std::numeric_limits<double>::max(),
57 bool limitless = false,
58 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 = 0 , Ki = 0, Kd = 0;
69 double integral;
70 double maxIntegral = std::numeric_limits<double>::max();
71 double conditionalIntegralErrorTreshold = std::numeric_limits<double>::max(); // anti-windup
72 double derivative;
75 double target;
76 IceUtil::Time lastUpdateTime;
83 bool threadSafe = true;
84 std::shared_ptr<rtfilters::RTFilterBase> differentialFilter;
85 std::shared_ptr<rtfilters::RTFilterBase> pdOutputFilter;
86
87 private:
88 using ScopedRecursiveLock = std::unique_lock<std::recursive_mutex>;
89 using ScopedRecursiveLockPtr = std::unique_ptr<ScopedRecursiveLock>;
90 ScopedRecursiveLockPtr getLock() const;
91 mutable std::recursive_mutex mutex;
92 };
93
94 using PIDControllerPtr = std::shared_ptr<PIDController>;
95
96
97} // namespace armarx
double getControlValue() const
void update(double deltaSec, double measuredValue, double targetValue)
std::shared_ptr< rtfilters::RTFilterBase > differentialFilter
double conditionalIntegralErrorTreshold
void setTarget(double newTarget)
void setMaxControlValue(double newMax)
PIDController & operator=(PIDController &&o)
IceUtil::Time lastUpdateTime
std::shared_ptr< rtfilters::RTFilterBase > pdOutputFilter
The RTFilterBase class is the base class for all real time capable filters.
This file offers overloads of toIce() and fromIce() functions for STL container types.
std::shared_ptr< PIDController > PIDControllerPtr