motorcontrollers.cpp
1 /********************************************************************************
2  * WorldSim -- library for robot simulations *
3  * Copyright (C) 2008-2011 Gianluca Massera <emmegian@yahoo.it> *
4  * *
5  * This program is free software; you can redistribute it and/or modify *
6  * it under the terms of the GNU General Public License as published by *
7  * the Free Software Foundation; either version 2 of the License, or *
8  * (at your option) any later version. *
9  * *
10  * This program is distributed in the hope that it will be useful, *
11  * but 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, write to the Free Software *
17  * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA *
18  ********************************************************************************/
19 
20 #include "worldsimconfig.h"
21 #include "motorcontrollers.h"
22 #include "phyjoint.h"
23 #include "world.h"
24 
25 #ifdef __GNUC__
26 #pragma GCC diagnostic ignored "-Wunused-parameter"
27 #endif
28  #include <yarp/os/Searchable.h>
29 #ifdef __GNUC__
30 #pragma GCC diagnostic warning "-Wunused-parameter"
31 #endif
32 
33 #ifdef FARSA_USE_YARP_AND_ICUB
34 using namespace yarp::dev;
35 using namespace yarp::os;
36 #endif
37 
38 namespace farsa {
39 
40 wPID::wPID() {
41  p_gain = 0;
42  i_gain = 0;
43  d_gain = 0;
44  acc_ff = 0;
45  fri_ff = 0;
46  vel_ff = 0;
47  bias = 0;
48  accel_r = 0;
49  setpt = 0;
50  min = 0;
51  max = 0;
52  slew = 0;
53  this_target = 0;
54  next_target = 0;
55  integral = 0;
56  last_error = 0;
57  last_output = 0;
58 }
59 
60 double wPID::pidloop( double PV ) {
61  double this_error;
62  double this_output;
63  double accel;
64  double deriv;
65  double friction;
66  /* the desired PV for this iteration is the value */
67  /* calculated as next_target during the last loop */
68  this_target = next_target;
69  /* test for acceleration, compute new target PV for */
70  /* the next pass through the loop */
71  if ( accel_r > 0 && this_target != setpt) {
72  if ( this_target < setpt ) {
73  next_target += accel_r;
74  if ( next_target > setpt ) {
75  next_target = setpt;
76  }
77  } else { /* this_target > setpoint */
78  next_target -= accel_r;
79  if ( next_target < setpt ) {
80  next_target = setpt;
81  }
82  }
83  } else {
84  next_target = setpt;
85  }
86  /* acceleration is the difference between the PV */
87  /* target on this pass and the next pass through the */
88  /* loop */
89  accel = next_target - this_target;
90  /* the error for the current pass is the difference */
91  /* between the current target and the current PV */
92  this_error = this_target - PV;
93  /* the derivative is the difference between the error */
94  /* for the current pass and the previous pass */
95  deriv = this_error - last_error;
96  /* a very simple determination of whether there is */
97  /* special friction to be overcome on the next pass, */
98  /* if the current PV is 0 and the target for the next */
99  /* pass is not 0, stiction could be a problem */
100  friction = ( PV == 0.0 && next_target != 0.0 );
101  /* the new error is added to the integral */
102  integral += this_target - PV;
103  /* now that all of the variable terms have been */
104  /* computed they can be multiplied by the appropriate */
105  /* coefficients and the resulting products summed */
106  this_output = p_gain * this_error
107  + i_gain * integral
108  + d_gain * deriv
109  + acc_ff * accel
110  + vel_ff * next_target
111  + fri_ff * friction
112  + bias;
113  last_error = this_error;
114  /* check for slew rate limiting on the output change */
115  if ( 0 != slew ) {
116  if ( this_output - last_output > slew ) {
117  this_output = last_output + slew;
118  } else if ( last_output - this_output > slew ) {
119  this_output = last_output - slew;
120  }
121  }
122  /* now check the output value for absolute limits */
123  if ( this_output < min ) {
124  this_output = min;
125  } else if ( this_output > max ) {
126  this_output = max;
127  }
128  /* store the new output value to be used as the old */
129  /* output value on the next loop pass */
130  return last_output = this_output;
131 }
132 
133 void wPID::reset() {
134  // Resetting status variables
135  this_target = 0;
136  next_target = 0;
137  integral = 0;
138  last_error = 0;
139  last_output = 0;
140 }
141 
142 MotorController::MotorController( World* world ) {
143  enabled = true;
144  worldv = world;
145 }
146 
147 MotorController::~MotorController() {
148 }
149 
150 
151 MultiMotorController::MultiMotorController( QVector<PhyDOF*> dofs, World* world ) :
152  MotorController(world),
153 #ifdef FARSA_USE_YARP_AND_ICUB
154  IPositionControl(),
155  IVelocityControl(),
156 #endif
157  motorsv(dofs)
158 {
159  //--- common control variable initialization
160  controlModes.fill( 1, motorsv.size() );
161  refsacc.fill( 1.0, motorsv.size() );
162  //--- IPositionControl variable initialization
163  refs.fill( 0.0, motorsv.size() );
164  refsvel.fill( 1.0, motorsv.size() );
165  xfx0.fill( 0.0, motorsv.size() );
166  x0.fill( 0.0, motorsv.size() );
167  dx0.fill( 0.0, motorsv.size() );
168  t.fill( 0.0, motorsv.size() );
169  T.fill( 0.0, motorsv.size() );
170  stops.fill( true, motorsv.size() );
171  lastErrors.fill( 0.0, motorsv.size() );
172  lastIs.fill( 0.0, motorsv.size() );
173  lastTorques.fill( 0.0, motorsv.size() );
174  // create PIDs with default values
175  pos_pids.resize( motorsv.size() );
176  for( int i=0; i<motorsv.size(); i++ ) {
177  pos_pids[i] = new wPID();
178  pos_pids[i]->p_gain = 0.8;
179  pos_pids[i]->i_gain = 0.05;
180  pos_pids[i]->d_gain = 0.0;
181  pos_pids[i]->accel_r = 0;
182  pos_pids[i]->min = -PI_GRECO/2.0;
183  pos_pids[i]->max = +PI_GRECO/2.0;
184  }
185  //--- IVelocityControl variable initialization
186  desiredVel.fill( 0.0, motorsv.size() );
187  // create PIDs with default values
188  vel_pids.resize( motorsv.size() );
189  for( int i=0; i<motorsv.size(); i++ ) {
190  vel_pids[i] = new wPID();
191  vel_pids[i]->p_gain = 0.8;
192  vel_pids[i]->i_gain = 0.1;
193  vel_pids[i]->d_gain = 0.0;
194  //vel_pids[i]->accel_r = 3;
195  //vel_pids[i]->acc_ff = 0.3;
196  vel_pids[i]->min = -toRad( 120 ); // rads / second
197  vel_pids[i]->max = +toRad( 120 ); // rads / second
198  }
199  //--- IControlLimits variable initialization
200  loLimits.resize( motorsv.size() );
201  hiLimits.resize( motorsv.size() );
202  for( int i=0; i<motorsv.size(); i++ ) {
203  real fmin, fmax;
204  motorsv[i]->limits( fmin, fmax );
205  loLimits[i] = fmin;
206  hiLimits[i] = fmax;
207  }
208 }
209 
211  for( int i=0; i<motorsv.size(); i++ ) {
212  delete (vel_pids[i]);
213  delete (pos_pids[i]);
214  }
215 }
216 
218  real accum, /*wishangle,*/ wishvel;
219  for( int i=0; i<motorsv.size(); i++ ) {
220  switch( controlModes[i] ) {
221  case 1: /* Position Controller */
222  if ( ! stops[i] ) {
223  real tFracT = t[i] / T[i];
224  real tFracT3= tFracT * tFracT * tFracT;
225  real tFracT4= tFracT * tFracT3;
226  real tFracT5= tFracT * tFracT4;
227 
228  //--- code from p5f code from iCub/src/controller4Dc/Code/trajectory.c
229  //float xfx0 = _xf[jj] - _x0[jj]; --- already computed when positionMove has been called
230  //float dx0 = _dx0[jj]; --- computed when positionMove has been called
231  accum = dx0[i] * tFracT;
232  accum = accum + tFracT3 * (10.0*xfx0[i] - 6.0*dx0[i]);
233  accum = accum - tFracT4 * (15.0*xfx0[i] - 8.0*dx0[i]);
234  accum = accum + tFracT5 * (6.0*xfx0[i] - 3.0*dx0[i]);
235  //--- in p5f code are missing x0 because it's added inside step_trajectory
236  accum += x0[i];
237  } else {
238  accum = refs[i];
239  }
240  //--- accum is the angle at which the joint must be at current time
241  pos_pids[i]->setpt = accum;
242 // wishangle = pos_pids[i]->pidloop( fromRawPosition(i) );
243  motorsv[i]->setDesiredPosition( toRawPosition(accum, i) /*wishangle*/ );
244  //--- advance t
245  t[i] += world()->timeStep();
246  //--- stop if necessary
247  stops[i] = ( t[i] / T[i] > 1.0 );
248  break;
249  case 2: /* Velocity Controller */
250  //--- the velocity at which the joint must be at current time
251  vel_pids[i]->setpt = desiredVel[i];
252  wishvel = vel_pids[i]->pidloop( motorsv[i]->velocity() );
253  motorsv[i]->setDesiredVelocity( wishvel );
254 // motorsv[i]->setDesiredVelocity(desiredVel[i]); // This disables the PID
255  break;
256  default:
257  break;
258  }
259  }
260  return;
261 }
262 
263 #ifdef FARSA_USE_YARP_AND_ICUB
264 
265 bool MultiMotorController::open( yarp::os::Searchable & ) {
266  return true;
267 }
268 
270  return true;
271 }
272 
273 bool MultiMotorController::configure( yarp::os::Searchable & ) {
274  return true;
275 }
276 
277 #endif
278 
280  *ax = motorsv.size();
281  return true;
282 }
283 
285  //controlMode = 1;
286  return true;
287 }
288 
289 bool MultiMotorController::positionMove(int j, double ref) {
290  if ( j < 0 && j >= motorsv.size() ) {
291  return false;
292  }
293  if ( motorsv[j]->translate() ) {
294  refs[j] = ref;
295  } else {
296  refs[j] = toRad( ref );
297  }
298  if ( motorsv[j]->isLimited() ) {
299  //--- check the limits
300  //--- stay too near to the limits may create oscillation of the joint
301  //--- about 0.5% of the range of the joint
302  real offset = (fabs(hiLimits[j])-fabs(loLimits[j]))*0.005;
303  refs[j] = ramp( loLimits[j]+offset, hiLimits[j]-offset, refs[j] );
304  }
305  //--- calculate xfx0, dx0, T
306  x0[j] = fromRawPosition(j);
307  xfx0[j] = refs[j] - x0[j];
308  dx0[j] = motorsv[j]->velocity();
309  T[j] = fabs( xfx0[j] ) / refsvel[j];
310  //--- reset t to zero
311  t[j] = 0.0;
312  // if T[j] is less that 10 ms, then it simply stay there
313  stops[j] = ( T[j] < 0.010 );
314  controlModes[j] = 1;
315  return true;
316 }
317 
318 bool MultiMotorController::positionMove(const double *newrefs) {
319  for( int i=0; i<refs.size(); i++ ) {
320  if ( motorsv[i]->translate() ) {
321  refs[i] = newrefs[i];
322  } else {
323  refs[i] = toRad( newrefs[i] );
324  }
325  if ( motorsv[i]->isLimited() ) {
326  //--- check the limits
327  //--- stay too near to the limits may create oscillation of the joint
328  //--- about 0.5% of the range of the joint
329  real offset = (fabs(hiLimits[i])-fabs(loLimits[i]))*0.005;
330  refs[i] = ramp( loLimits[i]+offset, hiLimits[i]-offset, refs[i] );
331  }
332  //--- calculate xfx0, dx0, T
333  x0[i] = fromRawPosition( i );
334  xfx0[i] = refs[i] - x0[i];
335  dx0[i] = motorsv[i]->velocity();
336  T[i] = fabs( xfx0[i] ) / refsvel[i];
337  //--- reset t to zero
338  t[i] = 0.0;
339  // if T[j] is less that 10 ms, then it simply stay there
340  stops[i] = ( T[i] < 0.010 );
341  controlModes[i] = 1;
342  }
343  return true;
344 }
345 
346 bool MultiMotorController::relativeMove(int j, double delta) {
347  if ( j < 0 && j >= motorsv.size() ) {
348  return false;
349  }
350  if ( motorsv[j]->translate() ) {
351  refs[j] += delta;
352  } else {
353  refs[j] += toRad( delta );
354  }
355  if ( motorsv[j]->isLimited() ) {
356  //--- check the limits
357  //--- stay too near to the limits may create oscillation of the joint
358  //--- about 0.5% of the range of the joint
359  real offset = (fabs(hiLimits[j])-fabs(loLimits[j]))*0.005;
360  refs[j] = ramp( loLimits[j]+offset, hiLimits[j]-offset, refs[j] );
361  }
362  //--- calculate xfx0, dx0, T
363  x0[j] = fromRawPosition(j);
364  xfx0[j] = refs[j] - x0[j];
365  dx0[j] = motorsv[j]->velocity();
366  T[j] = fabs( xfx0[j] ) / refsvel[j];
367  //--- reset t to zero
368  t[j] = 0.0;
369  stops[j] = false;
370  controlModes[j] = 1;
371  return true;
372 }
373 
374 bool MultiMotorController::relativeMove(const double *deltas) {
375  for( int i=0; i<refs.size(); i++ ) {
376  if ( motorsv[i]->translate() ) {
377  refs[i] += deltas[i];
378  } else {
379  refs[i] += toRad( deltas[i] );
380  }
381  if ( motorsv[i]->isLimited() ) {
382  //--- check the limits
383  //--- stay too near to the limits may create oscillation of the joint
384  //--- about 0.5% of the range of the joint
385  real offset = (fabs(hiLimits[i])-fabs(loLimits[i]))*0.005;
386  refs[i] = ramp( loLimits[i]+offset, hiLimits[i]-offset, refs[i] );
387  }
388  //--- calculate xfx0, dx0, T
389  x0[i] = fromRawPosition( i );
390  xfx0[i] = refs[i] - x0[i];
391  dx0[i] = motorsv[i]->velocity();
392  T[i] = fabs( xfx0[i] ) / refsvel[i];
393  //--- reset t to zero
394  t[i] = 0.0;
395  stops[i] = false;
396  controlModes[i] = 1;
397  }
398  return true;
399 }
400 
401 bool MultiMotorController::checkMotionDone(int j, bool *flag) {
402  if ( j < 0 && j >= motorsv.size() ) {
403  return false;
404  }
405  //--- I should check the actual position or just if stops[j] is true ??
406  *flag = ( fabs(fromRawPosition(j) - refs[j]) < 0.01745329 );
407  //*flag = stops[j];
408  return true;
409 }
410 
412  bool ends = true;
413  for( int i=0; i<refs.size(); i++ ) {
414  //--- I should check the actual position or just if stops[j] is true ??
415  ends &= ( fabs(fromRawPosition(i) - refs[i]) < 0.01745329 );
416  //ends &= stops[i];
417  if ( !ends ) break;
418  }
419  *flag = ends;
420  return true;
421 }
422 
423 bool MultiMotorController::setRefSpeed(int j, double sp) {
424  if ( j < 0 && j >= motorsv.size() ) {
425  return false;
426  }
427  if ( motorsv[j]->translate() ) {
428  refsvel[j] = sp;
429  } else {
430  refsvel[j] = toRad(sp);
431  }
432  motorsv[j]->setMaxVelocity( refsvel[j] );
433  return true;
434 }
435 
436 bool MultiMotorController::setRefSpeeds(const double *spds) {
437  for( int i=0; i<refs.size(); i++ ) {
438  if ( motorsv[i]->translate() ) {
439  refsvel[i] = spds[i];
440  } else {
441  refsvel[i] = toRad(spds[i]);
442  }
443  motorsv[i]->setMaxVelocity( refsvel[i] );
444  }
445  return true;
446 }
447 
449  if ( j < 0 && j >= motorsv.size() ) {
450  return false;
451  }
452  if ( motorsv[j]->translate() ) {
453  refsacc[j] = acc;
454  } else {
455  refsacc[j] = toRad(acc);
456  }
457  return true;
458 }
459 
461  for( int i=0; i<refs.size(); i++ ) {
462  if ( motorsv[i]->translate() ) {
463  refsacc[i] = accs[i];
464  } else {
465  refsacc[i] = toRad(accs[i]);
466  }
467  }
468  return true;
469 }
470 
471 bool MultiMotorController::getRefSpeed(int j, double *ref) {
472  if ( j < 0 && j >= motorsv.size() ) {
473  return false;
474  }
475  if ( motorsv[j]->translate() ) {
476  *ref = refsvel[j];
477  } else {
478  *ref = toDegree(refsvel[j]);
479  }
480  return true;
481 }
482 
484  for( int i=0; i<refsvel.size(); i++ ) {
485  if ( motorsv[i]->translate() ) {
486  spds[i] = refsvel[i];
487  } else {
488  spds[i] = toDegree(refsvel[i]);
489  }
490  }
491  return true;
492 }
493 
495  if ( j < 0 && j >= motorsv.size() ) {
496  return false;
497  }
498  if ( motorsv[j]->translate() ) {
499  *acc = refsacc[j];
500  } else {
501  *acc = toDegree(refsacc[j]);
502  }
503  return true;
504 }
505 
507  for( int i=0; i<refsvel.size(); i++ ) {
508  if ( motorsv[i]->translate() ) {
509  accs[i] = refsacc[i];
510  } else {
511  accs[i] = toDegree(refsacc[i]);
512  }
513  }
514  return true;
515 }
516 
518  if ( j < 0 && j >= motorsv.size() ) {
519  return false;
520  }
521  refs[j] = fromRawPosition(j);
522  stops[j] = true;
523  desiredVel[j] = 0;
524  motorsv[j]->setVelocity(0.0);
525  controlModes[j] = 1;
526  vel_pids[j]->reset();
527  return true;
528 }
529 
531  for( int i=0; i<motorsv.size(); i++ ) {
532  refs[i] = fromRawPosition(i);
533  stops[i] = true;
534  desiredVel[i] = 0;
535  motorsv[i]->setVelocity(0.0);
536  controlModes[i] = 1;
537  vel_pids[i]->reset();
538  }
539  return true;
540 }
541 
543  //controlMode = 2;
544  return true;
545 }
546 
547 bool MultiMotorController::velocityMove(int j, double sp) {
548  if ( j < 0 && j >= motorsv.size() ) {
549  return false;
550  }
551  controlModes[j] = 2;
552  desiredVel[j] = toRad(sp);
553  return true;
554 }
555 
556 bool MultiMotorController::velocityMove(const double *sp) {
557  for( int i=0; i<desiredVel.size(); i++ ) {
558  desiredVel[i] = toRad(sp[i]);
559  controlModes[i] = 2;
560  }
561  return true;
562 }
563 
565  if ( j < 0 && j >= motorsv.size() ) {
566  return false;
567  }
568  //--- set the position to actual position and stop the joint
569  refs[j] = fromRawPosition(j);
570  stops[j] = true;
571  controlModes[j] = 1;
572  return true;
573 }
574 
576  if ( j < 0 && j >= motorsv.size() ) {
577  return false;
578  }
579  //--- set the desired velocity to zero and stop the joint
580  desiredVel[j] = 0;
581  stops[j] = true;
582  controlModes[j] = 2;
583  return true;
584 }
585 
587  if ( j < 0 && j >= motorsv.size() ) {
588  return false;
589  }
590  //--- torque mode not implemented yet
591  return false;
592 }
593 
594 bool MultiMotorController::getControlMode( int j, int* mode ) {
595  if ( j < 0 && j >= motorsv.size() ) {
596  return false;
597  }
598  *mode = controlModes[j];
599  return true;
600 }
601 
603  for( int i=0; i<motorsv.size(); i++ ) {
604  modes[i] = controlModes[i];
605  }
606  return true;
607 }
608 
610  return false;
611 }
612 
614  return true;
615 }
616 
618  return true;
619 }
620 
621 bool MultiMotorController::setEncoder( int, double ) {
622  return true;
623 }
624 
625 bool MultiMotorController::setEncoders( const double* ) {
626  return true;
627 }
628 
629 bool MultiMotorController::getEncoder( int j, double *v ) {
630  if ( j < 0 && j >= motorsv.size() ) {
631  return false;
632  }
633  if ( motorsv[j]->translate() ) {
634  (*v) = fromRawPosition(j);
635  } else {
636  (*v) = toDegree( fromRawPosition(j) );
637  }
638  return true;
639 }
640 
641 bool MultiMotorController::getEncoders( double *encs ) {
642  for( int i=0; i<motorsv.size(); i++ ) {
643  if ( motorsv[i]->translate() ) {
644  encs[i] = fromRawPosition(i);
645  } else {
646  encs[i] = toDegree( fromRawPosition(i) );
647  }
648  }
649  return true;
650 }
651 
652 bool MultiMotorController::getEncoderSpeed( int j, double *sp ) {
653  if ( j < 0 && j >= motorsv.size() ) {
654  return false;
655  }
656  if ( motorsv[j]->translate() ) {
657  (*sp) = motorsv[j]->velocity();
658  } else {
659  (*sp) = toDegree(motorsv[j]->velocity());
660  }
661  return true;
662 }
663 
665  for( int i=0; i<motorsv.size(); i++ ) {
666  if ( motorsv[i]->translate() ) {
667  spds[i] = motorsv[i]->velocity();
668  } else {
669  spds[i] = toDegree(motorsv[i]->velocity());
670  }
671  }
672  return true;
673 }
674 
676  return false;
677 }
678 
680  return false;
681 }
682 
683 bool MultiMotorController::setLimits( int axis, double min, double max ) {
684  if ( axis < 0 && axis >= motorsv.size() ) {
685  return false;
686  }
687  if ( motorsv[axis]->translate() ) {
688  loLimits[axis] = min;
689  hiLimits[axis] = max;
690  } else {
691  loLimits[axis] = toRad( min );
692  hiLimits[axis] = toRad( max );
693  }
694  return true;
695 }
696 
697 bool MultiMotorController::getLimits( int axis, double *min, double *max ) {
698  if ( axis < 0 && axis >= motorsv.size() ) {
699  return false;
700  }
701  if ( motorsv[axis]->translate() ) {
702  *min = loLimits[axis];
703  *max = hiLimits[axis];
704  } else {
705  *min = toDegree( loLimits[axis] );
706  *max = toDegree( hiLimits[axis] );
707  }
708  return true;
709 }
710 
711 bool MultiMotorController::setLimitsRaw( int axis, double min, double max ) {
712  if ( axis < 0 && axis >= motorsv.size() ) {
713  return false;
714  }
715  if ( motorsv[axis]->translate() ) {
716  motorsv[axis]->setLimits( min, max );
717  } else {
718  motorsv[axis]->setLimits( toRad(min), toRad(max) );
719  }
720  return true;
721 }
722 
723 bool MultiMotorController::getLimitsRaw( int axis, double *min, double *max ) {
724  if ( axis < 0 && axis >= motorsv.size() ) {
725  return false;
726  }
727  real fmin, fmax;
728  motorsv[axis]->limits( fmin, fmax );
729  if ( motorsv[axis]->translate() ) {
730  *min = fmin;
731  *max = fmax;
732  } else {
733  *min = toDegree( fmin );
734  *max = toDegree( fmax );
735  }
736  return true;
737 }
738 
739 bool MultiMotorController::setEnableLimitsRaw( int axis, bool enable ) {
740  if ( axis < 0 && axis >= motorsv.size() ) {
741  return false;
742  }
743  if ( enable ) {
744  motorsv[axis]->enableLimits();
745  } else {
746  motorsv[axis]->disableLimits();
747  }
748  return true;
749 }
750 
751 real MultiMotorController::fromRawPosition( int i ) {
752  real rmin, rmax;
753  motorsv[i]->limits( rmin, rmax );
754  return linearMap( motorsv[i]->position(), rmin, rmax, loLimits[i], hiLimits[i] );
755 }
756 
757 real MultiMotorController::toRawPosition( real norawpos, int i ) {
758  real rmin, rmax;
759  motorsv[i]->limits( rmin, rmax );
760  return linearMap( norawpos, loLimits[i], hiLimits[i], rmin, rmax );
761 }
762 
763 WheelMotorController::WheelMotorController( QVector<PhyDOF*> wheels, World* world ) :
764  MotorController(world),
765  motorsv(wheels) {
766  desiredVel.fill( 0.0, motorsv.size() );
767  minVel.fill( -1.0, motorsv.size() );
768  maxVel.fill( 1.0, motorsv.size() );
769 }
770 
772  /* nothing to do */
773 }
774 
776  for( int i=0; i<motorsv.size(); i++ ) {
777  motorsv[i]->setDesiredVelocity( desiredVel[i] );
778  }
779 }
780 
781 void WheelMotorController::setSpeeds( QVector<double> speeds ) {
782  for( int i=0; i<qMin(speeds.size(), desiredVel.size()); i++ ) {
783  if ( speeds[i] < minVel[i] ) {
784  desiredVel[i] = minVel[i];
785  } else if ( speeds[i] > maxVel[i] ) {
786  desiredVel[i] = maxVel[i];
787  } else {
788  desiredVel[i] = speeds[i];
789  }
790  }
791 }
792 
793 void WheelMotorController::setSpeeds( double sp1, double sp2 ) {
794  if ( sp1 < minVel[0] ) {
795  desiredVel[0] = minVel[0];
796  } else if ( sp1 > maxVel[0] ) {
797  desiredVel[0] = maxVel[0];
798  } else {
799  desiredVel[0] = sp1;
800  }
801 
802  if ( sp2 < minVel[1] ) {
803  desiredVel[1] = minVel[1];
804  } else if ( sp2 > maxVel[1] ) {
805  desiredVel[1] = maxVel[1];
806  } else {
807  desiredVel[1] = sp2;
808  }
809 }
810 
811 void WheelMotorController::getSpeeds( QVector<double>& speeds ) {
812  speeds.clear();
813  for( int i=0; i<motorsv.size(); i++ ) {
814  speeds.append(motorsv[i]->velocity());
815  }
816 }
817 
818 void WheelMotorController::getSpeeds( double& sp1, double& sp2 ) {
819  sp1 = motorsv[0]->velocity();
820  sp2 = motorsv[1]->velocity();
821 }
822 
823 void WheelMotorController::setSpeedLimits( QVector<double> minSpeeds, QVector<double> maxSpeeds ) {
824  minVel = minSpeeds;
825  maxVel = maxSpeeds;
826 }
827 
828 void WheelMotorController::setSpeedLimits( double minSpeed1, double minSpeed2, double maxSpeed1, double maxSpeed2 ) {
829  minVel[0] = minSpeed1;
830  minVel[1] = minSpeed2;
831  maxVel[0] = maxSpeed1;
832  maxVel[1] = maxSpeed2;
833 }
834 
835 void WheelMotorController::getSpeedLimits( QVector<double>& minSpeeds, QVector<double>& maxSpeeds ) {
836  minSpeeds = minVel;
837  maxSpeeds = maxVel;
838 }
839 
840 void WheelMotorController::getSpeedLimits( double& minSpeed1, double& minSpeed2, double& maxSpeed1, double& maxSpeed2 ) {
841  minSpeed1 = minVel[0];
842  minSpeed2 = minVel[1];
843  maxSpeed1 = maxVel[0];
844  maxSpeed2 = maxVel[1];
845 }
846 
847 } // end namespace farsa