59 void update(
double deltaSec,
double measuredValue,
double targetValue);
60 void update(
double measuredValue,
double targetValue);
61 void update(
double measuredValue);
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;
double controlValueDerivation
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