YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
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>
13#include <yarp/os/LogStream.h>
14#include <yarp/os/NetType.h>
15#include <yarp/dev/Drivers.h>
16
17#include <sstream>
18#include <cstring>
19
20using namespace yarp::dev;
21using namespace yarp::os;
22using namespace yarp::os::impl;
23
24// macros
25#define NEW_JSTATUS_STRUCT 1
26#define VELOCITY_WATCHDOG 0.1
27#define OPENLOOP_WATCHDOG 0.1
28#define PWM_CONSTANT 0.1
29
30namespace {
31YARP_LOG_COMPONENT(FAKEMOTIONCONTROL, "yarp.device.fakeMotionControl")
32}
33
35{
36 std::lock_guard lock(_mutex);
37
38 _cycleTimestamp = yarp::os::Time::now();
39
40 for (int i=0;i <_njoints ;i++)
41 {
42 if (_controlModes[i] == VOCAB_CM_VELOCITY)
43 {
44 //increment joint position
45 if (this->_command_speeds[i]!=0)
46 {
47 double elapsed = yarp::os::Time::now()-prev_time;
48 double increment = _command_speeds[i]*elapsed;
49 pos[i]+=increment;
50 }
51
52 //velocity watchdog
53 if (velocity_watchdog_enabled && yarp::os::Time::now()-last_velocity_command[i]>=VELOCITY_WATCHDOG)
54 {
55 this->_command_speeds[i]=0.0;
56 }
57 }
58 else if (_controlModes[i] == VOCAB_CM_PWM)
59 {
60 //increment joint position
61 if (this->refpwm[i]!=0)
62 {
63 double elapsed = yarp::os::Time::now()-prev_time;
64 double increment = refpwm[i]*elapsed*PWM_CONSTANT;
65 pos[i]+=increment;
66 }
67
68 //pwm watchdog
69 if (openloop_watchdog_enabled && yarp::os::Time::now()-last_pwm_command[i]>=OPENLOOP_WATCHDOG)
70 {
71 this->refpwm[i]=0.0;
72 }
73 }
74 else if (_controlModes[i] == VOCAB_CM_POSITION_DIRECT)
75 {
76 pos[i] = _posDir_references[i];
77 }
78 else if (_controlModes[i] == VOCAB_CM_POSITION)
79 {
80 pos[i] = _posCtrl_references[i];
81 //do something with _ref_speeds[i];
82 }
83 else if (_controlModes[i] == VOCAB_CM_IDLE)
84 {
85 //do nothing
86 }
87 else if (_controlModes[i] == VOCAB_CM_MIXED)
88 {
89 //not yet implemented
90 }
91 else if (_controlModes[i] == VOCAB_CM_TORQUE)
92 {
93 //not yet implemented
94 }
95 else if (_controlModes[i] == VOCAB_CM_HW_FAULT)
96 {
97 //not yet implemented
98 }
99 else
100 {
101 //unsupported control mode
102 yCWarning(FAKEMOTIONCONTROL) << "Unsupported control mode, joint " << i << " " << yarp::os::Vocab32::decode(_controlModes[i]);
103 }
104 }
105 prev_time = yarp::os::Time::now();
106}
107
108static inline bool NOT_YET_IMPLEMENTED(const char *txt)
109{
110 yCDebug(FAKEMOTIONCONTROL) << txt << "is not yet implemented for FakeMotionControl";
111 return true;
112}
113
114static inline bool DEPRECATED(const char *txt)
115{
116 yCError(FAKEMOTIONCONTROL) << txt << "has been deprecated for FakeMotionControl";
117 return true;
118}
119
120
121// replace with to_string as soon as C++11 is required by YARP
126template<typename T>
127std::string toString(const T& value)
128{
129 std::ostringstream oss;
130 oss << value;
131 return oss.str();
132}
133
134//generic function that check is key1 is present in input bottle and that the result has size elements
135// return true/false
136/*
137bool FakeMotionControl::extractGroup(Bottle &input, Bottle &out, const std::string &key1, const std::string &txt, int size)
138{
139 size++;
140 Bottle &tmp=input.findGroup(key1, txt);
141
142 if (tmp.isNull())
143 {
144 yCError(FAKEMOTIONCONTROL) << key1.c_str() << "parameter not found";
145 return false;
146 }
147
148 if(tmp.size()!=(size_t) size)
149 {
150 yCError(FAKEMOTIONCONTROL) << key1.c_str() << "incorrect number of entries";
151 return false;
152 }
153
154 out=tmp;
155 return true;
156}
157*/
158
160{
161 pos.resize(_njoints);
162 dpos.resize(_njoints);
163 vel.resize(_njoints);
164 speed.resize(_njoints);
165 acc.resize(_njoints);
166 loc.resize(_njoints);
167 amp.resize(_njoints);
168
169 current.resize(_njoints);
170 nominalCurrent.resize(_njoints);
171 maxCurrent.resize(_njoints);
172 peakCurrent.resize(_njoints);
173 pwm.resize(_njoints);
174 refpwm.resize(_njoints);
175 pwmLimit.resize(_njoints);
176 supplyVoltage.resize(_njoints);
177 last_velocity_command.resize(_njoints);
178 last_pwm_command.resize(_njoints);
179
180 pos.zero();
181 dpos.zero();
182 vel.zero();
183 speed.zero();
184 acc.zero();
185 loc.zero();
186 amp.zero();
187
188 current.zero();
189 nominalCurrent.zero();
190 maxCurrent.zero();
191 peakCurrent.zero();
192
193 pwm.zero();
194 refpwm.zero();
195 pwmLimit.zero();
196 supplyVoltage.zero();
197}
198
200{
201 _axisMap = allocAndCheck<int>(nj);
202 _controlModes = allocAndCheck<int>(nj);
203 _interactMode = allocAndCheck<int>(nj);
204 _angleToEncoder = allocAndCheck<double>(nj);
205 _dutycycleToPWM = allocAndCheck<double>(nj);
206 _ampsToSensor = allocAndCheck<double>(nj);
207 _encodersStamp = allocAndCheck<double>(nj);
208 _DEPRECATED_encoderconversionoffset = allocAndCheck<float>(nj);
209 _DEPRECATED_encoderconversionfactor = allocAndCheck<float>(nj);
210 _jointEncoderRes = allocAndCheck<int>(nj);
211 _rotorEncoderRes = allocAndCheck<int>(nj);
212 _gearbox = allocAndCheck<double>(nj);
213 _torqueSensorId= allocAndCheck<int>(nj);
214 _torqueSensorChan= allocAndCheck<int>(nj);
215 _maxTorque=allocAndCheck<double>(nj);
216 _torques = allocAndCheck<double>(nj);
217 _maxJntCmdVelocity = allocAndCheck<double>(nj);
218 _maxMotorVelocity = allocAndCheck<double>(nj);
219 _newtonsToSensor=allocAndCheck<double>(nj);
220 _hasHallSensor = allocAndCheck<bool>(nj);
221 _hasTempSensor = allocAndCheck<bool>(nj);
222 _hasRotorEncoder = allocAndCheck<bool>(nj);
223 _hasRotorEncoderIndex = allocAndCheck<bool>(nj);
224 _rotorIndexOffset = allocAndCheck<int>(nj);
225 _motorPoles = allocAndCheck<int>(nj);
226 _rotorlimits_max = allocAndCheck<double>(nj);
227 _rotorlimits_min = allocAndCheck<double>(nj);
228 _hwfault_code = allocAndCheck<int>(nj);
229 _hwfault_message = allocAndCheck<std::string>(nj);
230
231
232 _ppids=allocAndCheck<Pid>(nj);
233 _tpids=allocAndCheck<Pid>(nj);
234 _cpids = allocAndCheck<Pid>(nj);
235 _vpids = allocAndCheck<Pid>(nj);
236 _ppids_ena=allocAndCheck<bool>(nj);
237 _tpids_ena=allocAndCheck<bool>(nj);
238 _cpids_ena = allocAndCheck<bool>(nj);
239 _vpids_ena = allocAndCheck<bool>(nj);
240 _ppids_lim=allocAndCheck<double>(nj);
241 _tpids_lim=allocAndCheck<double>(nj);
242 _cpids_lim = allocAndCheck<double>(nj);
243 _vpids_lim = allocAndCheck<double>(nj);
244 _ppids_ref=allocAndCheck<double>(nj);
245 _tpids_ref=allocAndCheck<double>(nj);
246 _cpids_ref = allocAndCheck<double>(nj);
247 _vpids_ref = allocAndCheck<double>(nj);
248
249// _impedance_params=allocAndCheck<ImpedanceParameters>(nj);
250// _impedance_limits=allocAndCheck<ImpedanceLimits>(nj);
251 _axisName = new std::string[nj];
252 _jointType = new JointTypeEnum[nj];
253
254 _limitsMax=allocAndCheck<double>(nj);
255 _limitsMin=allocAndCheck<double>(nj);
256 _kinematic_mj=allocAndCheck<double>(16);
257// _currentLimits=allocAndCheck<MotorCurrentLimits>(nj);
258 _motorPwmLimits=allocAndCheck<double>(nj);
259 checking_motiondone=allocAndCheck<bool>(nj);
260
261 _velocityShifts=allocAndCheck<int>(nj);
262 _velocityTimeout=allocAndCheck<int>(nj);
263 _kbemf=allocAndCheck<double>(nj);
264 _ktau=allocAndCheck<double>(nj);
265 _kbemf_scale = allocAndCheck<int>(nj);
266 _ktau_scale = allocAndCheck<int>(nj);
267 _filterType=allocAndCheck<int>(nj);
268 _last_position_move_time=allocAndCheck<double>(nj);
269 _viscousPos=allocAndCheck<double>(nj);
270 _viscousNeg=allocAndCheck<double>(nj);
271 _coulombPos=allocAndCheck<double>(nj);
272 _coulombNeg=allocAndCheck<double>(nj);
273 _velocityThres=allocAndCheck<double>(nj);
274
275 // Reserve space for data stored locally. values are initialized to 0
276 _posCtrl_references = allocAndCheck<double>(nj);
277 _posDir_references = allocAndCheck<double>(nj);
278 _command_speeds = allocAndCheck<double>(nj);
279 _ref_speeds = allocAndCheck<double>(nj);
280 _ref_accs = allocAndCheck<double>(nj);
281 _ref_torques = allocAndCheck<double>(nj);
282 _ref_currents = allocAndCheck<double>(nj);
283 _enabledAmp = allocAndCheck<bool>(nj);
284 _enabledPid = allocAndCheck<bool>(nj);
285 _calibrated = allocAndCheck<bool>(nj);
286// _cacheImpedance = allocAndCheck<eOmc_impedance_t>(nj);
287
289
290 return true;
291}
292
293bool FakeMotionControl::dealloc()
294{
295 checkAndDestroy(_axisMap);
296 checkAndDestroy(_controlModes);
297 checkAndDestroy(_interactMode);
298 checkAndDestroy(_angleToEncoder);
299 checkAndDestroy(_ampsToSensor);
300 checkAndDestroy(_dutycycleToPWM);
301 checkAndDestroy(_encodersStamp);
302 checkAndDestroy(_DEPRECATED_encoderconversionoffset);
303 checkAndDestroy(_DEPRECATED_encoderconversionfactor);
304 checkAndDestroy(_jointEncoderRes);
305 checkAndDestroy(_rotorEncoderRes);
306// checkAndDestroy(_jointEncoderType);
307// checkAndDestroy(_rotorEncoderType);
308 checkAndDestroy(_gearbox);
309 checkAndDestroy(_torqueSensorId);
310 checkAndDestroy(_torqueSensorChan);
311 checkAndDestroy(_maxTorque);
312 checkAndDestroy(_maxJntCmdVelocity);
313 checkAndDestroy(_maxMotorVelocity);
314 checkAndDestroy(_newtonsToSensor);
315 checkAndDestroy(_ppids);
316 checkAndDestroy(_tpids);
317 checkAndDestroy(_cpids);
318 checkAndDestroy(_vpids);
319 checkAndDestroy(_ppids_ena);
320 checkAndDestroy(_tpids_ena);
321 checkAndDestroy(_cpids_ena);
322 checkAndDestroy(_vpids_ena);
323 checkAndDestroy(_ppids_lim);
324 checkAndDestroy(_tpids_lim);
325 checkAndDestroy(_cpids_lim);
326 checkAndDestroy(_vpids_lim);
327 checkAndDestroy(_ppids_ref);
328 checkAndDestroy(_tpids_ref);
329 checkAndDestroy(_cpids_ref);
330 checkAndDestroy(_vpids_ref);
331// checkAndDestroy(_impedance_params);
332// checkAndDestroy(_impedance_limits);
333 checkAndDestroy(_limitsMax);
334 checkAndDestroy(_limitsMin);
335 checkAndDestroy(_kinematic_mj);
336// checkAndDestroy(_currentLimits);
337 checkAndDestroy(_motorPwmLimits);
338 checkAndDestroy(checking_motiondone);
339 checkAndDestroy(_velocityShifts);
340 checkAndDestroy(_velocityTimeout);
341 checkAndDestroy(_kbemf);
342 checkAndDestroy(_ktau);
343 checkAndDestroy(_kbemf_scale);
344 checkAndDestroy(_ktau_scale);
345 checkAndDestroy(_filterType);
346 checkAndDestroy(_viscousPos);
347 checkAndDestroy(_viscousNeg);
348 checkAndDestroy(_coulombPos);
349 checkAndDestroy(_coulombNeg);
350 checkAndDestroy(_velocityThres);
351 checkAndDestroy(_posCtrl_references);
352 checkAndDestroy(_posDir_references);
353 checkAndDestroy(_command_speeds);
354 checkAndDestroy(_ref_speeds);
355 checkAndDestroy(_ref_accs);
356 checkAndDestroy(_ref_torques);
357 checkAndDestroy(_ref_currents);
358 checkAndDestroy(_enabledAmp);
359 checkAndDestroy(_enabledPid);
360 checkAndDestroy(_calibrated);
361 checkAndDestroy(_hasHallSensor);
362 checkAndDestroy(_hasTempSensor);
363 checkAndDestroy(_hasRotorEncoder);
364 checkAndDestroy(_hasRotorEncoderIndex);
365 checkAndDestroy(_rotorIndexOffset);
366 checkAndDestroy(_motorPoles);
367 checkAndDestroy(_axisName);
368 checkAndDestroy(_jointType);
369 checkAndDestroy(_rotorlimits_max);
370 checkAndDestroy(_rotorlimits_min);
371 checkAndDestroy(_last_position_move_time);
372 checkAndDestroy(_torques);
373 checkAndDestroy(_hwfault_code);
374 checkAndDestroy(_hwfault_message);
375
376 return true;
377}
378
380 PeriodicThread(0.01),
400 _mutex(),
401 _njoints (0),
402 _axisMap (nullptr),
403 _angleToEncoder(nullptr),
404 _encodersStamp (nullptr),
405 _ampsToSensor (nullptr),
406 _dutycycleToPWM(nullptr),
407 _DEPRECATED_encoderconversionfactor (nullptr),
408 _DEPRECATED_encoderconversionoffset (nullptr),
409 _jointEncoderRes (nullptr),
410 _rotorEncoderRes (nullptr),
411 _gearbox (nullptr),
412 _hasHallSensor (nullptr),
413 _hasTempSensor (nullptr),
414 _hasRotorEncoder (nullptr),
415 _hasRotorEncoderIndex (nullptr),
416 _rotorIndexOffset (nullptr),
417 _motorPoles (nullptr),
418 _rotorlimits_max (nullptr),
419 _rotorlimits_min (nullptr),
420 _ppids (nullptr),
421 _tpids (nullptr),
422 _cpids (nullptr),
423 _vpids (nullptr),
424 _ppids_ena (nullptr),
425 _tpids_ena (nullptr),
426 _cpids_ena (nullptr),
427 _vpids_ena (nullptr),
428 _ppids_lim (nullptr),
429 _tpids_lim (nullptr),
430 _cpids_lim (nullptr),
431 _vpids_lim (nullptr),
432 _ppids_ref (nullptr),
433 _tpids_ref (nullptr),
434 _cpids_ref (nullptr),
435 _vpids_ref (nullptr),
436 _axisName (nullptr),
437 _jointType (nullptr),
438 _limitsMin (nullptr),
439 _limitsMax (nullptr),
440 _kinematic_mj (nullptr),
441 _maxJntCmdVelocity (nullptr),
442 _maxMotorVelocity (nullptr),
443 _velocityShifts (nullptr),
444 _velocityTimeout (nullptr),
445 _kbemf (nullptr),
446 _ktau (nullptr),
447 _kbemf_scale (nullptr),
448 _ktau_scale (nullptr),
449 _viscousPos (nullptr),
450 _viscousNeg (nullptr),
451 _coulombPos (nullptr),
452 _coulombNeg (nullptr),
453 _velocityThres (nullptr),
454 _filterType (nullptr),
455 _torqueSensorId (nullptr),
456 _torqueSensorChan (nullptr),
457 _maxTorque (nullptr),
458 _newtonsToSensor (nullptr),
459 checking_motiondone (nullptr),
460 _last_position_move_time(nullptr),
461 _motorPwmLimits (nullptr),
462 _torques (nullptr),
463 useRawEncoderData (false),
464 _pwmIsLimited (false),
465 _torqueControlEnabled (false),
466 _torqueControlUnits (T_MACHINE_UNITS),
467 _positionControlUnits (P_MACHINE_UNITS),
468 prev_time (0.0),
469 opened (false),
470 verbose (VERY_VERBOSE)
471{
473 std::string tmp = yarp::conf::environment::get_string("VERBOSE_STICA");
474 verbosewhenok = (tmp != "") ? (bool)yarp::conf::numeric::from_string<int>(tmp) :
475 false;
476}
477
483
485{
486 return opened;
487}
488
490{
492 for(int i=0; i<_njoints; i++)
493 {
494 pwm[i] = 33+i;
495 pwmLimit[i] = (33+i)*10;
496 current[i] = (33+i)*100;
497 maxCurrent[i] = (33+i)*1000;
498 peakCurrent[i] = (33+i)*2;
499 nominalCurrent[i] = (33+i)*20;
500 supplyVoltage[i] = (33+i)*200;
501 last_velocity_command[i] = -1;
502 last_pwm_command[i] = -1;
503 _controlModes[i] = VOCAB_CM_POSITION;
504 _maxJntCmdVelocity[i]=50.0;
505 }
506 prev_time = yarp::os::Time::now();
507 return true;
508}
509
513
515{
516 if (!this->parseParams(config)) {return false;}
517
518 std::string str;
519
520 //
521 // Read Configuration params from file
522 //
523 _njoints = m_GENERAL_Joints;
524
525 if(!alloc(_njoints))
526 {
527 yCError(FAKEMOTIONCONTROL) << "Malloc failed";
528 return false;
529 }
530
531 // Default value
532 for (int i = 0; i < _njoints; i++) {
533 _newtonsToSensor[i] = 1;
534 }
535
536 if(!fromConfig(config))
537 {
538 yCError(FAKEMOTIONCONTROL) << "Missing parameters in config file";
539 return false;
540 }
541
542 // INIT ALL INTERFACES
543 yarp::sig::Vector tmpZeros; tmpZeros.resize (_njoints, 0.0);
544 yarp::sig::Vector tmpOnes; tmpOnes.resize (_njoints, 1.0);
545 yarp::sig::Vector bemfToRaw; bemfToRaw.resize(_njoints, 1.0);
546 yarp::sig::Vector ktauToRaw; ktauToRaw.resize(_njoints, 1.0);
547 for (size_t i = 0; i < _njoints; i++) { bemfToRaw [i] = _newtonsToSensor[i] / _angleToEncoder[i];}
548 for (size_t i = 0; i < _njoints; i++) { ktauToRaw[i] = _dutycycleToPWM[i] / _newtonsToSensor[i]; }
549 ControlBoardHelper cb(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor, _ampsToSensor, _dutycycleToPWM);
551 ImplementControlCalibration::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
552 ImplementAmplifierControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
553 ImplementEncodersTimed::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
554 ImplementMotorEncoders::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
555 ImplementPositionControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
556 ImplementPidControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor, _ampsToSensor, _dutycycleToPWM);
557 ImplementPidControl::setConversionUnits(PidControlTypeEnum::VOCAB_PIDTYPE_POSITION, PidFeedbackUnitsEnum::METRIC, PidOutputUnitsEnum::DUTYCYCLE_PWM_PERCENT);
558 ImplementPidControl::setConversionUnits(PidControlTypeEnum::VOCAB_PIDTYPE_TORQUE, PidFeedbackUnitsEnum::METRIC, PidOutputUnitsEnum::DUTYCYCLE_PWM_PERCENT);
559 ImplementControlMode::initialize(_njoints, _axisMap);
560 ImplementVelocityControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
561 ImplementControlLimits::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
562 ImplementImpedanceControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor);
563 ImplementTorqueControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor, _ampsToSensor, _dutycycleToPWM, bemfToRaw.data(), ktauToRaw.data());
564 ImplementPositionDirect::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
565 ImplementInteractionMode::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
566 ImplementMotor::initialize(_njoints, _axisMap);
567 ImplementAxisInfo::initialize(_njoints, _axisMap);
568 ImplementPWMControl::initialize(_njoints, _axisMap, _dutycycleToPWM);
569 ImplementCurrentControl::initialize(_njoints, _axisMap, _ampsToSensor);
570 ImplementVirtualAnalogSensor::initialize(_njoints, _axisMap, _newtonsToSensor);
571 ImplementJointFault::initialize(_njoints, _axisMap);
572
573 //start the rateThread
574 bool init = this->start();
575 if(!init)
576 {
577 yCError(FAKEMOTIONCONTROL) << "open() has an error in call of FakeMotionControl::init() for board" ;
578 return false;
579 }
580 else
581 {
582 if(verbosewhenok)
583 {
584 yCDebug(FAKEMOTIONCONTROL) << "init() has successfully initted board ";
585 }
586 }
587 opened = true;
588
589 return true;
590}
591
593{
594 size_t i;
595
596 // AxisMap
597 if (!m_GENERAL_AxisMap.empty())
598 {
599 for (i = 0; i < m_GENERAL_AxisMap.size(); i++) {
600 _axisMap[i] = m_GENERAL_AxisMap[i];
601 }
602 }
603 else
604 {
605 for (i = 0; i < _njoints; i++) {
606 _axisMap[i] = i;
607 }
608 }
609 for (i = 0; i < _njoints; i++) {yDebug() << "_axisMap: " << _axisMap[i] << " "; }
610
611 // AxisName
612 if (!m_GENERAL_AxisName.empty())
613 {
614 for (i = 0; i < m_GENERAL_AxisName.size(); i++) {
615 _axisName[_axisMap[i]] = m_GENERAL_AxisName[i];
616 }
617 }
618 else
619 {
620 for (i = 0; i < _njoints; i++) {
621 _axisName[_axisMap[i]] = "joint" + toString(i);
622 }
623 }
624 for (i = 0; i < _njoints; i++) { yDebug() << "_axisName: " << _axisName[_axisMap[i]] << " "; }
625
626 // Axis Type
627 if (!m_GENERAL_AxisType.empty())
628 {
629 //beware: axis type has to be remapped here because they are not set using the toHw() helper function
630 for (i = 0; i < m_GENERAL_AxisType.size(); i++)
631 {
632 std::string typeString = m_GENERAL_AxisType[i];
633 if (typeString == "revolute") {
634 _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_REVOLUTE;
635 }
636 else if (typeString == "prismatic") {
637 _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_PRISMATIC;
638 }
639 else {
640 yCError(FAKEMOTIONCONTROL, "Unknown AxisType value %s!", typeString.c_str());
641 _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_UNKNOWN;
642 return false;
643 }
644 }
645 }
646 else
647 {
648 yCInfo(FAKEMOTIONCONTROL) << "Using default AxisType (revolute)";
649 for (i = 0; i < _njoints; i++) {
650 _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_REVOLUTE;
651 }
652 }
653
654 // current conversions factor
655 if (!m_GENERAL_ampsToSensor.empty())
656 {
657 for (i = 0; i < m_GENERAL_ampsToSensor.size(); i++) {
658 _ampsToSensor[i] = m_GENERAL_ampsToSensor[i];
659 }
660 }
661 else
662 {
663 yCInfo(FAKEMOTIONCONTROL) << "Using default ampsToSensor=1";
664 for (i = 0; i < _njoints; i++) {
665 _ampsToSensor[i] = 1;
666 }
667 }
668
669
670 // pwm conversions factor
671 if (!m_GENERAL_fullscalePWM.empty())
672 {
673 for (i = 0; i < m_GENERAL_fullscalePWM.size(); i++) {
674 _dutycycleToPWM[i] = m_GENERAL_fullscalePWM[i]/100;
675 }
676 }
677 else
678 {
679 yCInfo(FAKEMOTIONCONTROL) << "Using default fullscalePWM=1";
680 for (i = 0; i < _njoints; i++) {
681 _dutycycleToPWM[i] = 1;
682 }
683 }
684
685// double tmp_A2E;
686 // Encoder scales
687 if(!m_GENERAL_Encoder.empty())
688 {
689 for (i = 0; i < m_GENERAL_Encoder.size(); i++) {
690 _angleToEncoder[i] = m_GENERAL_Encoder[i]; }
691 }
692 else
693 {
694 yCInfo(FAKEMOTIONCONTROL) << "Using default Encoder=1";
695 for (i = 0; i < _njoints; i++) {
696 _angleToEncoder[i] = 1; }
697 }
698
700 if (!m_LIMITS_Max.empty())
701 {
702 for (i = 0; i < m_LIMITS_Max.size(); i++) {
703 _limitsMax[i] = m_LIMITS_Max[i];
704 }
705 }
706 else
707 {
708 yCInfo(FAKEMOTIONCONTROL) << "Using default m_LIMITS_Max=100";
709 for (i = 0; i < _njoints; i++) {
710 _limitsMax[i] = 100;
711 }
712 }
713
714 if (!m_LIMITS_Min.empty())
715 {
716 for (i = 0; i < m_LIMITS_Min.size(); i++) {
717 _limitsMin[i] = m_LIMITS_Min[i];
718 }
719 }
720 else
721 {
722 yCInfo(FAKEMOTIONCONTROL) << "Using default m_LIMITS_Min=0";
723 for (i = 0; i < _njoints; i++) {
724 _limitsMin[i] = 0;
725 }
726 }
727
728 return true;
729}
730
731
760
761void FakeMotionControl::cleanup()
762{
763
764}
765
766
767
769
771{
772 yCDebug(FAKEMOTIONCONTROL) << "setPidRaw" << pidtype << j << pid.kp;
773 switch (pidtype)
774 {
776 _ppids[j]=pid;
777 break;
779 _vpids[j]=pid;
780 break;
782 _cpids[j]=pid;
783 break;
785 _tpids[j]=pid;
786 break;
787 default:
788 break;
789 }
790 return true;
791}
792
794{
795 bool ret = true;
796 for(int j=0; j< _njoints; j++)
797 {
798 ret &= setPidRaw(pidtype, j, pids[j]);
799 }
800 return ret;
801}
802
804{
805 switch (pidtype)
806 {
808 _ppids_ref[j]=ref;
809 break;
811 _vpids_ref[j]=ref;
812 break;
814 _cpids_ref[j]=ref;
815 break;
817 _tpids_ref[j]=ref;
818 break;
819 default:
820 break;
821 }
822 return true;
823}
824
826{
827 bool ret = true;
828 for(int j=0, index=0; j< _njoints; j++, index++)
829 {
830 ret &= setPidReferenceRaw(pidtype, j, refs[index]);
831 }
832 return ret;
833}
834
836{
837 switch (pidtype)
838 {
840 _ppids_lim[j]=limit;
841 break;
843 _vpids_lim[j]=limit;
844 break;
846 _cpids_lim[j]=limit;
847 break;
849 _tpids_lim[j]=limit;
850 break;
851 default:
852 break;
853 }
854 return true;
855}
856
858{
859 bool ret = true;
860 for(int j=0, index=0; j< _njoints; j++, index++)
861 {
862 ret &= setPidErrorLimitRaw(pidtype, j, limits[index]);
863 }
864 return ret;
865}
866
868{
869 switch (pidtype)
870 {
872 *err=0.1;
873 break;
875 *err=0.2;
876 break;
878 *err=0.3;
879 break;
881 *err=0.4;
882 break;
883 default:
884 break;
885 }
886 return true;
887}
888
890{
891 bool ret = true;
892 for(int j=0; j< _njoints; j++)
893 {
894 ret &= getPidErrorRaw(pidtype, j, &errs[j]);
895 }
896 return ret;
897}
898
900{
901 switch (pidtype)
902 {
904 *pid=_ppids[j];
905 break;
907 *pid=_vpids[j];
908 break;
910 *pid=_cpids[j];
911 break;
913 *pid=_tpids[j];
914 break;
915 default:
916 break;
917 }
918 yCDebug(FAKEMOTIONCONTROL) << "getPidRaw" << pidtype << j << pid->kp;
919 return true;
920}
921
923{
924 bool ret = true;
925
926 // just one joint at time, wait answer before getting to the next.
927 // This is because otherwise too many msg will be placed into can queue
928 for(int j=0, index=0; j<_njoints; j++, index++)
929 {
930 ret &=getPidRaw(pidtype, j, &pids[j]);
931 }
932 return ret;
933}
934
936{
937 switch (pidtype)
938 {
940 *ref=_ppids_ref[j];
941 break;
943 *ref=_vpids_ref[j];
944 break;
946 *ref=_cpids_ref[j];
947 break;
949 *ref=_tpids_ref[j];
950 break;
951 default:
952 break;
953 }
954 return true;
955}
956
958{
959 bool ret = true;
960
961 // just one joint at time, wait answer before getting to the next.
962 // This is because otherwise too many msg will be placed into can queue
963 for(int j=0; j< _njoints; j++)
964 {
966 }
967 return ret;
968}
969
971{
972 switch (pidtype)
973 {
975 *limit=_ppids_lim[j];
976 break;
978 *limit=_vpids_lim[j];
979 break;
981 *limit=_cpids_lim[j];
982 break;
984 *limit=_tpids_lim[j];
985 break;
986 default:
987 break;
988 }
989 return true;
990}
991
993{
994 bool ret = true;
995 for(int j=0, index=0; j<_njoints; j++, index++)
996 {
997 ret &=getPidErrorLimitRaw(pidtype, j, &limits[j]);
998 }
999 return ret;
1000}
1001
1003{
1004 return true;
1005}
1006
1008{
1009 switch (pidtype)
1010 {
1012 _ppids_ena[j]=false;
1013 break;
1015 _vpids_ena[j]=false;
1016 break;
1018 _cpids_ena[j]=false;
1019 break;
1021 _tpids_ena[j]=false;
1022 break;
1023 default:
1024 break;
1025 }
1026 return true;
1027}
1028
1030{
1031 switch (pidtype)
1032 {
1034 _ppids_ena[j]=true;
1035 break;
1037 _vpids_ena[j]=true;
1038 break;
1040 _cpids_ena[j]=true;
1041 break;
1043 _tpids_ena[j]=true;
1044 break;
1045 default:
1046 break;
1047 }
1048 return true;
1049}
1050
1052{
1053 yCDebug(FAKEMOTIONCONTROL) << "setPidOffsetRaw" << pidtype << j << v;
1054 switch (pidtype)
1055 {
1057 _ppids[j].offset=v;
1058 break;
1060 _vpids[j].offset=v;
1061 break;
1063 _cpids[j].offset=v;
1064 break;
1066 _tpids[j].offset=v;
1067 break;
1068 default:
1069 break;
1070 }
1071 return true;
1072}
1073
1075{
1076 switch (pidtype)
1077 {
1079 *enabled=_ppids_ena[j];
1080 break;
1082 *enabled=_vpids_ena[j];
1083 break;
1085 *enabled=_cpids_ena[j];
1086 break;
1088 *enabled=_tpids_ena[j];
1089 break;
1090 default:
1091 break;
1092 }
1093 return true;
1094}
1095
1097{
1098 switch (pidtype)
1099 {
1101 *out=1.1 + j * 10;
1102 break;
1104 *out=1.2 + j * 10;
1105 break;
1107 *out=1.3 + j * 10;
1108 break;
1110 *out=1.4 + j * 10;
1111 break;
1112 default:
1113 break;
1114 }
1115 yCDebug(FAKEMOTIONCONTROL) << "getPidOutputRaw" << pidtype << j << *out;
1116 return true;
1117}
1118
1120{
1121 bool ret = true;
1122 for(int j=0; j< _njoints; j++)
1123 {
1124 ret &= getPidOutputRaw(pidtype, j, &outs[j]);
1125 }
1126 return ret;
1127}
1128
1130// Velocity control interface raw //
1132
1134{
1135 int mode=0;
1136 getControlModeRaw(j, &mode);
1137 if( (mode != VOCAB_CM_VELOCITY) &&
1138 (mode != VOCAB_CM_MIXED) &&
1139 (mode != VOCAB_CM_IMPEDANCE_VEL) &&
1140 (mode != VOCAB_CM_IDLE))
1141 {
1142 yCError(FAKEMOTIONCONTROL) << "velocityMoveRaw: skipping command because board " << " joint " << j << " is not in VOCAB_CM_VELOCITY mode";
1143 }
1144 _command_speeds[j] = sp;
1145 last_velocity_command[j]=yarp::os::Time::now();
1146 return true;
1147}
1148
1150{
1152 bool ret = true;
1153 for (int i = 0; i < _njoints; i++) {
1154 ret &= velocityMoveRaw(i, sp[i]);
1155 }
1156 return ret;
1157}
1158
1159
1161// Calibration control interface //
1163
1165{
1166 yCTrace(FAKEMOTIONCONTROL) << "setCalibrationParametersRaw for joint" << j;
1167 return true;
1168}
1169
1170bool FakeMotionControl::calibrateAxisWithParamsRaw(int j, unsigned int type, double p1, double p2, double p3)
1171{
1172 yCTrace(FAKEMOTIONCONTROL) << "calibrateRaw for joint" << j;
1173 return true;
1174}
1175
1177{
1178 return NOT_YET_IMPLEMENTED("calibrationDoneRaw");
1179}
1180
1182// Position control interface //
1184
1186{
1187 *ax=_njoints;
1188
1189 return true;
1190}
1191
1193{
1194 if (verbose >= VERY_VERBOSE) {
1195 yCTrace(FAKEMOTIONCONTROL) << "j " << j << " ref " << ref;
1196 }
1197
1198// if (yarp::os::Time::now()-_last_position_move_time[j]<MAX_POSITION_MOVE_INTERVAL)
1199// {
1200// 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.";
1201// }
1202// _last_position_move_time[j] = yarp::os::Time::now();
1203
1204 int mode = 0;
1205 getControlModeRaw(j, &mode);
1206 if( (mode != VOCAB_CM_POSITION) &&
1207 (mode != VOCAB_CM_MIXED) &&
1208 (mode != VOCAB_CM_IMPEDANCE_POS) &&
1209 (mode != VOCAB_CM_IDLE))
1210 {
1211 yCError(FAKEMOTIONCONTROL) << "positionMoveRaw: skipping command because joint " << j << " is not in VOCAB_CM_POSITION mode";
1212 }
1213 _posCtrl_references[j] = ref;
1214 return true;
1215}
1216
1218{
1219 if (verbose >= VERY_VERBOSE) {
1221 }
1222
1223 bool ret = true;
1224 for(int j=0, index=0; j< _njoints; j++, index++)
1225 {
1226 ret &= positionMoveRaw(j, refs[index]);
1227 }
1228 return ret;
1229}
1230
1232{
1233 if (verbose >= VERY_VERBOSE) {
1234 yCTrace(FAKEMOTIONCONTROL) << "j " << j << " ref " << delta;
1235 }
1236// if (yarp::os::Time::now()-_last_position_move_time[j]<MAX_POSITION_MOVE_INTERVAL)
1237// {
1238// 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.";
1239// }
1240// _last_position_move_time[j] = yarp::os::Time::now();
1241
1242 int mode = 0;
1243 getControlModeRaw(j, &mode);
1244 if( (mode != VOCAB_CM_POSITION) &&
1245 (mode != VOCAB_CM_MIXED) &&
1246 (mode != VOCAB_CM_IMPEDANCE_POS) &&
1247 (mode != VOCAB_CM_IDLE))
1248 {
1249 yCError(FAKEMOTIONCONTROL) << "relativeMoveRaw: skipping command because joint " << j << " is not in VOCAB_CM_POSITION mode";
1250 }
1251 _posCtrl_references[j] += delta;
1252 return true;
1253}
1254
1256{
1257 if (verbose >= VERY_VERBOSE) {
1259 }
1260
1261 bool ret = true;
1262 for(int j=0, index=0; j< _njoints; j++, index++)
1263 {
1264 ret &= relativeMoveRaw(j, deltas[index]);
1265 }
1266 return ret;
1267}
1268
1269
1271{
1272 if (verbose >= VERY_VERBOSE) {
1273 yCTrace(FAKEMOTIONCONTROL) << "j ";
1274 }
1275
1276 *flag = false;
1277 return true;
1278}
1279
1281{
1282 if (verbose >= VERY_VERBOSE) {
1284 }
1285
1286 bool ret = true;
1287 bool val, tot_res = true;
1288
1289 for(int j=0, index=0; j< _njoints; j++, index++)
1290 {
1291 ret &= checkMotionDoneRaw(j, &val);
1292 tot_res &= val;
1293 }
1294 *flag = tot_res;
1295 return ret;
1296}
1297
1299{
1300 // Velocity is expressed in iDegrees/s
1301 // save internally the new value of speed; it'll be used in the positionMove
1302 int index = j ;
1303 _ref_speeds[index] = sp;
1304 return true;
1305}
1306
1308{
1309 // Velocity is expressed in iDegrees/s
1310 // save internally the new value of speed; it'll be used in the positionMove
1311 for(int j=0, index=0; j< _njoints; j++, index++)
1312 {
1313 _ref_speeds[index] = spds[index];
1314 }
1315 return true;
1316}
1317
1319{
1320 // Acceleration is expressed in iDegrees/s^2
1321 // save internally the new value of the acceleration; it'll be used in the velocityMove command
1322
1323 if (acc > 1e6)
1324 {
1325 _ref_accs[j ] = 1e6;
1326 }
1327 else if (acc < -1e6)
1328 {
1329 _ref_accs[j ] = -1e6;
1330 }
1331 else
1332 {
1333 _ref_accs[j ] = acc;
1334 }
1335
1336 return true;
1337}
1338
1340{
1341 // Acceleration is expressed in iDegrees/s^2
1342 // save internally the new value of the acceleration; it'll be used in the velocityMove command
1343 for(int j=0, index=0; j< _njoints; j++, index++)
1344 {
1345 if (accs[j] > 1e6)
1346 {
1347 _ref_accs[index] = 1e6;
1348 }
1349 else if (accs[j] < -1e6)
1350 {
1351 _ref_accs[index] = -1e6;
1352 }
1353 else
1354 {
1355 _ref_accs[index] = accs[j];
1356 }
1357 }
1358 return true;
1359}
1360
1362{
1363 *spd = _ref_speeds[j];
1364 return true;
1365}
1366
1368{
1369 memcpy(spds, _ref_speeds, sizeof(double) * _njoints);
1370 return true;
1371}
1372
1374{
1375 *acc = _ref_accs[j];
1376 return true;
1377}
1378
1380{
1381 memcpy(accs, _ref_accs, sizeof(double) * _njoints);
1382 return true;
1383}
1384
1386{
1387 velocityMoveRaw(j,0);
1388 return true;
1389}
1390
1392{
1393 bool ret = true;
1394 for(int j=0; j< _njoints; j++)
1395 {
1396 ret &= stopRaw(j);
1397 }
1398 return ret;
1399}
1401
1403// Position control2 interface //
1405
1406bool FakeMotionControl::positionMoveRaw(const int n_joint, const int *joints, const double *refs)
1407{
1408 if (verbose >= VERY_VERBOSE) {
1409 yCTrace(FAKEMOTIONCONTROL) << " -> n_joint " << n_joint;
1410 }
1411
1412 for(int j=0; j<n_joint; j++)
1413 {
1414 yCDebug(FAKEMOTIONCONTROL, "j: %d; ref %f;\n", joints[j], refs[j]); fflush(stdout);
1415 }
1416
1417 bool ret = true;
1418 for(int j=0; j<n_joint; j++)
1419 {
1421 }
1422 return ret;
1423}
1424
1425bool FakeMotionControl::relativeMoveRaw(const int n_joint, const int *joints, const double *deltas)
1426{
1427 if (verbose >= VERY_VERBOSE) {
1428 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1429 }
1430
1431 bool ret = true;
1432 for(int j=0; j<n_joint; j++)
1433 {
1435 }
1436 return ret;
1437}
1438
1440{
1441 if (verbose >= VERY_VERBOSE) {
1442 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1443 }
1444
1445 bool ret = true;
1446 bool val = true;
1447 bool tot_val = true;
1448
1449 for(int j=0; j<n_joint; j++)
1450 {
1451 ret = ret && checkMotionDoneRaw(joints[j], &val);
1452 tot_val &= val;
1453 }
1454 *flag = tot_val;
1455 return ret;
1456}
1457
1458bool FakeMotionControl::setRefSpeedsRaw(const int n_joint, const int *joints, const double *spds)
1459{
1460 if (verbose >= VERY_VERBOSE) {
1461 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1462 }
1463
1464 bool ret = true;
1465 for(int j=0; j<n_joint; j++)
1466 {
1468 }
1469 return ret;
1470}
1471
1472bool FakeMotionControl::setRefAccelerationsRaw(const int n_joint, const int *joints, const double *accs)
1473{
1474 if (verbose >= VERY_VERBOSE) {
1475 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1476 }
1477
1478 bool ret = true;
1479 for(int j=0; j<n_joint; j++)
1480 {
1482 }
1483 return ret;
1484}
1485
1486bool FakeMotionControl::getRefSpeedsRaw(const int n_joint, const int *joints, double *spds)
1487{
1488 if (verbose >= VERY_VERBOSE) {
1489 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1490 }
1491
1492 bool ret = true;
1493 for(int j=0; j<n_joint; j++)
1494 {
1495 ret = ret && getRefSpeedRaw(joints[j], &spds[j]);
1496 }
1497 return ret;
1498}
1499
1501{
1502 if (verbose >= VERY_VERBOSE) {
1503 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1504 }
1505
1506 bool ret = true;
1507 for(int j=0; j<n_joint; j++)
1508 {
1510 }
1511 return ret;
1512}
1513
1514bool FakeMotionControl::stopRaw(const int n_joint, const int *joints)
1515{
1516 if (verbose >= VERY_VERBOSE) {
1517 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1518 }
1519
1520 bool ret = true;
1521 for(int j=0; j<n_joint; j++)
1522 {
1523 ret = ret &&stopRaw(joints[j]);
1524 }
1525 return ret;
1526}
1527
1529
1530// ControlMode
1531
1532// puo' essere richiesto con get
1534{
1535 if (verbose > VERY_VERY_VERBOSE) {
1536 yCTrace(FAKEMOTIONCONTROL) << "j: " << j;
1537 }
1538
1539 *v = _controlModes[j];
1540 return true;
1541}
1542
1543// IControl Mode 2
1545{
1546 bool ret = true;
1547 for(int j=0; j< _njoints; j++)
1548 {
1549 ret = ret && getControlModeRaw(j, &v[j]);
1550 }
1551 return ret;
1552}
1553
1555{
1556 bool ret = true;
1557 for(int j=0; j< n_joint; j++)
1558 {
1560 }
1561 return ret;
1562}
1563
1565{
1566 if (verbose >= VERY_VERBOSE) {
1567 yCTrace(FAKEMOTIONCONTROL) << "j: " << j << " mode: " << yarp::os::Vocab32::decode(_mode);
1568 }
1569
1571 {
1572 _controlModes[j] = VOCAB_CM_IDLE;
1573 }
1574 else
1575 {
1576 _controlModes[j] = _mode;
1577 }
1578 _posCtrl_references[j] = pos[j];
1579 return true;
1580}
1581
1582
1584{
1585 if (verbose >= VERY_VERBOSE) {
1586 yCTrace(FAKEMOTIONCONTROL) << "n_joints: " << n_joint;
1587 }
1588
1589 bool ret = true;
1590 for(int i=0; i<n_joint; i++)
1591 {
1593 }
1594 return ret;
1595}
1596
1598{
1599 if (verbose >= VERY_VERBOSE) {
1601 }
1602
1603 bool ret = true;
1604 for(int i=0; i<_njoints; i++)
1605 {
1607 }
1608 return ret;
1609}
1610
1611
1613
1615{
1616 return NOT_YET_IMPLEMENTED("setEncoder");
1617}
1618
1620{
1621 return NOT_YET_IMPLEMENTED("setEncoders");
1622}
1623
1625{
1626 return NOT_YET_IMPLEMENTED("resetEncoder");
1627}
1628
1630{
1631 return NOT_YET_IMPLEMENTED("resetEncoders");
1632}
1633
1634bool FakeMotionControl::getEncoderRaw(int j, double *value)
1635{
1636 bool ret = true;
1637
1638 // To simulate a real controlboard, we assume that the joint
1639 // encoders is exactly the last set by setPosition(s) or positionMove
1640 *value = pos[j];
1641
1642 return ret;
1643}
1644
1646{
1647 bool ret = true;
1648 for(int j=0; j< _njoints; j++)
1649 {
1650 bool ok = getEncoderRaw(j, &encs[j]);
1651 ret = ret && ok;
1652
1653 }
1654 return ret;
1655}
1656
1658{
1659 // To avoid returning uninitialized memory, we set the encoder speed to 0
1660 *sp = 0.0;
1661 return true;
1662}
1663
1665{
1666 bool ret = true;
1667 for(int j=0; j< _njoints; j++)
1668 {
1669 ret &= getEncoderSpeedRaw(j, &spds[j]);
1670 }
1671 return ret;
1672}
1673
1675{
1676 // To avoid returning uninitialized memory, we set the encoder acc to 0
1677 *acc = 0.0;
1678
1679 return true;
1680}
1681
1683{
1684 bool ret = true;
1685 for(int j=0; j< _njoints; j++)
1686 {
1688 }
1689 return ret;
1690}
1691
1693
1695{
1696 bool ret = getEncodersRaw(encs);
1697 _mutex.lock();
1698 for (int i = 0; i < _njoints; i++) {
1699 stamps[i] = _encodersStamp[i] = _cycleTimestamp;
1700 }
1701 _mutex.unlock();
1702 return ret;
1703}
1704
1705bool FakeMotionControl::getEncoderTimedRaw(int j, double *encs, double *stamp)
1706{
1707 bool ret = getEncoderRaw(j, encs);
1708 _mutex.lock();
1709 *stamp = _encodersStamp[j] = _cycleTimestamp;
1710 _mutex.unlock();
1711
1712 return ret;
1713}
1714
1716
1718{
1719 *num=_njoints;
1720 return true;
1721}
1722
1723bool FakeMotionControl::setMotorEncoderRaw(int m, const double val)
1724{
1725 return NOT_YET_IMPLEMENTED("setMotorEncoder");
1726}
1727
1729{
1730 return NOT_YET_IMPLEMENTED("setMotorEncoders");
1731}
1732
1734{
1735 return NOT_YET_IMPLEMENTED("setMotorEncoderCountsPerRevolutionRaw");
1736}
1737
1739{
1740 return NOT_YET_IMPLEMENTED("getMotorEncoderCountsPerRevolutionRaw");
1741}
1742
1744{
1745 return NOT_YET_IMPLEMENTED("resetMotorEncoder");
1746}
1747
1749{
1750 return NOT_YET_IMPLEMENTED("reseMotortEncoders");
1751}
1752
1754{
1755 *value = pos[m]*10;
1756 return true;
1757}
1758
1760{
1761 bool ret = true;
1762 for(int j=0; j< _njoints; j++)
1763 {
1764 ret &= getMotorEncoderRaw(j, &encs[j]);
1765
1766 }
1767 return ret;
1768}
1769
1771{
1772 *sp = 0.0;
1773 return true;
1774}
1775
1777{
1778 bool ret = true;
1779 for(int j=0; j< _njoints; j++)
1780 {
1782 }
1783 return ret;
1784}
1785
1787{
1788 *acc = 0.0;
1789 return true;
1790}
1791
1793{
1794 bool ret = true;
1795 for(int j=0; j< _njoints; j++)
1796 {
1798 }
1799 return ret;
1800}
1801
1803{
1805 _mutex.lock();
1806 for (int i = 0; i < _njoints; i++) {
1807 stamps[i] = _encodersStamp[i] = _cycleTimestamp;
1808 }
1809 _mutex.unlock();
1810
1811 return ret;
1812}
1813
1814bool FakeMotionControl::getMotorEncoderTimedRaw(int m, double *encs, double *stamp)
1815{
1816 bool ret = getMotorEncoderRaw(m, encs);
1817 _mutex.lock();
1818 *stamp = _encodersStamp[m] = _cycleTimestamp;
1819 _mutex.unlock();
1820
1821 return ret;
1822}
1824
1826
1828{
1829 return DEPRECATED("enableAmpRaw");
1830}
1831
1833{
1834 return DEPRECATED("disableAmpRaw");
1835}
1836
1837bool FakeMotionControl::getCurrentRaw(int j, double *value)
1838{
1839 //just for testing purposes, this is not a real implementation
1840 *value = current[j];
1841 return true;
1842}
1843
1845{
1846 //just for testing purposes, this is not a real implementation
1847 bool ret = true;
1848 for(int j=0; j< _njoints; j++)
1849 {
1850 ret &= getCurrentRaw(j, &vals[j]);
1851 }
1852 return ret;
1853}
1854
1856{
1857 maxCurrent[m] = val;
1858 return true;
1859}
1860
1862{
1863 *val = maxCurrent[m];
1864 return true;
1865}
1866
1868{
1869 (_enabledAmp[j ]) ? *st = 1 : *st = 0;
1870 return true;
1871}
1872
1874{
1875 bool ret = true;
1876 for(int j=0; j<_njoints; j++)
1877 {
1878 sts[j] = _enabledAmp[j];
1879 }
1880 return ret;
1881}
1882
1884{
1885 *val = peakCurrent[m];
1886 return true;
1887}
1888
1889bool FakeMotionControl::setPeakCurrentRaw(int m, const double val)
1890{
1891 peakCurrent[m] = val;
1892 return true;
1893}
1894
1896{
1897 *val = nominalCurrent[m];
1898 return true;
1899}
1900
1902{
1903 nominalCurrent[m] = val;
1904 return true;
1905}
1906
1907bool FakeMotionControl::getPWMRaw(int m, double *val)
1908{
1909 *val = pwm[m];
1910 return true;
1911}
1912
1914{
1915 *val = pwmLimit[m];
1916 return true;
1917}
1918
1919bool FakeMotionControl::setPWMLimitRaw(int m, const double val)
1920{
1921 pwmLimit[m] = val;
1922 return true;
1923}
1924
1926{
1927 *val = supplyVoltage[m];
1928 return true;
1929}
1930
1931
1932// Limit interface
1933bool FakeMotionControl::setLimitsRaw(int j, double min, double max)
1934{
1935 bool ret = true;
1936 return ret;
1937}
1938
1939bool FakeMotionControl::getLimitsRaw(int j, double *min, double *max)
1940{
1941 *min = _limitsMin[j];
1942 *max = _limitsMax[j];
1943 return true;
1944}
1945
1947{
1948 return NOT_YET_IMPLEMENTED("getGearboxRatioRaw");
1949}
1950
1951bool FakeMotionControl::setGearboxRatioRaw(int m, const double val)
1952{
1953 return NOT_YET_IMPLEMENTED("setGearboxRatioRaw");
1954}
1955
1957{
1958 return NOT_YET_IMPLEMENTED("getTorqueControlFilterType");
1959}
1960
1962{
1963 return NOT_YET_IMPLEMENTED("getRotorEncoderResolutionRaw");
1964}
1965
1967{
1968 return NOT_YET_IMPLEMENTED("getJointEncoderResolutionRaw");
1969}
1970
1972{
1973 return NOT_YET_IMPLEMENTED("getJointEncoderTypeRaw");
1974}
1975
1977{
1978 return NOT_YET_IMPLEMENTED("getRotorEncoderTypeRaw");
1979}
1980
1982{
1983 return NOT_YET_IMPLEMENTED("getKinematicMJRaw");
1984}
1985
1987{
1988 return NOT_YET_IMPLEMENTED("getHasTempSensorsRaw");
1989}
1990
1992{
1993 return NOT_YET_IMPLEMENTED("getHasHallSensorRaw");
1994}
1995
1997{
1998 return NOT_YET_IMPLEMENTED("getHasRotorEncoderRaw");
1999}
2000
2002{
2003 return NOT_YET_IMPLEMENTED("getHasRotorEncoderIndexRaw");
2004}
2005
2007{
2008 return NOT_YET_IMPLEMENTED("getMotorPolesRaw");
2009}
2010
2012{
2013 return NOT_YET_IMPLEMENTED("getRotorIndexOffsetRaw");
2014}
2015
2016bool FakeMotionControl::getAxisNameRaw(int axis, std::string& name)
2017{
2018 if (axis >= 0 && axis < _njoints)
2019 {
2020 name = _axisName[axis];
2021 return true;
2022 }
2023 else
2024 {
2025 name = "ERROR";
2026 return false;
2027 }
2028}
2029
2031{
2032 if (axis >= 0 && axis < _njoints)
2033 {
2034 type = _jointType[axis];
2035 return true;
2036 }
2037 else
2038 {
2039 return false;
2040 }
2041}
2042
2043// IControlLimits
2044bool FakeMotionControl::setVelLimitsRaw(int axis, double min, double max)
2045{
2046 return NOT_YET_IMPLEMENTED("setVelLimitsRaw");
2047}
2048
2049bool FakeMotionControl::getVelLimitsRaw(int axis, double *min, double *max)
2050{
2051 *min = 0.0;
2052 *max = _maxJntCmdVelocity[axis];
2053 return true;
2054}
2055
2056
2057// Torque control
2059{
2060 *t = _torques[j];
2061 return true;
2062}
2063
2065{
2066 for (int i = 0; i < _njoints; i++)
2067 {
2068 t[i]= _torques[i];
2069 }
2070 return true;
2071}
2072
2073bool FakeMotionControl::getTorqueRangeRaw(int j, double *min, double *max)
2074{
2075 return NOT_YET_IMPLEMENTED("getTorqueRangeRaw");
2076}
2077
2078bool FakeMotionControl::getTorqueRangesRaw(double *min, double *max)
2079{
2080 return NOT_YET_IMPLEMENTED("getTorqueRangesRaw");
2081}
2082
2084{
2085 bool ret = true;
2086 for (int j = 0; j < _njoints && ret; j++) {
2087 ret &= setRefTorqueRaw(j, t[j]);
2088 }
2089 return ret;
2090}
2091
2093{
2094 _mutex.lock();
2095 _ref_torques[j]=t;
2096
2097 if (t>1.0 || t< -1.0)
2098 {
2099 yCError(FAKEMOTIONCONTROL) << "Joint received a high torque command, and was put in hardware fault";
2100 _hwfault_code[j] = 1;
2101 _hwfault_message[j] = "test" + std::to_string(j) + " torque";
2102 _controlModes[j] = VOCAB_CM_HW_FAULT;
2103 }
2104 _mutex.unlock();
2105 return true;
2106}
2107
2108bool FakeMotionControl::setRefTorquesRaw(const int n_joint, const int *joints, const double *t)
2109{
2110 return NOT_YET_IMPLEMENTED("setRefTorquesRaw");
2111}
2112
2114{
2115 bool ret = true;
2116 for (int j = 0; j < _njoints && ret; j++) {
2117 ret &= getRefTorqueRaw(j, &_ref_torques[j]);
2118 }
2119 return true;
2120}
2121
2123{
2124 _mutex.lock();
2125 *t = _ref_torques[j];
2126 _mutex.unlock();
2127 return true;
2128}
2129
2130bool FakeMotionControl::getImpedanceRaw(int j, double *stiffness, double *damping)
2131{
2132 return NOT_YET_IMPLEMENTED("getImpedanceRaw");
2133}
2134
2135bool FakeMotionControl::setImpedanceRaw(int j, double stiffness, double damping)
2136{
2137 return NOT_YET_IMPLEMENTED("setImpedanceRaw");
2138}
2139
2141{
2142 return NOT_YET_IMPLEMENTED("setImpedanceOffsetRaw");
2143}
2144
2146{
2147 return NOT_YET_IMPLEMENTED("getImpedanceOffsetRaw");
2148}
2149
2150bool FakeMotionControl::getCurrentImpedanceLimitRaw(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp)
2151{
2152 return NOT_YET_IMPLEMENTED("getCurrentImpedanceLimitRaw");
2153}
2154
2156{
2157 params->bemf = _kbemf[j];
2158 params->bemf_scale = _kbemf_scale[j];
2159 params->ktau = _ktau[j];
2160 params->ktau_scale = _ktau_scale[j];
2161 params->viscousPos = _viscousPos[j];
2162 params->viscousNeg = _viscousNeg[j];
2163 params->coulombPos = _coulombPos[j];
2164 params->coulombNeg = _coulombNeg[j];
2165 params->velocityThres = _velocityThres[j];
2166 yCDebug(FAKEMOTIONCONTROL) << "getMotorTorqueParamsRaw" << params->bemf
2167 << params->bemf_scale
2168 << params->ktau
2169 << params->ktau_scale
2170 << params->viscousPos
2171 << params->viscousNeg
2172 << params->coulombPos
2173 << params->coulombNeg
2174 << params->velocityThres;
2175 return true;
2176}
2177
2179{
2180 _kbemf[j] = params.bemf;
2181 _ktau[j] = params.ktau;
2182 _kbemf_scale[j] = params.bemf_scale;
2183 _ktau_scale[j] = params.ktau_scale;
2184 _viscousPos[j] = params.viscousPos;
2185 _viscousNeg[j] = params.viscousNeg;
2186 _coulombPos[j] = params.coulombPos;
2187 _coulombNeg[j] = params.coulombNeg;
2188 _velocityThres[j] = params.velocityThres;
2189 yCDebug(FAKEMOTIONCONTROL) << "setMotorTorqueParamsRaw" << params.bemf
2190 << params.bemf_scale
2191 << params.ktau
2192 << params.ktau_scale
2193 << params.viscousPos
2194 << params.viscousNeg
2195 << params.coulombPos
2196 << params.coulombNeg
2197 << params.velocityThres;
2198 return true;
2199}
2200
2201// IVelocityControl interface
2202bool FakeMotionControl::velocityMoveRaw(const int n_joint, const int *joints, const double *spds)
2203{
2204 bool ret = true;
2205 for(int i=0; i<n_joint; i++)
2206 {
2208 }
2209 return ret;
2210}
2211
2212// PositionDirect Interface
2214{
2215 _posDir_references[j] = ref;
2216 return true;
2217}
2218
2219bool FakeMotionControl::setPositionsRaw(const int n_joint, const int *joints, const double *refs)
2220{
2221 for(int i=0; i< n_joint; i++)
2222 {
2223 _posDir_references[joints[i]] = refs[i];
2224 }
2225 return true;
2226}
2227
2229{
2230 for(int i=0; i< _njoints; i++)
2231 {
2232 _posDir_references[i] = refs[i];
2233 }
2234 return true;
2235}
2236
2237
2239{
2240 if (verbose >= VERY_VERBOSE) {
2241 yCTrace(FAKEMOTIONCONTROL) << "j " << axis << " ref " << _posCtrl_references[axis];
2242 }
2243
2244 int mode = 0;
2245 getControlModeRaw(axis, &mode);
2246 if( (mode != VOCAB_CM_POSITION) &&
2247 (mode != VOCAB_CM_MIXED) &&
2248 (mode != VOCAB_CM_IMPEDANCE_POS))
2249 {
2250 yCWarning(FAKEMOTIONCONTROL) << "getTargetPosition: Joint " << axis << " is not in POSITION mode, therefore the value returned by " <<
2251 "this call is for reference only and may not reflect the actual behaviour of the motor/firmware.";
2252 }
2253 *ref = _posCtrl_references[axis];
2254 return true;
2255}
2256
2258{
2259 bool ret = true;
2260 for (int i = 0; i < _njoints; i++) {
2262 }
2263 return ret;
2264}
2265
2266bool FakeMotionControl::getTargetPositionsRaw(int nj, const int * jnts, double *refs)
2267{
2268 bool ret = true;
2269 for (int i = 0; i<nj; i++)
2270 {
2272 }
2273 return ret;
2274}
2275
2277{
2278 *ref = _command_speeds[axis];
2279 return true;
2280}
2281
2283{
2284 bool ret = true;
2285 for (int i = 0; i<_njoints; i++)
2286 {
2287 ret &= getRefVelocityRaw(i, &refs[i]);
2288 }
2289 return ret;
2290}
2291
2292bool FakeMotionControl::getRefVelocitiesRaw(int nj, const int * jnts, double *refs)
2293{
2294 bool ret = true;
2295 for (int i = 0; i<nj; i++)
2296 {
2297 ret &= getRefVelocityRaw(jnts[i], &refs[i]);
2298 }
2299 return ret;
2300}
2301
2303{
2304 int mode = 0;
2305 getControlModeRaw(axis, &mode);
2306 if( (mode != VOCAB_CM_POSITION) &&
2307 (mode != VOCAB_CM_MIXED) &&
2308 (mode != VOCAB_CM_IMPEDANCE_POS) &&
2309 (mode != VOCAB_CM_POSITION_DIRECT) )
2310 {
2311 yCWarning(FAKEMOTIONCONTROL) << "getRefPosition: Joint " << axis << " is not in POSITION_DIRECT mode, therefore the value returned by \
2312 this call is for reference only and may not reflect the actual behaviour of the motor/firmware.";
2313 }
2314
2315 *ref = _posDir_references[axis];
2316
2317 return true;
2318}
2319
2321{
2322 bool ret = true;
2323 for (int i = 0; i<_njoints; i++)
2324 {
2325 ret &= getRefPositionRaw(i, &refs[i]);
2326 }
2327 return ret;
2328}
2329
2330bool FakeMotionControl::getRefPositionsRaw(int nj, const int * jnts, double *refs)
2331{
2332 bool ret = true;
2333 for (int i = 0; i<nj; i++)
2334 {
2335 ret &= getRefPositionRaw(jnts[i], &refs[i]);
2336 }
2337 return ret;
2338}
2339
2340
2341// InteractionMode
2343{
2344 if (verbose > VERY_VERY_VERBOSE) {
2345 yCTrace(FAKEMOTIONCONTROL) << "j: " << j;
2346 }
2347
2348 *_mode = (yarp::dev::InteractionModeEnum)_interactMode[j];
2349 return true;}
2350
2352{
2353 bool ret = true;
2354 for(int j=0; j< n_joints; j++)
2355 {
2357 }
2358 return ret;
2359
2360}
2361
2363{
2364 bool ret = true;
2365 for (int j = 0; j < _njoints; j++) {
2367 }
2368 return ret;
2369}
2370
2371// marco.accame: con alberto cardellino abbiamo parlato della correttezza di effettuare la verifica di quanto imposto (in setInteractionModeRaw() ed affini)
2372// andando a rileggere il valore nella scheda eth fino a che esso non sia quello atteso. si deve fare oppure no?
2373// con il interaction mode il can ora non lo fa. mentre lo fa per il control mode. perche' diverso?
2375{
2376 if (verbose >= VERY_VERBOSE) {
2377 yCTrace(FAKEMOTIONCONTROL) << "j: " << j << " interaction mode: " << yarp::os::Vocab32::decode(_mode);
2378 }
2379
2380 _interactMode[j] = _mode;
2381
2382 return true;
2383}
2384
2385
2387{
2388 bool ret = true;
2389 for(int i=0; i<n_joints; i++)
2390 {
2392 }
2393 return ret;
2394}
2395
2397{
2398 bool ret = true;
2399 for(int i=0; i<_njoints; i++)
2400 {
2402 }
2403 return ret;
2404
2405}
2406
2408{
2409 *num=_njoints;
2410 return true;
2411}
2412
2414{
2415 *val = 37.5+double(m);
2416 return true;
2417}
2418
2420{
2421 bool ret = true;
2422 for(int j=0; j< _njoints; j++)
2423 {
2424 ret &= getTemperatureRaw(j, &vals[j]);
2425 }
2426 return ret;
2427}
2428
2430{
2431 return NOT_YET_IMPLEMENTED("getTemperatureLimitRaw");
2432}
2433
2435{
2436 return NOT_YET_IMPLEMENTED("setTemperatureLimitRaw");
2437}
2438
2439//PWM interface
2441{
2442 refpwm[j] = v;
2443 pwm[j] = v;
2444 last_pwm_command[j]=yarp::os::Time::now();
2445 return true;
2446}
2447
2449{
2450 for (int i = 0; i < _njoints; i++)
2451 {
2453 }
2454 return true;
2455}
2456
2458{
2459 *v = refpwm[j];
2460 return true;
2461}
2462
2464{
2465 for (int i = 0; i < _njoints; i++)
2466 {
2467 v[i] = refpwm[i];
2468 }
2469 return true;
2470}
2471
2473{
2474 *v = pwm[j];
2475 return true;
2476}
2477
2479{
2480 for (int i = 0; i < _njoints; i++)
2481 {
2482 v[i] = pwm[i];
2483 }
2484 return true;
2485}
2486
2487// Current interface
2488/*bool FakeMotionControl::getCurrentRaw(int j, double *t)
2489{
2490 return NOT_YET_IMPLEMENTED("getCurrentRaw");
2491}
2492
2493bool FakeMotionControl::getCurrentsRaw(double *t)
2494{
2495 return NOT_YET_IMPLEMENTED("getCurrentsRaw");
2496}
2497*/
2498
2499bool FakeMotionControl::getCurrentRangeRaw(int j, double *min, double *max)
2500{
2501 //just for testing purposes, this is not a real implementation
2502 *min = _ref_currents[j] / 100;
2503 *max = _ref_currents[j] * 100;
2504 return true;
2505}
2506
2507bool FakeMotionControl::getCurrentRangesRaw(double *min, double *max)
2508{
2509 //just for testing purposes, this is not a real implementation
2510 for (int i = 0; i < _njoints; i++)
2511 {
2512 min[i] = _ref_currents[i] / 100;
2513 max[i] = _ref_currents[i] * 100;
2514 }
2515 return true;
2516}
2517
2519{
2520 for (int i = 0; i < _njoints; i++)
2521 {
2522 _ref_currents[i] = t[i];
2523 current[i] = t[i] / 2;
2524 }
2525 return true;
2526}
2527
2529{
2530 _ref_currents[j] = t;
2531 current[j] = t / 2;
2532 return true;
2533}
2534
2535bool FakeMotionControl::setRefCurrentsRaw(const int n_joint, const int *joints, const double *t)
2536{
2537 bool ret = true;
2538 for (int j = 0; j<n_joint; j++)
2539 {
2540 ret = ret &&setRefCurrentRaw(joints[j], t[j]);
2541 }
2542 return ret;
2543}
2544
2546{
2547 for (int i = 0; i < _njoints; i++)
2548 {
2549 t[i] = _ref_currents[i];
2550 }
2551 return true;
2552}
2553
2555{
2556 *t = _ref_currents[j];
2557 return true;
2558}
2559
2564
2566{
2567 return _njoints;
2568}
2569
2571{
2572 for (int i = 0; i < _njoints; i++)
2573 {
2574 measure[i] = _torques[i];
2575 }
2576 return true;
2577}
2578
2580{
2581 _torques[ch] = measure;
2582 return true;
2583}
2584
2585bool FakeMotionControl::getLastJointFaultRaw(int j, int& fault, std::string& message)
2586{
2587 _mutex.lock();
2588 fault = _hwfault_code[j];
2589 message = _hwfault_message[j];
2590 _mutex.unlock();
2591 return true;
2592}
2593
2594
2595/*
2596bool FakeMotionControl::parseImpedanceGroup_NewFormat(Bottle& pidsGroup, ImpedanceParameters vals[])
2597{
2598 int j=0;
2599 Bottle xtmp;
2600
2601 if (!extractGroup(pidsGroup, xtmp, "stiffness", "stiffness parameter", _njoints)) {
2602 return false;
2603 }
2604 for (j=0; j<_njoints; j++) {
2605 vals[j].stiffness = xtmp.get(j+1).asFloat64();
2606 }
2607
2608 if (!extractGroup(pidsGroup, xtmp, "damping", "damping parameter", _njoints)) {
2609 return false;
2610 }
2611 for (j=0; j<_njoints; j++) {
2612 vals[j].damping = xtmp.get(j+1).asFloat64();
2613 }
2614
2615 return true;
2616}
2617*/
2618
2619/*
2620bool FakeMotionControl::parsePositionPidsGroup(Bottle& pidsGroup, Pid myPid[])
2621{
2622 int j=0;
2623 Bottle xtmp;
2624
2625 if (!extractGroup(pidsGroup, xtmp, "kp", "Pid kp parameter", _njoints)) {
2626 return false;
2627 }
2628 for (j=0; j<_njoints; j++) {
2629 myPid[j].kp = xtmp.get(j+1).asFloat64();
2630 }
2631
2632 if (!extractGroup(pidsGroup, xtmp, "kd", "Pid kd parameter", _njoints)) {
2633 return false;
2634 }
2635 for (j=0; j<_njoints; j++) {
2636 myPid[j].kd = xtmp.get(j+1).asFloat64();
2637 }
2638
2639 if (!extractGroup(pidsGroup, xtmp, "ki", "Pid kp parameter", _njoints)) {
2640 return false;
2641 }
2642 for (j=0; j<_njoints; j++) {
2643 myPid[j].ki = xtmp.get(j+1).asFloat64();
2644 }
2645
2646 if (!extractGroup(pidsGroup, xtmp, "maxInt", "Pid maxInt parameter", _njoints)) {
2647 return false;
2648 }
2649 for (j=0; j<_njoints; j++) {
2650 myPid[j].max_int = xtmp.get(j+1).asFloat64();
2651 }
2652
2653 if (!extractGroup(pidsGroup, xtmp, "maxPwm", "Pid maxPwm parameter", _njoints)) {
2654 return false;
2655 }
2656 for (j=0; j<_njoints; j++) {
2657 myPid[j].max_output = xtmp.get(j+1).asFloat64();
2658 }
2659
2660 if (!extractGroup(pidsGroup, xtmp, "shift", "Pid shift parameter", _njoints)) {
2661 return false;
2662 }
2663 for (j=0; j<_njoints; j++) {
2664 myPid[j].scale = xtmp.get(j+1).asFloat64();
2665 }
2666
2667 if (!extractGroup(pidsGroup, xtmp, "ko", "Pid ko parameter", _njoints)) {
2668 return false;
2669 }
2670 for (j=0; j<_njoints; j++) {
2671 myPid[j].offset = xtmp.get(j+1).asFloat64();
2672 }
2673
2674 if (!extractGroup(pidsGroup, xtmp, "stictionUp", "Pid stictionUp", _njoints)) {
2675 return false;
2676 }
2677 for (j=0; j<_njoints; j++) {
2678 myPid[j].stiction_up_val = xtmp.get(j+1).asFloat64();
2679 }
2680
2681 if (!extractGroup(pidsGroup, xtmp, "stictionDwn", "Pid stictionDwn", _njoints)) {
2682 return false;
2683 }
2684 for (j=0; j<_njoints; j++) {
2685 myPid[j].stiction_down_val = xtmp.get(j+1).asFloat64();
2686 }
2687
2688 if (!extractGroup(pidsGroup, xtmp, "kff", "Pid kff parameter", _njoints)) {
2689 return false;
2690 }
2691 for (j=0; j<_njoints; j++) {
2692 myPid[j].kff = xtmp.get(j+1).asFloat64();
2693 }
2694
2695 //conversion from metric to machine units (if applicable)
2696 if (_positionControlUnits==P_METRIC_UNITS)
2697 {
2698 for (j=0; j<_njoints; j++)
2699 {
2700 myPid[j].kp = myPid[j].kp / _angleToEncoder[j]; //[PWM/deg]
2701 myPid[j].ki = myPid[j].ki / _angleToEncoder[j]; //[PWM/deg]
2702 myPid[j].kd = myPid[j].kd / _angleToEncoder[j]; //[PWM/deg]
2703 }
2704 }
2705 else
2706 {
2707 //do nothing
2708 }
2709
2710 //optional PWM limit
2711 if(_pwmIsLimited)
2712 { // check for value in the file
2713 if (!extractGroup(pidsGroup, xtmp, "limPwm", "Limited PWD", _njoints))
2714 {
2715 yCError(FAKEMOTIONCONTROL) << "The PID parameter limPwm was requested but was not correctly set in the configuration file, please fill it.";
2716 return false;
2717 }
2718
2719 yCInfo(FAKEMOTIONCONTROL) << "Using LIMITED PWM!!";
2720 for (j = 0; j < _njoints; j++) {
2721 myPid[j].max_output = xtmp.get(j + 1).asFloat64();
2722 }
2723 }
2724
2725 return true;
2726}
2727*/
2728
2729/*
2730bool FakeMotionControl::parseTorquePidsGroup(Bottle& pidsGroup, Pid myPid[], double kbemf[], double ktau[], int filterType[], double viscousPos[], double viscousNeg[], double coulombPos[], double coulombNeg[], double velocityThres[])
2731{
2732 int j=0;
2733 Bottle xtmp;
2734 if (!extractGroup(pidsGroup, xtmp, "kp", "Pid kp parameter", _njoints)) {
2735 return false;
2736 }
2737 for (j=0; j<_njoints; j++) {
2738 myPid[j].kp = xtmp.get(j+1).asFloat64();
2739 }
2740
2741 if (!extractGroup(pidsGroup, xtmp, "kd", "Pid kd parameter", _njoints)) {
2742 return false;
2743 }
2744 for (j=0; j<_njoints; j++) {
2745 myPid[j].kd = xtmp.get(j+1).asFloat64();
2746 }
2747
2748 if (!extractGroup(pidsGroup, xtmp, "ki", "Pid kp parameter", _njoints)) {
2749 return false;
2750 }
2751 for (j=0; j<_njoints; j++) {
2752 myPid[j].ki = xtmp.get(j+1).asFloat64();
2753 }
2754
2755 if (!extractGroup(pidsGroup, xtmp, "maxInt", "Pid maxInt parameter", _njoints)) {
2756 return false;
2757 }
2758 for (j=0; j<_njoints; j++) {
2759 myPid[j].max_int = xtmp.get(j+1).asFloat64();
2760 }
2761
2762 if (!extractGroup(pidsGroup, xtmp, "maxPwm", "Pid maxPwm parameter", _njoints)) {
2763 return false;
2764 }
2765 for (j=0; j<_njoints; j++) {
2766 myPid[j].max_output = xtmp.get(j+1).asFloat64();
2767 }
2768
2769 if (!extractGroup(pidsGroup, xtmp, "shift", "Pid shift parameter", _njoints)) {
2770 return false;
2771 }
2772 for (j=0; j<_njoints; j++) {
2773 myPid[j].scale = xtmp.get(j+1).asFloat64();
2774 }
2775
2776 if (!extractGroup(pidsGroup, xtmp, "ko", "Pid ko parameter", _njoints)) {
2777 return false;
2778 }
2779 for (j=0; j<_njoints; j++) {
2780 myPid[j].offset = xtmp.get(j+1).asFloat64();
2781 }
2782
2783 if (!extractGroup(pidsGroup, xtmp, "stictionUp", "Pid stictionUp", _njoints)) {
2784 return false;
2785 }
2786 for (j=0; j<_njoints; j++) {
2787 myPid[j].stiction_up_val = xtmp.get(j+1).asFloat64();
2788 }
2789
2790 if (!extractGroup(pidsGroup, xtmp, "stictionDwn", "Pid stictionDwn", _njoints)) {
2791 return false;
2792 }
2793 for (j=0; j<_njoints; j++) {
2794 myPid[j].stiction_down_val = xtmp.get(j+1).asFloat64();
2795 }
2796
2797 if (!extractGroup(pidsGroup, xtmp, "kff", "Pid kff parameter", _njoints)) {
2798 return false;
2799 }
2800 for (j=0; j<_njoints; j++) {
2801 myPid[j].kff = xtmp.get(j+1).asFloat64();
2802 }
2803
2804 if (!extractGroup(pidsGroup, xtmp, "kbemf", "kbemf parameter", _njoints)) {
2805 return false;
2806 }
2807 for (j=0; j<_njoints; j++) {
2808 kbemf[j] = xtmp.get(j+1).asFloat64();
2809 }
2810
2811 if (!extractGroup(pidsGroup, xtmp, "ktau", "ktau parameter", _njoints)) {
2812 return false;
2813 }
2814 for (j=0; j<_njoints; j++) {
2815 ktau[j] = xtmp.get(j+1).asFloat64();
2816 }
2817
2818 if (!extractGroup(pidsGroup, xtmp, "filterType", "filterType param", _njoints)) {
2819 return false;
2820 }
2821 for (j=0; j<_njoints; j++) {
2822 filterType[j] = xtmp.get(j+1).asInt32();
2823 }
2824
2825 if (!extractGroup(pidsGroup, xtmp, "viscousPos", "viscous pos parameter", _njoints)) {
2826 return false;
2827 }
2828 for (j=0; j<_njoints; j++) {
2829 viscousPos[j] = xtmp.get(j+1).asFloat64();
2830 }
2831
2832 if (!extractGroup(pidsGroup, xtmp, "viscousNeg", "viscous neg parameter", _njoints)) {
2833 return false;
2834 }
2835 for (j=0; j<_njoints; j++) {
2836 viscousNeg[j] = xtmp.get(j+1).asFloat64();
2837 }
2838
2839 if (!extractGroup(pidsGroup, xtmp, "coulombPos", "coulomb pos parameter", _njoints)) {
2840 return false;
2841 }
2842 for (j=0; j<_njoints; j++) {
2843 coulombPos[j] = xtmp.get(j+1).asFloat64();
2844 }
2845
2846 if (!extractGroup(pidsGroup, xtmp, "coulombNeg", "coulomb neg parameter", _njoints)) {
2847 return false;
2848 }
2849 for (j=0; j<_njoints; j++) {
2850 coulombNeg[j] = xtmp.get(j+1).asFloat64();
2851 }
2852
2853 if (!extractGroup(pidsGroup, xtmp, "velocityThres", "velocity threshold parameter", _njoints)) {
2854 return false;
2855 }
2856 for (j=0; j<_njoints; j++) {
2857 velocityThres[j] = xtmp.get(j+1).asFloat64();
2858 }
2859
2860
2861 //conversion from metric to machine units (if applicable)
2862// for (j=0; j<_njoints; j++)
2863// {
2864// myPid[j].kp = myPid[j].kp / _torqueControlHelper->getNewtonsToSensor(j); //[PWM/Nm]
2865// myPid[j].ki = myPid[j].ki / _torqueControlHelper->getNewtonsToSensor(j); //[PWM/Nm]
2866// myPid[j].kd = myPid[j].kd / _torqueControlHelper->getNewtonsToSensor(j); //[PWM/Nm]
2867// myPid[j].stiction_up_val = myPid[j].stiction_up_val * _torqueControlHelper->getNewtonsToSensor(j); //[Nm]
2868// myPid[j].stiction_down_val = myPid[j].stiction_down_val * _torqueControlHelper->getNewtonsToSensor(j); //[Nm]
2869// }
2870
2871 //optional PWM limit
2872 if(_pwmIsLimited)
2873 { // check for value in the file
2874 if (!extractGroup(pidsGroup, xtmp, "limPwm", "Limited PWM", _njoints))
2875 {
2876 yCError(FAKEMOTIONCONTROL) << "The PID parameter limPwm was requested but was not correctly set in the configuration file, please fill it.";
2877 return false;
2878 }
2879
2880 yCInfo(FAKEMOTIONCONTROL) << "Using LIMITED PWM!!";
2881 for (j = 0; j < _njoints; j++) {
2882 myPid[j].max_output = xtmp.get(j + 1).asFloat64();
2883 }
2884 }
2885
2886 return true;
2887}
2888*/
2889
2890// eof
void checkAndDestroy(T *&p)
bool NOT_YET_IMPLEMENTED(const char *txt)
#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
float t
constexpr yarp::conf::vocab32_t VOCAB_CM_MIXED
constexpr yarp::conf::vocab32_t VOCAB_CM_TORQUE
constexpr yarp::conf::vocab32_t VOCAB_CM_PWM
constexpr yarp::conf::vocab32_t VOCAB_CM_HW_FAULT
constexpr yarp::conf::vocab32_t VOCAB_CM_IMPEDANCE_VEL
constexpr yarp::conf::vocab32_t VOCAB_CM_IDLE
constexpr yarp::conf::vocab32_t VOCAB_CM_POSITION
constexpr yarp::conf::vocab32_t VOCAB_CM_IMPEDANCE_POS
constexpr yarp::conf::vocab32_t VOCAB_CM_POSITION_DIRECT
constexpr yarp::conf::vocab32_t VOCAB_CM_VELOCITY
constexpr yarp::conf::vocab32_t VOCAB_CM_FORCE_IDLE
bool ret
#define yDebug(...)
Definition Log.h:275
bool parseParams(const yarp::os::Searchable &config) override
Parse the DeviceDriver parameters.
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
Get the number of available motors.
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 setGearboxRatioRaw(int m, const double val) override
Set the gearbox ratio for a specific motor.
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 getLastJointFaultRaw(int j, int &fault, std::string &message) 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)
bool initialize(int size, const int *amap, const double *enc, const double *zos, const double *ampereFactor=NULL, const double *voltFactor=NULL)
Initialize the internal data and alloc memory.
bool uninitialize()
Clean up internal data and memory.
bool uninitialize()
Clean up internal data and memory.
bool initialize(int size, const int *amap)
Initialize the internal data and alloc memory.
bool initialize(int size, const int *amap, const double *enc, const double *zos)
Initialize the internal data and alloc memory.
bool uninitialize()
Clean up internal data and memory.
class ImplementControlLimits; class StubImplControlLimitsRaw;
bool uninitialize()
Clean up internal data and memory.
bool initialize(int size, const int *amap, const double *enc, const double *zos)
Initialize the internal data and alloc memory.
bool initialize(int k, const int *amap)
bool initialize(int size, const int *amap, const double *ampsToSens)
Initialize the internal data and alloc memory.
bool initialize(int size, const int *amap, const double *enc, const double *zos)
Initialize the internal data and alloc memory.
bool uninitialize()
Clean up internal data and memory.
bool uninitialize()
Clean up internal data and memory.
bool initialize(int size, const int *amap, const double *enc, const double *zos, const double *nw)
Initialize the internal data and alloc memory.
Interface settings the way the robot interacts with the environment: basic interaction types are Stif...
bool uninitialize()
Clean up internal data and memory.
bool initialize(int size, const int *amap)
Initialize the internal data and alloc memory, smaller version.
bool initialize(int size, const int *amap)
Initialize the internal data and alloc memory.
bool uninitialize()
Clean up internal data and memory.
bool initialize(int size, const int *amap, const double *enc, const double *zos)
Initialize the internal data and alloc memory.
bool initialize(int size, const int *amap)
Initialize the internal data and alloc memory.
bool initialize(int k, const int *amap, const double *dutyToPWM)
bool uninitialize()
Clean up internal data and memory.
bool initialize(int size, const int *amap, const double *enc, const double *zos, const double *newtons, const double *amps, const double *dutys)
Initialize the internal data and alloc memory.
bool setConversionUnits(const PidControlTypeEnum &pidtype, const PidFeedbackUnitsEnum fbk_conv_units, const PidOutputUnitsEnum out_conv_units)
Default implementation of the IPositionControl interface.
bool uninitialize()
Clean up internal data and memory.
bool initialize(int size, const int *amap, const double *enc, const double *zos)
Initialize the internal data and alloc memory.
Default implementation of the IPositionDirect interface.
bool uninitialize()
Clean up internal data and memory.
bool initialize(int size, const int *amap, const double *enc, const double *zos)
Initialize the internal data and alloc memory.
bool initialize(int size, const int *amap, const double *enc, const double *zos, const double *nw, const double *amps, const double *dutys, const double *bemfs, const double *ktaus)
Initialize the internal data and alloc memory.
bool uninitialize()
Clean up internal data and memory.
bool uninitialize()
Clean up internal data and memory.
bool initialize(int size, const int *amap, const double *enc, const double *zos)
Initialize the internal data and alloc memory.
bool initialize(int k, const int *amap, const double *userToRaw)
Contains the parameters for a PID.
double offset
pwm offset added to the pid output
double kp
proportional gain
A mini-server for performing network communication in the background.
An abstraction for a periodic thread.
bool start()
Call this to start the thread.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
A base class for nested structures that can be searched.
Definition Searchable.h:31
void resize(size_t size) override
Resize the vector.
Definition Vector.h:221
void zero()
Zero the elements of the vector.
Definition Vector.h:363
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
std::string get_string(const std::string &key, bool *found=nullptr)
Read a string from an environment variable.
Definition environment.h:66
For streams capable of holding different kinds of content, check what they actually have.
Definition jointData.cpp:13
PidControlTypeEnum
Definition PidEnums.h:15
@ VOCAB_PIDTYPE_TORQUE
Definition PidEnums.h:18
@ VOCAB_PIDTYPE_VELOCITY
Definition PidEnums.h:17
@ VOCAB_PIDTYPE_POSITION
Definition PidEnums.h:16
@ VOCAB_PIDTYPE_CURRENT
Definition PidEnums.h:19
@ VOCAB_JOINTTYPE_REVOLUTE
Definition IAxisInfo.h:24
@ VOCAB_JOINTTYPE_PRISMATIC
Definition IAxisInfo.h:25
@ VOCAB_JOINTTYPE_UNKNOWN
Definition IAxisInfo.h:26
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.