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 _stiffness = allocAndCheck<double>(nj);
231 _damping = allocAndCheck<double>(nj);
232 _force_offset =allocAndCheck<double>(nj);
233
234 _ppids=allocAndCheck<Pid>(nj);
235 _tpids=allocAndCheck<Pid>(nj);
236 _cpids = allocAndCheck<Pid>(nj);
237 _vpids = allocAndCheck<Pid>(nj);
238 _ppids_ena=allocAndCheck<bool>(nj);
239 _tpids_ena=allocAndCheck<bool>(nj);
240 _cpids_ena = allocAndCheck<bool>(nj);
241 _vpids_ena = allocAndCheck<bool>(nj);
242 _ppids_lim=allocAndCheck<double>(nj);
243 _tpids_lim=allocAndCheck<double>(nj);
244 _cpids_lim = allocAndCheck<double>(nj);
245 _vpids_lim = allocAndCheck<double>(nj);
246 _ppids_ref=allocAndCheck<double>(nj);
247 _tpids_ref=allocAndCheck<double>(nj);
248 _cpids_ref = allocAndCheck<double>(nj);
249 _vpids_ref = allocAndCheck<double>(nj);
250
251// _impedance_params=allocAndCheck<ImpedanceParameters>(nj);
252// _impedance_limits=allocAndCheck<ImpedanceLimits>(nj);
253 _axisName = new std::string[nj];
254 _jointType = new JointTypeEnum[nj];
255
256 _limitsMax=allocAndCheck<double>(nj);
257 _limitsMin=allocAndCheck<double>(nj);
258 _kinematic_mj=allocAndCheck<double>(16);
259// _currentLimits=allocAndCheck<MotorCurrentLimits>(nj);
260 _motorPwmLimits=allocAndCheck<double>(nj);
261 checking_motiondone=allocAndCheck<bool>(nj);
262
263 _velocityShifts=allocAndCheck<int>(nj);
264 _velocityTimeout=allocAndCheck<int>(nj);
265 _kbemf=allocAndCheck<double>(nj);
266 _ktau=allocAndCheck<double>(nj);
267 _kbemf_scale = allocAndCheck<int>(nj);
268 _ktau_scale = allocAndCheck<int>(nj);
269 _filterType=allocAndCheck<int>(nj);
270 _last_position_move_time=allocAndCheck<double>(nj);
271 _viscousPos=allocAndCheck<double>(nj);
272 _viscousNeg=allocAndCheck<double>(nj);
273 _coulombPos=allocAndCheck<double>(nj);
274 _coulombNeg=allocAndCheck<double>(nj);
275 _velocityThres=allocAndCheck<double>(nj);
276
277 // Reserve space for data stored locally. values are initialized to 0
278 _posCtrl_references = allocAndCheck<double>(nj);
279 _posDir_references = allocAndCheck<double>(nj);
280 _command_speeds = allocAndCheck<double>(nj);
281 _ref_speeds = allocAndCheck<double>(nj);
282 _ref_accs = allocAndCheck<double>(nj);
283 _ref_torques = allocAndCheck<double>(nj);
284 _ref_currents = allocAndCheck<double>(nj);
285 _enabledAmp = allocAndCheck<bool>(nj);
286 _enabledPid = allocAndCheck<bool>(nj);
287 _calibrated = allocAndCheck<bool>(nj);
288// _cacheImpedance = allocAndCheck<eOmc_impedance_t>(nj);
289
291
292 return true;
293}
294
295bool FakeMotionControl::dealloc()
296{
297 checkAndDestroy(_axisMap);
298 checkAndDestroy(_controlModes);
299 checkAndDestroy(_interactMode);
300 checkAndDestroy(_angleToEncoder);
301 checkAndDestroy(_ampsToSensor);
302 checkAndDestroy(_dutycycleToPWM);
303 checkAndDestroy(_encodersStamp);
304 checkAndDestroy(_DEPRECATED_encoderconversionoffset);
305 checkAndDestroy(_DEPRECATED_encoderconversionfactor);
306 checkAndDestroy(_jointEncoderRes);
307 checkAndDestroy(_rotorEncoderRes);
308// checkAndDestroy(_jointEncoderType);
309// checkAndDestroy(_rotorEncoderType);
310 checkAndDestroy(_gearbox);
311 checkAndDestroy(_torqueSensorId);
312 checkAndDestroy(_torqueSensorChan);
313 checkAndDestroy(_maxTorque);
314 checkAndDestroy(_maxJntCmdVelocity);
315 checkAndDestroy(_maxMotorVelocity);
316 checkAndDestroy(_newtonsToSensor);
317 checkAndDestroy(_ppids);
318 checkAndDestroy(_tpids);
319 checkAndDestroy(_cpids);
320 checkAndDestroy(_vpids);
321 checkAndDestroy(_ppids_ena);
322 checkAndDestroy(_tpids_ena);
323 checkAndDestroy(_cpids_ena);
324 checkAndDestroy(_vpids_ena);
325 checkAndDestroy(_ppids_lim);
326 checkAndDestroy(_tpids_lim);
327 checkAndDestroy(_cpids_lim);
328 checkAndDestroy(_vpids_lim);
329 checkAndDestroy(_ppids_ref);
330 checkAndDestroy(_tpids_ref);
331 checkAndDestroy(_cpids_ref);
332 checkAndDestroy(_vpids_ref);
333// checkAndDestroy(_impedance_params);
334// checkAndDestroy(_impedance_limits);
335 checkAndDestroy(_limitsMax);
336 checkAndDestroy(_limitsMin);
337 checkAndDestroy(_kinematic_mj);
338// checkAndDestroy(_currentLimits);
339 checkAndDestroy(_motorPwmLimits);
340 checkAndDestroy(checking_motiondone);
341 checkAndDestroy(_velocityShifts);
342 checkAndDestroy(_velocityTimeout);
343 checkAndDestroy(_kbemf);
344 checkAndDestroy(_ktau);
345 checkAndDestroy(_kbemf_scale);
346 checkAndDestroy(_ktau_scale);
347 checkAndDestroy(_filterType);
348 checkAndDestroy(_viscousPos);
349 checkAndDestroy(_viscousNeg);
350 checkAndDestroy(_coulombPos);
351 checkAndDestroy(_coulombNeg);
352 checkAndDestroy(_velocityThres);
353 checkAndDestroy(_posCtrl_references);
354 checkAndDestroy(_posDir_references);
355 checkAndDestroy(_command_speeds);
356 checkAndDestroy(_ref_speeds);
357 checkAndDestroy(_ref_accs);
358 checkAndDestroy(_ref_torques);
359 checkAndDestroy(_ref_currents);
360 checkAndDestroy(_enabledAmp);
361 checkAndDestroy(_enabledPid);
362 checkAndDestroy(_calibrated);
363 checkAndDestroy(_hasHallSensor);
364 checkAndDestroy(_hasTempSensor);
365 checkAndDestroy(_hasRotorEncoder);
366 checkAndDestroy(_hasRotorEncoderIndex);
367 checkAndDestroy(_rotorIndexOffset);
368 checkAndDestroy(_motorPoles);
369 checkAndDestroy(_axisName);
370 checkAndDestroy(_jointType);
371 checkAndDestroy(_rotorlimits_max);
372 checkAndDestroy(_rotorlimits_min);
373 checkAndDestroy(_last_position_move_time);
374 checkAndDestroy(_torques);
375 checkAndDestroy(_hwfault_code);
376 checkAndDestroy(_hwfault_message);
377 checkAndDestroy(_stiffness);
378 checkAndDestroy(_damping);
379 checkAndDestroy(_force_offset);
380 return true;
381}
382
384 PeriodicThread(0.01),
404 _mutex(),
405 _njoints (0),
406 _axisMap (nullptr),
407 _angleToEncoder(nullptr),
408 _encodersStamp (nullptr),
409 _ampsToSensor (nullptr),
410 _dutycycleToPWM(nullptr),
411 _DEPRECATED_encoderconversionfactor (nullptr),
412 _DEPRECATED_encoderconversionoffset (nullptr),
413 _jointEncoderRes (nullptr),
414 _rotorEncoderRes (nullptr),
415 _gearbox (nullptr),
416 _hasHallSensor (nullptr),
417 _hasTempSensor (nullptr),
418 _hasRotorEncoder (nullptr),
419 _hasRotorEncoderIndex (nullptr),
420 _rotorIndexOffset (nullptr),
421 _motorPoles (nullptr),
422 _rotorlimits_max (nullptr),
423 _rotorlimits_min (nullptr),
424 _ppids (nullptr),
425 _tpids (nullptr),
426 _cpids (nullptr),
427 _vpids (nullptr),
428 _ppids_ena (nullptr),
429 _tpids_ena (nullptr),
430 _cpids_ena (nullptr),
431 _vpids_ena (nullptr),
432 _ppids_lim (nullptr),
433 _tpids_lim (nullptr),
434 _cpids_lim (nullptr),
435 _vpids_lim (nullptr),
436 _ppids_ref (nullptr),
437 _tpids_ref (nullptr),
438 _cpids_ref (nullptr),
439 _vpids_ref (nullptr),
440 _axisName (nullptr),
441 _jointType (nullptr),
442 _limitsMin (nullptr),
443 _limitsMax (nullptr),
444 _kinematic_mj (nullptr),
445 _maxJntCmdVelocity (nullptr),
446 _maxMotorVelocity (nullptr),
447 _velocityShifts (nullptr),
448 _velocityTimeout (nullptr),
449 _kbemf (nullptr),
450 _ktau (nullptr),
451 _kbemf_scale (nullptr),
452 _ktau_scale (nullptr),
453 _viscousPos (nullptr),
454 _viscousNeg (nullptr),
455 _coulombPos (nullptr),
456 _coulombNeg (nullptr),
457 _velocityThres (nullptr),
458 _filterType (nullptr),
459 _torqueSensorId (nullptr),
460 _torqueSensorChan (nullptr),
461 _maxTorque (nullptr),
462 _newtonsToSensor (nullptr),
463 checking_motiondone (nullptr),
464 _last_position_move_time(nullptr),
465 _motorPwmLimits (nullptr),
466 _torques (nullptr),
467 useRawEncoderData (false),
468 _pwmIsLimited (false),
469 _torqueControlEnabled (false),
470 _torqueControlUnits (T_MACHINE_UNITS),
471 _positionControlUnits (P_MACHINE_UNITS),
472 prev_time (0.0),
473 opened (false),
474 verbose (VERY_VERBOSE)
475{
477 std::string tmp = yarp::conf::environment::get_string("VERBOSE_STICA");
478 verbosewhenok = (tmp != "") ? (bool)yarp::conf::numeric::from_string<int>(tmp) :
479 false;
480}
481
487
489{
490 return opened;
491}
492
494{
496 for(int i=0; i<_njoints; i++)
497 {
498 pwm[i] = 33+i;
499 pwmLimit[i] = (33+i)*10;
500 current[i] = (33+i)*100;
501 maxCurrent[i] = (33+i)*1000;
502 peakCurrent[i] = (33+i)*2;
503 nominalCurrent[i] = (33+i)*20;
504 supplyVoltage[i] = (33+i)*200;
505 last_velocity_command[i] = -1;
506 last_pwm_command[i] = -1;
507 _controlModes[i] = VOCAB_CM_POSITION;
508 _maxJntCmdVelocity[i]=50.0;
509 }
510 prev_time = yarp::os::Time::now();
511 return true;
512}
513
517
519{
520 if (!this->parseParams(config)) {return false;}
521
522 std::string str;
523
524 //
525 // Read Configuration params from file
526 //
527 _njoints = m_GENERAL_Joints;
528
529 if(!alloc(_njoints))
530 {
531 yCError(FAKEMOTIONCONTROL) << "Malloc failed";
532 return false;
533 }
534
535 // Default value
536 for (int i = 0; i < _njoints; i++) {
537 _newtonsToSensor[i] = 1;
538 }
539
540 if(!fromConfig(config))
541 {
542 yCError(FAKEMOTIONCONTROL) << "Missing parameters in config file";
543 return false;
544 }
545
546 // INIT ALL INTERFACES
547 yarp::sig::Vector tmpZeros; tmpZeros.resize (_njoints, 0.0);
548 yarp::sig::Vector tmpOnes; tmpOnes.resize (_njoints, 1.0);
549 yarp::sig::Vector bemfToRaw; bemfToRaw.resize(_njoints, 1.0);
550 yarp::sig::Vector ktauToRaw; ktauToRaw.resize(_njoints, 1.0);
551 for (size_t i = 0; i < _njoints; i++) { bemfToRaw [i] = _newtonsToSensor[i] / _angleToEncoder[i];}
552 for (size_t i = 0; i < _njoints; i++) { ktauToRaw[i] = _dutycycleToPWM[i] / _newtonsToSensor[i]; }
553 ControlBoardHelper cb(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor, _ampsToSensor, _dutycycleToPWM);
555 ImplementControlCalibration::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
556 ImplementAmplifierControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
557 ImplementEncodersTimed::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
558 ImplementMotorEncoders::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
559 ImplementPositionControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
560 ImplementPidControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor, _ampsToSensor, _dutycycleToPWM);
561 ImplementPidControl::setConversionUnits(PidControlTypeEnum::VOCAB_PIDTYPE_POSITION, PidFeedbackUnitsEnum::METRIC, PidOutputUnitsEnum::DUTYCYCLE_PWM_PERCENT);
562 ImplementPidControl::setConversionUnits(PidControlTypeEnum::VOCAB_PIDTYPE_TORQUE, PidFeedbackUnitsEnum::METRIC, PidOutputUnitsEnum::DUTYCYCLE_PWM_PERCENT);
563 ImplementControlMode::initialize(_njoints, _axisMap);
564 ImplementVelocityControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
565 ImplementControlLimits::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
566 ImplementImpedanceControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor);
567 ImplementTorqueControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor, _ampsToSensor, _dutycycleToPWM, bemfToRaw.data(), ktauToRaw.data());
568 ImplementPositionDirect::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
569 ImplementInteractionMode::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
570 ImplementMotor::initialize(_njoints, _axisMap);
571 ImplementAxisInfo::initialize(_njoints, _axisMap);
572 ImplementPWMControl::initialize(_njoints, _axisMap, _dutycycleToPWM);
573 ImplementCurrentControl::initialize(_njoints, _axisMap, _ampsToSensor);
574 ImplementVirtualAnalogSensor::initialize(_njoints, _axisMap, _newtonsToSensor);
575 ImplementJointFault::initialize(_njoints, _axisMap);
576
577 //start the rateThread
578 bool init = this->start();
579 if(!init)
580 {
581 yCError(FAKEMOTIONCONTROL) << "open() has an error in call of FakeMotionControl::init() for board" ;
582 return false;
583 }
584 else
585 {
586 if(verbosewhenok)
587 {
588 yCDebug(FAKEMOTIONCONTROL) << "init() has successfully initted board ";
589 }
590 }
591 opened = true;
592
593 return true;
594}
595
597{
598 size_t i;
599
600 // AxisMap
601 if (!m_GENERAL_AxisMap.empty())
602 {
603 for (i = 0; i < m_GENERAL_AxisMap.size(); i++) {
604 _axisMap[i] = m_GENERAL_AxisMap[i];
605 }
606 }
607 else
608 {
609 for (i = 0; i < _njoints; i++) {
610 _axisMap[i] = i;
611 }
612 }
613 for (i = 0; i < _njoints; i++) {yDebug() << "_axisMap: " << _axisMap[i] << " "; }
614
615 // AxisName
616 if (!m_GENERAL_AxisName.empty())
617 {
618 for (i = 0; i < m_GENERAL_AxisName.size(); i++) {
619 _axisName[_axisMap[i]] = m_GENERAL_AxisName[i];
620 }
621 }
622 else
623 {
624 for (i = 0; i < _njoints; i++) {
625 _axisName[_axisMap[i]] = "joint" + toString(i);
626 }
627 }
628 for (i = 0; i < _njoints; i++) { yDebug() << "_axisName: " << _axisName[_axisMap[i]] << " "; }
629
630 // Axis Type
631 if (!m_GENERAL_AxisType.empty())
632 {
633 //beware: axis type has to be remapped here because they are not set using the toHw() helper function
634 for (i = 0; i < m_GENERAL_AxisType.size(); i++)
635 {
636 std::string typeString = m_GENERAL_AxisType[i];
637 if (typeString == "revolute") {
638 _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_REVOLUTE;
639 }
640 else if (typeString == "prismatic") {
641 _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_PRISMATIC;
642 }
643 else {
644 yCError(FAKEMOTIONCONTROL, "Unknown AxisType value %s!", typeString.c_str());
645 _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_UNKNOWN;
646 return false;
647 }
648 }
649 }
650 else
651 {
652 yCInfo(FAKEMOTIONCONTROL) << "Using default AxisType (revolute)";
653 for (i = 0; i < _njoints; i++) {
654 _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_REVOLUTE;
655 }
656 }
657
658 // current conversions factor
659 if (!m_GENERAL_ampsToSensor.empty())
660 {
661 for (i = 0; i < m_GENERAL_ampsToSensor.size(); i++) {
662 _ampsToSensor[i] = m_GENERAL_ampsToSensor[i];
663 }
664 }
665 else
666 {
667 yCInfo(FAKEMOTIONCONTROL) << "Using default ampsToSensor=1";
668 for (i = 0; i < _njoints; i++) {
669 _ampsToSensor[i] = 1;
670 }
671 }
672
673
674 // pwm conversions factor
675 if (!m_GENERAL_fullscalePWM.empty())
676 {
677 for (i = 0; i < m_GENERAL_fullscalePWM.size(); i++) {
678 _dutycycleToPWM[i] = m_GENERAL_fullscalePWM[i]/100;
679 }
680 }
681 else
682 {
683 yCInfo(FAKEMOTIONCONTROL) << "Using default fullscalePWM=1";
684 for (i = 0; i < _njoints; i++) {
685 _dutycycleToPWM[i] = 1;
686 }
687 }
688
689// double tmp_A2E;
690 // Encoder scales
691 if(!m_GENERAL_Encoder.empty())
692 {
693 for (i = 0; i < m_GENERAL_Encoder.size(); i++) {
694 _angleToEncoder[i] = m_GENERAL_Encoder[i]; }
695 }
696 else
697 {
698 yCInfo(FAKEMOTIONCONTROL) << "Using default Encoder=1";
699 for (i = 0; i < _njoints; i++) {
700 _angleToEncoder[i] = 1; }
701 }
702
704 if (!m_LIMITS_Max.empty())
705 {
706 for (i = 0; i < m_LIMITS_Max.size(); i++) {
707 _limitsMax[i] = m_LIMITS_Max[i];
708 }
709 }
710 else
711 {
712 yCInfo(FAKEMOTIONCONTROL) << "Using default m_LIMITS_Max=100";
713 for (i = 0; i < _njoints; i++) {
714 _limitsMax[i] = 100;
715 }
716 }
717
718 if (!m_LIMITS_Min.empty())
719 {
720 for (i = 0; i < m_LIMITS_Min.size(); i++) {
721 _limitsMin[i] = m_LIMITS_Min[i];
722 }
723 }
724 else
725 {
726 yCInfo(FAKEMOTIONCONTROL) << "Using default m_LIMITS_Min=0";
727 for (i = 0; i < _njoints; i++) {
728 _limitsMin[i] = 0;
729 }
730 }
731
732 return true;
733}
734
735
764
765void FakeMotionControl::cleanup()
766{
767
768}
769
770
771
773
775{
776 yCDebug(FAKEMOTIONCONTROL) << "setPidRaw" << pidtype << j << pid.kp;
777 switch (pidtype)
778 {
780 _ppids[j]=pid;
781 break;
783 _vpids[j]=pid;
784 break;
786 _cpids[j]=pid;
787 break;
789 _tpids[j]=pid;
790 break;
791 default:
792 break;
793 }
794 return true;
795}
796
798{
799 bool ret = true;
800 for(int j=0; j< _njoints; j++)
801 {
802 ret &= setPidRaw(pidtype, j, pids[j]);
803 }
804 return ret;
805}
806
808{
809 switch (pidtype)
810 {
812 _ppids_ref[j]=ref;
813 break;
815 _vpids_ref[j]=ref;
816 break;
818 _cpids_ref[j]=ref;
819 break;
821 _tpids_ref[j]=ref;
822 break;
823 default:
824 break;
825 }
826 return true;
827}
828
830{
831 bool ret = true;
832 for(int j=0, index=0; j< _njoints; j++, index++)
833 {
834 ret &= setPidReferenceRaw(pidtype, j, refs[index]);
835 }
836 return ret;
837}
838
840{
841 switch (pidtype)
842 {
844 _ppids_lim[j]=limit;
845 break;
847 _vpids_lim[j]=limit;
848 break;
850 _cpids_lim[j]=limit;
851 break;
853 _tpids_lim[j]=limit;
854 break;
855 default:
856 break;
857 }
858 return true;
859}
860
862{
863 bool ret = true;
864 for(int j=0, index=0; j< _njoints; j++, index++)
865 {
866 ret &= setPidErrorLimitRaw(pidtype, j, limits[index]);
867 }
868 return ret;
869}
870
872{
873 switch (pidtype)
874 {
876 *err=0.1;
877 break;
879 *err=0.2;
880 break;
882 *err=0.3;
883 break;
885 *err=0.4;
886 break;
887 default:
888 break;
889 }
890 return true;
891}
892
894{
895 bool ret = true;
896 for(int j=0; j< _njoints; j++)
897 {
898 ret &= getPidErrorRaw(pidtype, j, &errs[j]);
899 }
900 return ret;
901}
902
904{
905 switch (pidtype)
906 {
908 *pid=_ppids[j];
909 break;
911 *pid=_vpids[j];
912 break;
914 *pid=_cpids[j];
915 break;
917 *pid=_tpids[j];
918 break;
919 default:
920 break;
921 }
922 yCDebug(FAKEMOTIONCONTROL) << "getPidRaw" << pidtype << j << pid->kp;
923 return true;
924}
925
927{
928 bool ret = true;
929
930 // just one joint at time, wait answer before getting to the next.
931 // This is because otherwise too many msg will be placed into can queue
932 for(int j=0, index=0; j<_njoints; j++, index++)
933 {
934 ret &=getPidRaw(pidtype, j, &pids[j]);
935 }
936 return ret;
937}
938
940{
941 switch (pidtype)
942 {
944 *ref=_ppids_ref[j];
945 break;
947 *ref=_vpids_ref[j];
948 break;
950 *ref=_cpids_ref[j];
951 break;
953 *ref=_tpids_ref[j];
954 break;
955 default:
956 break;
957 }
958 return true;
959}
960
962{
963 bool ret = true;
964
965 // just one joint at time, wait answer before getting to the next.
966 // This is because otherwise too many msg will be placed into can queue
967 for(int j=0; j< _njoints; j++)
968 {
970 }
971 return ret;
972}
973
975{
976 switch (pidtype)
977 {
979 *limit=_ppids_lim[j];
980 break;
982 *limit=_vpids_lim[j];
983 break;
985 *limit=_cpids_lim[j];
986 break;
988 *limit=_tpids_lim[j];
989 break;
990 default:
991 break;
992 }
993 return true;
994}
995
997{
998 bool ret = true;
999 for(int j=0, index=0; j<_njoints; j++, index++)
1000 {
1001 ret &=getPidErrorLimitRaw(pidtype, j, &limits[j]);
1002 }
1003 return ret;
1004}
1005
1007{
1008 return true;
1009}
1010
1012{
1013 switch (pidtype)
1014 {
1016 _ppids_ena[j]=false;
1017 break;
1019 _vpids_ena[j]=false;
1020 break;
1022 _cpids_ena[j]=false;
1023 break;
1025 _tpids_ena[j]=false;
1026 break;
1027 default:
1028 break;
1029 }
1030 return true;
1031}
1032
1034{
1035 switch (pidtype)
1036 {
1038 _ppids_ena[j]=true;
1039 break;
1041 _vpids_ena[j]=true;
1042 break;
1044 _cpids_ena[j]=true;
1045 break;
1047 _tpids_ena[j]=true;
1048 break;
1049 default:
1050 break;
1051 }
1052 return true;
1053}
1054
1056{
1057 yCDebug(FAKEMOTIONCONTROL) << "setPidOffsetRaw" << pidtype << j << v;
1058 switch (pidtype)
1059 {
1061 _ppids[j].offset=v;
1062 break;
1064 _vpids[j].offset=v;
1065 break;
1067 _cpids[j].offset=v;
1068 break;
1070 _tpids[j].offset=v;
1071 break;
1072 default:
1073 break;
1074 }
1075 return true;
1076}
1077
1079{
1080 switch (pidtype)
1081 {
1083 *enabled=_ppids_ena[j];
1084 break;
1086 *enabled=_vpids_ena[j];
1087 break;
1089 *enabled=_cpids_ena[j];
1090 break;
1092 *enabled=_tpids_ena[j];
1093 break;
1094 default:
1095 break;
1096 }
1097 return true;
1098}
1099
1101{
1102 switch (pidtype)
1103 {
1105 *out=1.1 + j * 10;
1106 break;
1108 *out=1.2 + j * 10;
1109 break;
1111 *out=1.3 + j * 10;
1112 break;
1114 *out=1.4 + j * 10;
1115 break;
1116 default:
1117 break;
1118 }
1119 yCDebug(FAKEMOTIONCONTROL) << "getPidOutputRaw" << pidtype << j << *out;
1120 return true;
1121}
1122
1124{
1125 bool ret = true;
1126 for(int j=0; j< _njoints; j++)
1127 {
1128 ret &= getPidOutputRaw(pidtype, j, &outs[j]);
1129 }
1130 return ret;
1131}
1132
1134// Velocity control interface raw //
1136
1138{
1139 int mode=0;
1140 getControlModeRaw(j, &mode);
1141 if( (mode != VOCAB_CM_VELOCITY) &&
1142 (mode != VOCAB_CM_MIXED) &&
1143 (mode != VOCAB_CM_IMPEDANCE_VEL) &&
1144 (mode != VOCAB_CM_IDLE))
1145 {
1146 yCError(FAKEMOTIONCONTROL) << "velocityMoveRaw: skipping command because board " << " joint " << j << " is not in VOCAB_CM_VELOCITY mode";
1147 }
1148 _command_speeds[j] = sp;
1149 last_velocity_command[j]=yarp::os::Time::now();
1150 return true;
1151}
1152
1154{
1156 bool ret = true;
1157 for (int i = 0; i < _njoints; i++) {
1158 ret &= velocityMoveRaw(i, sp[i]);
1159 }
1160 return ret;
1161}
1162
1163
1165// Calibration control interface //
1167
1169{
1170 yCTrace(FAKEMOTIONCONTROL) << "setCalibrationParametersRaw for joint" << j;
1171 return true;
1172}
1173
1174bool FakeMotionControl::calibrateAxisWithParamsRaw(int j, unsigned int type, double p1, double p2, double p3)
1175{
1176 yCTrace(FAKEMOTIONCONTROL) << "calibrateRaw for joint" << j;
1177 return true;
1178}
1179
1181{
1182 return NOT_YET_IMPLEMENTED("calibrationDoneRaw");
1183}
1184
1186// Position control interface //
1188
1190{
1191 *ax=_njoints;
1192
1193 return true;
1194}
1195
1197{
1198 if (verbose >= VERY_VERBOSE) {
1199 yCTrace(FAKEMOTIONCONTROL) << "j " << j << " ref " << ref;
1200 }
1201
1202// if (yarp::os::Time::now()-_last_position_move_time[j]<MAX_POSITION_MOVE_INTERVAL)
1203// {
1204// 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.";
1205// }
1206// _last_position_move_time[j] = yarp::os::Time::now();
1207
1208 int mode = 0;
1209 getControlModeRaw(j, &mode);
1210 if( (mode != VOCAB_CM_POSITION) &&
1211 (mode != VOCAB_CM_MIXED) &&
1212 (mode != VOCAB_CM_IMPEDANCE_POS) &&
1213 (mode != VOCAB_CM_IDLE))
1214 {
1215 yCError(FAKEMOTIONCONTROL) << "positionMoveRaw: skipping command because joint " << j << " is not in VOCAB_CM_POSITION mode";
1216 }
1217 _posCtrl_references[j] = ref;
1218 return true;
1219}
1220
1222{
1223 if (verbose >= VERY_VERBOSE) {
1225 }
1226
1227 bool ret = true;
1228 for(int j=0, index=0; j< _njoints; j++, index++)
1229 {
1230 ret &= positionMoveRaw(j, refs[index]);
1231 }
1232 return ret;
1233}
1234
1236{
1237 if (verbose >= VERY_VERBOSE) {
1238 yCTrace(FAKEMOTIONCONTROL) << "j " << j << " ref " << delta;
1239 }
1240// if (yarp::os::Time::now()-_last_position_move_time[j]<MAX_POSITION_MOVE_INTERVAL)
1241// {
1242// 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.";
1243// }
1244// _last_position_move_time[j] = yarp::os::Time::now();
1245
1246 int mode = 0;
1247 getControlModeRaw(j, &mode);
1248 if( (mode != VOCAB_CM_POSITION) &&
1249 (mode != VOCAB_CM_MIXED) &&
1250 (mode != VOCAB_CM_IMPEDANCE_POS) &&
1251 (mode != VOCAB_CM_IDLE))
1252 {
1253 yCError(FAKEMOTIONCONTROL) << "relativeMoveRaw: skipping command because joint " << j << " is not in VOCAB_CM_POSITION mode";
1254 }
1255 _posCtrl_references[j] += delta;
1256 return true;
1257}
1258
1260{
1261 if (verbose >= VERY_VERBOSE) {
1263 }
1264
1265 bool ret = true;
1266 for(int j=0, index=0; j< _njoints; j++, index++)
1267 {
1268 ret &= relativeMoveRaw(j, deltas[index]);
1269 }
1270 return ret;
1271}
1272
1273
1275{
1276 if (verbose >= VERY_VERBOSE) {
1277 yCTrace(FAKEMOTIONCONTROL) << "j ";
1278 }
1279
1280 *flag = false;
1281 return true;
1282}
1283
1285{
1286 if (verbose >= VERY_VERBOSE) {
1288 }
1289
1290 bool ret = true;
1291 bool val, tot_res = true;
1292
1293 for(int j=0, index=0; j< _njoints; j++, index++)
1294 {
1295 ret &= checkMotionDoneRaw(j, &val);
1296 tot_res &= val;
1297 }
1298 *flag = tot_res;
1299 return ret;
1300}
1301
1303{
1304 // Velocity is expressed in iDegrees/s
1305 // save internally the new value of speed; it'll be used in the positionMove
1306 int index = j ;
1307 _ref_speeds[index] = sp;
1308 return true;
1309}
1310
1312{
1313 // Velocity is expressed in iDegrees/s
1314 // save internally the new value of speed; it'll be used in the positionMove
1315 for(int j=0, index=0; j< _njoints; j++, index++)
1316 {
1317 _ref_speeds[index] = spds[index];
1318 }
1319 return true;
1320}
1321
1323{
1324 // Acceleration is expressed in iDegrees/s^2
1325 // save internally the new value of the acceleration; it'll be used in the velocityMove command
1326
1327 if (acc > 1e6)
1328 {
1329 _ref_accs[j ] = 1e6;
1330 }
1331 else if (acc < -1e6)
1332 {
1333 _ref_accs[j ] = -1e6;
1334 }
1335 else
1336 {
1337 _ref_accs[j ] = acc;
1338 }
1339
1340 return true;
1341}
1342
1344{
1345 // Acceleration is expressed in iDegrees/s^2
1346 // save internally the new value of the acceleration; it'll be used in the velocityMove command
1347 for(int j=0, index=0; j< _njoints; j++, index++)
1348 {
1349 if (accs[j] > 1e6)
1350 {
1351 _ref_accs[index] = 1e6;
1352 }
1353 else if (accs[j] < -1e6)
1354 {
1355 _ref_accs[index] = -1e6;
1356 }
1357 else
1358 {
1359 _ref_accs[index] = accs[j];
1360 }
1361 }
1362 return true;
1363}
1364
1366{
1367 *spd = _ref_speeds[j];
1368 return true;
1369}
1370
1372{
1373 memcpy(spds, _ref_speeds, sizeof(double) * _njoints);
1374 return true;
1375}
1376
1378{
1379 *acc = _ref_accs[j];
1380 return true;
1381}
1382
1384{
1385 memcpy(accs, _ref_accs, sizeof(double) * _njoints);
1386 return true;
1387}
1388
1390{
1391 velocityMoveRaw(j,0);
1392 return true;
1393}
1394
1396{
1397 bool ret = true;
1398 for(int j=0; j< _njoints; j++)
1399 {
1400 ret &= stopRaw(j);
1401 }
1402 return ret;
1403}
1405
1407// Position control2 interface //
1409
1410bool FakeMotionControl::positionMoveRaw(const int n_joint, const int *joints, const double *refs)
1411{
1412 if (verbose >= VERY_VERBOSE) {
1413 yCTrace(FAKEMOTIONCONTROL) << " -> n_joint " << n_joint;
1414 }
1415
1416 for(int j=0; j<n_joint; j++)
1417 {
1418 yCDebug(FAKEMOTIONCONTROL, "j: %d; ref %f;\n", joints[j], refs[j]); fflush(stdout);
1419 }
1420
1421 bool ret = true;
1422 for(int j=0; j<n_joint; j++)
1423 {
1425 }
1426 return ret;
1427}
1428
1429bool FakeMotionControl::relativeMoveRaw(const int n_joint, const int *joints, const double *deltas)
1430{
1431 if (verbose >= VERY_VERBOSE) {
1432 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1433 }
1434
1435 bool ret = true;
1436 for(int j=0; j<n_joint; j++)
1437 {
1439 }
1440 return ret;
1441}
1442
1444{
1445 if (verbose >= VERY_VERBOSE) {
1446 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1447 }
1448
1449 bool ret = true;
1450 bool val = true;
1451 bool tot_val = true;
1452
1453 for(int j=0; j<n_joint; j++)
1454 {
1455 ret = ret && checkMotionDoneRaw(joints[j], &val);
1456 tot_val &= val;
1457 }
1458 *flag = tot_val;
1459 return ret;
1460}
1461
1462bool FakeMotionControl::setRefSpeedsRaw(const int n_joint, const int *joints, const double *spds)
1463{
1464 if (verbose >= VERY_VERBOSE) {
1465 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1466 }
1467
1468 bool ret = true;
1469 for(int j=0; j<n_joint; j++)
1470 {
1472 }
1473 return ret;
1474}
1475
1476bool FakeMotionControl::setRefAccelerationsRaw(const int n_joint, const int *joints, const double *accs)
1477{
1478 if (verbose >= VERY_VERBOSE) {
1479 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1480 }
1481
1482 bool ret = true;
1483 for(int j=0; j<n_joint; j++)
1484 {
1486 }
1487 return ret;
1488}
1489
1490bool FakeMotionControl::getRefSpeedsRaw(const int n_joint, const int *joints, double *spds)
1491{
1492 if (verbose >= VERY_VERBOSE) {
1493 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1494 }
1495
1496 bool ret = true;
1497 for(int j=0; j<n_joint; j++)
1498 {
1499 ret = ret && getRefSpeedRaw(joints[j], &spds[j]);
1500 }
1501 return ret;
1502}
1503
1505{
1506 if (verbose >= VERY_VERBOSE) {
1507 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1508 }
1509
1510 bool ret = true;
1511 for(int j=0; j<n_joint; j++)
1512 {
1514 }
1515 return ret;
1516}
1517
1518bool FakeMotionControl::stopRaw(const int n_joint, const int *joints)
1519{
1520 if (verbose >= VERY_VERBOSE) {
1521 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1522 }
1523
1524 bool ret = true;
1525 for(int j=0; j<n_joint; j++)
1526 {
1527 ret = ret &&stopRaw(joints[j]);
1528 }
1529 return ret;
1530}
1531
1533
1534// ControlMode
1535
1536// puo' essere richiesto con get
1538{
1539 if (verbose > VERY_VERY_VERBOSE) {
1540 yCTrace(FAKEMOTIONCONTROL) << "j: " << j;
1541 }
1542
1543 *v = _controlModes[j];
1544 return true;
1545}
1546
1547// IControl Mode 2
1549{
1550 bool ret = true;
1551 for(int j=0; j< _njoints; j++)
1552 {
1553 ret = ret && getControlModeRaw(j, &v[j]);
1554 }
1555 return ret;
1556}
1557
1559{
1560 bool ret = true;
1561 for(int j=0; j< n_joint; j++)
1562 {
1564 }
1565 return ret;
1566}
1567
1569{
1570 if (verbose >= VERY_VERBOSE) {
1571 yCTrace(FAKEMOTIONCONTROL) << "j: " << j << " mode: " << yarp::os::Vocab32::decode(_mode);
1572 }
1573
1575 {
1576 _controlModes[j] = VOCAB_CM_IDLE;
1577 }
1578 else
1579 {
1580 _controlModes[j] = _mode;
1581 }
1582 _posCtrl_references[j] = pos[j];
1583 return true;
1584}
1585
1586
1588{
1589 if (verbose >= VERY_VERBOSE) {
1590 yCTrace(FAKEMOTIONCONTROL) << "n_joints: " << n_joint;
1591 }
1592
1593 bool ret = true;
1594 for(int i=0; i<n_joint; i++)
1595 {
1596 ret &= setControlModeRaw(joints[i], modes[i]);
1597 }
1598 return ret;
1599}
1600
1602{
1603 if (verbose >= VERY_VERBOSE) {
1605 }
1606
1607 bool ret = true;
1608 for(int i=0; i<_njoints; i++)
1609 {
1610 ret &= setControlModeRaw(i, modes[i]);
1611 }
1612 return ret;
1613}
1614
1615
1617
1619{
1620 return NOT_YET_IMPLEMENTED("setEncoder");
1621}
1622
1624{
1625 return NOT_YET_IMPLEMENTED("setEncoders");
1626}
1627
1629{
1630 return NOT_YET_IMPLEMENTED("resetEncoder");
1631}
1632
1634{
1635 return NOT_YET_IMPLEMENTED("resetEncoders");
1636}
1637
1638bool FakeMotionControl::getEncoderRaw(int j, double *value)
1639{
1640 bool ret = true;
1641
1642 // To simulate a real controlboard, we assume that the joint
1643 // encoders is exactly the last set by setPosition(s) or positionMove
1644 *value = pos[j];
1645
1646 return ret;
1647}
1648
1650{
1651 bool ret = true;
1652 for(int j=0; j< _njoints; j++)
1653 {
1654 bool ok = getEncoderRaw(j, &encs[j]);
1655 ret = ret && ok;
1656
1657 }
1658 return ret;
1659}
1660
1662{
1663 // To avoid returning uninitialized memory, we set the encoder speed to 0
1664 *sp = 0.0;
1665 return true;
1666}
1667
1669{
1670 bool ret = true;
1671 for(int j=0; j< _njoints; j++)
1672 {
1673 ret &= getEncoderSpeedRaw(j, &spds[j]);
1674 }
1675 return ret;
1676}
1677
1679{
1680 // To avoid returning uninitialized memory, we set the encoder acc to 0
1681 *acc = 0.0;
1682
1683 return true;
1684}
1685
1687{
1688 bool ret = true;
1689 for(int j=0; j< _njoints; j++)
1690 {
1692 }
1693 return ret;
1694}
1695
1697
1699{
1700 bool ret = getEncodersRaw(encs);
1701 _mutex.lock();
1702 for (int i = 0; i < _njoints; i++) {
1703 stamps[i] = _encodersStamp[i] = _cycleTimestamp;
1704 }
1705 _mutex.unlock();
1706 return ret;
1707}
1708
1709bool FakeMotionControl::getEncoderTimedRaw(int j, double *encs, double *stamp)
1710{
1711 bool ret = getEncoderRaw(j, encs);
1712 _mutex.lock();
1713 *stamp = _encodersStamp[j] = _cycleTimestamp;
1714 _mutex.unlock();
1715
1716 return ret;
1717}
1718
1720
1722{
1723 *num=_njoints;
1724 return true;
1725}
1726
1727bool FakeMotionControl::setMotorEncoderRaw(int m, const double val)
1728{
1729 return NOT_YET_IMPLEMENTED("setMotorEncoder");
1730}
1731
1733{
1734 return NOT_YET_IMPLEMENTED("setMotorEncoders");
1735}
1736
1738{
1739 return NOT_YET_IMPLEMENTED("setMotorEncoderCountsPerRevolutionRaw");
1740}
1741
1743{
1744 return NOT_YET_IMPLEMENTED("getMotorEncoderCountsPerRevolutionRaw");
1745}
1746
1748{
1749 return NOT_YET_IMPLEMENTED("resetMotorEncoder");
1750}
1751
1753{
1754 return NOT_YET_IMPLEMENTED("reseMotortEncoders");
1755}
1756
1758{
1759 *value = pos[m]*10;
1760 return true;
1761}
1762
1764{
1765 bool ret = true;
1766 for(int j=0; j< _njoints; j++)
1767 {
1768 ret &= getMotorEncoderRaw(j, &encs[j]);
1769
1770 }
1771 return ret;
1772}
1773
1775{
1776 *sp = 0.0;
1777 return true;
1778}
1779
1781{
1782 bool ret = true;
1783 for(int j=0; j< _njoints; j++)
1784 {
1786 }
1787 return ret;
1788}
1789
1791{
1792 *acc = 0.0;
1793 return true;
1794}
1795
1797{
1798 bool ret = true;
1799 for(int j=0; j< _njoints; j++)
1800 {
1802 }
1803 return ret;
1804}
1805
1807{
1808 bool ret = getMotorEncodersRaw(encs);
1809 _mutex.lock();
1810 for (int i = 0; i < _njoints; i++) {
1811 stamps[i] = _encodersStamp[i] = _cycleTimestamp;
1812 }
1813 _mutex.unlock();
1814
1815 return ret;
1816}
1817
1818bool FakeMotionControl::getMotorEncoderTimedRaw(int m, double *encs, double *stamp)
1819{
1820 bool ret = getMotorEncoderRaw(m, encs);
1821 _mutex.lock();
1822 *stamp = _encodersStamp[m] = _cycleTimestamp;
1823 _mutex.unlock();
1824
1825 return ret;
1826}
1828
1830
1832{
1833 return DEPRECATED("enableAmpRaw");
1834}
1835
1837{
1838 return DEPRECATED("disableAmpRaw");
1839}
1840
1841bool FakeMotionControl::getCurrentRaw(int j, double *value)
1842{
1843 //just for testing purposes, this is not a real implementation
1844 *value = current[j];
1845 return true;
1846}
1847
1849{
1850 //just for testing purposes, this is not a real implementation
1851 bool ret = true;
1852 for(int j=0; j< _njoints; j++)
1853 {
1854 ret &= getCurrentRaw(j, &vals[j]);
1855 }
1856 return ret;
1857}
1858
1860{
1861 maxCurrent[m] = val;
1862 return true;
1863}
1864
1866{
1867 *val = maxCurrent[m];
1868 return true;
1869}
1870
1872{
1873 (_enabledAmp[j ]) ? *st = 1 : *st = 0;
1874 return true;
1875}
1876
1878{
1879 bool ret = true;
1880 for(int j=0; j<_njoints; j++)
1881 {
1882 sts[j] = _enabledAmp[j];
1883 }
1884 return ret;
1885}
1886
1888{
1889 *val = peakCurrent[m];
1890 return true;
1891}
1892
1893bool FakeMotionControl::setPeakCurrentRaw(int m, const double val)
1894{
1895 peakCurrent[m] = val;
1896 return true;
1897}
1898
1900{
1901 *val = nominalCurrent[m];
1902 return true;
1903}
1904
1906{
1907 nominalCurrent[m] = val;
1908 return true;
1909}
1910
1911bool FakeMotionControl::getPWMRaw(int m, double *val)
1912{
1913 *val = pwm[m];
1914 return true;
1915}
1916
1918{
1919 *val = pwmLimit[m];
1920 return true;
1921}
1922
1923bool FakeMotionControl::setPWMLimitRaw(int m, const double val)
1924{
1925 pwmLimit[m] = val;
1926 return true;
1927}
1928
1930{
1931 *val = supplyVoltage[m];
1932 return true;
1933}
1934
1935
1936// Limit interface
1937bool FakeMotionControl::setLimitsRaw(int j, double min, double max)
1938{
1939 bool ret = true;
1940 return ret;
1941}
1942
1943bool FakeMotionControl::getLimitsRaw(int j, double *min, double *max)
1944{
1945 *min = _limitsMin[j];
1946 *max = _limitsMax[j];
1947 return true;
1948}
1949
1951{
1952 return NOT_YET_IMPLEMENTED("getGearboxRatioRaw");
1953}
1954
1955bool FakeMotionControl::setGearboxRatioRaw(int m, const double val)
1956{
1957 return NOT_YET_IMPLEMENTED("setGearboxRatioRaw");
1958}
1959
1961{
1962 return NOT_YET_IMPLEMENTED("getTorqueControlFilterType");
1963}
1964
1966{
1967 return NOT_YET_IMPLEMENTED("getRotorEncoderResolutionRaw");
1968}
1969
1971{
1972 return NOT_YET_IMPLEMENTED("getJointEncoderResolutionRaw");
1973}
1974
1976{
1977 return NOT_YET_IMPLEMENTED("getJointEncoderTypeRaw");
1978}
1979
1981{
1982 return NOT_YET_IMPLEMENTED("getRotorEncoderTypeRaw");
1983}
1984
1986{
1987 return NOT_YET_IMPLEMENTED("getKinematicMJRaw");
1988}
1989
1991{
1992 return NOT_YET_IMPLEMENTED("getHasTempSensorsRaw");
1993}
1994
1996{
1997 return NOT_YET_IMPLEMENTED("getHasHallSensorRaw");
1998}
1999
2001{
2002 return NOT_YET_IMPLEMENTED("getHasRotorEncoderRaw");
2003}
2004
2006{
2007 return NOT_YET_IMPLEMENTED("getHasRotorEncoderIndexRaw");
2008}
2009
2011{
2012 return NOT_YET_IMPLEMENTED("getMotorPolesRaw");
2013}
2014
2016{
2017 return NOT_YET_IMPLEMENTED("getRotorIndexOffsetRaw");
2018}
2019
2020bool FakeMotionControl::getAxisNameRaw(int axis, std::string& name)
2021{
2022 if (axis >= 0 && axis < _njoints)
2023 {
2024 name = _axisName[axis];
2025 return true;
2026 }
2027 else
2028 {
2029 name = "ERROR";
2030 return false;
2031 }
2032}
2033
2035{
2036 if (axis >= 0 && axis < _njoints)
2037 {
2038 type = _jointType[axis];
2039 return true;
2040 }
2041 else
2042 {
2043 return false;
2044 }
2045}
2046
2047// IControlLimits
2048bool FakeMotionControl::setVelLimitsRaw(int axis, double min, double max)
2049{
2050 return NOT_YET_IMPLEMENTED("setVelLimitsRaw");
2051}
2052
2053bool FakeMotionControl::getVelLimitsRaw(int axis, double *min, double *max)
2054{
2055 *min = 0.0;
2056 *max = _maxJntCmdVelocity[axis];
2057 return true;
2058}
2059
2060
2061// Torque control
2063{
2064 *t = _torques[j];
2065 return true;
2066}
2067
2069{
2070 for (int i = 0; i < _njoints; i++)
2071 {
2072 t[i]= _torques[i];
2073 }
2074 return true;
2075}
2076
2077bool FakeMotionControl::getTorqueRangeRaw(int j, double *min, double *max)
2078{
2079 return NOT_YET_IMPLEMENTED("getTorqueRangeRaw");
2080}
2081
2082bool FakeMotionControl::getTorqueRangesRaw(double *min, double *max)
2083{
2084 return NOT_YET_IMPLEMENTED("getTorqueRangesRaw");
2085}
2086
2088{
2089 bool ret = true;
2090 for (int j = 0; j < _njoints && ret; j++) {
2091 ret &= setRefTorqueRaw(j, t[j]);
2092 }
2093 return ret;
2094}
2095
2097{
2098 _mutex.lock();
2099 _ref_torques[j]=t;
2100
2101 if (t>1.0 || t< -1.0)
2102 {
2103 yCError(FAKEMOTIONCONTROL) << "Joint received a high torque command, and was put in hardware fault";
2104 _hwfault_code[j] = 1;
2105 _hwfault_message[j] = "test" + std::to_string(j) + " torque";
2106 _controlModes[j] = VOCAB_CM_HW_FAULT;
2107 }
2108 _mutex.unlock();
2109 return true;
2110}
2111
2112bool FakeMotionControl::setRefTorquesRaw(const int n_joint, const int *joints, const double *t)
2113{
2114 return NOT_YET_IMPLEMENTED("setRefTorquesRaw");
2115}
2116
2118{
2119 bool ret = true;
2120 for (int j = 0; j < _njoints && ret; j++) {
2121 ret &= getRefTorqueRaw(j, &_ref_torques[j]);
2122 }
2123 return true;
2124}
2125
2127{
2128 _mutex.lock();
2129 *t = _ref_torques[j];
2130 _mutex.unlock();
2131 return true;
2132}
2133
2134bool FakeMotionControl::getImpedanceRaw(int j, double *stiffness, double *damping)
2135{
2136 _mutex.lock();
2137 *stiffness = _stiffness[j];
2138 *damping = _damping[j];
2139 _mutex.unlock();
2140 return true;
2141}
2142
2143bool FakeMotionControl::setImpedanceRaw(int j, double stiffness, double damping)
2144{
2145 _mutex.lock();
2146 _stiffness[j] = stiffness;
2147 _damping[j] = damping;
2148 _mutex.unlock();
2149 return true;
2150}
2151
2153{
2154 _mutex.lock();
2155 _force_offset[j] = offset;
2156 _mutex.unlock();
2157 return true;
2158}
2159
2161{
2162 _mutex.lock();
2163 *offset = _force_offset[j];
2164 _mutex.unlock();
2165 return true;
2166}
2167
2168bool FakeMotionControl::getCurrentImpedanceLimitRaw(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp)
2169{
2170 *min_stiff=1.0;
2171 *max_stiff=10.0;
2172 *min_damp=2.0;
2173 *max_damp=20.0;
2174 return true;
2175}
2176
2178{
2179 params->bemf = _kbemf[j];
2180 params->bemf_scale = _kbemf_scale[j];
2181 params->ktau = _ktau[j];
2182 params->ktau_scale = _ktau_scale[j];
2183 params->viscousPos = _viscousPos[j];
2184 params->viscousNeg = _viscousNeg[j];
2185 params->coulombPos = _coulombPos[j];
2186 params->coulombNeg = _coulombNeg[j];
2187 params->velocityThres = _velocityThres[j];
2188 yCDebug(FAKEMOTIONCONTROL) << "getMotorTorqueParamsRaw" << params->bemf
2189 << params->bemf_scale
2190 << params->ktau
2191 << params->ktau_scale
2192 << params->viscousPos
2193 << params->viscousNeg
2194 << params->coulombPos
2195 << params->coulombNeg
2196 << params->velocityThres;
2197 return true;
2198}
2199
2201{
2202 _kbemf[j] = params.bemf;
2203 _ktau[j] = params.ktau;
2204 _kbemf_scale[j] = params.bemf_scale;
2205 _ktau_scale[j] = params.ktau_scale;
2206 _viscousPos[j] = params.viscousPos;
2207 _viscousNeg[j] = params.viscousNeg;
2208 _coulombPos[j] = params.coulombPos;
2209 _coulombNeg[j] = params.coulombNeg;
2210 _velocityThres[j] = params.velocityThres;
2211 yCDebug(FAKEMOTIONCONTROL) << "setMotorTorqueParamsRaw" << params.bemf
2212 << params.bemf_scale
2213 << params.ktau
2214 << params.ktau_scale
2215 << params.viscousPos
2216 << params.viscousNeg
2217 << params.coulombPos
2218 << params.coulombNeg
2219 << params.velocityThres;
2220 return true;
2221}
2222
2223// IVelocityControl interface
2224bool FakeMotionControl::velocityMoveRaw(const int n_joint, const int *joints, const double *spds)
2225{
2226 bool ret = true;
2227 for(int i=0; i<n_joint; i++)
2228 {
2229 ret &= velocityMoveRaw(joints[i], spds[i]);
2230 }
2231 return ret;
2232}
2233
2234// PositionDirect Interface
2236{
2237 _posDir_references[j] = ref;
2238 return true;
2239}
2240
2241bool FakeMotionControl::setPositionsRaw(const int n_joint, const int *joints, const double *refs)
2242{
2243 for(int i=0; i< n_joint; i++)
2244 {
2245 _posDir_references[joints[i]] = refs[i];
2246 }
2247 return true;
2248}
2249
2251{
2252 for(int i=0; i< _njoints; i++)
2253 {
2254 _posDir_references[i] = refs[i];
2255 }
2256 return true;
2257}
2258
2259
2261{
2262 if (verbose >= VERY_VERBOSE) {
2263 yCTrace(FAKEMOTIONCONTROL) << "j " << axis << " ref " << _posCtrl_references[axis];
2264 }
2265
2266 int mode = 0;
2267 getControlModeRaw(axis, &mode);
2268 if( (mode != VOCAB_CM_POSITION) &&
2269 (mode != VOCAB_CM_MIXED) &&
2270 (mode != VOCAB_CM_IMPEDANCE_POS))
2271 {
2272 yCWarning(FAKEMOTIONCONTROL) << "getTargetPosition: Joint " << axis << " is not in POSITION mode, therefore the value returned by " <<
2273 "this call is for reference only and may not reflect the actual behaviour of the motor/firmware.";
2274 }
2275 *ref = _posCtrl_references[axis];
2276 return true;
2277}
2278
2280{
2281 bool ret = true;
2282 for (int i = 0; i < _njoints; i++) {
2283 ret &= getTargetPositionRaw(i, &refs[i]);
2284 }
2285 return ret;
2286}
2287
2288bool FakeMotionControl::getTargetPositionsRaw(int nj, const int * jnts, double *refs)
2289{
2290 bool ret = true;
2291 for (int i = 0; i<nj; i++)
2292 {
2293 ret &= getTargetPositionRaw(jnts[i], &refs[i]);
2294 }
2295 return ret;
2296}
2297
2299{
2300 *ref = _command_speeds[axis];
2301 return true;
2302}
2303
2305{
2306 bool ret = true;
2307 for (int i = 0; i<_njoints; i++)
2308 {
2309 ret &= getRefVelocityRaw(i, &refs[i]);
2310 }
2311 return ret;
2312}
2313
2314bool FakeMotionControl::getRefVelocitiesRaw(int nj, const int * jnts, double *refs)
2315{
2316 bool ret = true;
2317 for (int i = 0; i<nj; i++)
2318 {
2319 ret &= getRefVelocityRaw(jnts[i], &refs[i]);
2320 }
2321 return ret;
2322}
2323
2325{
2326 int mode = 0;
2327 getControlModeRaw(axis, &mode);
2328 if( (mode != VOCAB_CM_POSITION) &&
2329 (mode != VOCAB_CM_MIXED) &&
2330 (mode != VOCAB_CM_IMPEDANCE_POS) &&
2331 (mode != VOCAB_CM_POSITION_DIRECT) )
2332 {
2333 yCWarning(FAKEMOTIONCONTROL) << "getRefPosition: Joint " << axis << " is not in POSITION_DIRECT mode, therefore the value returned by \
2334 this call is for reference only and may not reflect the actual behaviour of the motor/firmware.";
2335 }
2336
2337 *ref = _posDir_references[axis];
2338
2339 return true;
2340}
2341
2343{
2344 bool ret = true;
2345 for (int i = 0; i<_njoints; i++)
2346 {
2347 ret &= getRefPositionRaw(i, &refs[i]);
2348 }
2349 return ret;
2350}
2351
2352bool FakeMotionControl::getRefPositionsRaw(int nj, const int * jnts, double *refs)
2353{
2354 bool ret = true;
2355 for (int i = 0; i<nj; i++)
2356 {
2357 ret &= getRefPositionRaw(jnts[i], &refs[i]);
2358 }
2359 return ret;
2360}
2361
2362
2363// InteractionMode
2365{
2366 if (verbose > VERY_VERY_VERBOSE) {
2367 yCTrace(FAKEMOTIONCONTROL) << "j: " << j;
2368 }
2369
2370 *_mode = (yarp::dev::InteractionModeEnum)_interactMode[j];
2371 return true;}
2372
2374{
2375 bool ret = true;
2376 for(int j=0; j< n_joints; j++)
2377 {
2379 }
2380 return ret;
2381
2382}
2383
2385{
2386 bool ret = true;
2387 for (int j = 0; j < _njoints; j++) {
2389 }
2390 return ret;
2391}
2392
2393// marco.accame: con alberto cardellino abbiamo parlato della correttezza di effettuare la verifica di quanto imposto (in setInteractionModeRaw() ed affini)
2394// andando a rileggere il valore nella scheda eth fino a che esso non sia quello atteso. si deve fare oppure no?
2395// con il interaction mode il can ora non lo fa. mentre lo fa per il control mode. perche' diverso?
2397{
2398 if (verbose >= VERY_VERBOSE) {
2399 yCTrace(FAKEMOTIONCONTROL) << "j: " << j << " interaction mode: " << yarp::os::Vocab32::decode(_mode);
2400 }
2401
2402 _interactMode[j] = _mode;
2403
2404 return true;
2405}
2406
2407
2409{
2410 bool ret = true;
2411 for(int i=0; i<n_joints; i++)
2412 {
2414 }
2415 return ret;
2416}
2417
2419{
2420 bool ret = true;
2421 for(int i=0; i<_njoints; i++)
2422 {
2424 }
2425 return ret;
2426
2427}
2428
2430{
2431 *num=_njoints;
2432 return true;
2433}
2434
2436{
2437 *val = 37.5+double(m);
2438 return true;
2439}
2440
2442{
2443 bool ret = true;
2444 for(int j=0; j< _njoints; j++)
2445 {
2446 ret &= getTemperatureRaw(j, &vals[j]);
2447 }
2448 return ret;
2449}
2450
2452{
2453 return NOT_YET_IMPLEMENTED("getTemperatureLimitRaw");
2454}
2455
2457{
2458 return NOT_YET_IMPLEMENTED("setTemperatureLimitRaw");
2459}
2460
2461//PWM interface
2463{
2464 refpwm[j] = v;
2465 pwm[j] = v;
2466 last_pwm_command[j]=yarp::os::Time::now();
2467 return true;
2468}
2469
2471{
2472 for (int i = 0; i < _njoints; i++)
2473 {
2474 setRefDutyCycleRaw(i,v[i]);
2475 }
2476 return true;
2477}
2478
2480{
2481 *v = refpwm[j];
2482 return true;
2483}
2484
2486{
2487 for (int i = 0; i < _njoints; i++)
2488 {
2489 v[i] = refpwm[i];
2490 }
2491 return true;
2492}
2493
2495{
2496 *v = pwm[j];
2497 return true;
2498}
2499
2501{
2502 for (int i = 0; i < _njoints; i++)
2503 {
2504 v[i] = pwm[i];
2505 }
2506 return true;
2507}
2508
2509// Current interface
2510/*bool FakeMotionControl::getCurrentRaw(int j, double *t)
2511{
2512 return NOT_YET_IMPLEMENTED("getCurrentRaw");
2513}
2514
2515bool FakeMotionControl::getCurrentsRaw(double *t)
2516{
2517 return NOT_YET_IMPLEMENTED("getCurrentsRaw");
2518}
2519*/
2520
2521bool FakeMotionControl::getCurrentRangeRaw(int j, double *min, double *max)
2522{
2523 //just for testing purposes, this is not a real implementation
2524 *min = _ref_currents[j] / 100;
2525 *max = _ref_currents[j] * 100;
2526 return true;
2527}
2528
2529bool FakeMotionControl::getCurrentRangesRaw(double *min, double *max)
2530{
2531 //just for testing purposes, this is not a real implementation
2532 for (int i = 0; i < _njoints; i++)
2533 {
2534 min[i] = _ref_currents[i] / 100;
2535 max[i] = _ref_currents[i] * 100;
2536 }
2537 return true;
2538}
2539
2541{
2542 for (int i = 0; i < _njoints; i++)
2543 {
2544 _ref_currents[i] = t[i];
2545 current[i] = t[i] / 2;
2546 }
2547 return true;
2548}
2549
2551{
2552 _ref_currents[j] = t;
2553 current[j] = t / 2;
2554 return true;
2555}
2556
2557bool FakeMotionControl::setRefCurrentsRaw(const int n_joint, const int *joints, const double *t)
2558{
2559 bool ret = true;
2560 for (int j = 0; j<n_joint; j++)
2561 {
2562 ret = ret &&setRefCurrentRaw(joints[j], t[j]);
2563 }
2564 return ret;
2565}
2566
2568{
2569 for (int i = 0; i < _njoints; i++)
2570 {
2571 t[i] = _ref_currents[i];
2572 }
2573 return true;
2574}
2575
2577{
2578 *t = _ref_currents[j];
2579 return true;
2580}
2581
2586
2588{
2589 return _njoints;
2590}
2591
2593{
2594 for (int i = 0; i < _njoints; i++)
2595 {
2596 measure[i] = _torques[i];
2597 }
2598 return true;
2599}
2600
2602{
2603 _torques[ch] = measure;
2604 return true;
2605}
2606
2607bool FakeMotionControl::getLastJointFaultRaw(int j, int& fault, std::string& message)
2608{
2609 _mutex.lock();
2610 fault = _hwfault_code[j];
2611 message = _hwfault_message[j];
2612 _mutex.unlock();
2613 return true;
2614}
2615
2616
2617/*
2618bool FakeMotionControl::parseImpedanceGroup_NewFormat(Bottle& pidsGroup, ImpedanceParameters vals[])
2619{
2620 int j=0;
2621 Bottle xtmp;
2622
2623 if (!extractGroup(pidsGroup, xtmp, "stiffness", "stiffness parameter", _njoints)) {
2624 return false;
2625 }
2626 for (j=0; j<_njoints; j++) {
2627 vals[j].stiffness = xtmp.get(j+1).asFloat64();
2628 }
2629
2630 if (!extractGroup(pidsGroup, xtmp, "damping", "damping parameter", _njoints)) {
2631 return false;
2632 }
2633 for (j=0; j<_njoints; j++) {
2634 vals[j].damping = xtmp.get(j+1).asFloat64();
2635 }
2636
2637 return true;
2638}
2639*/
2640
2641/*
2642bool FakeMotionControl::parsePositionPidsGroup(Bottle& pidsGroup, Pid myPid[])
2643{
2644 int j=0;
2645 Bottle xtmp;
2646
2647 if (!extractGroup(pidsGroup, xtmp, "kp", "Pid kp parameter", _njoints)) {
2648 return false;
2649 }
2650 for (j=0; j<_njoints; j++) {
2651 myPid[j].kp = xtmp.get(j+1).asFloat64();
2652 }
2653
2654 if (!extractGroup(pidsGroup, xtmp, "kd", "Pid kd parameter", _njoints)) {
2655 return false;
2656 }
2657 for (j=0; j<_njoints; j++) {
2658 myPid[j].kd = xtmp.get(j+1).asFloat64();
2659 }
2660
2661 if (!extractGroup(pidsGroup, xtmp, "ki", "Pid kp parameter", _njoints)) {
2662 return false;
2663 }
2664 for (j=0; j<_njoints; j++) {
2665 myPid[j].ki = xtmp.get(j+1).asFloat64();
2666 }
2667
2668 if (!extractGroup(pidsGroup, xtmp, "maxInt", "Pid maxInt parameter", _njoints)) {
2669 return false;
2670 }
2671 for (j=0; j<_njoints; j++) {
2672 myPid[j].max_int = xtmp.get(j+1).asFloat64();
2673 }
2674
2675 if (!extractGroup(pidsGroup, xtmp, "maxPwm", "Pid maxPwm parameter", _njoints)) {
2676 return false;
2677 }
2678 for (j=0; j<_njoints; j++) {
2679 myPid[j].max_output = xtmp.get(j+1).asFloat64();
2680 }
2681
2682 if (!extractGroup(pidsGroup, xtmp, "shift", "Pid shift parameter", _njoints)) {
2683 return false;
2684 }
2685 for (j=0; j<_njoints; j++) {
2686 myPid[j].scale = xtmp.get(j+1).asFloat64();
2687 }
2688
2689 if (!extractGroup(pidsGroup, xtmp, "ko", "Pid ko parameter", _njoints)) {
2690 return false;
2691 }
2692 for (j=0; j<_njoints; j++) {
2693 myPid[j].offset = xtmp.get(j+1).asFloat64();
2694 }
2695
2696 if (!extractGroup(pidsGroup, xtmp, "stictionUp", "Pid stictionUp", _njoints)) {
2697 return false;
2698 }
2699 for (j=0; j<_njoints; j++) {
2700 myPid[j].stiction_up_val = xtmp.get(j+1).asFloat64();
2701 }
2702
2703 if (!extractGroup(pidsGroup, xtmp, "stictionDwn", "Pid stictionDwn", _njoints)) {
2704 return false;
2705 }
2706 for (j=0; j<_njoints; j++) {
2707 myPid[j].stiction_down_val = xtmp.get(j+1).asFloat64();
2708 }
2709
2710 if (!extractGroup(pidsGroup, xtmp, "kff", "Pid kff parameter", _njoints)) {
2711 return false;
2712 }
2713 for (j=0; j<_njoints; j++) {
2714 myPid[j].kff = xtmp.get(j+1).asFloat64();
2715 }
2716
2717 //conversion from metric to machine units (if applicable)
2718 if (_positionControlUnits==P_METRIC_UNITS)
2719 {
2720 for (j=0; j<_njoints; j++)
2721 {
2722 myPid[j].kp = myPid[j].kp / _angleToEncoder[j]; //[PWM/deg]
2723 myPid[j].ki = myPid[j].ki / _angleToEncoder[j]; //[PWM/deg]
2724 myPid[j].kd = myPid[j].kd / _angleToEncoder[j]; //[PWM/deg]
2725 }
2726 }
2727 else
2728 {
2729 //do nothing
2730 }
2731
2732 //optional PWM limit
2733 if(_pwmIsLimited)
2734 { // check for value in the file
2735 if (!extractGroup(pidsGroup, xtmp, "limPwm", "Limited PWD", _njoints))
2736 {
2737 yCError(FAKEMOTIONCONTROL) << "The PID parameter limPwm was requested but was not correctly set in the configuration file, please fill it.";
2738 return false;
2739 }
2740
2741 yCInfo(FAKEMOTIONCONTROL) << "Using LIMITED PWM!!";
2742 for (j = 0; j < _njoints; j++) {
2743 myPid[j].max_output = xtmp.get(j + 1).asFloat64();
2744 }
2745 }
2746
2747 return true;
2748}
2749*/
2750
2751/*
2752bool FakeMotionControl::parseTorquePidsGroup(Bottle& pidsGroup, Pid myPid[], double kbemf[], double ktau[], int filterType[], double viscousPos[], double viscousNeg[], double coulombPos[], double coulombNeg[], double velocityThres[])
2753{
2754 int j=0;
2755 Bottle xtmp;
2756 if (!extractGroup(pidsGroup, xtmp, "kp", "Pid kp parameter", _njoints)) {
2757 return false;
2758 }
2759 for (j=0; j<_njoints; j++) {
2760 myPid[j].kp = xtmp.get(j+1).asFloat64();
2761 }
2762
2763 if (!extractGroup(pidsGroup, xtmp, "kd", "Pid kd parameter", _njoints)) {
2764 return false;
2765 }
2766 for (j=0; j<_njoints; j++) {
2767 myPid[j].kd = xtmp.get(j+1).asFloat64();
2768 }
2769
2770 if (!extractGroup(pidsGroup, xtmp, "ki", "Pid kp parameter", _njoints)) {
2771 return false;
2772 }
2773 for (j=0; j<_njoints; j++) {
2774 myPid[j].ki = xtmp.get(j+1).asFloat64();
2775 }
2776
2777 if (!extractGroup(pidsGroup, xtmp, "maxInt", "Pid maxInt parameter", _njoints)) {
2778 return false;
2779 }
2780 for (j=0; j<_njoints; j++) {
2781 myPid[j].max_int = xtmp.get(j+1).asFloat64();
2782 }
2783
2784 if (!extractGroup(pidsGroup, xtmp, "maxPwm", "Pid maxPwm parameter", _njoints)) {
2785 return false;
2786 }
2787 for (j=0; j<_njoints; j++) {
2788 myPid[j].max_output = xtmp.get(j+1).asFloat64();
2789 }
2790
2791 if (!extractGroup(pidsGroup, xtmp, "shift", "Pid shift parameter", _njoints)) {
2792 return false;
2793 }
2794 for (j=0; j<_njoints; j++) {
2795 myPid[j].scale = xtmp.get(j+1).asFloat64();
2796 }
2797
2798 if (!extractGroup(pidsGroup, xtmp, "ko", "Pid ko parameter", _njoints)) {
2799 return false;
2800 }
2801 for (j=0; j<_njoints; j++) {
2802 myPid[j].offset = xtmp.get(j+1).asFloat64();
2803 }
2804
2805 if (!extractGroup(pidsGroup, xtmp, "stictionUp", "Pid stictionUp", _njoints)) {
2806 return false;
2807 }
2808 for (j=0; j<_njoints; j++) {
2809 myPid[j].stiction_up_val = xtmp.get(j+1).asFloat64();
2810 }
2811
2812 if (!extractGroup(pidsGroup, xtmp, "stictionDwn", "Pid stictionDwn", _njoints)) {
2813 return false;
2814 }
2815 for (j=0; j<_njoints; j++) {
2816 myPid[j].stiction_down_val = xtmp.get(j+1).asFloat64();
2817 }
2818
2819 if (!extractGroup(pidsGroup, xtmp, "kff", "Pid kff parameter", _njoints)) {
2820 return false;
2821 }
2822 for (j=0; j<_njoints; j++) {
2823 myPid[j].kff = xtmp.get(j+1).asFloat64();
2824 }
2825
2826 if (!extractGroup(pidsGroup, xtmp, "kbemf", "kbemf parameter", _njoints)) {
2827 return false;
2828 }
2829 for (j=0; j<_njoints; j++) {
2830 kbemf[j] = xtmp.get(j+1).asFloat64();
2831 }
2832
2833 if (!extractGroup(pidsGroup, xtmp, "ktau", "ktau parameter", _njoints)) {
2834 return false;
2835 }
2836 for (j=0; j<_njoints; j++) {
2837 ktau[j] = xtmp.get(j+1).asFloat64();
2838 }
2839
2840 if (!extractGroup(pidsGroup, xtmp, "filterType", "filterType param", _njoints)) {
2841 return false;
2842 }
2843 for (j=0; j<_njoints; j++) {
2844 filterType[j] = xtmp.get(j+1).asInt32();
2845 }
2846
2847 if (!extractGroup(pidsGroup, xtmp, "viscousPos", "viscous pos parameter", _njoints)) {
2848 return false;
2849 }
2850 for (j=0; j<_njoints; j++) {
2851 viscousPos[j] = xtmp.get(j+1).asFloat64();
2852 }
2853
2854 if (!extractGroup(pidsGroup, xtmp, "viscousNeg", "viscous neg parameter", _njoints)) {
2855 return false;
2856 }
2857 for (j=0; j<_njoints; j++) {
2858 viscousNeg[j] = xtmp.get(j+1).asFloat64();
2859 }
2860
2861 if (!extractGroup(pidsGroup, xtmp, "coulombPos", "coulomb pos parameter", _njoints)) {
2862 return false;
2863 }
2864 for (j=0; j<_njoints; j++) {
2865 coulombPos[j] = xtmp.get(j+1).asFloat64();
2866 }
2867
2868 if (!extractGroup(pidsGroup, xtmp, "coulombNeg", "coulomb neg parameter", _njoints)) {
2869 return false;
2870 }
2871 for (j=0; j<_njoints; j++) {
2872 coulombNeg[j] = xtmp.get(j+1).asFloat64();
2873 }
2874
2875 if (!extractGroup(pidsGroup, xtmp, "velocityThres", "velocity threshold parameter", _njoints)) {
2876 return false;
2877 }
2878 for (j=0; j<_njoints; j++) {
2879 velocityThres[j] = xtmp.get(j+1).asFloat64();
2880 }
2881
2882
2883 //conversion from metric to machine units (if applicable)
2884// for (j=0; j<_njoints; j++)
2885// {
2886// myPid[j].kp = myPid[j].kp / _torqueControlHelper->getNewtonsToSensor(j); //[PWM/Nm]
2887// myPid[j].ki = myPid[j].ki / _torqueControlHelper->getNewtonsToSensor(j); //[PWM/Nm]
2888// myPid[j].kd = myPid[j].kd / _torqueControlHelper->getNewtonsToSensor(j); //[PWM/Nm]
2889// myPid[j].stiction_up_val = myPid[j].stiction_up_val * _torqueControlHelper->getNewtonsToSensor(j); //[Nm]
2890// myPid[j].stiction_down_val = myPid[j].stiction_down_val * _torqueControlHelper->getNewtonsToSensor(j); //[Nm]
2891// }
2892
2893 //optional PWM limit
2894 if(_pwmIsLimited)
2895 { // check for value in the file
2896 if (!extractGroup(pidsGroup, xtmp, "limPwm", "Limited PWM", _njoints))
2897 {
2898 yCError(FAKEMOTIONCONTROL) << "The PID parameter limPwm was requested but was not correctly set in the configuration file, please fill it.";
2899 return false;
2900 }
2901
2902 yCInfo(FAKEMOTIONCONTROL) << "Using LIMITED PWM!!";
2903 for (j = 0; j < _njoints; j++) {
2904 myPid[j].max_output = xtmp.get(j + 1).asFloat64();
2905 }
2906 }
2907
2908 return true;
2909}
2910*/
2911
2912// 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
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.
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.