13#include <yarp/os/Log.h>
14#include <yarp/math/Math.h>
18#define PID_SAT(x,L,H) ((x)>(H)?(H):((x)<(L)?(L):(x)))
21using namespace yarp::os;
22using namespace yarp::sig;
23using namespace yarp::math;
28Integrator::Integrator(
const double _Ts,
const Vector &y0,
const Matrix &_lim)
30 yAssert(_lim.rows()==y0.length());
31 dim=(
unsigned int)y0.length();
42Integrator::Integrator(
const double _Ts,
const Vector &y0)
44 dim=(
unsigned int)y0.length();
73 for (
unsigned int i=0; i<
dim; i++)
76 else if (res[i]>
lim(i,1))
106 yAssert(_lim.rows()==
dim);
117 yAssert(
x.length()==
dim);
130 yAssert(y0.length()==
dim);
139 Bottle &bKey=option.addList();
141 Bottle &bKeyContent=bKey.addList();
142 for (
size_t i=0; i<val.length(); i++)
143 bKeyContent.addFloat64(val[i]);
149 Vector &val,
int &size)
151 if (options.check(key))
153 if (Bottle *b=options.find(key).asList())
155 int len=(int)val.length();
156 int bSize=(int)b->size();
158 size=bSize<len?bSize:len;
159 for (
int i=0; i<size; i++)
160 val[i]=b->get(i).asFloat64();
171parallelPID::parallelPID(
const double _Ts,
172 const Vector &_Kp,
const Vector &_Ki,
const Vector &_Kd,
173 const Vector &_Wp,
const Vector &_Wi,
const Vector &_Wd,
174 const Vector &_N,
const Vector &_Tt,
const Matrix &_satLim) :
175 Ts(_Ts), Kp(_Kp), Ki(_Ki), Kd(_Kd), Wp(_Wp), Wi(_Wi), Wd(_Wd),
176 N(_N), Tt(_Tt), satLim(_satLim)
178 dim=(
unsigned int)N.length();
181 uSat.resize(dim,0.0);
182 for (
unsigned int i=0; i<dim; i++)
183 uSat[i]=
PID_SAT(u[i],satLim(i,0),satLim(i,1));
188 Vector num(2),den(2);
189 for (
unsigned int i=0; i<dim; i++)
191 if ((Kp[i]!=0.0) && (N[i]!=0.0))
193 double tau=Kd[i]/(Kp[i]*N[i]);
194 num[0]=2.0; num[1]=-2.0;
195 den[0]=Ts+2.0*tau; den[1]=Ts-2.0*tau;
199 num[0]=num[1]=den[1]=0.0;
203 Der.push_back(
new Filter(num,den,u0));
222 for (
unsigned int i=0; i<
dim; i++)
227 Vector inputD=
Kd*(
Wd*ref-fb);
228 for (
unsigned int i=0; i<
dim; i++)
230 Vector inputDi(1,inputD[i]);
231 Vector outputDi=
Der[i]->filt(inputDi);
239 for (
unsigned int i=0; i<
dim; i++)
249 size_t len=u0.length()>(size_t)
dim?(
size_t)
dim:u0.length();
253 for (
size_t i=0; i<len; i++)
267 for (
int r=0; r<
satLim.rows(); r++)
268 for (
int c=0; c<
satLim.cols(); c++)
282 Bottle &bTs=options.addList();
292 for (
int r=0; r<
satLim.rows(); r++)
293 for (
int c=0; c<
satLim.cols(); c++)
296 bool recomputeQuantities=
false;
305 recomputeQuantities=
true;
308 recomputeQuantities=
true;
311 recomputeQuantities=
true;
315 for (
int r=0; r<
satLim.rows(); r++)
316 for (
int c=0; c<
satLim.cols(); c++)
319 recomputeQuantities=
true;
322 if (options.check(
"Ts"))
324 double _Ts=options.find(
"Ts").asFloat64();
328 recomputeQuantities=
true;
332 if (recomputeQuantities)
334 for (
unsigned int i=0; i<
dim; i++)
338 Vector num(2),den(2);
339 for (
unsigned int i=0; i<
dim; i++)
341 if ((
Kp[i]!=0.0) && (
N[i]!=0.0))
343 double tau=
Kd[i]/(
Kp[i]*
N[i]);
344 num[0]=2.0; num[1]=-2.0;
345 den[0]=
Ts+2.0*tau; den[1]=
Ts-2.0*tau;
349 num[0]=num[1]=den[1]=0.0;
353 Der[i]->adjustCoeffs(num,den);
364 for (
int i=0; i<size; i++)
377 for (
unsigned int i=0; i<
dim; i++)
385seriesPID::seriesPID(
const double _Ts,
386 const Vector &_Kp,
const Vector &_Ti,
const Vector &_Kd,
387 const Vector &_N,
const Matrix &_satLim) :
388 Ts(_Ts), Kp(_Kp), Ti(_Ti), Kd(_Kd), N(_N), satLim(_satLim)
390 dim=(
unsigned int)
N.length();
394 for (
unsigned int i=0; i<
dim; i++)
398 Vector num(2),den(2);
399 for (
unsigned int i=0; i<
dim; i++)
401 num[0]=
Ts; num[1]=
Ts;
402 den[0]=
Ts+2.0*Ti[i]; den[1]=
Ts-2.0*Ti[i];
405 if ((
Kp[i]!=0.0) && (
N[i]!=0.0))
407 double tau=
Kd[i]/(
Kp[i]*
N[i]);
408 num[0]=2.0; num[1]=-2.0;
409 den[0]=
Ts+2.0*tau; den[1]=
Ts-2.0*tau;
413 num[0]=num[1]=den[1]=0.0;
434 for (
unsigned int i=0; i<
dim; i++)
436 Vector inputDi(1,
Kd[i]*
e[i]);
437 Vector outputDi=
Der[i]->filt(inputDi);
445 for (
unsigned int i=0; i<
dim; i++)
451 outputIi=
Int[i]->filt(inputIi);
460 for (
unsigned int i=0; i<
dim; i++)
471 for (
unsigned int i=0; i<
dim; i++)
483 for (
int r=0; r<
satLim.rows(); r++)
484 for (
int c=0; c<
satLim.cols(); c++)
494 Bottle &bTs=options.addList();
504 for (
int r=0; r<
satLim.rows(); r++)
505 for (
int c=0; c<
satLim.cols(); c++)
508 bool recomputeQuantities=
false;
511 recomputeQuantities=
true;
514 recomputeQuantities=
true;
517 recomputeQuantities=
true;
520 recomputeQuantities=
true;
524 for (
int r=0; r<
satLim.rows(); r++)
525 for (
int c=0; c<
satLim.cols(); c++)
528 recomputeQuantities=
true;
531 if (options.check(
"Ts"))
533 double _Ts=options.find(
"Ts").asFloat64();
537 recomputeQuantities=
true;
541 if (recomputeQuantities)
543 for (
unsigned int i=0; i<
dim; i++)
547 Vector num(2),den(2);
548 for (
unsigned int i=0; i<
dim; i++)
550 num[0]=
Ts; num[1]=
Ts;
551 den[0]=
Ts+2.0*
Ti[i]; den[1]=
Ts-2.0*
Ti[i];
552 Int[i]->adjustCoeffs(num,den);
555 if ((
Kp[i]!=0.0) && (
N[i]!=0.0))
557 double tau=
Kd[i]/(
Kp[i]*
N[i]);
558 num[0]=2.0; num[1]=-2.0;
559 den[0]=
Ts+2.0*tau; den[1]=
Ts-2.0*tau;
563 num[0]=num[1]=den[1]=0.0;
567 Der[i]->adjustCoeffs(num,den);
572 if (options.check(
"reset"))
580 for (
unsigned int i=0; i<
dim; i++)
A class for defining a saturated integrator based on Tustin formula: .
const yarp::sig::Vector & get() const
Returns the current output vector.
const yarp::sig::Vector & integrate(const yarp::sig::Vector &x)
Executes one-step integration of input vector.
void setSaturation(bool _applySat)
Sets the saturation status.
void reset(const yarp::sig::Vector &y0)
Resets the internal state and sets the output vector to the given value.
void allocate(const Integrator &I)
yarp::sig::Vector saturate(const yarp::sig::Vector &v)
void setTs(const double _Ts)
Sets the sample time.
void setLim(const yarp::sig::Matrix &_lim)
Sets the output vector constraints matrix.
static void addVectorToOption(yarp::os::Bottle &option, const char *key, const yarp::sig::Vector &val)
Add the data contained in the specified vector to the specified bottle, using property-like form (i....
static bool getVectorFromOption(const yarp::os::Bottle &options, const char *key, yarp::sig::Vector &val, int &size)
Fill the specified vector with the data associated with the specified key in the specified property-l...
virtual void getOptions(yarp::os::Bottle &options)
Returns the current options used by the pid.
~parallelPID()
Destructor.
virtual void setOptions(const yarp::os::Bottle &options)
Update the options used by the pid.
std::deque< Filter * > Der
virtual void reset(const yarp::sig::Vector &u0)
Resets the internal state of integral and derivative part.
virtual const yarp::sig::Vector & compute(const yarp::sig::Vector &ref, const yarp::sig::Vector &fb)
Computes the PID output.
virtual void setOptions(const yarp::os::Bottle &options)
Update the options used by the pid.
std::deque< Filter * > Int
virtual void reset()
Resets the internal state of integral and derivative part.
virtual const yarp::sig::Vector & compute(const yarp::sig::Vector &ref, const yarp::sig::Vector &fb)
Computes the PID output.
std::deque< Filter * > Der
virtual void getOptions(yarp::os::Bottle &options)
Returns the current options used by the pid.