Go to the documentation of this file.
59 void update(
double deltaSec,
double measuredValue,
double targetValue);
60 void update(
double measuredValue,
double targetValue);
61 void update(
double measuredValue);
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;
double conditionalIntegralErrorTreshold
PIDController & operator=(PIDController &&o)
std::shared_ptr< PIDController > PIDControllerPtr
double getControlValue() const
void setTarget(double newTarget)
void update(double deltaSec, double measuredValue, double targetValue)
armarx::core::time::DateTime Time
double controlValueDerivation
Base Class for all Logging classes.
IceUtil::Time lastUpdateTime
std::shared_ptr< rtfilters::RTFilterBase > pdOutputFilter
This file offers overloads of toIce() and fromIce() functions for STL container types.
std::shared_ptr< rtfilters::RTFilterBase > differentialFilter
void setMaxControlValue(double newMax)