YARP
Yet Another Robot Platform
fakeMotionControl.cpp
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-License-Identifier: BSD-3-Clause
4  */
5 
6 #include "fakeMotionControl.h"
7 
9 
10 #include <yarp/os/Bottle.h>
11 #include <yarp/os/Time.h>
12 #include <yarp/os/LogComponent.h>
13 #include <yarp/os/LogStream.h>
14 #include <yarp/os/NetType.h>
15 #include <yarp/dev/Drivers.h>
16 #include <yarp/math/Math.h>
17 
18 #include <sstream>
19 #include <cstring>
20 
21 using namespace yarp::dev;
22 using namespace yarp::os;
23 using namespace yarp::os::impl;
24 using namespace yarp::math;
25 
26 // macros
27 #define NEW_JSTATUS_STRUCT 1
28 #define VELOCITY_WATCHDOG 0.1
29 #define OPENLOOP_WATCHDOG 0.1
30 #define PWM_CONSTANT 0.1
31 
32 namespace {
33 YARP_LOG_COMPONENT(FAKEMOTIONCONTROL, "yarp.device.fakeMotionControl")
34 }
35 
37 {
38  for (int i=0;i <_njoints ;i++)
39  {
40  if (_controlModes[i] == VOCAB_CM_VELOCITY)
41  {
42  //increment joint position
43  if (this->_command_speeds[i]!=0)
44  {
45  double elapsed = yarp::os::Time::now()-prev_time;
46  double increment = _command_speeds[i]*elapsed;
47  pos[i]+=increment;
48  }
49 
50  //velocity watchdog
51  if (yarp::os::Time::now()-last_velocity_command[i]>=VELOCITY_WATCHDOG)
52  {
53  this->_command_speeds[i]=0.0;
54  }
55  }
56  else if (_controlModes[i] == VOCAB_CM_PWM)
57  {
58  //increment joint position
59  if (this->refpwm[i]!=0)
60  {
61  double elapsed = yarp::os::Time::now()-prev_time;
62  double increment = refpwm[i]*elapsed*PWM_CONSTANT;
63  pos[i]+=increment;
64  }
65 
66  //pwm watchdog
67  if (yarp::os::Time::now()-last_pwm_command[i]>=OPENLOOP_WATCHDOG)
68  {
69  this->refpwm[i]=0.0;
70  }
71  }
72  else if (_controlModes[i] == VOCAB_CM_POSITION_DIRECT)
73  {
74  pos[i] = _posDir_references[i];
75  }
76  else if (_controlModes[i] == VOCAB_CM_POSITION)
77  {
78  pos[i] = _posCtrl_references[i];
79  //do something with _ref_speeds[i];
80  }
81  else if (_controlModes[i] == VOCAB_CM_IDLE)
82  {
83  //do nothing
84  }
85  else if (_controlModes[i] == VOCAB_CM_MIXED)
86  {
87  //not yet implemented
88  }
89  else
90  {
91  //unsupported control mode
92  yCWarning(FAKEMOTIONCONTROL) << "Unsupported control mode, joint " << i << " " << yarp::os::Vocab32::decode(_controlModes[i]);
93  }
94  }
95  prev_time = yarp::os::Time::now();
96 }
97 
98 static inline bool NOT_YET_IMPLEMENTED(const char *txt)
99 {
100  yCError(FAKEMOTIONCONTROL) << txt << "is not yet implemented for FakeMotionControl";
101  return true;
102 }
103 
104 static inline bool DEPRECATED(const char *txt)
105 {
106  yCError(FAKEMOTIONCONTROL) << txt << "has been deprecated for FakeMotionControl";
107  return true;
108 }
109 
110 
111 // replace with to_string as soon as C++11 is required by YARP
116 template<typename T>
117 std::string toString(const T& value)
118 {
119  std::ostringstream oss;
120  oss << value;
121  return oss.str();
122 }
123 
124 //generic function that check is key1 is present in input bottle and that the result has size elements
125 // return true/false
126 bool FakeMotionControl::extractGroup(Bottle &input, Bottle &out, const std::string &key1, const std::string &txt, int size)
127 {
128  size++;
129  Bottle &tmp=input.findGroup(key1, txt);
130 
131  if (tmp.isNull())
132  {
133  yCError(FAKEMOTIONCONTROL) << key1.c_str() << "parameter not found";
134  return false;
135  }
136 
137  if(tmp.size()!=(size_t) size)
138  {
139  yCError(FAKEMOTIONCONTROL) << key1.c_str() << "incorrect number of entries";
140  return false;
141  }
142 
143  out=tmp;
144  return true;
145 }
146 
148 {
149  pos.resize(_njoints);
150  dpos.resize(_njoints);
151  vel.resize(_njoints);
152  speed.resize(_njoints);
153  acc.resize(_njoints);
154  loc.resize(_njoints);
155  amp.resize(_njoints);
156 
157  current.resize(_njoints);
158  nominalCurrent.resize(_njoints);
159  maxCurrent.resize(_njoints);
160  peakCurrent.resize(_njoints);
161  pwm.resize(_njoints);
162  refpwm.resize(_njoints);
163  pwmLimit.resize(_njoints);
164  supplyVoltage.resize(_njoints);
165  last_velocity_command.resize(_njoints);
166  last_pwm_command.resize(_njoints);
167 
168  pos.zero();
169  dpos.zero();
170  vel.zero();
171  speed.zero();
172  acc.zero();
173  loc.zero();
174  amp.zero();
175 
176  current.zero();
177  nominalCurrent.zero();
178  maxCurrent.zero();
179  peakCurrent.zero();
180 
181  pwm.zero();
182  refpwm.zero();
183  pwmLimit.zero();
184  supplyVoltage.zero();
185 }
186 
188 {
189  _axisMap = allocAndCheck<int>(nj);
190  _controlModes = allocAndCheck<int>(nj);
191  _interactMode = allocAndCheck<int>(nj);
192  _angleToEncoder = allocAndCheck<double>(nj);
193  _dutycycleToPWM = allocAndCheck<double>(nj);
194  _ampsToSensor = allocAndCheck<double>(nj);
195  _encodersStamp = allocAndCheck<double>(nj);
196  _DEPRECATED_encoderconversionoffset = allocAndCheck<float>(nj);
197  _DEPRECATED_encoderconversionfactor = allocAndCheck<float>(nj);
198 // _jointEncoderType = allocAndCheck<uint8_t>(nj);
199 // _rotorEncoderType = allocAndCheck<uint8_t>(nj);
200  _jointEncoderRes = allocAndCheck<int>(nj);
201  _rotorEncoderRes = allocAndCheck<int>(nj);
202  _gearbox = allocAndCheck<double>(nj);
203  _torqueSensorId= allocAndCheck<int>(nj);
204  _torqueSensorChan= allocAndCheck<int>(nj);
205  _maxTorque=allocAndCheck<double>(nj);
206  _torques = allocAndCheck<double>(nj);
207  _maxJntCmdVelocity = allocAndCheck<double>(nj);
208  _maxMotorVelocity = allocAndCheck<double>(nj);
209  _newtonsToSensor=allocAndCheck<double>(nj);
210  _hasHallSensor = allocAndCheck<bool>(nj);
211  _hasTempSensor = allocAndCheck<bool>(nj);
212  _hasRotorEncoder = allocAndCheck<bool>(nj);
213  _hasRotorEncoderIndex = allocAndCheck<bool>(nj);
214  _rotorIndexOffset = allocAndCheck<int>(nj);
215  _motorPoles = allocAndCheck<int>(nj);
216  _rotorlimits_max = allocAndCheck<double>(nj);
217  _rotorlimits_min = allocAndCheck<double>(nj);
218 
219  _ppids=allocAndCheck<Pid>(nj);
220  _tpids=allocAndCheck<Pid>(nj);
221  _cpids = allocAndCheck<Pid>(nj);
222  _vpids = allocAndCheck<Pid>(nj);
223  _ppids_ena=allocAndCheck<bool>(nj);
224  _tpids_ena=allocAndCheck<bool>(nj);
225  _cpids_ena = allocAndCheck<bool>(nj);
226  _vpids_ena = allocAndCheck<bool>(nj);
227  _ppids_lim=allocAndCheck<double>(nj);
228  _tpids_lim=allocAndCheck<double>(nj);
229  _cpids_lim = allocAndCheck<double>(nj);
230  _vpids_lim = allocAndCheck<double>(nj);
231  _ppids_ref=allocAndCheck<double>(nj);
232  _tpids_ref=allocAndCheck<double>(nj);
233  _cpids_ref = allocAndCheck<double>(nj);
234  _vpids_ref = allocAndCheck<double>(nj);
235 
236 // _impedance_params=allocAndCheck<ImpedanceParameters>(nj);
237 // _impedance_limits=allocAndCheck<ImpedanceLimits>(nj);
238  _axisName = new std::string[nj];
239  _jointType = new JointTypeEnum[nj];
240 
241  _limitsMax=allocAndCheck<double>(nj);
242  _limitsMin=allocAndCheck<double>(nj);
243  _kinematic_mj=allocAndCheck<double>(16);
244 // _currentLimits=allocAndCheck<MotorCurrentLimits>(nj);
245  _motorPwmLimits=allocAndCheck<double>(nj);
246  checking_motiondone=allocAndCheck<bool>(nj);
247 
248  _velocityShifts=allocAndCheck<int>(nj);
249  _velocityTimeout=allocAndCheck<int>(nj);
250  _kbemf=allocAndCheck<double>(nj);
251  _ktau=allocAndCheck<double>(nj);
252  _kbemf_scale = allocAndCheck<int>(nj);
253  _ktau_scale = allocAndCheck<int>(nj);
254  _filterType=allocAndCheck<int>(nj);
255  _last_position_move_time=allocAndCheck<double>(nj);
256 
257  // Reserve space for data stored locally. values are initialized to 0
258  _posCtrl_references = allocAndCheck<double>(nj);
259  _posDir_references = allocAndCheck<double>(nj);
260  _command_speeds = allocAndCheck<double>(nj);
261  _ref_speeds = allocAndCheck<double>(nj);
262  _ref_accs = allocAndCheck<double>(nj);
263  _ref_torques = allocAndCheck<double>(nj);
264  _ref_currents = allocAndCheck<double>(nj);
265  _enabledAmp = allocAndCheck<bool>(nj);
266  _enabledPid = allocAndCheck<bool>(nj);
267  _calibrated = allocAndCheck<bool>(nj);
268 // _cacheImpedance = allocAndCheck<eOmc_impedance_t>(nj);
269 
270  resizeBuffers();
271 
272  return true;
273 }
274 
275 bool FakeMotionControl::dealloc()
276 {
277  checkAndDestroy(_axisMap);
278  checkAndDestroy(_controlModes);
279  checkAndDestroy(_interactMode);
280  checkAndDestroy(_angleToEncoder);
281  checkAndDestroy(_ampsToSensor);
282  checkAndDestroy(_dutycycleToPWM);
283  checkAndDestroy(_encodersStamp);
284  checkAndDestroy(_DEPRECATED_encoderconversionoffset);
285  checkAndDestroy(_DEPRECATED_encoderconversionfactor);
286  checkAndDestroy(_jointEncoderRes);
287  checkAndDestroy(_rotorEncoderRes);
288 // checkAndDestroy(_jointEncoderType);
289 // checkAndDestroy(_rotorEncoderType);
290  checkAndDestroy(_gearbox);
291  checkAndDestroy(_torqueSensorId);
292  checkAndDestroy(_torqueSensorChan);
293  checkAndDestroy(_maxTorque);
294  checkAndDestroy(_maxJntCmdVelocity);
295  checkAndDestroy(_maxMotorVelocity);
296  checkAndDestroy(_newtonsToSensor);
297  checkAndDestroy(_ppids);
298  checkAndDestroy(_tpids);
299  checkAndDestroy(_cpids);
300  checkAndDestroy(_vpids);
301  checkAndDestroy(_ppids_ena);
302  checkAndDestroy(_tpids_ena);
303  checkAndDestroy(_cpids_ena);
304  checkAndDestroy(_vpids_ena);
305  checkAndDestroy(_ppids_lim);
306  checkAndDestroy(_tpids_lim);
307  checkAndDestroy(_cpids_lim);
308  checkAndDestroy(_vpids_lim);
309  checkAndDestroy(_ppids_ref);
310  checkAndDestroy(_tpids_ref);
311  checkAndDestroy(_cpids_ref);
312  checkAndDestroy(_vpids_ref);
313 // checkAndDestroy(_impedance_params);
314 // checkAndDestroy(_impedance_limits);
315  checkAndDestroy(_limitsMax);
316  checkAndDestroy(_limitsMin);
317  checkAndDestroy(_kinematic_mj);
318 // checkAndDestroy(_currentLimits);
319  checkAndDestroy(_motorPwmLimits);
320  checkAndDestroy(checking_motiondone);
321  checkAndDestroy(_velocityShifts);
322  checkAndDestroy(_velocityTimeout);
323  checkAndDestroy(_kbemf);
324  checkAndDestroy(_ktau);
325  checkAndDestroy(_kbemf_scale);
326  checkAndDestroy(_ktau_scale);
327  checkAndDestroy(_filterType);
328  checkAndDestroy(_posCtrl_references);
329  checkAndDestroy(_posDir_references);
330  checkAndDestroy(_command_speeds);
331  checkAndDestroy(_ref_speeds);
332  checkAndDestroy(_ref_accs);
333  checkAndDestroy(_ref_torques);
334  checkAndDestroy(_ref_currents);
335  checkAndDestroy(_enabledAmp);
336  checkAndDestroy(_enabledPid);
337  checkAndDestroy(_calibrated);
338  checkAndDestroy(_hasHallSensor);
339  checkAndDestroy(_hasTempSensor);
340  checkAndDestroy(_hasRotorEncoder);
341  checkAndDestroy(_hasRotorEncoderIndex);
342  checkAndDestroy(_rotorIndexOffset);
343  checkAndDestroy(_motorPoles);
344  checkAndDestroy(_axisName);
345  checkAndDestroy(_jointType);
346  checkAndDestroy(_rotorlimits_max);
347  checkAndDestroy(_rotorlimits_min);
348  checkAndDestroy(_last_position_move_time);
349  checkAndDestroy(_torques);
350 
351  return true;
352 }
353 
355  PeriodicThread(0.01),
358  ImplementPidControl(this),
362  ImplementControlMode(this),
370  ImplementPWMControl(this),
371  ImplementMotor(this),
372  ImplementAxisInfo(this),
374  _mutex(),
375  _njoints (0),
376  _axisMap (nullptr),
377  _angleToEncoder(nullptr),
378  _encodersStamp (nullptr),
379  _ampsToSensor (nullptr),
380  _dutycycleToPWM(nullptr),
381  _DEPRECATED_encoderconversionfactor (nullptr),
382  _DEPRECATED_encoderconversionoffset (nullptr),
383  _jointEncoderRes (nullptr),
384  _rotorEncoderRes (nullptr),
385  _gearbox (nullptr),
386  _hasHallSensor (nullptr),
387  _hasTempSensor (nullptr),
388  _hasRotorEncoder (nullptr),
389  _hasRotorEncoderIndex (nullptr),
390  _rotorIndexOffset (nullptr),
391  _motorPoles (nullptr),
392  _rotorlimits_max (nullptr),
393  _rotorlimits_min (nullptr),
394  _ppids (nullptr),
395  _tpids (nullptr),
396  _cpids (nullptr),
397  _vpids (nullptr),
398  _ppids_ena (nullptr),
399  _tpids_ena (nullptr),
400  _cpids_ena (nullptr),
401  _vpids_ena (nullptr),
402  _ppids_lim (nullptr),
403  _tpids_lim (nullptr),
404  _cpids_lim (nullptr),
405  _vpids_lim (nullptr),
406  _ppids_ref (nullptr),
407  _tpids_ref (nullptr),
408  _cpids_ref (nullptr),
409  _vpids_ref (nullptr),
410  _axisName (nullptr),
411  _jointType (nullptr),
412  _limitsMin (nullptr),
413  _limitsMax (nullptr),
414  _kinematic_mj (nullptr),
415  _maxJntCmdVelocity (nullptr),
416  _maxMotorVelocity (nullptr),
417  _velocityShifts (nullptr),
418  _velocityTimeout (nullptr),
419  _kbemf (nullptr),
420  _ktau (nullptr),
421  _kbemf_scale (nullptr),
422  _ktau_scale (nullptr),
423  _filterType (nullptr),
424  _torqueSensorId (nullptr),
425  _torqueSensorChan (nullptr),
426  _maxTorque (nullptr),
427  _newtonsToSensor (nullptr),
428  checking_motiondone (nullptr),
429  _last_position_move_time(nullptr),
430  _motorPwmLimits (nullptr),
431  _torques (nullptr),
432  useRawEncoderData (false),
433  _pwmIsLimited (false),
434  _torqueControlEnabled (false),
435  _torqueControlUnits (T_MACHINE_UNITS),
436  _positionControlUnits (P_MACHINE_UNITS),
437  _controlModes (nullptr),
438  _interactMode (nullptr),
439  _enabledAmp (nullptr),
440  _enabledPid (nullptr),
441  _calibrated (nullptr),
442  _posCtrl_references (nullptr),
443  _posDir_references (nullptr),
444  _ref_speeds (nullptr),
445  _command_speeds (nullptr),
446  _ref_accs (nullptr),
447  _ref_torques (nullptr),
448  _ref_currents (nullptr),
449  prev_time (0.0),
450  opened (false),
451  verbose (VERY_VERBOSE)
452 {
453  resizeBuffers();
454  std::string tmp = yarp::conf::environment::get_string("VERBOSE_STICA");
455  verbosewhenok = (tmp != "") ? (bool)yarp::conf::numeric::from_string<int>(tmp) :
456  false;
457 }
458 
460 {
461  yCTrace(FAKEMOTIONCONTROL);
462  dealloc();
463 }
464 
466 {
467  return opened;
468 }
469 
471 {
472  yCTrace(FAKEMOTIONCONTROL);
473  for(int i=0; i<_njoints; i++)
474  {
475  pwm[i] = 33+i;
476  pwmLimit[i] = (33+i)*10;
477  current[i] = (33+i)*100;
478  maxCurrent[i] = (33+i)*1000;
479  peakCurrent[i] = (33+i)*2;
480  nominalCurrent[i] = (33+i)*20;
481  supplyVoltage[i] = (33+i)*200;
482  last_velocity_command[i] = -1;
483  last_pwm_command[i] = -1;
484  _controlModes[i] = VOCAB_CM_POSITION;
485  _maxJntCmdVelocity[i]=50.0;
486  }
487  prev_time = yarp::os::Time::now();
488  return true;
489 }
490 
492 {
493 }
494 
496 {
497  std::string str;
498 
499 // if (!config.findGroup("GENERAL").find("MotioncontrolVersion").isInt32())
500 // {
501 // yCError(FAKEMOTIONCONTROL) << "Missing MotioncontrolVersion parameter. yarprobotinterface cannot start. Please contact icub-support@iit.it";
502 // return false;
503 // }
504 // else
505 // {
506 // int mcv = config.findGroup("GENERAL").find("MotioncontrolVersion").asInt32();
507 // if (mcv != 2)
508 // {
509 // yCError(FAKEMOTIONCONTROL) << "Wrong MotioncontrolVersion parameter. yarprobotinterface cannot start. Please contact icub-support@iit.it";
510 // return false;
511 // }
512 // }
513 
514 // if(!config.findGroup("GENERAL").find("verbose").isBool())
515 // {
516 // yCError(FAKEMOTIONCONTROL) << "open() detects that general->verbose bool param is different from accepted values (true / false). Assuming false";
517 // str=" ";
518 // }
519 // else
520 // {
521 // if(config.findGroup("GENERAL").find("verbose").asBool())
522 // str=config.toString().c_str();
523 // else
524 // str=" ";
525 // }
526  str=config.toString();
527  yCTrace(FAKEMOTIONCONTROL) << str;
528 
529  //
530  // Read Configuration params from file
531  //
532  _njoints = config.findGroup("GENERAL").check("Joints",Value(1), "Number of degrees of freedom").asInt32();
533  yCInfo(FAKEMOTIONCONTROL, "Using %d joint%s", _njoints, ((_njoints != 1) ? "s" : ""));
534 
535  if(!alloc(_njoints))
536  {
537  yCError(FAKEMOTIONCONTROL) << "Malloc failed";
538  return false;
539  }
540 
541  // Default value
542  for (int i = 0; i < _njoints; i++) {
543  _newtonsToSensor[i] = 1;
544  }
545 
546  if(!fromConfig(config))
547  {
548  yCError(FAKEMOTIONCONTROL) << "Missing parameters in config file";
549  return false;
550  }
551 
552  // INIT ALL INTERFACES
553  yarp::sig::Vector tmpZeros; tmpZeros.resize (_njoints, 0.0);
554  yarp::sig::Vector tmpOnes; tmpOnes.resize (_njoints, 1.0);
555  yarp::sig::Vector bemfToRaw; bemfToRaw.resize(_njoints, 1.0);
556  yarp::sig::Vector ktauToRaw; ktauToRaw.resize(_njoints, 1.0);
557  bemfToRaw = yarp::sig::Vector(_njoints, _newtonsToSensor) / yarp::sig::Vector(_njoints, _angleToEncoder);
558  ktauToRaw = yarp::sig::Vector(_njoints, _dutycycleToPWM) / yarp::sig::Vector(_njoints, _newtonsToSensor);
559 
560  ControlBoardHelper cb(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor, _ampsToSensor, _dutycycleToPWM);
561  ControlBoardHelper cb_copy_test(cb);
562  ImplementControlCalibration::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
563  ImplementAmplifierControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
564  ImplementEncodersTimed::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
565  ImplementMotorEncoders::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
566  ImplementPositionControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
567  ImplementPidControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor, _ampsToSensor, _dutycycleToPWM);
568  ImplementPidControl::setConversionUnits(PidControlTypeEnum::VOCAB_PIDTYPE_POSITION, PidFeedbackUnitsEnum::METRIC, PidOutputUnitsEnum::DUTYCYCLE_PWM_PERCENT);
569  ImplementPidControl::setConversionUnits(PidControlTypeEnum::VOCAB_PIDTYPE_TORQUE, PidFeedbackUnitsEnum::METRIC, PidOutputUnitsEnum::DUTYCYCLE_PWM_PERCENT);
570  ImplementControlMode::initialize(_njoints, _axisMap);
571  ImplementVelocityControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
572  ImplementControlLimits::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
573  ImplementImpedanceControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor);
574  ImplementTorqueControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor, _ampsToSensor, _dutycycleToPWM, bemfToRaw.data(), ktauToRaw.data());
575  ImplementPositionDirect::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
576  ImplementInteractionMode::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
577  ImplementMotor::initialize(_njoints, _axisMap);
578  ImplementAxisInfo::initialize(_njoints, _axisMap);
579  ImplementPWMControl::initialize(_njoints, _axisMap, _dutycycleToPWM);
580  ImplementCurrentControl::initialize(_njoints, _axisMap, _ampsToSensor);
581  ImplementVirtualAnalogSensor::initialize(_njoints, _axisMap, _newtonsToSensor);
582 
583  //start the rateThread
584  bool init = this->start();
585  if(!init)
586  {
587  yCError(FAKEMOTIONCONTROL) << "open() has an error in call of FakeMotionControl::init() for board" ;
588  return false;
589  }
590  else
591  {
592  if(verbosewhenok)
593  {
594  yCDebug(FAKEMOTIONCONTROL) << "init() has successfully initted board ";
595  }
596  }
597  opened = true;
598 
599  return true;
600 }
601 
602 bool FakeMotionControl::parseImpedanceGroup_NewFormat(Bottle& pidsGroup, ImpedanceParameters vals[])
603 {
604  int j=0;
605  Bottle xtmp;
606 
607  if (!extractGroup(pidsGroup, xtmp, "stiffness", "stiffness parameter", _njoints)) {
608  return false;
609  }
610  for (j=0; j<_njoints; j++) {
611  vals[j].stiffness = xtmp.get(j+1).asFloat64();
612  }
613 
614  if (!extractGroup(pidsGroup, xtmp, "damping", "damping parameter", _njoints)) {
615  return false;
616  }
617  for (j=0; j<_njoints; j++) {
618  vals[j].damping = xtmp.get(j+1).asFloat64();
619  }
620 
621  return true;
622 }
623 
624 bool FakeMotionControl::parsePositionPidsGroup(Bottle& pidsGroup, Pid myPid[])
625 {
626  int j=0;
627  Bottle xtmp;
628 
629  if (!extractGroup(pidsGroup, xtmp, "kp", "Pid kp parameter", _njoints)) {
630  return false;
631  }
632  for (j=0; j<_njoints; j++) {
633  myPid[j].kp = xtmp.get(j+1).asFloat64();
634  }
635 
636  if (!extractGroup(pidsGroup, xtmp, "kd", "Pid kd parameter", _njoints)) {
637  return false;
638  }
639  for (j=0; j<_njoints; j++) {
640  myPid[j].kd = xtmp.get(j+1).asFloat64();
641  }
642 
643  if (!extractGroup(pidsGroup, xtmp, "ki", "Pid kp parameter", _njoints)) {
644  return false;
645  }
646  for (j=0; j<_njoints; j++) {
647  myPid[j].ki = xtmp.get(j+1).asFloat64();
648  }
649 
650  if (!extractGroup(pidsGroup, xtmp, "maxInt", "Pid maxInt parameter", _njoints)) {
651  return false;
652  }
653  for (j=0; j<_njoints; j++) {
654  myPid[j].max_int = xtmp.get(j+1).asFloat64();
655  }
656 
657  if (!extractGroup(pidsGroup, xtmp, "maxPwm", "Pid maxPwm parameter", _njoints)) {
658  return false;
659  }
660  for (j=0; j<_njoints; j++) {
661  myPid[j].max_output = xtmp.get(j+1).asFloat64();
662  }
663 
664  if (!extractGroup(pidsGroup, xtmp, "shift", "Pid shift parameter", _njoints)) {
665  return false;
666  }
667  for (j=0; j<_njoints; j++) {
668  myPid[j].scale = xtmp.get(j+1).asFloat64();
669  }
670 
671  if (!extractGroup(pidsGroup, xtmp, "ko", "Pid ko parameter", _njoints)) {
672  return false;
673  }
674  for (j=0; j<_njoints; j++) {
675  myPid[j].offset = xtmp.get(j+1).asFloat64();
676  }
677 
678  if (!extractGroup(pidsGroup, xtmp, "stictionUp", "Pid stictionUp", _njoints)) {
679  return false;
680  }
681  for (j=0; j<_njoints; j++) {
682  myPid[j].stiction_up_val = xtmp.get(j+1).asFloat64();
683  }
684 
685  if (!extractGroup(pidsGroup, xtmp, "stictionDwn", "Pid stictionDwn", _njoints)) {
686  return false;
687  }
688  for (j=0; j<_njoints; j++) {
689  myPid[j].stiction_down_val = xtmp.get(j+1).asFloat64();
690  }
691 
692  if (!extractGroup(pidsGroup, xtmp, "kff", "Pid kff parameter", _njoints)) {
693  return false;
694  }
695  for (j=0; j<_njoints; j++) {
696  myPid[j].kff = xtmp.get(j+1).asFloat64();
697  }
698 
699  //conversion from metric to machine units (if applicable)
700  if (_positionControlUnits==P_METRIC_UNITS)
701  {
702  for (j=0; j<_njoints; j++)
703  {
704  myPid[j].kp = myPid[j].kp / _angleToEncoder[j]; //[PWM/deg]
705  myPid[j].ki = myPid[j].ki / _angleToEncoder[j]; //[PWM/deg]
706  myPid[j].kd = myPid[j].kd / _angleToEncoder[j]; //[PWM/deg]
707  }
708  }
709  else
710  {
711  //do nothing
712  }
713 
714  //optional PWM limit
715  if(_pwmIsLimited)
716  { // check for value in the file
717  if (!extractGroup(pidsGroup, xtmp, "limPwm", "Limited PWD", _njoints))
718  {
719  yCError(FAKEMOTIONCONTROL) << "The PID parameter limPwm was requested but was not correctly set in the configuration file, please fill it.";
720  return false;
721  }
722 
723  yCInfo(FAKEMOTIONCONTROL) << "Using LIMITED PWM!!";
724  for (j = 0; j < _njoints; j++) {
725  myPid[j].max_output = xtmp.get(j + 1).asFloat64();
726  }
727  }
728 
729  return true;
730 }
731 
732 bool FakeMotionControl::parseTorquePidsGroup(Bottle& pidsGroup, Pid myPid[], double kbemf[], double ktau[], int filterType[])
733 {
734  int j=0;
735  Bottle xtmp;
736  if (!extractGroup(pidsGroup, xtmp, "kp", "Pid kp parameter", _njoints)) {
737  return false;
738  }
739  for (j=0; j<_njoints; j++) {
740  myPid[j].kp = xtmp.get(j+1).asFloat64();
741  }
742 
743  if (!extractGroup(pidsGroup, xtmp, "kd", "Pid kd parameter", _njoints)) {
744  return false;
745  }
746  for (j=0; j<_njoints; j++) {
747  myPid[j].kd = xtmp.get(j+1).asFloat64();
748  }
749 
750  if (!extractGroup(pidsGroup, xtmp, "ki", "Pid kp parameter", _njoints)) {
751  return false;
752  }
753  for (j=0; j<_njoints; j++) {
754  myPid[j].ki = xtmp.get(j+1).asFloat64();
755  }
756 
757  if (!extractGroup(pidsGroup, xtmp, "maxInt", "Pid maxInt parameter", _njoints)) {
758  return false;
759  }
760  for (j=0; j<_njoints; j++) {
761  myPid[j].max_int = xtmp.get(j+1).asFloat64();
762  }
763 
764  if (!extractGroup(pidsGroup, xtmp, "maxPwm", "Pid maxPwm parameter", _njoints)) {
765  return false;
766  }
767  for (j=0; j<_njoints; j++) {
768  myPid[j].max_output = xtmp.get(j+1).asFloat64();
769  }
770 
771  if (!extractGroup(pidsGroup, xtmp, "shift", "Pid shift parameter", _njoints)) {
772  return false;
773  }
774  for (j=0; j<_njoints; j++) {
775  myPid[j].scale = xtmp.get(j+1).asFloat64();
776  }
777 
778  if (!extractGroup(pidsGroup, xtmp, "ko", "Pid ko parameter", _njoints)) {
779  return false;
780  }
781  for (j=0; j<_njoints; j++) {
782  myPid[j].offset = xtmp.get(j+1).asFloat64();
783  }
784 
785  if (!extractGroup(pidsGroup, xtmp, "stictionUp", "Pid stictionUp", _njoints)) {
786  return false;
787  }
788  for (j=0; j<_njoints; j++) {
789  myPid[j].stiction_up_val = xtmp.get(j+1).asFloat64();
790  }
791 
792  if (!extractGroup(pidsGroup, xtmp, "stictionDwn", "Pid stictionDwn", _njoints)) {
793  return false;
794  }
795  for (j=0; j<_njoints; j++) {
796  myPid[j].stiction_down_val = xtmp.get(j+1).asFloat64();
797  }
798 
799  if (!extractGroup(pidsGroup, xtmp, "kff", "Pid kff parameter", _njoints)) {
800  return false;
801  }
802  for (j=0; j<_njoints; j++) {
803  myPid[j].kff = xtmp.get(j+1).asFloat64();
804  }
805 
806  if (!extractGroup(pidsGroup, xtmp, "kbemf", "kbemf parameter", _njoints)) {
807  return false;
808  }
809  for (j=0; j<_njoints; j++) {
810  kbemf[j] = xtmp.get(j+1).asFloat64();
811  }
812 
813  if (!extractGroup(pidsGroup, xtmp, "ktau", "ktau parameter", _njoints)) {
814  return false;
815  }
816  for (j=0; j<_njoints; j++) {
817  ktau[j] = xtmp.get(j+1).asFloat64();
818  }
819 
820  if (!extractGroup(pidsGroup, xtmp, "filterType", "filterType param", _njoints)) {
821  return false;
822  }
823  for (j=0; j<_njoints; j++) {
824  filterType[j] = xtmp.get(j+1).asInt32();
825  }
826 
827  //conversion from metric to machine units (if applicable)
828 // for (j=0; j<_njoints; j++)
829 // {
830 // myPid[j].kp = myPid[j].kp / _torqueControlHelper->getNewtonsToSensor(j); //[PWM/Nm]
831 // myPid[j].ki = myPid[j].ki / _torqueControlHelper->getNewtonsToSensor(j); //[PWM/Nm]
832 // myPid[j].kd = myPid[j].kd / _torqueControlHelper->getNewtonsToSensor(j); //[PWM/Nm]
833 // myPid[j].stiction_up_val = myPid[j].stiction_up_val * _torqueControlHelper->getNewtonsToSensor(j); //[Nm]
834 // myPid[j].stiction_down_val = myPid[j].stiction_down_val * _torqueControlHelper->getNewtonsToSensor(j); //[Nm]
835 // }
836 
837  //optional PWM limit
838  if(_pwmIsLimited)
839  { // check for value in the file
840  if (!extractGroup(pidsGroup, xtmp, "limPwm", "Limited PWM", _njoints))
841  {
842  yCError(FAKEMOTIONCONTROL) << "The PID parameter limPwm was requested but was not correctly set in the configuration file, please fill it.";
843  return false;
844  }
845 
846  yCInfo(FAKEMOTIONCONTROL) << "Using LIMITED PWM!!";
847  for (j = 0; j < _njoints; j++) {
848  myPid[j].max_output = xtmp.get(j + 1).asFloat64();
849  }
850  }
851 
852  return true;
853 }
854 
856 {
857  Bottle xtmp;
858  int i;
859  Bottle general = config.findGroup("GENERAL");
860 
861  // read AxisMap values from file
862  if(general.check("AxisMap"))
863  {
864  if(extractGroup(general, xtmp, "AxisMap", "a list of reordered indices for the axes", _njoints))
865  {
866  for (i = 1; (size_t)i < xtmp.size(); i++) {
867  _axisMap[i - 1] = xtmp.get(i).asInt32();
868  }
869  } else {
870  return false;
871  }
872  }
873  else
874  {
875  yCInfo(FAKEMOTIONCONTROL) << "Using default AxisMap";
876  for (i = 0; i < _njoints; i++) {
877  _axisMap[i] = i;
878  }
879  }
880 
881  if(general.check("AxisName"))
882  {
883  if (extractGroup(general, xtmp, "AxisName", "a list of strings representing the axes names", _njoints))
884  {
885  //beware: axis name has to be remapped here because they are not set using the toHw() helper function
886  for (i = 1; (size_t) i < xtmp.size(); i++)
887  {
888  _axisName[_axisMap[i - 1]] = xtmp.get(i).asString();
889  }
890  } else {
891  return false;
892  }
893  }
894  else
895  {
896  yCInfo(FAKEMOTIONCONTROL) << "Using default AxisName";
897  for (i = 0; i < _njoints; i++)
898  {
899  _axisName[_axisMap[i]] = "joint" + toString(i);
900  }
901  }
902  if(general.check("AxisType"))
903  {
904  if (extractGroup(general, xtmp, "AxisType", "a list of strings representing the axes type (revolute/prismatic)", _njoints))
905  {
906  //beware: axis type has to be remapped here because they are not set using the toHw() helper function
907  for (i = 1; (size_t) i < xtmp.size(); i++)
908  {
909  std::string typeString = xtmp.get(i).asString();
910  if (typeString == "revolute") {
911  _jointType[_axisMap[i - 1]] = VOCAB_JOINTTYPE_REVOLUTE;
912  } else if (typeString == "prismatic") {
913  _jointType[_axisMap[i - 1]] = VOCAB_JOINTTYPE_PRISMATIC;
914  } else {
915  yCError(FAKEMOTIONCONTROL, "Unknown AxisType value %s!", typeString.c_str());
916  _jointType[_axisMap[i - 1]] = VOCAB_JOINTTYPE_UNKNOWN;
917  return false;
918  }
919  }
920  } else {
921  return false;
922  }
923  }
924  else
925  {
926  yCInfo(FAKEMOTIONCONTROL) << "Using default AxisType (revolute)";
927  for (i = 0; i < _njoints; i++)
928  {
929  _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_REVOLUTE;
930  }
931  }
932 
933  // current conversions factor
934  if (general.check("ampsToSensor"))
935  {
936  if (extractGroup(general, xtmp, "ampsToSensor", "a list of scales for the ampsToSensor conversion factors", _njoints))
937  {
938  for (i = 1; (size_t) i < xtmp.size(); i++)
939  {
940  if (xtmp.get(i).isFloat64())
941  {
942  _ampsToSensor[i - 1] = xtmp.get(i).asFloat64();
943  }
944  }
945  } else {
946  return false;
947  }
948  }
949  else
950  {
951  yCInfo(FAKEMOTIONCONTROL) << "Using default ampsToSensor";
952  for (i = 0; i < _njoints; i++)
953  {
954  _ampsToSensor[i] = 1.0;
955  }
956  }
957 
958  // pwm conversions factor
959  if (general.check("fullscalePWM"))
960  {
961  if (extractGroup(general, xtmp, "fullscalePWM", "a list of scales for the fullscalePWM conversion factors", _njoints))
962  {
963  for (i = 1; (size_t) i < xtmp.size(); i++)
964  {
965  if (xtmp.get(i).isFloat64() || xtmp.get(i).isInt32())
966  {
967  _dutycycleToPWM[i - 1] = xtmp.get(i).asFloat64() / 100.0;
968  }
969  }
970  } else {
971  return false;
972  }
973  }
974  else
975  {
976  yCInfo(FAKEMOTIONCONTROL) << "Using default dutycycleToPWM=1.0";
977  for (i = 0; i < _njoints; i++) {
978  _dutycycleToPWM[i] = 1.0;
979  }
980  }
981 
982 // double tmp_A2E;
983  // Encoder scales
984  if(general.check("Encoder"))
985  {
986  if (extractGroup(general, xtmp, "Encoder", "a list of scales for the encoders", _njoints))
987  {
988  for (i = 1; (size_t) i < xtmp.size(); i++)
989  {
990  _angleToEncoder[i-1] = xtmp.get(i).asFloat64();
991  }
992  } else {
993  return false;
994  }
995  }
996  else
997  {
998  yCInfo(FAKEMOTIONCONTROL) << "Using default Encoder";
999  for (i = 0; i < _njoints; i++) {
1000  _angleToEncoder[i] = 1;
1001  }
1002  }
1003 
1004  // Joint encoder resolution
1005  /*if (!extractGroup(general, xtmp, "JointEncoderRes", "the resolution of the joint encoder", _njoints))
1006  {
1007  return false;
1008  }
1009  else
1010  {
1011  int test = xtmp.size();
1012  for (i = 1; i < xtmp.size(); i++)
1013  _jointEncoderRes[i - 1] = xtmp.get(i).asInt32();
1014  }
1015 
1016  // Joint encoder type
1017  if (!extractGroup(general, xtmp, "JointEncoderType", "JointEncoderType", _njoints))
1018  {
1019  return false;
1020  }
1021  else
1022  {
1023  int test = xtmp.size();
1024  for (i = 1; i < xtmp.size(); i++)
1025  {
1026  uint8_t val;
1027  std::string s = xtmp.get(i).asString();
1028  bool b = EncoderType_iCub2eo(&s, &val);
1029  if (b == false)
1030  {
1031  yCError(FAKEMOTIONCONTROL, "Invalid JointEncoderType: %s!", s.c_str()); return false;
1032  }
1033 // _jointEncoderType[i - 1] = val;
1034  }
1035  }
1036 */
1037 
1038  // Motor capabilities
1039 /* if (!extractGroup(general, xtmp, "HasHallSensor", "HasHallSensor 0/1 ", _njoints))
1040  {
1041  return false;
1042  }
1043  else
1044  {
1045  int test = xtmp.size();
1046  for (i = 1; i < xtmp.size(); i++)
1047  _hasHallSensor[i - 1] = xtmp.get(i).asInt32();
1048  }
1049  if (!extractGroup(general, xtmp, "HasTempSensor", "HasTempSensor 0/1 ", _njoints))
1050  {
1051  return false;
1052  }
1053  else
1054  {
1055  int test = xtmp.size();
1056  for (i = 1; i < xtmp.size(); i++)
1057  _hasTempSensor[i - 1] = xtmp.get(i).asInt32();
1058  }
1059  if (!extractGroup(general, xtmp, "HasRotorEncoder", "HasRotorEncoder 0/1 ", _njoints))
1060  {
1061  return false;
1062  }
1063  else
1064  {
1065  int test = xtmp.size();
1066  for (i = 1; i < xtmp.size(); i++)
1067  _hasRotorEncoder[i - 1] = xtmp.get(i).asInt32();
1068  }
1069  if (!extractGroup(general, xtmp, "HasRotorEncoderIndex", "HasRotorEncoderIndex 0/1 ", _njoints))
1070  {
1071  return false;
1072  }
1073  else
1074  {
1075  int test = xtmp.size();
1076  for (i = 1; i < xtmp.size(); i++)
1077  _hasRotorEncoderIndex[i - 1] = xtmp.get(i).asInt32();
1078  }
1079 
1080  // Rotor encoder res
1081  if (!extractGroup(general, xtmp, "RotorEncoderRes", "a list of scales for the rotor encoders", _njoints))
1082  {
1083  return false;
1084  }
1085  else
1086  {
1087  int test = xtmp.size();
1088  for (i = 1; i < xtmp.size(); i++)
1089  _rotorEncoderRes[i - 1] = xtmp.get(i).asInt32();
1090  }
1091 
1092  // joint encoder res
1093  if (!extractGroup(general, xtmp, "JointEncoderRes", "a list of scales for the joint encoders", _njoints))
1094  {
1095  return false;
1096  }
1097  else
1098  {
1099  int test = xtmp.size();
1100  for (i = 1; i < xtmp.size(); i++)
1101  _jointEncoderRes[i - 1] = xtmp.get(i).asInt32();
1102  }
1103 */
1104  // Number of motor poles
1105  /*if (!extractGroup(general, xtmp, "MotorPoles", "MotorPoles", _njoints))
1106  {
1107  return false;
1108  }
1109  else
1110  {
1111  int test = xtmp.size();
1112  for (i = 1; i < xtmp.size(); i++)
1113  _motorPoles[i - 1] = xtmp.get(i).asInt32();
1114  }
1115 
1116  // Rotor encoder index
1117  if (!extractGroup(general, xtmp, "RotorIndexOffset", "RotorIndexOffset", _njoints))
1118  {
1119  return false;
1120  }
1121  else
1122  {
1123  int test = xtmp.size();
1124  for (i = 1; i < xtmp.size(); i++)
1125  _rotorIndexOffset[i - 1] = xtmp.get(i).asInt32();
1126  }
1127 */
1128 
1129  // Rotor encoder type
1130 /*
1131  if (!extractGroup(general, xtmp, "RotorEncoderType", "RotorEncoderType", _njoints))
1132  {
1133  return false;
1134  }
1135  else
1136  {
1137  int test = xtmp.size();
1138  for (i = 1; i < xtmp.size(); i++)
1139  {
1140  uint8_t val;
1141  std::string s = xtmp.get(i).asString();
1142  bool b = EncoderType_iCub2eo(&s, &val);
1143  if (b == false)
1144  {
1145  yCError(FAKEMOTIONCONTROL, "Invalid RotorEncoderType: %s", s.c_str()); return false;
1146  }
1147  _rotorEncoderType[i - 1] = val;
1148  }
1149  }
1150 */
1151 /*
1152  // Gearbox
1153  if (!extractGroup(general, xtmp, "Gearbox", "The gearbox reduction ratio", _njoints))
1154  {
1155  return false;
1156  }
1157  else
1158  {
1159  int test = xtmp.size();
1160  for (i = 1; i < xtmp.size(); i++)
1161  {
1162  _gearbox[i-1] = xtmp.get(i).asFloat64();
1163  if (_gearbox[i-1]==0) {yCError(FAKEMOTIONCONTROL) << "Using a gearbox value = 0 may cause problems! Check your configuration files"; return false;}
1164  }
1165  }
1166 
1167  // Torque sensors stuff
1168  if (!extractGroup(general, xtmp, "TorqueId","a list of associated joint torque sensor ids", _njoints))
1169  {
1170  yCWarning(FAKEMOTIONCONTROL, "Using default value = 0 (disabled)");
1171  for(i=1; i<_njoints+1; i++)
1172  _torqueSensorId[i-1] = 0;
1173  }
1174  else
1175  {
1176  for (i = 1; i < xtmp.size(); i++) _torqueSensorId[i-1] = xtmp.get(i).asInt32();
1177  }
1178 
1179 
1180  if (!extractGroup(general, xtmp, "TorqueChan","a list of associated joint torque sensor channels", _njoints))
1181  {
1182  yCWarning(FAKEMOTIONCONTROL) << "fromConfig() detected that TorqueChan is not present: using default value = 0 (disabled)";
1183  for(i=1; i<_njoints+1; i++)
1184  _torqueSensorChan[i-1] = 0;
1185  }
1186  else
1187  {
1188  for (i = 1; i < xtmp.size(); i++) _torqueSensorChan[i-1] = xtmp.get(i).asInt32();
1189  }
1190 
1191 
1192  if (!extractGroup(general, xtmp, "TorqueMax","full scale value for a joint torque sensor", _njoints))
1193  {
1194  return false;
1195  }
1196  else
1197  {
1198  for (i = 1; i < xtmp.size(); i++)
1199  {
1200  _maxTorque[i-1] = xtmp.get(i).asInt32();
1201  _newtonsToSensor[i-1] = 1000.0f; // conversion from Nm into milliNm
1202  }
1203  }
1204 */
1205 
1207 /*
1208  {
1209  Bottle posPidsGroup;
1210  posPidsGroup=config.findGroup("POSITION_CONTROL", "Position Pid parameters new format");
1211  if (posPidsGroup.isNull()==false)
1212  {
1213  Value &controlUnits=posPidsGroup.find("controlUnits");
1214  if (controlUnits.isNull() == false && controlUnits.isString() == true)
1215  {
1216  if (controlUnits.toString()==std::string("metric_units"))
1217  {
1218  yCDebug(FAKEMOTIONCONTROL, "POSITION_CONTROL: using metric_units"); _positionControlUnits=P_METRIC_UNITS;
1219  }
1220  else if (controlUnits.toString()==std::string("machine_units"))
1221  {
1222  yCDebug(FAKEMOTIONCONTROL, "POSITION_CONTROL: using machine_units"); _positionControlUnits=P_MACHINE_UNITS;
1223  }
1224  else
1225  {
1226  yCError(FAKEMOTIONCONTROL) << "fromConfig(): POSITION_CONTROL section: invalid controlUnits value";
1227  return false;
1228  }
1229  }
1230  else
1231  {
1232  yCError(FAKEMOTIONCONTROL) << "fromConfig(): POSITION_CONTROL section: missing controlUnits parameter. Assuming machine_units. Please fix your configuration file.";
1233  _positionControlUnits=P_MACHINE_UNITS;
1234  }
1235 
1236 // Value &controlLaw=posPidsGroup.find("controlLaw");
1237 // if (controlLaw.isNull() == false && controlLaw.isString() == true)
1238 // {
1239 // std::string s_controlaw = controlLaw.toString();
1240 // if (s_controlaw==std::string("joint_pid_v1"))
1241 // {
1242 // if (!parsePositionPidsGroup (posPidsGroup, _pids))
1243 // {
1244 // yCError(FAKEMOTIONCONTROL) << "fromConfig(): POSITION_CONTROL section: error detected in parameters syntax";
1245 // return false;
1246 // }
1247 // else
1248 // {
1249 // yCDebug(FAKEMOTIONCONTROL, "POSITION_CONTROL: using control law joint_pid_v1");
1250 // }
1251 // }
1252 // else if (s_controlaw==std::string("not_implemented"))
1253 // {
1254 // yCDebug(FAKEMOTIONCONTROL) << "found 'not_impelemented' in position control_law. This will terminate yarprobotinterface execution.";
1255 // return false;
1256 // }
1257 // else if (s_controlaw==std::string("disabled"))
1258 // {
1259 // yCDebug(FAKEMOTIONCONTROL) << "found 'disabled' in position control_law. This will terminate yarprobotinterface execution.";
1260 // return false;
1261 // }
1262 // else
1263 // {
1264 // yCError(FAKEMOTIONCONTROL) << "Unable to use control law " << s_controlaw << " por position control. Quitting.";
1265 // return false;
1266 // }
1267 // }
1268  }
1269  else
1270  {
1271  yCError(FAKEMOTIONCONTROL) <<"fromConfig(): Error: no POS_PIDS group found in config file, returning";
1272  return false;
1273  }
1274  }
1275 */
1276 
1277 
1279 /*
1280  {
1281  Bottle trqPidsGroup;
1282  trqPidsGroup=config.findGroup("TORQUE_CONTROL", "Torque control parameters new format");
1283  if (trqPidsGroup.isNull()==false)
1284  {
1285  Value &controlUnits=trqPidsGroup.find("controlUnits");
1286  if (controlUnits.isNull() == false && controlUnits.isString() == true)
1287  {
1288  if (controlUnits.toString()==std::string("metric_units")) {yCDebug(FAKEMOTIONCONTROL, "TORQUE_CONTROL: using metric_units"); _torqueControlUnits=T_METRIC_UNITS;}
1289  else if (controlUnits.toString()==std::string("machine_units")) {yCDebug(FAKEMOTIONCONTROL, "TORQUE_CONTROL: using metric_units"); _torqueControlUnits=T_MACHINE_UNITS;}
1290  else {yCError(FAKEMOTIONCONTROL) << "fromConfig(): TORQUE_CONTROL section: invalid controlUnits value";
1291  return false;}
1292  }
1293  else
1294  {
1295  yCError(FAKEMOTIONCONTROL) << "fromConfig(): TORQUE_CONTROL section: missing controlUnits parameter. Assuming machine_units. Please fix your configuration file.";
1296  _torqueControlUnits=T_MACHINE_UNITS;
1297  }
1298 
1299  if(_torqueControlUnits==T_MACHINE_UNITS)
1300  {
1301  yarp::sig::Vector tmpOnes; tmpOnes.resize(_njoints,1.0);
1302  }
1303  else if (_torqueControlUnits==T_METRIC_UNITS)
1304  {
1305  }
1306  else
1307  {
1308  yCError(FAKEMOTIONCONTROL) << "fromConfig(): TORQUE_CONTROL section: invalid controlUnits value (_torqueControlUnits=" << _torqueControlUnits << ")";
1309  return false;
1310  }
1311  }
1312  else
1313  {
1314  yCError(FAKEMOTIONCONTROL) <<"fromConfig(): Error: no TORQUE_CONTROL group found in config file";
1315  _torqueControlEnabled = false;
1316  return false; //torque control group is mandatory
1317  }
1318  }
1319 */
1320 
1322 /*
1323  for(j=0; j<_njoints; j++)
1324  {
1325  // got from canBusMotionControl, ask to Randazzo Marco
1326  _impedance_limits[j].min_damp= 0.001;
1327  _impedance_limits[j].max_damp= 9.888;
1328  _impedance_limits[j].min_stiff= 0.002;
1329  _impedance_limits[j].max_stiff= 9.889;
1330  _impedance_limits[j].param_a= 0.011;
1331  _impedance_limits[j].param_b= 0.012;
1332  _impedance_limits[j].param_c= 0.013;
1333  }
1334 */
1335 
1337 /*
1338  if (_njoints<=4)
1339  {
1340  Bottle &coupling=config.findGroup("JOINTS_COUPLING");
1341  if (coupling.isNull())
1342  {
1343  yCWarning(FAKEMOTIONCONTROL) << "fromConfig() detected that Group JOINTS_COUPLING is not found in configuration file";
1344  //return false;
1345  }
1346  // current limit
1347  if (!extractGroup(coupling, xtmp, "kinematic_mj","the kinematic matrix 4x4 which transforms from joint space to motor space", 16))
1348  {
1349  for(i=1; i<xtmp.size(); i++) _kinematic_mj[i-1]=0.0;
1350  }
1351  else
1352  for(i=1; i<xtmp.size(); i++) _kinematic_mj[i-1]=xtmp.get(i).asFloat64();
1353  }
1354  else
1355  {
1356  //we are skipping JOINTS_COUPLING for EMS boards which control MC4 boards (for now)
1357  }
1358 */
1359 
1361 /*
1362  Bottle &limits=config.findGroup("LIMITS");
1363  if (limits.isNull())
1364  {
1365  yCWarning(FAKEMOTIONCONTROL) << "fromConfig() detected that Group LIMITS is not found in configuration file";
1366  return false;
1367  }
1368  // current limit
1369  if (!extractGroup(limits, xtmp, "OverloadCurrents","a list of current limits", _njoints))
1370  return false;
1371  else
1372  for(i=1; i<xtmp.size(); i++) _currentLimits[i-1].overloadCurrent=xtmp.get(i).asFloat64();
1373 
1374  // nominal current
1375  if (!extractGroup(limits, xtmp, "MotorNominalCurrents","a list of nominal current limits", _njoints))
1376  return false;
1377  else
1378  for(i=1; i<xtmp.size(); i++) _currentLimits[i-1].nominalCurrent =xtmp.get(i).asFloat64();
1379 
1380  // nominal current
1381  if (!extractGroup(limits, xtmp, "MotorPeakCurrents","a list of peak current limits", _njoints))
1382  return false;
1383  else
1384  for(i=1; i<xtmp.size(); i++) _currentLimits[i-1].peakCurrent=xtmp.get(i).asFloat64();
1385 
1386  // max limit
1387  if (!extractGroup(limits, xtmp, "Max","a list of maximum angles (in degrees)", _njoints))
1388  return false;
1389  else
1390  for(i=1; i<xtmp.size(); i++) _limitsMax[i-1]=xtmp.get(i).asFloat64();
1391 
1392  // min limit
1393  if (!extractGroup(limits, xtmp, "Min","a list of minimum angles (in degrees)", _njoints))
1394  return false;
1395  else
1396  for(i=1; i<xtmp.size(); i++) _limitsMin[i-1]=xtmp.get(i).asFloat64();
1397 
1398  // Rotor max limit
1399  if (!extractGroup(limits, xtmp, "RotorMax","a list of maximum rotor angles (in degrees)", _njoints))
1400  return false;
1401  else
1402  for(i=1; i<xtmp.size(); i++) _rotorlimits_max[i-1]=xtmp.get(i).asFloat64();
1403 
1404  // joint Velocity command max limit
1405  if (!extractGroup(limits, xtmp, "JntVelocityMax", "a list of maximum velocities for the joints (in degrees/s)", _njoints))
1406  return false;
1407  else
1408  for (i = 1; i<xtmp.size(); i++) _maxJntCmdVelocity[i - 1] = xtmp.get(i).asFloat64();
1409 
1410  // Rotor min limit
1411  if (!extractGroup(limits, xtmp, "RotorMin","a list of minimum roto angles (in degrees)", _njoints))
1412  return false;
1413  else
1414  for(i=1; i<xtmp.size(); i++) _rotorlimits_min[i-1]=xtmp.get(i).asFloat64();
1415 
1416  // Motor pwm limit
1417  if (!extractGroup(limits, xtmp, "MotorPwmLimit","a list of motor PWM limits", _njoints))
1418  return false;
1419  else
1420  {
1421  for(i=1; i<xtmp.size(); i++)
1422  {
1423  _motorPwmLimits[i-1]=xtmp.get(i).asFloat64();
1424  if(_motorPwmLimits[i-1]<0)
1425  {
1426  yCError(FAKEMOTIONCONTROL) << "MotorPwmLimit should be a positive value";
1427  return false;
1428  }
1429  }
1430  }
1431 */
1432  return true;
1433 }
1434 
1435 
1437 {
1438  yCTrace(FAKEMOTIONCONTROL) << " close()";
1439 
1440  ImplementControlMode::uninitialize();
1441  ImplementEncodersTimed::uninitialize();
1442  ImplementMotorEncoders::uninitialize();
1443  ImplementPositionControl::uninitialize();
1444  ImplementVelocityControl::uninitialize();
1445  ImplementPidControl::uninitialize();
1446  ImplementControlCalibration::uninitialize();
1447  ImplementAmplifierControl::uninitialize();
1448  ImplementImpedanceControl::uninitialize();
1449  ImplementControlLimits::uninitialize();
1450  ImplementTorqueControl::uninitialize();
1451  ImplementPositionDirect::uninitialize();
1452  ImplementInteractionMode::uninitialize();
1453  ImplementAxisInfo::uninitialize();
1454  ImplementVirtualAnalogSensor::uninitialize();
1455 
1456 // cleanup();
1457 
1458  return true;
1459 }
1460 
1461 void FakeMotionControl::cleanup()
1462 {
1463 
1464 }
1465 
1466 
1467 
1469 
1470 bool FakeMotionControl::setPidRaw(const PidControlTypeEnum& pidtype, int j, const Pid &pid)
1471 {
1472  yCDebug(FAKEMOTIONCONTROL) << "setPidRaw" << pidtype << j << pid.kp;
1473  switch (pidtype)
1474  {
1476  _ppids[j]=pid;
1477  break;
1479  _vpids[j]=pid;
1480  break;
1481  case VOCAB_PIDTYPE_CURRENT:
1482  _cpids[j]=pid;
1483  break;
1484  case VOCAB_PIDTYPE_TORQUE:
1485  _tpids[j]=pid;
1486  break;
1487  default:
1488  break;
1489  }
1490  return true;
1491 }
1492 
1493 bool FakeMotionControl::setPidsRaw(const PidControlTypeEnum& pidtype, const Pid *pids)
1494 {
1495  bool ret = true;
1496  for(int j=0; j< _njoints; j++)
1497  {
1498  ret &= setPidRaw(pidtype, j, pids[j]);
1499  }
1500  return ret;
1501 }
1502 
1503 bool FakeMotionControl::setPidReferenceRaw(const PidControlTypeEnum& pidtype, int j, double ref)
1504 {
1505  switch (pidtype)
1506  {
1508  _ppids_ref[j]=ref;
1509  break;
1511  _vpids_ref[j]=ref;
1512  break;
1513  case VOCAB_PIDTYPE_CURRENT:
1514  _cpids_ref[j]=ref;
1515  break;
1516  case VOCAB_PIDTYPE_TORQUE:
1517  _tpids_ref[j]=ref;
1518  break;
1519  default:
1520  break;
1521  }
1522  return true;
1523 }
1524 
1525 bool FakeMotionControl::setPidReferencesRaw(const PidControlTypeEnum& pidtype, const double *refs)
1526 {
1527  bool ret = true;
1528  for(int j=0, index=0; j< _njoints; j++, index++)
1529  {
1530  ret &= setPidReferenceRaw(pidtype, j, refs[index]);
1531  }
1532  return ret;
1533 }
1534 
1535 bool FakeMotionControl::setPidErrorLimitRaw(const PidControlTypeEnum& pidtype, int j, double limit)
1536 {
1537  switch (pidtype)
1538  {
1540  _ppids_lim[j]=limit;
1541  break;
1543  _vpids_lim[j]=limit;
1544  break;
1545  case VOCAB_PIDTYPE_CURRENT:
1546  _cpids_lim[j]=limit;
1547  break;
1548  case VOCAB_PIDTYPE_TORQUE:
1549  _tpids_lim[j]=limit;
1550  break;
1551  default:
1552  break;
1553  }
1554  return true;
1555 }
1556 
1557 bool FakeMotionControl::setPidErrorLimitsRaw(const PidControlTypeEnum& pidtype, const double *limits)
1558 {
1559  bool ret = true;
1560  for(int j=0, index=0; j< _njoints; j++, index++)
1561  {
1562  ret &= setPidErrorLimitRaw(pidtype, j, limits[index]);
1563  }
1564  return ret;
1565 }
1566 
1567 bool FakeMotionControl::getPidErrorRaw(const PidControlTypeEnum& pidtype, int j, double *err)
1568 {
1569  switch (pidtype)
1570  {
1572  *err=0.1;
1573  break;
1575  *err=0.2;
1576  break;
1577  case VOCAB_PIDTYPE_CURRENT:
1578  *err=0.3;
1579  break;
1580  case VOCAB_PIDTYPE_TORQUE:
1581  *err=0.4;
1582  break;
1583  default:
1584  break;
1585  }
1586  return true;
1587 }
1588 
1589 bool FakeMotionControl::getPidErrorsRaw(const PidControlTypeEnum& pidtype, double *errs)
1590 {
1591  bool ret = true;
1592  for(int j=0; j< _njoints; j++)
1593  {
1594  ret &= getPidErrorRaw(pidtype, j, &errs[j]);
1595  }
1596  return ret;
1597 }
1598 
1599 bool FakeMotionControl::getPidRaw(const PidControlTypeEnum& pidtype, int j, Pid *pid)
1600 {
1601  switch (pidtype)
1602  {
1604  *pid=_ppids[j];
1605  break;
1607  *pid=_vpids[j];
1608  break;
1609  case VOCAB_PIDTYPE_CURRENT:
1610  *pid=_cpids[j];
1611  break;
1612  case VOCAB_PIDTYPE_TORQUE:
1613  *pid=_tpids[j];
1614  break;
1615  default:
1616  break;
1617  }
1618  yCDebug(FAKEMOTIONCONTROL) << "getPidRaw" << pidtype << j << pid->kp;
1619  return true;
1620 }
1621 
1623 {
1624  bool ret = true;
1625 
1626  // just one joint at time, wait answer before getting to the next.
1627  // This is because otherwise too many msg will be placed into can queue
1628  for(int j=0, index=0; j<_njoints; j++, index++)
1629  {
1630  ret &=getPidRaw(pidtype, j, &pids[j]);
1631  }
1632  return ret;
1633 }
1634 
1635 bool FakeMotionControl::getPidReferenceRaw(const PidControlTypeEnum& pidtype, int j, double *ref)
1636 {
1637  switch (pidtype)
1638  {
1640  *ref=_ppids_ref[j];
1641  break;
1643  *ref=_vpids_ref[j];
1644  break;
1645  case VOCAB_PIDTYPE_CURRENT:
1646  *ref=_cpids_ref[j];
1647  break;
1648  case VOCAB_PIDTYPE_TORQUE:
1649  *ref=_tpids_ref[j];
1650  break;
1651  default:
1652  break;
1653  }
1654  return true;
1655 }
1656 
1658 {
1659  bool ret = true;
1660 
1661  // just one joint at time, wait answer before getting to the next.
1662  // This is because otherwise too many msg will be placed into can queue
1663  for(int j=0; j< _njoints; j++)
1664  {
1665  ret &= getPidReferenceRaw(pidtype, j, &refs[j]);
1666  }
1667  return ret;
1668 }
1669 
1670 bool FakeMotionControl::getPidErrorLimitRaw(const PidControlTypeEnum& pidtype, int j, double *limit)
1671 {
1672  switch (pidtype)
1673  {
1675  *limit=_ppids_lim[j];
1676  break;
1678  *limit=_vpids_lim[j];
1679  break;
1680  case VOCAB_PIDTYPE_CURRENT:
1681  *limit=_cpids_lim[j];
1682  break;
1683  case VOCAB_PIDTYPE_TORQUE:
1684  *limit=_tpids_lim[j];
1685  break;
1686  default:
1687  break;
1688  }
1689  return true;
1690 }
1691 
1693 {
1694  bool ret = true;
1695  for(int j=0, index=0; j<_njoints; j++, index++)
1696  {
1697  ret &=getPidErrorLimitRaw(pidtype, j, &limits[j]);
1698  }
1699  return ret;
1700 }
1701 
1703 {
1704  return true;
1705 }
1706 
1708 {
1709  switch (pidtype)
1710  {
1712  _ppids_ena[j]=false;
1713  break;
1715  _vpids_ena[j]=false;
1716  break;
1717  case VOCAB_PIDTYPE_CURRENT:
1718  _cpids_ena[j]=false;
1719  break;
1720  case VOCAB_PIDTYPE_TORQUE:
1721  _tpids_ena[j]=false;
1722  break;
1723  default:
1724  break;
1725  }
1726  return true;
1727 }
1728 
1730 {
1731  switch (pidtype)
1732  {
1734  _ppids_ena[j]=true;
1735  break;
1737  _vpids_ena[j]=true;
1738  break;
1739  case VOCAB_PIDTYPE_CURRENT:
1740  _cpids_ena[j]=true;
1741  break;
1742  case VOCAB_PIDTYPE_TORQUE:
1743  _tpids_ena[j]=true;
1744  break;
1745  default:
1746  break;
1747  }
1748  return true;
1749 }
1750 
1751 bool FakeMotionControl::setPidOffsetRaw(const PidControlTypeEnum& pidtype, int j, double v)
1752 {
1753  yCDebug(FAKEMOTIONCONTROL) << "setPidOffsetRaw" << pidtype << j << v;
1754  switch (pidtype)
1755  {
1757  _ppids[j].offset=v;
1758  break;
1760  _vpids[j].offset=v;
1761  break;
1762  case VOCAB_PIDTYPE_CURRENT:
1763  _cpids[j].offset=v;
1764  break;
1765  case VOCAB_PIDTYPE_TORQUE:
1766  _tpids[j].offset=v;
1767  break;
1768  default:
1769  break;
1770  }
1771  return true;
1772 }
1773 
1774 bool FakeMotionControl::isPidEnabledRaw(const PidControlTypeEnum& pidtype, int j, bool* enabled)
1775 {
1776  switch (pidtype)
1777  {
1779  *enabled=_ppids_ena[j];
1780  break;
1782  *enabled=_vpids_ena[j];
1783  break;
1784  case VOCAB_PIDTYPE_CURRENT:
1785  *enabled=_cpids_ena[j];
1786  break;
1787  case VOCAB_PIDTYPE_TORQUE:
1788  *enabled=_tpids_ena[j];
1789  break;
1790  default:
1791  break;
1792  }
1793  return true;
1794 }
1795 
1796 bool FakeMotionControl::getPidOutputRaw(const PidControlTypeEnum& pidtype, int j, double *out)
1797 {
1798  switch (pidtype)
1799  {
1801  *out=1.1 + j * 10;
1802  break;
1804  *out=1.2 + j * 10;
1805  break;
1806  case VOCAB_PIDTYPE_CURRENT:
1807  *out=1.3 + j * 10;
1808  break;
1809  case VOCAB_PIDTYPE_TORQUE:
1810  *out=1.4 + j * 10;
1811  break;
1812  default:
1813  break;
1814  }
1815  yCDebug(FAKEMOTIONCONTROL) << "getPidOutputRaw" << pidtype << j << *out;
1816  return true;
1817 }
1818 
1820 {
1821  bool ret = true;
1822  for(int j=0; j< _njoints; j++)
1823  {
1824  ret &= getPidOutputRaw(pidtype, j, &outs[j]);
1825  }
1826  return ret;
1827 }
1828 
1830 // Velocity control interface raw //
1832 
1834 {
1835  int mode=0;
1836  getControlModeRaw(j, &mode);
1837  if( (mode != VOCAB_CM_VELOCITY) &&
1838  (mode != VOCAB_CM_MIXED) &&
1839  (mode != VOCAB_CM_IMPEDANCE_VEL) &&
1840  (mode != VOCAB_CM_IDLE))
1841  {
1842  yCError(FAKEMOTIONCONTROL) << "velocityMoveRaw: skipping command because board " << " joint " << j << " is not in VOCAB_CM_VELOCITY mode";
1843  }
1844  _command_speeds[j] = sp;
1845  last_velocity_command[j]=yarp::os::Time::now();
1846  return true;
1847 }
1848 
1850 {
1851  yCTrace(FAKEMOTIONCONTROL);
1852  bool ret = true;
1853  for (int i = 0; i < _njoints; i++) {
1854  ret &= velocityMoveRaw(i, sp[i]);
1855  }
1856  return ret;
1857 }
1858 
1859 
1861 // Calibration control interface //
1863 
1865 {
1866  yCTrace(FAKEMOTIONCONTROL) << "setCalibrationParametersRaw for joint" << j;
1867  return true;
1868 }
1869 
1870 bool FakeMotionControl::calibrateAxisWithParamsRaw(int j, unsigned int type, double p1, double p2, double p3)
1871 {
1872  yCTrace(FAKEMOTIONCONTROL) << "calibrateRaw for joint" << j;
1873  return true;
1874 }
1875 
1877 {
1878  bool result = false;
1879 
1880  return result;
1881 }
1882 
1884 // Position control interface //
1886 
1888 {
1889  *ax=_njoints;
1890 
1891  return true;
1892 }
1893 
1894 bool FakeMotionControl::positionMoveRaw(int j, double ref)
1895 {
1896  if (verbose >= VERY_VERBOSE) {
1897  yCTrace(FAKEMOTIONCONTROL) << "j " << j << " ref " << ref;
1898  }
1899 
1900 // if (yarp::os::Time::now()-_last_position_move_time[j]<MAX_POSITION_MOVE_INTERVAL)
1901 // {
1902 // yCWarning(FAKEMOTIONCONTROL) << "Performance warning: You are using positionMove commands at high rate (<"<< MAX_POSITION_MOVE_INTERVAL*1000.0 <<" ms). Probably position control mode is not the right control mode to use.";
1903 // }
1904 // _last_position_move_time[j] = yarp::os::Time::now();
1905 
1906  int mode = 0;
1907  getControlModeRaw(j, &mode);
1908  if( (mode != VOCAB_CM_POSITION) &&
1909  (mode != VOCAB_CM_MIXED) &&
1910  (mode != VOCAB_CM_IMPEDANCE_POS) &&
1911  (mode != VOCAB_CM_IDLE))
1912  {
1913  yCError(FAKEMOTIONCONTROL) << "positionMoveRaw: skipping command because joint " << j << " is not in VOCAB_CM_POSITION mode";
1914  }
1915  _posCtrl_references[j] = ref;
1916  return true;
1917 }
1918 
1919 bool FakeMotionControl::positionMoveRaw(const double *refs)
1920 {
1921  if (verbose >= VERY_VERBOSE) {
1922  yCTrace(FAKEMOTIONCONTROL);
1923  }
1924 
1925  bool ret = true;
1926  for(int j=0, index=0; j< _njoints; j++, index++)
1927  {
1928  ret &= positionMoveRaw(j, refs[index]);
1929  }
1930  return ret;
1931 }
1932 
1933 bool FakeMotionControl::relativeMoveRaw(int j, double delta)
1934 {
1935  if (verbose >= VERY_VERBOSE) {
1936  yCTrace(FAKEMOTIONCONTROL) << "j " << j << " ref " << delta;
1937  }
1938 // if (yarp::os::Time::now()-_last_position_move_time[j]<MAX_POSITION_MOVE_INTERVAL)
1939 // {
1940 // yCWarning(FAKEMOTIONCONTROL) << "Performance warning: You are using positionMove commands at high rate (<"<< MAX_POSITION_MOVE_INTERVAL*1000.0 <<" ms). Probably position control mode is not the right control mode to use.";
1941 // }
1942 // _last_position_move_time[j] = yarp::os::Time::now();
1943 
1944  int mode = 0;
1945  getControlModeRaw(j, &mode);
1946  if( (mode != VOCAB_CM_POSITION) &&
1947  (mode != VOCAB_CM_MIXED) &&
1948  (mode != VOCAB_CM_IMPEDANCE_POS) &&
1949  (mode != VOCAB_CM_IDLE))
1950  {
1951  yCError(FAKEMOTIONCONTROL) << "relativeMoveRaw: skipping command because joint " << j << " is not in VOCAB_CM_POSITION mode";
1952  }
1953  _posCtrl_references[j] += delta;
1954  return false;
1955 }
1956 
1957 bool FakeMotionControl::relativeMoveRaw(const double *deltas)
1958 {
1959  if (verbose >= VERY_VERBOSE) {
1960  yCTrace(FAKEMOTIONCONTROL);
1961  }
1962 
1963  bool ret = true;
1964  for(int j=0, index=0; j< _njoints; j++, index++)
1965  {
1966  ret &= relativeMoveRaw(j, deltas[index]);
1967  }
1968  return ret;
1969 }
1970 
1971 
1973 {
1974  if (verbose >= VERY_VERBOSE) {
1975  yCTrace(FAKEMOTIONCONTROL) << "j ";
1976  }
1977 
1978  *flag = false;
1979  return false;
1980 }
1981 
1983 {
1984  if (verbose >= VERY_VERBOSE) {
1985  yCTrace(FAKEMOTIONCONTROL);
1986  }
1987 
1988  bool ret = true;
1989  bool val, tot_res = true;
1990 
1991  for(int j=0, index=0; j< _njoints; j++, index++)
1992  {
1993  ret &= checkMotionDoneRaw(&val);
1994  tot_res &= val;
1995  }
1996  *flag = tot_res;
1997  return ret;
1998 }
1999 
2001 {
2002  // Velocity is expressed in iDegrees/s
2003  // save internally the new value of speed; it'll be used in the positionMove
2004  int index = j ;
2005  _ref_speeds[index] = sp;
2006  return true;
2007 }
2008 
2009 bool FakeMotionControl::setRefSpeedsRaw(const double *spds)
2010 {
2011  // Velocity is expressed in iDegrees/s
2012  // save internally the new value of speed; it'll be used in the positionMove
2013  for(int j=0, index=0; j< _njoints; j++, index++)
2014  {
2015  _ref_speeds[index] = spds[index];
2016  }
2017  return true;
2018 }
2019 
2021 {
2022  // Acceleration is expressed in iDegrees/s^2
2023  // save internally the new value of the acceleration; it'll be used in the velocityMove command
2024 
2025  if (acc > 1e6)
2026  {
2027  _ref_accs[j ] = 1e6;
2028  }
2029  else if (acc < -1e6)
2030  {
2031  _ref_accs[j ] = -1e6;
2032  }
2033  else
2034  {
2035  _ref_accs[j ] = acc;
2036  }
2037 
2038  return true;
2039 }
2040 
2042 {
2043  // Acceleration is expressed in iDegrees/s^2
2044  // save internally the new value of the acceleration; it'll be used in the velocityMove command
2045  for(int j=0, index=0; j< _njoints; j++, index++)
2046  {
2047  if (accs[j] > 1e6)
2048  {
2049  _ref_accs[index] = 1e6;
2050  }
2051  else if (accs[j] < -1e6)
2052  {
2053  _ref_accs[index] = -1e6;
2054  }
2055  else
2056  {
2057  _ref_accs[index] = accs[j];
2058  }
2059  }
2060  return true;
2061 }
2062 
2063 bool FakeMotionControl::getRefSpeedRaw(int j, double *spd)
2064 {
2065  *spd = _ref_speeds[j];
2066  return true;
2067 }
2068 
2070 {
2071  memcpy(spds, _ref_speeds, sizeof(double) * _njoints);
2072  return true;
2073 }
2074 
2076 {
2077  *acc = _ref_accs[j];
2078  return true;
2079 }
2080 
2082 {
2083  memcpy(accs, _ref_accs, sizeof(double) * _njoints);
2084  return true;
2085 }
2086 
2088 {
2089  return false;
2090 }
2091 
2093 {
2094  bool ret = true;
2095  for(int j=0; j< _njoints; j++)
2096  {
2097  ret &= stopRaw(j);
2098  }
2099  return ret;
2100 }
2102 
2104 // Position control2 interface //
2106 
2107 bool FakeMotionControl::positionMoveRaw(const int n_joint, const int *joints, const double *refs)
2108 {
2109  if (verbose >= VERY_VERBOSE) {
2110  yCTrace(FAKEMOTIONCONTROL) << " -> n_joint " << n_joint;
2111  }
2112 
2113  for(int j=0; j<n_joint; j++)
2114  {
2115  yCDebug(FAKEMOTIONCONTROL, "j: %d; ref %f;\n", joints[j], refs[j]); fflush(stdout);
2116  }
2117 
2118  bool ret = true;
2119  for(int j=0; j<n_joint; j++)
2120  {
2121  ret = ret &&positionMoveRaw(joints[j], refs[j]);
2122  }
2123  return ret;
2124 }
2125 
2126 bool FakeMotionControl::relativeMoveRaw(const int n_joint, const int *joints, const double *deltas)
2127 {
2128  if (verbose >= VERY_VERBOSE) {
2129  yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
2130  }
2131 
2132  bool ret = true;
2133  for(int j=0; j<n_joint; j++)
2134  {
2135  ret = ret &&relativeMoveRaw(joints[j], deltas[j]);
2136  }
2137  return ret;
2138 }
2139 
2140 bool FakeMotionControl::checkMotionDoneRaw(const int n_joint, const int *joints, bool *flag)
2141 {
2142  if (verbose >= VERY_VERBOSE) {
2143  yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
2144  }
2145 
2146  bool ret = true;
2147  bool val = true;
2148  bool tot_val = true;
2149 
2150  for(int j=0; j<n_joint; j++)
2151  {
2152  ret = ret && checkMotionDoneRaw(joints[j], &val);
2153  tot_val &= val;
2154  }
2155  *flag = tot_val;
2156  return ret;
2157 }
2158 
2159 bool FakeMotionControl::setRefSpeedsRaw(const int n_joint, const int *joints, const double *spds)
2160 {
2161  if (verbose >= VERY_VERBOSE) {
2162  yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
2163  }
2164 
2165  bool ret = true;
2166  for(int j=0; j<n_joint; j++)
2167  {
2168  ret = ret &&setRefSpeedRaw(joints[j], spds[j]);
2169  }
2170  return ret;
2171 }
2172 
2173 bool FakeMotionControl::setRefAccelerationsRaw(const int n_joint, const int *joints, const double *accs)
2174 {
2175  if (verbose >= VERY_VERBOSE) {
2176  yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
2177  }
2178 
2179  bool ret = true;
2180  for(int j=0; j<n_joint; j++)
2181  {
2182  ret = ret &&setRefAccelerationRaw(joints[j], accs[j]);
2183  }
2184  return ret;
2185 }
2186 
2187 bool FakeMotionControl::getRefSpeedsRaw(const int n_joint, const int *joints, double *spds)
2188 {
2189  if (verbose >= VERY_VERBOSE) {
2190  yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
2191  }
2192 
2193  bool ret = true;
2194  for(int j=0; j<n_joint; j++)
2195  {
2196  ret = ret && getRefSpeedRaw(joints[j], &spds[j]);
2197  }
2198  return ret;
2199 }
2200 
2201 bool FakeMotionControl::getRefAccelerationsRaw(const int n_joint, const int *joints, double *accs)
2202 {
2203  if (verbose >= VERY_VERBOSE) {
2204  yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
2205  }
2206 
2207  bool ret = true;
2208  for(int j=0; j<n_joint; j++)
2209  {
2210  ret = ret && getRefAccelerationRaw(joints[j], &accs[j]);
2211  }
2212  return ret;
2213 }
2214 
2215 bool FakeMotionControl::stopRaw(const int n_joint, const int *joints)
2216 {
2217  if (verbose >= VERY_VERBOSE) {
2218  yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
2219  }
2220 
2221  bool ret = true;
2222  for(int j=0; j<n_joint; j++)
2223  {
2224  ret = ret &&stopRaw(joints[j]);
2225  }
2226  return ret;
2227 }
2228 
2230 
2231 // ControlMode
2232 
2233 // puo' essere richiesto con get
2235 {
2236  if (verbose > VERY_VERY_VERBOSE) {
2237  yCTrace(FAKEMOTIONCONTROL) << "j: " << j;
2238  }
2239 
2240  *v = _controlModes[j];
2241  return true;
2242 }
2243 
2244 // IControl Mode 2
2246 {
2247  bool ret = true;
2248  for(int j=0; j< _njoints; j++)
2249  {
2250  ret = ret && getControlModeRaw(j, &v[j]);
2251  }
2252  return ret;
2253 }
2254 
2255 bool FakeMotionControl::getControlModesRaw(const int n_joint, const int *joints, int *modes)
2256 {
2257  bool ret = true;
2258  for(int j=0; j< n_joint; j++)
2259  {
2260  ret = ret && getControlModeRaw(joints[j], &modes[j]);
2261  }
2262  return ret;
2263 }
2264 
2265 
2266 
2267 // marco.accame: con alberto cardellino abbiamo parlato della correttezza di effettuare la verifica di quanto imposto (in setControlModeRaw() ed affini)
2268 // andando a rileggere il valore nella scheda eth fino a che esso non sia quello atteso. si deve fare oppure no?
2269 // con il control mode il can ora lo fa ma e' giusto? era cosi' anche in passato?
2270 bool FakeMotionControl::setControlModeRaw(const int j, const int _mode)
2271 {
2272  if (verbose >= VERY_VERBOSE) {
2273  yCTrace(FAKEMOTIONCONTROL) << "j: " << j << " mode: " << yarp::os::Vocab32::decode(_mode);
2274  }
2275 
2276  if (_mode==VOCAB_CM_FORCE_IDLE)
2277  {
2278  _controlModes[j] = VOCAB_CM_IDLE;
2279  }
2280  else
2281  {
2282  _controlModes[j] = _mode;
2283  }
2284  _posCtrl_references[j] = pos[j];
2285  return true;
2286 }
2287 
2288 
2289 bool FakeMotionControl::setControlModesRaw(const int n_joint, const int *joints, int *modes)
2290 {
2291  if (verbose >= VERY_VERBOSE) {
2292  yCTrace(FAKEMOTIONCONTROL) << "n_joints: " << n_joint;
2293  }
2294 
2295  bool ret = true;
2296  for(int i=0; i<n_joint; i++)
2297  {
2298  ret &= setControlModeRaw(joints[i], modes[i]);
2299  }
2300  return ret;
2301 }
2302 
2304 {
2305  if (verbose >= VERY_VERBOSE) {
2306  yCTrace(FAKEMOTIONCONTROL);
2307  }
2308 
2309  bool ret = true;
2310  for(int i=0; i<_njoints; i++)
2311  {
2312  ret &= setControlModeRaw(i, modes[i]);
2313  }
2314  return ret;
2315 }
2316 
2317 
2319 
2320 bool FakeMotionControl::setEncoderRaw(int j, double val)
2321 {
2322  return NOT_YET_IMPLEMENTED("setEncoder");
2323 }
2324 
2325 bool FakeMotionControl::setEncodersRaw(const double *vals)
2326 {
2327  return NOT_YET_IMPLEMENTED("setEncoders");
2328 }
2329 
2331 {
2332  return NOT_YET_IMPLEMENTED("resetEncoder");
2333 }
2334 
2336 {
2337  return NOT_YET_IMPLEMENTED("resetEncoders");
2338 }
2339 
2340 bool FakeMotionControl::getEncoderRaw(int j, double *value)
2341 {
2342  bool ret = true;
2343 
2344  // To simulate a real controlboard, we assume that the joint
2345  // encoders is exactly the last set by setPosition(s) or positionMove
2346  *value = pos[j];
2347 
2348  return ret;
2349 }
2350 
2352 {
2353  bool ret = true;
2354  for(int j=0; j< _njoints; j++)
2355  {
2356  bool ok = getEncoderRaw(j, &encs[j]);
2357  ret = ret && ok;
2358 
2359  }
2360  return ret;
2361 }
2362 
2364 {
2365  // To avoid returning uninitialized memory, we set the encoder speed to 0
2366  *sp = 0.0;
2367  return true;
2368 }
2369 
2371 {
2372  bool ret = true;
2373  for(int j=0; j< _njoints; j++)
2374  {
2375  ret &= getEncoderSpeedRaw(j, &spds[j]);
2376  }
2377  return ret;
2378 }
2379 
2381 {
2382  // To avoid returning uninitialized memory, we set the encoder acc to 0
2383  *acc = 0.0;
2384 
2385  return true;
2386 }
2387 
2389 {
2390  bool ret = true;
2391  for(int j=0; j< _njoints; j++)
2392  {
2393  ret &= getEncoderAccelerationRaw(j, &accs[j]);
2394  }
2395  return ret;
2396 }
2397 
2399 
2400 bool FakeMotionControl::getEncodersTimedRaw(double *encs, double *stamps)
2401 {
2402  bool ret = getEncodersRaw(encs);
2403  _mutex.lock();
2404  for (int i = 0; i < _njoints; i++) {
2405  stamps[i] = _encodersStamp[i];
2406  }
2407  _mutex.unlock();
2408  return ret;
2409 }
2410 
2411 bool FakeMotionControl::getEncoderTimedRaw(int j, double *encs, double *stamp)
2412 {
2413  bool ret = getEncoderRaw(j, encs);
2414  _mutex.lock();
2415  *stamp = _encodersStamp[j];
2416  _mutex.unlock();
2417 
2418  return ret;
2419 }
2420 
2422 
2424 {
2425  *num=_njoints;
2426  return true;
2427 }
2428 
2429 bool FakeMotionControl::setMotorEncoderRaw(int m, const double val)
2430 {
2431  return NOT_YET_IMPLEMENTED("setMotorEncoder");
2432 }
2433 
2435 {
2436  return NOT_YET_IMPLEMENTED("setMotorEncoders");
2437 }
2438 
2440 {
2441  return NOT_YET_IMPLEMENTED("setMotorEncoderCountsPerRevolutionRaw");
2442 }
2443 
2445 {
2446  return NOT_YET_IMPLEMENTED("getMotorEncoderCountsPerRevolutionRaw");
2447 }
2448 
2450 {
2451  return NOT_YET_IMPLEMENTED("resetMotorEncoder");
2452 }
2453 
2455 {
2456  return NOT_YET_IMPLEMENTED("reseMotortEncoders");
2457 }
2458 
2459 bool FakeMotionControl::getMotorEncoderRaw(int m, double *value)
2460 {
2461  *value = 0.0;
2462  return true;
2463 }
2464 
2466 {
2467  bool ret = true;
2468  for(int j=0; j< _njoints; j++)
2469  {
2470  ret &= getMotorEncoderRaw(j, &encs[j]);
2471 
2472  }
2473  return ret;
2474 }
2475 
2477 {
2478  *sp = 0.0;
2479  return true;
2480 }
2481 
2483 {
2484  bool ret = true;
2485  for(int j=0; j< _njoints; j++)
2486  {
2487  ret &= getMotorEncoderSpeedRaw(j, &spds[j]);
2488  }
2489  return ret;
2490 }
2491 
2493 {
2494  *acc = 0.0;
2495  return true;
2496 }
2497 
2499 {
2500  bool ret = true;
2501  for(int j=0; j< _njoints; j++)
2502  {
2503  ret &= getMotorEncoderAccelerationRaw(j, &accs[j]);
2504  }
2505  return ret;
2506 }
2507 
2508 bool FakeMotionControl::getMotorEncodersTimedRaw(double *encs, double *stamps)
2509 {
2510  bool ret = getMotorEncodersRaw(encs);
2511  _mutex.lock();
2512  for (int i = 0; i < _njoints; i++) {
2513  stamps[i] = _encodersStamp[i];
2514  }
2515  _mutex.unlock();
2516 
2517  return ret;
2518 }
2519 
2520 bool FakeMotionControl::getMotorEncoderTimedRaw(int m, double *encs, double *stamp)
2521 {
2522  bool ret = getMotorEncoderRaw(m, encs);
2523  _mutex.lock();
2524  *stamp = _encodersStamp[m];
2525  _mutex.unlock();
2526 
2527  return ret;
2528 }
2530 
2532 
2534 {
2535  return DEPRECATED("enableAmpRaw");
2536 }
2537 
2539 {
2540  return DEPRECATED("disableAmpRaw");
2541 }
2542 
2543 bool FakeMotionControl::getCurrentRaw(int j, double *value)
2544 {
2545  //just for testing purposes, this is not a real implementation
2546  *value = current[j];
2547  return true;
2548 }
2549 
2551 {
2552  //just for testing purposes, this is not a real implementation
2553  bool ret = true;
2554  for(int j=0; j< _njoints; j++)
2555  {
2556  ret &= getCurrentRaw(j, &vals[j]);
2557  }
2558  return ret;
2559 }
2560 
2562 {
2563  maxCurrent[m] = val;
2564  return true;
2565 }
2566 
2567 bool FakeMotionControl::getMaxCurrentRaw(int m, double *val)
2568 {
2569  *val = maxCurrent[m];
2570  return true;
2571 }
2572 
2574 {
2575  (_enabledAmp[j ]) ? *st = 1 : *st = 0;
2576  return true;
2577 }
2578 
2580 {
2581  bool ret = true;
2582  for(int j=0; j<_njoints; j++)
2583  {
2584  sts[j] = _enabledAmp[j];
2585  }
2586  return ret;
2587 }
2588 
2590 {
2591  *val = peakCurrent[m];
2592  return true;
2593 }
2594 
2595 bool FakeMotionControl::setPeakCurrentRaw(int m, const double val)
2596 {
2597  peakCurrent[m] = val;
2598  return true;
2599 }
2600 
2602 {
2603  *val = nominalCurrent[m];
2604  return true;
2605 }
2606 
2607 bool FakeMotionControl::setNominalCurrentRaw(int m, const double val)
2608 {
2609  nominalCurrent[m] = val;
2610  return true;
2611 }
2612 
2613 bool FakeMotionControl::getPWMRaw(int m, double *val)
2614 {
2615  *val = pwm[m];
2616  return true;
2617 }
2618 
2619 bool FakeMotionControl::getPWMLimitRaw(int m, double* val)
2620 {
2621  *val = pwmLimit[m];
2622  return true;
2623 }
2624 
2625 bool FakeMotionControl::setPWMLimitRaw(int m, const double val)
2626 {
2627  pwmLimit[m] = val;
2628  return true;
2629 }
2630 
2632 {
2633  *val = supplyVoltage[m];
2634  return true;
2635 }
2636 
2637 
2638 // Limit interface
2639 bool FakeMotionControl::setLimitsRaw(int j, double min, double max)
2640 {
2641  bool ret = true;
2642  return ret;
2643 }
2644 
2645 bool FakeMotionControl::getLimitsRaw(int j, double *min, double *max)
2646 {
2647  return false;
2648 }
2649 
2650 bool FakeMotionControl::getGearboxRatioRaw(int j, double *gearbox)
2651 {
2652  return true;
2653 }
2654 
2656 {
2657  return true;
2658 }
2659 
2661 {
2662  return true;
2663 }
2664 
2666 {
2667  return true;
2668 }
2669 
2671 {
2672  return true;
2673 }
2674 
2676 {
2677  return true;
2678 }
2679 
2680 bool FakeMotionControl::getKinematicMJRaw(int j, double &rotres)
2681 {
2682  yCError(FAKEMOTIONCONTROL, "getKinematicMJRaw not yet implemented");
2683  return false;
2684 }
2685 
2687 {
2688  return true;
2689 }
2690 
2692 {
2693  return true;
2694 }
2695 
2697 {
2698  return true;
2699 }
2700 
2702 {
2703  return true;
2704 }
2705 
2707 {
2708  return true;
2709 }
2710 
2711 bool FakeMotionControl::getRotorIndexOffsetRaw(int j, double& rotorOffset)
2712 {
2713  return true;
2714 }
2715 
2716 bool FakeMotionControl::getAxisNameRaw(int axis, std::string& name)
2717 {
2718  if (axis >= 0 && axis < _njoints)
2719  {
2720  name = _axisName[axis];
2721  return true;
2722  }
2723  else
2724  {
2725  name = "ERROR";
2726  return false;
2727  }
2728 }
2729 
2731 {
2732  if (axis >= 0 && axis < _njoints)
2733  {
2734  type = _jointType[axis];
2735  return true;
2736  }
2737  else
2738  {
2739  return false;
2740  }
2741 }
2742 
2743 // IControlLimits
2744 bool FakeMotionControl::setVelLimitsRaw(int axis, double min, double max)
2745 {
2746  return NOT_YET_IMPLEMENTED("setVelLimitsRaw");
2747 }
2748 
2749 bool FakeMotionControl::getVelLimitsRaw(int axis, double *min, double *max)
2750 {
2751  *min = 0.0;
2752  *max = _maxJntCmdVelocity[axis];
2753  return true;
2754 }
2755 
2756 
2757 // Torque control
2759 {
2760  *t = _torques[j];
2761  return true;
2762 }
2763 
2765 {
2766  for (int i = 0; i < _njoints; i++)
2767  {
2768  t[i]= _torques[i];
2769  }
2770  return true;
2771 }
2772 
2773 bool FakeMotionControl::getTorqueRangeRaw(int j, double *min, double *max)
2774 {
2775  return NOT_YET_IMPLEMENTED("getTorqueRangeRaw");
2776 }
2777 
2778 bool FakeMotionControl::getTorqueRangesRaw(double *min, double *max)
2779 {
2780  return NOT_YET_IMPLEMENTED("getTorqueRangesRaw");
2781 }
2782 
2784 {
2785  bool ret = true;
2786  for (int j = 0; j < _njoints && ret; j++) {
2787  ret &= setRefTorqueRaw(j, t[j]);
2788  }
2789  return ret;
2790 }
2791 
2793 {
2794  return false;
2795 }
2796 
2797 bool FakeMotionControl::setRefTorquesRaw(const int n_joint, const int *joints, const double *t)
2798 {
2799  return false;
2800 }
2801 
2803 {
2804  return false;
2805 }
2806 
2808 {
2809  return false;
2810 }
2811 
2812 bool FakeMotionControl::getImpedanceRaw(int j, double *stiffness, double *damping)
2813 {
2814  return false;
2815 }
2816 
2817 bool FakeMotionControl::setImpedanceRaw(int j, double stiffness, double damping)
2818 {
2819  return false;
2820 }
2821 
2823 {
2824  return false;
2825 }
2826 
2827 bool FakeMotionControl::getImpedanceOffsetRaw(int j, double *offset)
2828 {
2829  return false;
2830 }
2831 
2832 bool FakeMotionControl::getCurrentImpedanceLimitRaw(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp)
2833 {
2834  return false;
2835 }
2836 
2838 {
2839  params->bemf = _kbemf[j];
2840  params->bemf_scale = _kbemf_scale[j];
2841  params->ktau = _ktau[j];
2842  params->ktau_scale = _ktau_scale[j];
2843  yCDebug(FAKEMOTIONCONTROL) << "getMotorTorqueParamsRaw" << params->bemf << params->bemf_scale << params->ktau << params->ktau_scale;
2844  return true;
2845 }
2846 
2848 {
2849  _kbemf[j] = params.bemf;
2850  _ktau[j] = params.ktau;
2851  _kbemf_scale[j] = params.bemf_scale;
2852  _ktau_scale[j] = params.ktau_scale;
2853  yCDebug(FAKEMOTIONCONTROL) << "setMotorTorqueParamsRaw" << params.bemf << params.bemf_scale << params.ktau << params.ktau_scale;
2854  return true;
2855 }
2856 
2857 // IVelocityControl interface
2858 bool FakeMotionControl::velocityMoveRaw(const int n_joint, const int *joints, const double *spds)
2859 {
2860  bool ret = true;
2861  for(int i=0; i<n_joint; i++)
2862  {
2863  ret &= velocityMoveRaw(joints[i], spds[i]);
2864  }
2865  return ret;
2866 }
2867 
2868 // PositionDirect Interface
2869 bool FakeMotionControl::setPositionRaw(int j, double ref)
2870 {
2871  _posDir_references[j] = ref;
2872  return true;
2873 }
2874 
2875 bool FakeMotionControl::setPositionsRaw(const int n_joint, const int *joints, const double *refs)
2876 {
2877  for(int i=0; i< n_joint; i++)
2878  {
2879  _posDir_references[joints[i]] = refs[i];
2880  }
2881  return true;
2882 }
2883 
2884 bool FakeMotionControl::setPositionsRaw(const double *refs)
2885 {
2886  for(int i=0; i< _njoints; i++)
2887  {
2888  _posDir_references[i] = refs[i];
2889  }
2890  return true;
2891 }
2892 
2893 
2894 bool FakeMotionControl::getTargetPositionRaw(int axis, double *ref)
2895 {
2896  if (verbose >= VERY_VERBOSE) {
2897  yCTrace(FAKEMOTIONCONTROL) << "j " << axis << " ref " << _posCtrl_references[axis];
2898  }
2899 
2900  int mode = 0;
2901  getControlModeRaw(axis, &mode);
2902  if( (mode != VOCAB_CM_POSITION) &&
2903  (mode != VOCAB_CM_MIXED) &&
2904  (mode != VOCAB_CM_IMPEDANCE_POS))
2905  {
2906  yCWarning(FAKEMOTIONCONTROL) << "getTargetPosition: Joint " << axis << " is not in POSITION mode, therefore the value returned by " <<
2907  "this call is for reference only and may not reflect the actual behaviour of the motor/firmware.";
2908  }
2909  *ref = _posCtrl_references[axis];
2910  return true;
2911 }
2912 
2914 {
2915  bool ret = true;
2916  for (int i = 0; i < _njoints; i++) {
2917  ret &= getTargetPositionRaw(i, &refs[i]);
2918  }
2919  return ret;
2920 }
2921 
2922 bool FakeMotionControl::getTargetPositionsRaw(int nj, const int * jnts, double *refs)
2923 {
2924  bool ret = true;
2925  for (int i = 0; i<nj; i++)
2926  {
2927  ret &= getTargetPositionRaw(jnts[i], &refs[i]);
2928  }
2929  return ret;
2930 }
2931 
2932 bool FakeMotionControl::getRefVelocityRaw(int axis, double *ref)
2933 {
2934  *ref = _command_speeds[axis];
2935  return true;
2936 }
2937 
2939 {
2940  bool ret = true;
2941  for (int i = 0; i<_njoints; i++)
2942  {
2943  ret &= getRefVelocityRaw(i, &refs[i]);
2944  }
2945  return ret;
2946 }
2947 
2948 bool FakeMotionControl::getRefVelocitiesRaw(int nj, const int * jnts, double *refs)
2949 {
2950  bool ret = true;
2951  for (int i = 0; i<nj; i++)
2952  {
2953  ret &= getRefVelocityRaw(jnts[i], &refs[i]);
2954  }
2955  return ret;
2956 }
2957 
2958 bool FakeMotionControl::getRefPositionRaw(int axis, double *ref)
2959 {
2960  int mode = 0;
2961  getControlModeRaw(axis, &mode);
2962  if( (mode != VOCAB_CM_POSITION) &&
2963  (mode != VOCAB_CM_MIXED) &&
2964  (mode != VOCAB_CM_IMPEDANCE_POS) &&
2965  (mode != VOCAB_CM_POSITION_DIRECT) )
2966  {
2967  yCWarning(FAKEMOTIONCONTROL) << "getRefPosition: Joint " << axis << " is not in POSITION_DIRECT mode, therefore the value returned by \
2968  this call is for reference only and may not reflect the actual behaviour of the motor/firmware.";
2969  }
2970 
2971  *ref = _posDir_references[axis];
2972 
2973  return true;
2974 }
2975 
2977 {
2978  bool ret = true;
2979  for (int i = 0; i<_njoints; i++)
2980  {
2981  ret &= getRefPositionRaw(i, &refs[i]);
2982  }
2983  return ret;
2984 }
2985 
2986 bool FakeMotionControl::getRefPositionsRaw(int nj, const int * jnts, double *refs)
2987 {
2988  bool ret = true;
2989  for (int i = 0; i<nj; i++)
2990  {
2991  ret &= getRefPositionRaw(jnts[i], &refs[i]);
2992  }
2993  return ret;
2994 }
2995 
2996 
2997 // InteractionMode
2999 {
3000  if (verbose > VERY_VERY_VERBOSE) {
3001  yCTrace(FAKEMOTIONCONTROL) << "j: " << j;
3002  }
3003 
3004  *_mode = (yarp::dev::InteractionModeEnum)_interactMode[j];
3005  return true;}
3006 
3008 {
3009  bool ret = true;
3010  for(int j=0; j< n_joints; j++)
3011  {
3012  ret = ret && getInteractionModeRaw(joints[j], &modes[j]);
3013  }
3014  return ret;
3015 
3016 }
3017 
3019 {
3020  bool ret = true;
3021  for (int j = 0; j < _njoints; j++) {
3022  ret = ret && getInteractionModeRaw(j, &modes[j]);
3023  }
3024  return ret;
3025 }
3026 
3027 // marco.accame: con alberto cardellino abbiamo parlato della correttezza di effettuare la verifica di quanto imposto (in setInteractionModeRaw() ed affini)
3028 // andando a rileggere il valore nella scheda eth fino a che esso non sia quello atteso. si deve fare oppure no?
3029 // con il interaction mode il can ora non lo fa. mentre lo fa per il control mode. perche' diverso?
3031 {
3032  if (verbose >= VERY_VERBOSE) {
3033  yCTrace(FAKEMOTIONCONTROL) << "j: " << j << " interaction mode: " << yarp::os::Vocab32::decode(_mode);
3034  }
3035 
3036  _interactMode[j] = _mode;
3037 
3038  return true;
3039 }
3040 
3041 
3043 {
3044  bool ret = true;
3045  for(int i=0; i<n_joints; i++)
3046  {
3047  ret &= setInteractionModeRaw(joints[i], modes[i]);
3048  }
3049  return ret;
3050 }
3051 
3053 {
3054  bool ret = true;
3055  for(int i=0; i<_njoints; i++)
3056  {
3057  ret &= setInteractionModeRaw(i, modes[i]);
3058  }
3059  return ret;
3060 
3061 }
3062 
3064 {
3065  *num=_njoints;
3066  return true;
3067 }
3068 
3070 {
3071  return false;
3072 }
3073 
3075 {
3076  bool ret = true;
3077  for(int j=0; j< _njoints; j++)
3078  {
3079  ret &= getTemperatureRaw(j, &vals[j]);
3080  }
3081  return ret;
3082 }
3083 
3085 {
3086  return false;
3087 }
3088 
3089 bool FakeMotionControl::setTemperatureLimitRaw(int m, const double temp)
3090 {
3091  return false;
3092 }
3093 
3094 //PWM interface
3096 {
3097  refpwm[j] = v;
3098  pwm[j] = v;
3099  last_pwm_command[j]=yarp::os::Time::now();
3100  return true;
3101 }
3102 
3104 {
3105  for (int i = 0; i < _njoints; i++)
3106  {
3107  setRefDutyCycleRaw(i,v[i]);
3108  }
3109  return true;
3110 }
3111 
3113 {
3114  *v = refpwm[j];
3115  return true;
3116 }
3117 
3119 {
3120  for (int i = 0; i < _njoints; i++)
3121  {
3122  v[i] = refpwm[i];
3123  }
3124  return true;
3125 }
3126 
3128 {
3129  *v = pwm[j];
3130  return true;
3131 }
3132 
3134 {
3135  for (int i = 0; i < _njoints; i++)
3136  {
3137  v[i] = pwm[i];
3138  }
3139  return true;
3140 }
3141 
3142 // Current interface
3143 /*bool FakeMotionControl::getCurrentRaw(int j, double *t)
3144 {
3145  return NOT_YET_IMPLEMENTED("getCurrentRaw");
3146 }
3147 
3148 bool FakeMotionControl::getCurrentsRaw(double *t)
3149 {
3150  return NOT_YET_IMPLEMENTED("getCurrentsRaw");
3151 }
3152 */
3153 
3154 bool FakeMotionControl::getCurrentRangeRaw(int j, double *min, double *max)
3155 {
3156  //just for testing purposes, this is not a real implementation
3157  *min = _ref_currents[j] / 100;
3158  *max = _ref_currents[j] * 100;
3159  return true;
3160 }
3161 
3162 bool FakeMotionControl::getCurrentRangesRaw(double *min, double *max)
3163 {
3164  //just for testing purposes, this is not a real implementation
3165  for (int i = 0; i < _njoints; i++)
3166  {
3167  min[i] = _ref_currents[i] / 100;
3168  max[i] = _ref_currents[i] * 100;
3169  }
3170  return true;
3171 }
3172 
3174 {
3175  for (int i = 0; i < _njoints; i++)
3176  {
3177  _ref_currents[i] = t[i];
3178  current[i] = t[i] / 2;
3179  }
3180  return true;
3181 }
3182 
3184 {
3185  _ref_currents[j] = t;
3186  current[j] = t / 2;
3187  return true;
3188 }
3189 
3190 bool FakeMotionControl::setRefCurrentsRaw(const int n_joint, const int *joints, const double *t)
3191 {
3192  bool ret = true;
3193  for (int j = 0; j<n_joint; j++)
3194  {
3195  ret = ret &&setRefCurrentRaw(joints[j], t[j]);
3196  }
3197  return ret;
3198 }
3199 
3201 {
3202  for (int i = 0; i < _njoints; i++)
3203  {
3204  t[i] = _ref_currents[i];
3205  }
3206  return true;
3207 }
3208 
3210 {
3211  *t = _ref_currents[j];
3212  return true;
3213 }
3214 
3215 // bool FakeMotionControl::checkRemoteControlModeStatus(int joint, int target_mode)
3216 // {
3217 // return false;
3218 // }
3219 
3221 {
3223 }
3224 
3226 {
3227  return _njoints;
3228 }
3229 
3231 {
3232  for (int i = 0; i < _njoints; i++)
3233  {
3234  measure[i] = _torques[i];
3235  }
3236  return true;
3237 }
3238 
3240 {
3241  _torques[ch] = measure;
3242  return true;
3243 }
3244 
3245 
3246 // eof
void checkAndDestroy(T *&p)
float t
constexpr yarp::conf::vocab32_t VOCAB_CM_MIXED
Definition: IControlMode.h:135
constexpr yarp::conf::vocab32_t VOCAB_CM_PWM
Definition: IControlMode.h:129
constexpr yarp::conf::vocab32_t VOCAB_CM_IMPEDANCE_VEL
Definition: IControlMode.h:131
constexpr yarp::conf::vocab32_t VOCAB_CM_IDLE
Definition: IControlMode.h:123
constexpr yarp::conf::vocab32_t VOCAB_CM_POSITION
Definition: IControlMode.h:125
constexpr yarp::conf::vocab32_t VOCAB_CM_IMPEDANCE_POS
Definition: IControlMode.h:130
constexpr yarp::conf::vocab32_t VOCAB_CM_POSITION_DIRECT
Definition: IControlMode.h:126
constexpr yarp::conf::vocab32_t VOCAB_CM_VELOCITY
Definition: IControlMode.h:127
constexpr yarp::conf::vocab32_t VOCAB_CM_FORCE_IDLE
Definition: IControlMode.h:138
bool ret
bool getPowerSupplyVoltageRaw(int j, double *val) override
bool getRefSpeedRaw(int j, double *ref) override
Get reference speed for a joint.
virtual bool getHasTempSensorsRaw(int j, int &ret)
bool setRefCurrentsRaw(const double *t) override
Set the reference value of the currents for all motors.
bool setRefTorqueRaw(int j, double t) override
Set the reference value of the torque for a given joint.
bool getCurrentsRaw(double *vals) override
bool getImpedanceOffsetRaw(int j, double *offset) override
Get current force Offset for a specific joint.
bool getTargetPositionRaw(const int joint, double *ref) override
Get the last position reference for the specified axis.
bool getTorqueRangeRaw(int j, double *min, double *max) override
Get the full scale of the torque sensor of a given joint.
bool getCurrentImpedanceLimitRaw(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp) override
Get the current impedandance limits for a specific joint.
bool setTemperatureLimitRaw(int m, const double temp) override
Set the temperature limit for a specific motor.
bool getPidErrorRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *err) override
Get the current error for a joint.
bool setPeakCurrentRaw(int m, const double val) override
bool velocityMoveRaw(int j, double sp) override
Start motion at a given speed, single joint.
bool checkMotionDoneRaw(bool *flag) override
Check if the current trajectory is terminated.
bool getMotorEncoderSpeedRaw(int m, double *sp) override
Read the istantaneous speed of a motor encoder.
virtual bool getJointEncoderTypeRaw(int j, int &type)
bool setRefDutyCycleRaw(int j, double v) override
Sets the reference dutycycle of a single motor.
bool getTemperatureRaw(int m, double *val) override
Get temperature of a motor.
bool getEncoderAccelerationRaw(int j, double *spds) override
Read the instantaneous acceleration of an axis.
bool getRefAccelerationRaw(int j, double *acc) override
Get reference acceleration for a joint.
bool getMotorEncoderSpeedsRaw(double *spds) override
Read the instantaneous speed of all motor encoders.
bool setPidsRaw(const yarp::dev::PidControlTypeEnum &pidtype, const yarp::dev::Pid *pids) override
Set new pid value on multiple axes.
bool setVelLimitsRaw(int axis, double min, double max) override
Set the software speed limits for a particular axis, the behavior of the control card when these limi...
bool getJointTypeRaw(int axis, yarp::dev::JointTypeEnum &type) override
bool setMotorEncoderRaw(int m, const double val) override
Set the value of the motor encoder for a given motor.
bool getPidErrorLimitRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *limit) override
Get the error limit for the controller on a specific joint.
bool getPidOutputRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *out) override
Get the output of the controller (e.g.
bool setControlModeRaw(const int j, const int mode) override
bool getMotorEncoderAccelerationRaw(int m, double *spds) override
Read the instantaneous acceleration of a motor encoder.
bool open(yarp::os::Searchable &par) override
Open the DeviceDriver.
virtual bool getHasHallSensorRaw(int j, int &ret)
bool getTemperatureLimitRaw(int m, double *temp) override
Retreives the current temperature limit for a specific motor.
bool getNumberOfMotorsRaw(int *num) override
Retrieves the number of controlled motors from the current physical interface.
bool disableAmpRaw(int j) override
Disable the amplifier on a specific joint.
bool setMotorTorqueParamsRaw(int j, const yarp::dev::MotorTorqueParameters params) override
Set the motor parameters.
bool calibrateAxisWithParamsRaw(int axis, unsigned int type, double p1, double p2, double p3) override
Start calibration, this method is very often platform specific.
bool setRefAccelerationRaw(int j, double acc) override
Set reference acceleration for a joint.
virtual bool initialised()
bool setEncodersRaw(const double *vals) override
Set the value of all encoders.
bool getPidOutputsRaw(const yarp::dev::PidControlTypeEnum &pidtype, double *outs) override
Get the output of the controllers (e.g.
bool isPidEnabledRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, bool *enabled) override
Get the current status (enabled/disabled) of the pid controller.
bool setRefSpeedsRaw(const double *spds) override
Set reference speed on all joints.
bool getTargetPositionsRaw(double *refs) override
Get the last position reference for all axes.
bool getRefDutyCycleRaw(int j, double *v) override
Gets the last reference sent using the setRefDutyCycleRaw function.
bool setMotorEncoderCountsPerRevolutionRaw(int m, const double cpr) override
Sets number of counts per revolution for motor encoder m.
bool setPidErrorLimitsRaw(const yarp::dev::PidControlTypeEnum &pidtype, const double *limits) override
Get the error limit for the controller on all joints.
bool getPidReferenceRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *ref) override
Get the current reference of the pid controller for a specific joint.
bool getNominalCurrentRaw(int m, double *val) override
bool getControlModeRaw(int j, int *v) override
bool calibrationDoneRaw(int j) override
Check if the calibration is terminated, on a particular joint.
bool threadInit() override
Initialization method.
bool getRefDutyCyclesRaw(double *v) override
Gets the last reference sent using the setRefDutyCyclesRaw function.
bool getRefVelocityRaw(const int joint, double *ref) override
Get the last reference speed set by velocityMove for single joint.
bool getEncoderTimedRaw(int j, double *encs, double *stamp) override
Read the instantaneous acceleration of all axes.
bool disablePidRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j) override
Disable the pid computation for a joint.
yarp::dev::VAS_status getVirtualAnalogSensorStatusRaw(int ch) override
Check the status of a given channel.
bool getMotorEncodersRaw(double *encs) override
Read the position of all motor encoders.
bool getTorqueRangesRaw(double *min, double *max) override
Get the full scale of the torque sensors of all joints.
bool getRefCurrentsRaw(double *t) override
Get the reference value of the currents for all motors.
bool setRefDutyCyclesRaw(const double *v) override
Sets the reference dutycycle for all motors.
bool getEncoderSpeedRaw(int j, double *sp) override
Read the instantaneous speed of an axis.
int getVirtualAnalogSensorChannelsRaw() override
Get the number of channels of the virtual sensor.
bool resetPidRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j) override
Reset the controller of a given joint, usually sets the current status of the joint as the reference ...
bool getCurrentRangesRaw(double *min, double *max) override
Get the full scale of the current measurements for all motors motor (e.g.
bool getEncoderRaw(int j, double *v) override
Read the value of an encoder.
bool getPidErrorLimitsRaw(const yarp::dev::PidControlTypeEnum &pidtype, double *limits) override
Get the error limit for all controllers.
bool enableAmpRaw(int j) override
Enable the amplifier on a specific joint.
bool fromConfig(yarp::os::Searchable &config)
bool getPidsRaw(const yarp::dev::PidControlTypeEnum &pidtype, yarp::dev::Pid *pids) override
Get current pid value for a specific joint.
bool getRefPositionsRaw(double *refs) override
Get the last position reference for all axes.
bool getMotorTorqueParamsRaw(int j, yarp::dev::MotorTorqueParameters *params) override
Get the motor parameters.
bool setControlModesRaw(const int n_joint, const int *joints, int *modes) override
bool setRefSpeedRaw(int j, double sp) override
Set reference speed for a joint, this is the speed used during the interpolation of the trajectory.
virtual bool getHasRotorEncoderIndexRaw(int j, int &ret)
bool updateVirtualAnalogSensorMeasureRaw(yarp::sig::Vector &measure) override
Set a vector of torque values for virtual sensor.
void resizeBuffers()
Resize previously allocated buffers.
void threadRelease() override
Release method.
bool getAmpStatusRaw(int *st) override
bool setImpedanceRaw(int j, double stiffness, double damping) override
Set current impedance parameters (stiffness,damping) for a specific joint.
bool setPWMLimitRaw(int j, const double val) override
bool relativeMoveRaw(int j, double delta) override
Set relative position.
virtual bool getMotorPolesRaw(int j, int &poles)
bool getPidRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, yarp::dev::Pid *pid) override
Get current pid value for a specific joint.
bool getCurrentRaw(int j, double *val) override
bool getPeakCurrentRaw(int m, double *val) override
bool getDutyCyclesRaw(double *v) override
Gets the current dutycycle of the output of the amplifier (i.e.
bool setEncoderRaw(int j, double val) override
Set the value of the encoder for a given joint.
bool getRefPositionRaw(const int joint, double *ref) override
Get the last position reference for the specified axis.
bool getLimitsRaw(int axis, double *min, double *max) override
Get the software limits for a particular axis.
virtual bool getRotorIndexOffsetRaw(int j, double &rotorOffset)
bool getVelLimitsRaw(int axis, double *min, double *max) override
Get the software speed limits for a particular axis.
bool setPositionsRaw(const int n_joint, const int *joints, const double *refs) override
Set new reference point for all axes.
bool setPidReferenceRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double ref) override
Set the controller reference for a given axis.
bool resetEncodersRaw() override
Reset encoders.
bool getPWMRaw(int j, double *val) override
bool getAxisNameRaw(int axis, std::string &name) override
bool setCalibrationParametersRaw(int axis, const yarp::dev::CalibrationParameters &params) override
Start calibration, this method is very often platform specific.
bool setPidOffsetRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double v) override
Set an offset value on the ourput of pid controller.
bool getInteractionModeRaw(int j, yarp::dev::InteractionModeEnum *_mode) override
Get the current interaction mode of the robot, values can be stiff or compliant.
bool getCurrentRangeRaw(int j, double *min, double *max) override
Get the full scale of the current measurement for a given motor (e.g.
bool stopRaw() override
Stop motion, multiple joints.
virtual bool getKinematicMJRaw(int j, double &rotres)
bool getRefSpeedsRaw(double *spds) override
Get reference speed of all joints.
bool getRefAccelerationsRaw(double *accs) override
Get reference acceleration of all joints.
virtual bool getJointEncoderResolutionRaw(int m, double &jntres)
bool getAxes(int *ax) override
Get the number of controlled axes.
bool setMaxCurrentRaw(int j, double val) override
bool alloc(int njoints)
Allocated buffers.
bool resetMotorEncodersRaw() override
Reset motor encoders.
bool setRefTorquesRaw(const double *t) override
Set the reference value of the torque for all joints.
bool getEncodersRaw(double *encs) override
Read the position of all axes.
bool setRefAccelerationsRaw(const double *accs) override
Set reference acceleration on all joints.
bool getControlModesRaw(int *v) override
bool setPidRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, const yarp::dev::Pid &pid) override
Set new pid value for a joint axis.
bool getPWMLimitRaw(int j, double *val) override
virtual bool getRotorEncoderTypeRaw(int j, int &type)
bool getRefCurrentRaw(int j, double *t) override
Get the reference value of the current for a single motor.
bool getDutyCycleRaw(int j, double *v) override
Gets the current dutycycle of the output of the amplifier (i.e.
bool setPidErrorLimitRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double limit) override
Set the error limit for the controller on a specific joint.
bool getInteractionModesRaw(int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes) override
Get the current interaction mode of the robot for a set of joints, values can be stiff or compliant.
bool positionMoveRaw(int j, double ref) override
Set new reference point for a single axis.
bool getMotorEncoderCountsPerRevolutionRaw(int m, double *v) override
Gets number of counts per revolution for motor encoder m.
bool setImpedanceOffsetRaw(int j, double offset) override
Set current force Offset for a specific joint.
bool setMotorEncodersRaw(const double *vals) override
Set the value of all motor encoders.
bool getPidErrorsRaw(const yarp::dev::PidControlTypeEnum &pidtype, double *errs) override
Get the error of all joints.
bool getGearboxRatioRaw(int m, double *gearbox) override
Get the gearbox ratio for a specific motor.
bool getMaxCurrentRaw(int j, double *val) override
Returns the maximum electric current allowed for a given motor.
bool close() override
Close the DeviceDriver.
bool getRefTorquesRaw(double *t) override
Get the reference value of the torque for all joints.
bool setRefCurrentRaw(int j, double t) override
Set the reference value of the current for a single motor.
bool getNumberOfMotorEncodersRaw(int *num) override
Get the number of available motor encoders.
bool getPidReferencesRaw(const yarp::dev::PidControlTypeEnum &pidtype, double *refs) override
Get the current reference of all pid controllers.
bool getTorqueRaw(int j, double *t) override
Get the value of the torque on a given joint (this is the feedback if you have a torque sensor).
bool getImpedanceRaw(int j, double *stiffness, double *damping) override
Get current impedance parameters (stiffness,damping,offset) for a specific joint.
bool enablePidRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j) override
Enable the pid computation for a joint.
bool getRefVelocitiesRaw(double *refs) override
Get the last reference speed set by velocityMove for all joints.
bool setPositionRaw(int j, double ref) override
Set new position for a single axis.
bool getEncoderAccelerationsRaw(double *accs) override
Read the instantaneous acceleration of all axes.
bool setPidReferencesRaw(const yarp::dev::PidControlTypeEnum &pidtype, const double *refs) override
Set the controller reference, multiple axes.
bool getMotorEncoderRaw(int m, double *v) override
Read the value of a motor encoder.
bool getRefTorqueRaw(int j, double *t) override
Set the reference value of the torque for a given joint.
bool getMotorEncoderAccelerationsRaw(double *accs) override
Read the instantaneous acceleration of all motor encoders.
bool setInteractionModesRaw(int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes) override
Set the interaction mode of the robot for a set of joints, values can be stiff or compliant.
bool getTemperaturesRaw(double *vals) override
Get temperature of all the motors.
bool resetMotorEncoderRaw(int m) override
Reset motor encoder, single motor.
bool setNominalCurrentRaw(int m, const double val) override
virtual bool getRotorEncoderResolutionRaw(int m, double &rotres)
virtual bool getHasRotorEncoderRaw(int j, int &ret)
bool getMotorEncodersTimedRaw(double *encs, double *stamps) override
Read the instantaneous position of all motor encoders.
bool resetEncoderRaw(int j) override
Reset encoder, single joint.
bool getTorquesRaw(double *t) override
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
bool setLimitsRaw(int axis, double min, double max) override
Set the software limits for a particular axis, the behavior of the control card when these limits are...
bool setInteractionModeRaw(int j, yarp::dev::InteractionModeEnum _mode) override
Set the interaction mode of the robot, values can be stiff or compliant.
void run() override
Loop function.
bool getMotorEncoderTimedRaw(int m, double *encs, double *stamp) override
Read the instantaneous position of a motor encoder.
bool getEncodersTimedRaw(double *encs, double *stamps) override
Read the instantaneous acceleration of all axes.
bool getEncoderSpeedsRaw(double *spds) override
Read the instantaneous acceleration of an axis.
virtual bool getTorqueControlFilterType(int j, int &type)
class ImplementControlLimits; class StubImplControlLimitsRaw;
Interface settings the way the robot interacts with the environment: basic interaction types are Stif...
Default implementation of the IPositionControl interface.
Default implementation of the IPositionDirect interface.
Contains the parameters for a PID.
double kd
derivative gain
double scale
scale for the pid output
double offset
pwm offset added to the pid output
double stiction_down_val
down stiction offset added to the pid output
double stiction_up_val
up stiction offset added to the pid output
double max_output
max output
double kff
feedforward gain
double ki
integrative gain
double max_int
saturation threshold for the integrator
double kp
proportional gain
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:74
size_type size() const
Gets the number of elements in the bottle.
Definition: Bottle.cpp:251
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:246
Bottle & findGroup(const std::string &key) const override
Gets a list corresponding to a given keyword.
Definition: Bottle.cpp:302
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Bottle.cpp:277
bool isNull() const override
Checks if the object is invalid.
Definition: Bottle.cpp:370
An abstraction for a periodic thread.
bool start()
Call this to start the thread.
A base class for nested structures that can be searched.
Definition: Searchable.h:66
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
A single value (typically within a Bottle).
Definition: Value.h:45
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition: Value.cpp:204
virtual bool isFloat64() const
Checks if value is a 64-bit floating point number.
Definition: Value.cpp:150
virtual bool isInt32() const
Checks if value is a 32-bit integer.
Definition: Value.cpp:132
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
void resize(size_t size) override
Resize the vector.
Definition: Vector.h:222
T * data()
Return a pointer to the first element of the vector.
Definition: Vector.h:207
#define OPENLOOP_WATCHDOG
std::string toString(const T &value)
convert an arbitrary type to string.
#define PWM_CONSTANT
static bool NOT_YET_IMPLEMENTED(const char *txt)
static bool DEPRECATED(const char *txt)
#define VELOCITY_WATCHDOG
#define yCInfo(component,...)
Definition: LogComponent.h:132
#define yCError(component,...)
Definition: LogComponent.h:154
#define yCTrace(component,...)
Definition: LogComponent.h:85
#define yCWarning(component,...)
Definition: LogComponent.h:143
#define yCDebug(component,...)
Definition: LogComponent.h:109
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:77
std::string get_string(const std::string &key, bool *found=nullptr)
Read a string from an environment variable.
Definition: environment.h:68
An interface for the device drivers.
PidControlTypeEnum
Definition: PidEnums.h:18
@ VOCAB_PIDTYPE_TORQUE
Definition: PidEnums.h:21
@ VOCAB_PIDTYPE_VELOCITY
Definition: PidEnums.h:20
@ VOCAB_PIDTYPE_POSITION
Definition: PidEnums.h:19
@ VOCAB_PIDTYPE_CURRENT
Definition: PidEnums.h:22
@ VOCAB_JOINTTYPE_REVOLUTE
Definition: IAxisInfo.h:27
@ VOCAB_JOINTTYPE_PRISMATIC
Definition: IAxisInfo.h:28
@ VOCAB_JOINTTYPE_UNKNOWN
Definition: IAxisInfo.h:29
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:121
std::string decode(NetInt32 code)
Convert a vocabulary identifier into a string.
Definition: Vocab.cpp:33
The components from which ports and connections are built.
An interface to the operating system, including Port based communication.
VectorOf< double > Vector
Definition: Vector.h:30