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_CURRENT)
88 {
89 //do nothing
90 }
91 else if (_controlModes[i] == VOCAB_CM_VELOCITY_DIRECT)
92 {
93 //not yet implemented
94 }
95 else if (_controlModes[i] == VOCAB_CM_MIXED)
96 {
97 //not yet implemented
98 }
99 else if (_controlModes[i] == VOCAB_CM_TORQUE)
100 {
101 //not yet implemented
102 }
103 else if (_controlModes[i] == VOCAB_CM_HW_FAULT)
104 {
105 //not yet implemented
106 }
107 else
108 {
109 //unsupported control mode
110 yCWarning(FAKEMOTIONCONTROL) << "Unsupported control mode, joint " << i << " " << yarp::os::Vocab32::decode(_controlModes[i]);
111 }
112 }
113 prev_time = yarp::os::Time::now();
114}
115
116static inline bool NOT_YET_IMPLEMENTED(const char *txt)
117{
118 yCDebug(FAKEMOTIONCONTROL) << txt << "is not yet implemented for FakeMotionControl";
119 return true;
120}
121
122static inline bool DEPRECATED(const char *txt)
123{
124 yCError(FAKEMOTIONCONTROL) << txt << "has been deprecated for FakeMotionControl";
125 return true;
126}
127
128
129// replace with to_string as soon as C++11 is required by YARP
134template<typename T>
135std::string toString(const T& value)
136{
137 std::ostringstream oss;
138 oss << value;
139 return oss.str();
140}
141
142//generic function that check is key1 is present in input bottle and that the result has size elements
143// return true/false
144/*
145bool FakeMotionControl::extractGroup(Bottle &input, Bottle &out, const std::string &key1, const std::string &txt, int size)
146{
147 size++;
148 Bottle &tmp=input.findGroup(key1, txt);
149
150 if (tmp.isNull())
151 {
152 yCError(FAKEMOTIONCONTROL) << key1.c_str() << "parameter not found";
153 return false;
154 }
155
156 if(tmp.size()!=(size_t) size)
157 {
158 yCError(FAKEMOTIONCONTROL) << key1.c_str() << "incorrect number of entries";
159 return false;
160 }
161
162 out=tmp;
163 return true;
164}
165*/
166
168{
169 pos.resize(_njoints);
170 dpos.resize(_njoints);
171 vel.resize(_njoints);
172 speed.resize(_njoints);
173 acc.resize(_njoints);
174 loc.resize(_njoints);
175 amp.resize(_njoints);
176
177 current.resize(_njoints);
178 nominalCurrent.resize(_njoints);
179 maxCurrent.resize(_njoints);
180 peakCurrent.resize(_njoints);
181 pwm.resize(_njoints);
182 refpwm.resize(_njoints);
183 pwmLimit.resize(_njoints);
184 supplyVoltage.resize(_njoints);
185 last_velocity_command.resize(_njoints);
186 last_pwm_command.resize(_njoints);
187
188 pos.zero();
189 dpos.zero();
190 vel.zero();
191 speed.zero();
192 acc.zero();
193 loc.zero();
194 amp.zero();
195
196 current.zero();
197 nominalCurrent.zero();
198 maxCurrent.zero();
199 peakCurrent.zero();
200
201 pwm.zero();
202 refpwm.zero();
203 pwmLimit.zero();
204 supplyVoltage.zero();
205}
206
208{
209 _axisMap = allocAndCheck<int>(nj);
210 _controlModes = allocAndCheck<int>(nj);
211 _interactMode = allocAndCheck<int>(nj);
212 _angleToEncoder = allocAndCheck<double>(nj);
213 _dutycycleToPWM = allocAndCheck<double>(nj);
214 _ampsToSensor = allocAndCheck<double>(nj);
215 _encodersStamp = allocAndCheck<double>(nj);
216 _DEPRECATED_encoderconversionoffset = allocAndCheck<float>(nj);
217 _DEPRECATED_encoderconversionfactor = allocAndCheck<float>(nj);
218 _jointEncoderRes = allocAndCheck<int>(nj);
219 _rotorEncoderRes = allocAndCheck<int>(nj);
220 _gearbox = allocAndCheck<double>(nj);
221 _torqueSensorId= allocAndCheck<int>(nj);
222 _torqueSensorChan= allocAndCheck<int>(nj);
223 _maxTorque=allocAndCheck<double>(nj);
224 _torques = allocAndCheck<double>(nj);
225 _maxJntCmdVelocity = allocAndCheck<double>(nj);
226 _maxMotorVelocity = allocAndCheck<double>(nj);
227 _newtonsToSensor=allocAndCheck<double>(nj);
228 _hasHallSensor = allocAndCheck<bool>(nj);
229 _hasTempSensor = allocAndCheck<bool>(nj);
230 _hasRotorEncoder = allocAndCheck<bool>(nj);
231 _hasRotorEncoderIndex = allocAndCheck<bool>(nj);
232 _rotorIndexOffset = allocAndCheck<int>(nj);
233 _motorPoles = allocAndCheck<int>(nj);
234 _rotorlimits_max = allocAndCheck<double>(nj);
235 _rotorlimits_min = allocAndCheck<double>(nj);
236 _hwfault_code = allocAndCheck<int>(nj);
237 _hwfault_message = allocAndCheck<std::string>(nj);
238 _braked = allocAndCheck<bool>(nj);
239 _autobraked = allocAndCheck<bool>(nj);
240
241 _ppids=allocAndCheck<Pid>(nj);
242 _tpids=allocAndCheck<Pid>(nj);
243 _cpids = allocAndCheck<Pid>(nj);
244 _vpids = allocAndCheck<Pid>(nj);
245 _ppids_ena=allocAndCheck<bool>(nj);
246 _tpids_ena=allocAndCheck<bool>(nj);
247 _cpids_ena = allocAndCheck<bool>(nj);
248 _vpids_ena = allocAndCheck<bool>(nj);
249 _ppids_lim=allocAndCheck<double>(nj);
250 _tpids_lim=allocAndCheck<double>(nj);
251 _cpids_lim = allocAndCheck<double>(nj);
252 _vpids_lim = allocAndCheck<double>(nj);
253 _ppids_ref=allocAndCheck<double>(nj);
254 _tpids_ref=allocAndCheck<double>(nj);
255 _cpids_ref = allocAndCheck<double>(nj);
256 _vpids_ref = allocAndCheck<double>(nj);
257
258// _impedance_params=allocAndCheck<ImpedanceParameters>(nj);
259// _impedance_limits=allocAndCheck<ImpedanceLimits>(nj);
260 _axisName = new std::string[nj];
261 _jointType = new JointTypeEnum[nj];
262
263 _limitsMax=allocAndCheck<double>(nj);
264 _limitsMin=allocAndCheck<double>(nj);
265 _kinematic_mj=allocAndCheck<double>(16);
266// _currentLimits=allocAndCheck<MotorCurrentLimits>(nj);
267 _motorPwmLimits=allocAndCheck<double>(nj);
268 checking_motiondone=allocAndCheck<bool>(nj);
269
270 _velocityShifts=allocAndCheck<int>(nj);
271 _velocityTimeout=allocAndCheck<int>(nj);
272 _kbemf=allocAndCheck<double>(nj);
273 _ktau=allocAndCheck<double>(nj);
274 _kbemf_scale = allocAndCheck<int>(nj);
275 _ktau_scale = allocAndCheck<int>(nj);
276 _filterType=allocAndCheck<int>(nj);
277 _last_position_move_time=allocAndCheck<double>(nj);
278 _viscousPos=allocAndCheck<double>(nj);
279 _viscousNeg=allocAndCheck<double>(nj);
280 _coulombPos=allocAndCheck<double>(nj);
281 _coulombNeg=allocAndCheck<double>(nj);
282 _velocityThres=allocAndCheck<double>(nj);
283
284 // Reserve space for data stored locally. values are initialized to 0
285 _posCtrl_references = allocAndCheck<double>(nj);
286 _posDir_references = allocAndCheck<double>(nj);
287 _command_speeds = allocAndCheck<double>(nj);
288 _dir_vel_commands = allocAndCheck<double>(nj);
289 _ref_speeds = allocAndCheck<double>(nj);
290 _ref_accs = allocAndCheck<double>(nj);
291 _ref_torques = allocAndCheck<double>(nj);
292 _ref_currents = allocAndCheck<double>(nj);
293 _enabledAmp = allocAndCheck<bool>(nj);
294 _enabledPid = allocAndCheck<bool>(nj);
295 _calibrated = allocAndCheck<bool>(nj);
296// _cacheImpedance = allocAndCheck<eOmc_impedance_t>(nj);
297
299
300 return true;
301}
302
303bool FakeMotionControl::dealloc()
304{
305 checkAndDestroy(_axisMap);
306 checkAndDestroy(_controlModes);
307 checkAndDestroy(_interactMode);
308 checkAndDestroy(_angleToEncoder);
309 checkAndDestroy(_ampsToSensor);
310 checkAndDestroy(_dutycycleToPWM);
311 checkAndDestroy(_encodersStamp);
312 checkAndDestroy(_DEPRECATED_encoderconversionoffset);
313 checkAndDestroy(_DEPRECATED_encoderconversionfactor);
314 checkAndDestroy(_jointEncoderRes);
315 checkAndDestroy(_rotorEncoderRes);
316// checkAndDestroy(_jointEncoderType);
317// checkAndDestroy(_rotorEncoderType);
318 checkAndDestroy(_gearbox);
319 checkAndDestroy(_torqueSensorId);
320 checkAndDestroy(_torqueSensorChan);
321 checkAndDestroy(_braked);
322 checkAndDestroy(_autobraked);
323 checkAndDestroy(_maxTorque);
324 checkAndDestroy(_maxJntCmdVelocity);
325 checkAndDestroy(_maxMotorVelocity);
326 checkAndDestroy(_newtonsToSensor);
327 checkAndDestroy(_ppids);
328 checkAndDestroy(_tpids);
329 checkAndDestroy(_cpids);
330 checkAndDestroy(_vpids);
331 checkAndDestroy(_ppids_ena);
332 checkAndDestroy(_tpids_ena);
333 checkAndDestroy(_cpids_ena);
334 checkAndDestroy(_vpids_ena);
335 checkAndDestroy(_ppids_lim);
336 checkAndDestroy(_tpids_lim);
337 checkAndDestroy(_cpids_lim);
338 checkAndDestroy(_vpids_lim);
339 checkAndDestroy(_ppids_ref);
340 checkAndDestroy(_tpids_ref);
341 checkAndDestroy(_cpids_ref);
342 checkAndDestroy(_vpids_ref);
343// checkAndDestroy(_impedance_params);
344// checkAndDestroy(_impedance_limits);
345 checkAndDestroy(_limitsMax);
346 checkAndDestroy(_limitsMin);
347 checkAndDestroy(_kinematic_mj);
348// checkAndDestroy(_currentLimits);
349 checkAndDestroy(_motorPwmLimits);
350 checkAndDestroy(checking_motiondone);
351 checkAndDestroy(_velocityShifts);
352 checkAndDestroy(_velocityTimeout);
353 checkAndDestroy(_kbemf);
354 checkAndDestroy(_ktau);
355 checkAndDestroy(_kbemf_scale);
356 checkAndDestroy(_ktau_scale);
357 checkAndDestroy(_filterType);
358 checkAndDestroy(_viscousPos);
359 checkAndDestroy(_viscousNeg);
360 checkAndDestroy(_coulombPos);
361 checkAndDestroy(_coulombNeg);
362 checkAndDestroy(_velocityThres);
363 checkAndDestroy(_posCtrl_references);
364 checkAndDestroy(_posDir_references);
365 checkAndDestroy(_command_speeds);
366 checkAndDestroy(_dir_vel_commands);
367 checkAndDestroy(_ref_speeds);
368 checkAndDestroy(_ref_accs);
369 checkAndDestroy(_ref_torques);
370 checkAndDestroy(_ref_currents);
371 checkAndDestroy(_enabledAmp);
372 checkAndDestroy(_enabledPid);
373 checkAndDestroy(_calibrated);
374 checkAndDestroy(_hasHallSensor);
375 checkAndDestroy(_hasTempSensor);
376 checkAndDestroy(_hasRotorEncoder);
377 checkAndDestroy(_hasRotorEncoderIndex);
378 checkAndDestroy(_rotorIndexOffset);
379 checkAndDestroy(_motorPoles);
380 checkAndDestroy(_axisName);
381 checkAndDestroy(_jointType);
382 checkAndDestroy(_rotorlimits_max);
383 checkAndDestroy(_rotorlimits_min);
384 checkAndDestroy(_last_position_move_time);
385 checkAndDestroy(_torques);
386 checkAndDestroy(_hwfault_code);
387 checkAndDestroy(_hwfault_message);
388 checkAndDestroy(_stiffness);
389 checkAndDestroy(_damping);
390 checkAndDestroy(_force_offset);
391 return true;
392}
393
395 PeriodicThread(0.01),
417 _mutex(),
418 _njoints (0),
419 _axisMap (nullptr),
420 _angleToEncoder(nullptr),
421 _encodersStamp (nullptr),
422 _ampsToSensor (nullptr),
423 _dutycycleToPWM(nullptr),
424 _DEPRECATED_encoderconversionfactor (nullptr),
425 _DEPRECATED_encoderconversionoffset (nullptr),
426 _jointEncoderRes (nullptr),
427 _rotorEncoderRes (nullptr),
428 _gearbox (nullptr),
429 _hasHallSensor (nullptr),
430 _hasTempSensor (nullptr),
431 _hasRotorEncoder (nullptr),
432 _hasRotorEncoderIndex (nullptr),
433 _rotorIndexOffset (nullptr),
434 _motorPoles (nullptr),
435 _rotorlimits_max (nullptr),
436 _rotorlimits_min (nullptr),
437 _ppids (nullptr),
438 _tpids (nullptr),
439 _cpids (nullptr),
440 _vpids (nullptr),
441 _ppids_ena (nullptr),
442 _tpids_ena (nullptr),
443 _cpids_ena (nullptr),
444 _vpids_ena (nullptr),
445 _ppids_lim (nullptr),
446 _tpids_lim (nullptr),
447 _cpids_lim (nullptr),
448 _vpids_lim (nullptr),
449 _ppids_ref (nullptr),
450 _tpids_ref (nullptr),
451 _cpids_ref (nullptr),
452 _vpids_ref (nullptr),
453 _axisName (nullptr),
454 _jointType (nullptr),
455 _limitsMin (nullptr),
456 _limitsMax (nullptr),
457 _kinematic_mj (nullptr),
458 _maxJntCmdVelocity (nullptr),
459 _maxMotorVelocity (nullptr),
460 _velocityShifts (nullptr),
461 _velocityTimeout (nullptr),
462 _kbemf (nullptr),
463 _ktau (nullptr),
464 _kbemf_scale (nullptr),
465 _ktau_scale (nullptr),
466 _viscousPos (nullptr),
467 _viscousNeg (nullptr),
468 _coulombPos (nullptr),
469 _coulombNeg (nullptr),
470 _velocityThres (nullptr),
471 _filterType (nullptr),
472 _torqueSensorId (nullptr),
473 _torqueSensorChan (nullptr),
474 _maxTorque (nullptr),
475 _newtonsToSensor (nullptr),
476 checking_motiondone (nullptr),
477 _last_position_move_time(nullptr),
478 _motorPwmLimits (nullptr),
479 _torques (nullptr),
480 useRawEncoderData (false),
481 _pwmIsLimited (false),
482 _torqueControlEnabled (false),
483 _torqueControlUnits (T_MACHINE_UNITS),
484 _positionControlUnits (P_MACHINE_UNITS),
485 prev_time (0.0),
486 opened (false),
487 verbose (VERY_VERBOSE)
488{
490 std::string tmp = yarp::conf::environment::get_string("VERBOSE_STICA");
491 verbosewhenok = (tmp != "") ? (bool)yarp::conf::numeric::from_string<int>(tmp) :
492 false;
493}
494
500
502{
503 return opened;
504}
505
507{
509 for(int i=0; i<_njoints; i++)
510 {
511 pwm[i] = 33+i;
512 pwmLimit[i] = (33+i)*10;
513 current[i] = (33+i)*100;
514 maxCurrent[i] = (33+i)*1000;
515 peakCurrent[i] = (33+i)*2;
516 nominalCurrent[i] = (33+i)*20;
517 supplyVoltage[i] = (33+i)*200;
518 last_velocity_command[i] = -1;
519 last_pwm_command[i] = -1;
520 _controlModes[i] = VOCAB_CM_POSITION;
521 _maxJntCmdVelocity[i]=50.0;
522 }
523 prev_time = yarp::os::Time::now();
524 return true;
525}
526
530
532{
533 if (!this->parseParams(config)) {return false;}
534
535 std::string str;
536
537 //
538 // Read Configuration params from file
539 //
540 _njoints = m_GENERAL_Joints;
541
542 if(!alloc(_njoints))
543 {
544 yCError(FAKEMOTIONCONTROL) << "Malloc failed";
545 return false;
546 }
547
548 // Default value
549 for (int i = 0; i < _njoints; i++) {
550 _newtonsToSensor[i] = 1;
551 }
552
553 if(!fromConfig(config))
554 {
555 yCError(FAKEMOTIONCONTROL) << "Missing parameters in config file";
556 return false;
557 }
558
559 // INIT ALL INTERFACES
560 yarp::sig::Vector tmpZeros; tmpZeros.resize (_njoints, 0.0);
561 yarp::sig::Vector tmpOnes; tmpOnes.resize (_njoints, 1.0);
562 yarp::sig::Vector bemfToRaw; bemfToRaw.resize(_njoints, 1.0);
563 yarp::sig::Vector ktauToRaw; ktauToRaw.resize(_njoints, 1.0);
564 for (size_t i = 0; i < _njoints; i++) { bemfToRaw [i] = _newtonsToSensor[i] / _angleToEncoder[i];}
565 for (size_t i = 0; i < _njoints; i++) { ktauToRaw[i] = _dutycycleToPWM[i] / _newtonsToSensor[i]; }
566 ControlBoardHelper cb(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor, _ampsToSensor, _dutycycleToPWM);
568 ImplementControlCalibration::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
569 ImplementAmplifierControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
570 ImplementEncodersTimed::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
571 ImplementMotorEncoders::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
572 ImplementPositionControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
573 ImplementPidControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor, _ampsToSensor, _dutycycleToPWM);
574 ImplementPidControl::setConversionUnits(PidControlTypeEnum::VOCAB_PIDTYPE_POSITION, PidFeedbackUnitsEnum::METRIC, PidOutputUnitsEnum::DUTYCYCLE_PWM_PERCENT);
575 ImplementPidControl::setConversionUnits(PidControlTypeEnum::VOCAB_PIDTYPE_TORQUE, PidFeedbackUnitsEnum::METRIC, PidOutputUnitsEnum::DUTYCYCLE_PWM_PERCENT);
576 ImplementControlMode::initialize(_njoints, _axisMap);
577 ImplementVelocityControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
578 ImplementVelocityDirect::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
579 ImplementControlLimits::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
580 ImplementImpedanceControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor);
581 ImplementTorqueControl::initialize(_njoints, _axisMap, _angleToEncoder, nullptr, _newtonsToSensor, _ampsToSensor, _dutycycleToPWM, bemfToRaw.data(), ktauToRaw.data());
582 ImplementPositionDirect::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
583 ImplementInteractionMode::initialize(_njoints, _axisMap, _angleToEncoder, nullptr);
584 ImplementMotor::initialize(_njoints, _axisMap);
585 ImplementAxisInfo::initialize(_njoints, _axisMap);
586 ImplementPWMControl::initialize(_njoints, _axisMap, _dutycycleToPWM);
587 ImplementCurrentControl::initialize(_njoints, _axisMap, _ampsToSensor);
588 ImplementVirtualAnalogSensor::initialize(_njoints, _axisMap, _newtonsToSensor);
589 ImplementJointFault::initialize(_njoints, _axisMap);
590 ImplementJointBrake::initialize(_njoints, _axisMap);
591
592 //start the rateThread
593 bool init = this->start();
594 if(!init)
595 {
596 yCError(FAKEMOTIONCONTROL) << "open() has an error in call of FakeMotionControl::init() for board" ;
597 return false;
598 }
599 else
600 {
601 if(verbosewhenok)
602 {
603 yCDebug(FAKEMOTIONCONTROL) << "init() has successfully initted board ";
604 }
605 }
606 opened = true;
607
608 return true;
609}
610
612{
613 size_t i;
614
615 // AxisMap
616 if (!m_GENERAL_AxisMap.empty())
617 {
618 for (i = 0; i < m_GENERAL_AxisMap.size(); i++) {
619 _axisMap[i] = m_GENERAL_AxisMap[i];
620 }
621 }
622 else
623 {
624 for (i = 0; i < _njoints; i++) {
625 _axisMap[i] = i;
626 }
627 }
628 for (i = 0; i < _njoints; i++) {yDebug() << "_axisMap: " << _axisMap[i] << " "; }
629
630 // AxisName
631 if (!m_GENERAL_AxisName.empty())
632 {
633 for (i = 0; i < m_GENERAL_AxisName.size(); i++) {
634 _axisName[_axisMap[i]] = m_GENERAL_AxisName[i];
635 }
636 }
637 else
638 {
639 for (i = 0; i < _njoints; i++) {
640 _axisName[_axisMap[i]] = "joint" + toString(i);
641 }
642 }
643 for (i = 0; i < _njoints; i++) { yDebug() << "_axisName: " << _axisName[_axisMap[i]] << " "; }
644
645 // Axis Type
646 if (!m_GENERAL_AxisType.empty())
647 {
648 //beware: axis type has to be remapped here because they are not set using the toHw() helper function
649 for (i = 0; i < m_GENERAL_AxisType.size(); i++)
650 {
651 std::string typeString = m_GENERAL_AxisType[i];
652 if (typeString == "revolute") {
653 _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_REVOLUTE;
654 }
655 else if (typeString == "prismatic") {
656 _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_PRISMATIC;
657 }
658 else {
659 yCError(FAKEMOTIONCONTROL, "Unknown AxisType value %s!", typeString.c_str());
660 _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_UNKNOWN;
661 return false;
662 }
663 }
664 }
665 else
666 {
667 yCInfo(FAKEMOTIONCONTROL) << "Using default AxisType (revolute)";
668 for (i = 0; i < _njoints; i++) {
669 _jointType[_axisMap[i]] = VOCAB_JOINTTYPE_REVOLUTE;
670 }
671 }
672
673 // current conversions factor
674 if (!m_GENERAL_ampsToSensor.empty())
675 {
676 for (i = 0; i < m_GENERAL_ampsToSensor.size(); i++) {
677 _ampsToSensor[i] = m_GENERAL_ampsToSensor[i];
678 }
679 }
680 else
681 {
682 yCInfo(FAKEMOTIONCONTROL) << "Using default ampsToSensor=1";
683 for (i = 0; i < _njoints; i++) {
684 _ampsToSensor[i] = 1;
685 }
686 }
687
688
689 // pwm conversions factor
690 if (!m_GENERAL_fullscalePWM.empty())
691 {
692 for (i = 0; i < m_GENERAL_fullscalePWM.size(); i++) {
693 _dutycycleToPWM[i] = m_GENERAL_fullscalePWM[i]/100;
694 }
695 }
696 else
697 {
698 yCInfo(FAKEMOTIONCONTROL) << "Using default fullscalePWM=1";
699 for (i = 0; i < _njoints; i++) {
700 _dutycycleToPWM[i] = 1;
701 }
702 }
703
704// double tmp_A2E;
705 // Encoder scales
706 if(!m_GENERAL_Encoder.empty())
707 {
708 for (i = 0; i < m_GENERAL_Encoder.size(); i++) {
709 _angleToEncoder[i] = m_GENERAL_Encoder[i]; }
710 }
711 else
712 {
713 yCInfo(FAKEMOTIONCONTROL) << "Using default Encoder=1";
714 for (i = 0; i < _njoints; i++) {
715 _angleToEncoder[i] = 1; }
716 }
717
719 if (!m_LIMITS_Max.empty())
720 {
721 for (i = 0; i < m_LIMITS_Max.size(); i++) {
722 _limitsMax[i] = m_LIMITS_Max[i];
723 }
724 }
725 else
726 {
727 yCInfo(FAKEMOTIONCONTROL) << "Using default m_LIMITS_Max=100";
728 for (i = 0; i < _njoints; i++) {
729 _limitsMax[i] = 100;
730 }
731 }
732
733 if (!m_LIMITS_Min.empty())
734 {
735 for (i = 0; i < m_LIMITS_Min.size(); i++) {
736 _limitsMin[i] = m_LIMITS_Min[i];
737 }
738 }
739 else
740 {
741 yCInfo(FAKEMOTIONCONTROL) << "Using default m_LIMITS_Min=0";
742 for (i = 0; i < _njoints; i++) {
743 _limitsMin[i] = 0;
744 }
745 }
746
747 return true;
748}
749
750
782
783void FakeMotionControl::cleanup()
784{
785
786}
787
788
789
791
793{
794 yCDebug(FAKEMOTIONCONTROL) << "setPidRaw" << pidtype << j << pid.kp;
795 switch (pidtype)
796 {
798 _ppids[j]=pid;
799 break;
801 _vpids[j]=pid;
802 break;
804 _cpids[j]=pid;
805 break;
807 _tpids[j]=pid;
808 break;
809 default:
810 break;
811 }
812 return true;
813}
814
816{
817 bool ret = true;
818 for(int j=0; j< _njoints; j++)
819 {
820 ret &= setPidRaw(pidtype, j, pids[j]);
821 }
822 return ret;
823}
824
826{
827 switch (pidtype)
828 {
830 _ppids_ref[j]=ref;
831 break;
833 _vpids_ref[j]=ref;
834 break;
836 _cpids_ref[j]=ref;
837 break;
839 _tpids_ref[j]=ref;
840 break;
841 default:
842 break;
843 }
844 return true;
845}
846
848{
849 bool ret = true;
850 for(int j=0, index=0; j< _njoints; j++, index++)
851 {
852 ret &= setPidReferenceRaw(pidtype, j, refs[index]);
853 }
854 return ret;
855}
856
858{
859 switch (pidtype)
860 {
862 _ppids_lim[j]=limit;
863 break;
865 _vpids_lim[j]=limit;
866 break;
868 _cpids_lim[j]=limit;
869 break;
871 _tpids_lim[j]=limit;
872 break;
873 default:
874 break;
875 }
876 return true;
877}
878
880{
881 bool ret = true;
882 for(int j=0, index=0; j< _njoints; j++, index++)
883 {
884 ret &= setPidErrorLimitRaw(pidtype, j, limits[index]);
885 }
886 return ret;
887}
888
890{
891 switch (pidtype)
892 {
894 *err=0.1;
895 break;
897 *err=0.2;
898 break;
900 *err=0.3;
901 break;
903 *err=0.4;
904 break;
905 default:
906 break;
907 }
908 return true;
909}
910
912{
913 bool ret = true;
914 for(int j=0; j< _njoints; j++)
915 {
916 ret &= getPidErrorRaw(pidtype, j, &errs[j]);
917 }
918 return ret;
919}
920
922{
923 switch (pidtype)
924 {
926 *pid=_ppids[j];
927 break;
929 *pid=_vpids[j];
930 break;
932 *pid=_cpids[j];
933 break;
935 *pid=_tpids[j];
936 break;
937 default:
938 break;
939 }
940 yCDebug(FAKEMOTIONCONTROL) << "getPidRaw" << pidtype << j << pid->kp;
941 return true;
942}
943
945{
946 bool ret = true;
947
948 // just one joint at time, wait answer before getting to the next.
949 // This is because otherwise too many msg will be placed into can queue
950 for(int j=0, index=0; j<_njoints; j++, index++)
951 {
952 ret &=getPidRaw(pidtype, j, &pids[j]);
953 }
954 return ret;
955}
956
958{
959 switch (pidtype)
960 {
962 *ref=_ppids_ref[j];
963 break;
965 *ref=_vpids_ref[j];
966 break;
968 *ref=_cpids_ref[j];
969 break;
971 *ref=_tpids_ref[j];
972 break;
973 default:
974 break;
975 }
976 return true;
977}
978
980{
981 bool ret = true;
982
983 // just one joint at time, wait answer before getting to the next.
984 // This is because otherwise too many msg will be placed into can queue
985 for(int j=0; j< _njoints; j++)
986 {
988 }
989 return ret;
990}
991
993{
994 switch (pidtype)
995 {
997 *limit=_ppids_lim[j];
998 break;
1000 *limit=_vpids_lim[j];
1001 break;
1003 *limit=_cpids_lim[j];
1004 break;
1006 *limit=_tpids_lim[j];
1007 break;
1008 default:
1009 break;
1010 }
1011 return true;
1012}
1013
1015{
1016 bool ret = true;
1017 for(int j=0, index=0; j<_njoints; j++, index++)
1018 {
1019 ret &=getPidErrorLimitRaw(pidtype, j, &limits[j]);
1020 }
1021 return ret;
1022}
1023
1025{
1026 return true;
1027}
1028
1030{
1031 switch (pidtype)
1032 {
1034 _ppids_ena[j]=false;
1035 break;
1037 _vpids_ena[j]=false;
1038 break;
1040 _cpids_ena[j]=false;
1041 break;
1043 _tpids_ena[j]=false;
1044 break;
1045 default:
1046 break;
1047 }
1048 return true;
1049}
1050
1052{
1053 switch (pidtype)
1054 {
1056 _ppids_ena[j]=true;
1057 break;
1059 _vpids_ena[j]=true;
1060 break;
1062 _cpids_ena[j]=true;
1063 break;
1065 _tpids_ena[j]=true;
1066 break;
1067 default:
1068 break;
1069 }
1070 return true;
1071}
1072
1074{
1075 yCDebug(FAKEMOTIONCONTROL) << "setPidOffsetRaw" << pidtype << j << v;
1076 switch (pidtype)
1077 {
1079 _ppids[j].offset=v;
1080 break;
1082 _vpids[j].offset=v;
1083 break;
1085 _cpids[j].offset=v;
1086 break;
1088 _tpids[j].offset=v;
1089 break;
1090 default:
1091 break;
1092 }
1093 return true;
1094}
1095
1097{
1098 switch (pidtype)
1099 {
1101 *enabled=_ppids_ena[j];
1102 break;
1104 *enabled=_vpids_ena[j];
1105 break;
1107 *enabled=_cpids_ena[j];
1108 break;
1110 *enabled=_tpids_ena[j];
1111 break;
1112 default:
1113 break;
1114 }
1115 return true;
1116}
1117
1119{
1120 switch (pidtype)
1121 {
1123 *out=1.1 + j * 10;
1124 break;
1126 *out=1.2 + j * 10;
1127 break;
1129 *out=1.3 + j * 10;
1130 break;
1132 *out=1.4 + j * 10;
1133 break;
1134 default:
1135 break;
1136 }
1137 yCDebug(FAKEMOTIONCONTROL) << "getPidOutputRaw" << pidtype << j << *out;
1138 return true;
1139}
1140
1142{
1143 bool ret = true;
1144 for(int j=0; j< _njoints; j++)
1145 {
1146 ret &= getPidOutputRaw(pidtype, j, &outs[j]);
1147 }
1148 return ret;
1149}
1150
1152// Velocity control interface raw //
1154
1156{
1157 int mode=0;
1159 if( (mode != VOCAB_CM_VELOCITY) &&
1160 (mode != VOCAB_CM_MIXED) &&
1162 (mode != VOCAB_CM_IDLE))
1163 {
1164 yCError(FAKEMOTIONCONTROL) << "velocityMoveRaw: skipping command because board " << " joint " << j << " is not in VOCAB_CM_VELOCITY mode";
1165 }
1166 _command_speeds[j] = sp;
1167 last_velocity_command[j]=yarp::os::Time::now();
1168 return true;
1169}
1170
1172{
1174 bool ret = true;
1175 for (int i = 0; i < _njoints; i++) {
1176 ret &= velocityMoveRaw(i, sp[i]);
1177 }
1178 return ret;
1179}
1180
1181
1183// Calibration control interface //
1185
1187{
1188 yCTrace(FAKEMOTIONCONTROL) << "setCalibrationParametersRaw for joint" << j;
1189 return true;
1190}
1191
1192bool FakeMotionControl::calibrateAxisWithParamsRaw(int j, unsigned int type, double p1, double p2, double p3)
1193{
1194 yCTrace(FAKEMOTIONCONTROL) << "calibrateRaw for joint" << j;
1195 return true;
1196}
1197
1199{
1200 return NOT_YET_IMPLEMENTED("calibrationDoneRaw");
1201}
1202
1204// Position control interface //
1206
1208{
1209 *ax=_njoints;
1210
1211 return true;
1212}
1213
1215{
1216 if (verbose >= VERY_VERBOSE) {
1217 yCTrace(FAKEMOTIONCONTROL) << "j " << j << " ref " << ref;
1218 }
1219
1220// if (yarp::os::Time::now()-_last_position_move_time[j]<MAX_POSITION_MOVE_INTERVAL)
1221// {
1222// 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.";
1223// }
1224// _last_position_move_time[j] = yarp::os::Time::now();
1225
1226 int mode = 0;
1228 if( (mode != VOCAB_CM_POSITION) &&
1229 (mode != VOCAB_CM_MIXED) &&
1231 (mode != VOCAB_CM_IDLE))
1232 {
1233 yCError(FAKEMOTIONCONTROL) << "positionMoveRaw: skipping command because joint " << j << " is not in VOCAB_CM_POSITION mode";
1234 }
1235 _posCtrl_references[j] = ref;
1236 return true;
1237}
1238
1240{
1241 if (verbose >= VERY_VERBOSE) {
1243 }
1244
1245 bool ret = true;
1246 for(int j=0, index=0; j< _njoints; j++, index++)
1247 {
1248 ret &= positionMoveRaw(j, refs[index]);
1249 }
1250 return ret;
1251}
1252
1254{
1255 if (verbose >= VERY_VERBOSE) {
1256 yCTrace(FAKEMOTIONCONTROL) << "j " << j << " ref " << delta;
1257 }
1258// if (yarp::os::Time::now()-_last_position_move_time[j]<MAX_POSITION_MOVE_INTERVAL)
1259// {
1260// 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.";
1261// }
1262// _last_position_move_time[j] = yarp::os::Time::now();
1263
1264 int mode = 0;
1266 if( (mode != VOCAB_CM_POSITION) &&
1267 (mode != VOCAB_CM_MIXED) &&
1269 (mode != VOCAB_CM_IDLE))
1270 {
1271 yCError(FAKEMOTIONCONTROL) << "relativeMoveRaw: skipping command because joint " << j << " is not in VOCAB_CM_POSITION mode";
1272 }
1273 _posCtrl_references[j] += delta;
1274 return true;
1275}
1276
1278{
1279 if (verbose >= VERY_VERBOSE) {
1281 }
1282
1283 bool ret = true;
1284 for(int j=0, index=0; j< _njoints; j++, index++)
1285 {
1286 ret &= relativeMoveRaw(j, deltas[index]);
1287 }
1288 return ret;
1289}
1290
1291
1293{
1294 if (verbose >= VERY_VERBOSE) {
1295 yCTrace(FAKEMOTIONCONTROL) << "j ";
1296 }
1297
1298 *flag = false;
1299 return true;
1300}
1301
1303{
1304 if (verbose >= VERY_VERBOSE) {
1306 }
1307
1308 bool ret = true;
1309 bool val, tot_res = true;
1310
1311 for(int j=0, index=0; j< _njoints; j++, index++)
1312 {
1313 ret &= checkMotionDoneRaw(j, &val);
1314 tot_res &= val;
1315 }
1316 *flag = tot_res;
1317 return ret;
1318}
1319
1321{
1322 // Velocity is expressed in iDegrees/s
1323 // save internally the new value of speed; it'll be used in the positionMove
1324 int index = j ;
1325 _ref_speeds[index] = sp;
1326 return true;
1327}
1328
1330{
1331 // Velocity is expressed in iDegrees/s
1332 // save internally the new value of speed; it'll be used in the positionMove
1333 for(int j=0, index=0; j< _njoints; j++, index++)
1334 {
1335 _ref_speeds[index] = spds[index];
1336 }
1337 return true;
1338}
1339
1341{
1342 // Acceleration is expressed in iDegrees/s^2
1343 // save internally the new value of the acceleration; it'll be used in the velocityMove command
1344
1345 if (acc > 1e6)
1346 {
1347 _ref_accs[j ] = 1e6;
1348 }
1349 else if (acc < -1e6)
1350 {
1351 _ref_accs[j ] = -1e6;
1352 }
1353 else
1354 {
1355 _ref_accs[j ] = acc;
1356 }
1357
1358 return true;
1359}
1360
1362{
1363 // Acceleration is expressed in iDegrees/s^2
1364 // save internally the new value of the acceleration; it'll be used in the velocityMove command
1365 for(int j=0, index=0; j< _njoints; j++, index++)
1366 {
1367 if (accs[j] > 1e6)
1368 {
1369 _ref_accs[index] = 1e6;
1370 }
1371 else if (accs[j] < -1e6)
1372 {
1373 _ref_accs[index] = -1e6;
1374 }
1375 else
1376 {
1377 _ref_accs[index] = accs[j];
1378 }
1379 }
1380 return true;
1381}
1382
1384{
1385 *spd = _ref_speeds[j];
1386 return true;
1387}
1388
1390{
1391 memcpy(spds, _ref_speeds, sizeof(double) * _njoints);
1392 return true;
1393}
1394
1396{
1397 *acc = _ref_accs[j];
1398 return true;
1399}
1400
1402{
1403 memcpy(accs, _ref_accs, sizeof(double) * _njoints);
1404 return true;
1405}
1406
1408{
1409 velocityMoveRaw(j,0);
1410 return true;
1411}
1412
1414{
1415 bool ret = true;
1416 for(int j=0; j< _njoints; j++)
1417 {
1418 ret &= stopRaw(j);
1419 }
1420 return ret;
1421}
1423
1425// Position control2 interface //
1427
1428bool FakeMotionControl::positionMoveRaw(const int n_joint, const int *joints, const double *refs)
1429{
1430 if (verbose >= VERY_VERBOSE) {
1431 yCTrace(FAKEMOTIONCONTROL) << " -> n_joint " << n_joint;
1432 }
1433
1434 for(int j=0; j<n_joint; j++)
1435 {
1436 yCDebug(FAKEMOTIONCONTROL, "j: %d; ref %f;\n", joints[j], refs[j]); fflush(stdout);
1437 }
1438
1439 bool ret = true;
1440 for(int j=0; j<n_joint; j++)
1441 {
1442 ret = ret &&positionMoveRaw(joints[j], refs[j]);
1443 }
1444 return ret;
1445}
1446
1447bool FakeMotionControl::relativeMoveRaw(const int n_joint, const int *joints, const double *deltas)
1448{
1449 if (verbose >= VERY_VERBOSE) {
1450 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1451 }
1452
1453 bool ret = true;
1454 for(int j=0; j<n_joint; j++)
1455 {
1456 ret = ret &&relativeMoveRaw(joints[j], deltas[j]);
1457 }
1458 return ret;
1459}
1460
1462{
1463 if (verbose >= VERY_VERBOSE) {
1464 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1465 }
1466
1467 bool ret = true;
1468 bool val = true;
1469 bool tot_val = true;
1470
1471 for(int j=0; j<n_joint; j++)
1472 {
1473 ret = ret && checkMotionDoneRaw(joints[j], &val);
1474 tot_val &= val;
1475 }
1476 *flag = tot_val;
1477 return ret;
1478}
1479
1480bool FakeMotionControl::setRefSpeedsRaw(const int n_joint, const int *joints, const double *spds)
1481{
1482 if (verbose >= VERY_VERBOSE) {
1483 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1484 }
1485
1486 bool ret = true;
1487 for(int j=0; j<n_joint; j++)
1488 {
1489 ret = ret &&setRefSpeedRaw(joints[j], spds[j]);
1490 }
1491 return ret;
1492}
1493
1494bool FakeMotionControl::setRefAccelerationsRaw(const int n_joint, const int *joints, const double *accs)
1495{
1496 if (verbose >= VERY_VERBOSE) {
1497 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1498 }
1499
1500 bool ret = true;
1501 for(int j=0; j<n_joint; j++)
1502 {
1504 }
1505 return ret;
1506}
1507
1508bool FakeMotionControl::getRefSpeedsRaw(const int n_joint, const int *joints, double *spds)
1509{
1510 if (verbose >= VERY_VERBOSE) {
1511 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1512 }
1513
1514 bool ret = true;
1515 for(int j=0; j<n_joint; j++)
1516 {
1517 ret = ret && getRefSpeedRaw(joints[j], &spds[j]);
1518 }
1519 return ret;
1520}
1521
1523{
1524 if (verbose >= VERY_VERBOSE) {
1525 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1526 }
1527
1528 bool ret = true;
1529 for(int j=0; j<n_joint; j++)
1530 {
1531 ret = ret && getRefAccelerationRaw(joints[j], &accs[j]);
1532 }
1533 return ret;
1534}
1535
1536bool FakeMotionControl::stopRaw(const int n_joint, const int *joints)
1537{
1538 if (verbose >= VERY_VERBOSE) {
1539 yCTrace(FAKEMOTIONCONTROL) << "n_joint " << _njoints;
1540 }
1541
1542 bool ret = true;
1543 for(int j=0; j<n_joint; j++)
1544 {
1545 ret = ret &&stopRaw(joints[j]);
1546 }
1547 return ret;
1548}
1549
1551
1552// ControlMode
1553
1554// puo' essere richiesto con get
1556{
1557 if (verbose > VERY_VERY_VERBOSE) {
1558 yCTrace(FAKEMOTIONCONTROL) << "j: " << j;
1559 }
1560
1561 *v = _controlModes[j];
1562 return true;
1563}
1564
1565// IControl Mode 2
1567{
1568 bool ret = true;
1569 for(int j=0; j< _njoints; j++)
1570 {
1571 ret = ret && getControlModeRaw(j, &v[j]);
1572 }
1573 return ret;
1574}
1575
1577{
1578 bool ret = true;
1579 for(int j=0; j< n_joint; j++)
1580 {
1581 ret = ret && getControlModeRaw(joints[j], &modes[j]);
1582 }
1583 return ret;
1584}
1585
1587{
1588 if (verbose >= VERY_VERBOSE) {
1589 yCTrace(FAKEMOTIONCONTROL) << "j: " << j << " mode: " << yarp::os::Vocab32::decode(_mode);
1590 }
1591
1593 {
1594 _controlModes[j] = VOCAB_CM_IDLE;
1595 }
1596 else
1597 {
1598 _controlModes[j] = _mode;
1599 }
1600 _posCtrl_references[j] = pos[j];
1601 return true;
1602}
1603
1604
1606{
1607 if (verbose >= VERY_VERBOSE) {
1608 yCTrace(FAKEMOTIONCONTROL) << "n_joints: " << n_joint;
1609 }
1610
1611 bool ret = true;
1612 for(int i=0; i<n_joint; i++)
1613 {
1614 ret &= setControlModeRaw(joints[i], modes[i]);
1615 }
1616 return ret;
1617}
1618
1620{
1621 if (verbose >= VERY_VERBOSE) {
1623 }
1624
1625 bool ret = true;
1626 for(int i=0; i<_njoints; i++)
1627 {
1628 ret &= setControlModeRaw(i, modes[i]);
1629 }
1630 return ret;
1631}
1632
1633
1635
1637{
1638 return NOT_YET_IMPLEMENTED("setEncoder");
1639}
1640
1642{
1643 return NOT_YET_IMPLEMENTED("setEncoders");
1644}
1645
1647{
1648 return NOT_YET_IMPLEMENTED("resetEncoder");
1649}
1650
1652{
1653 return NOT_YET_IMPLEMENTED("resetEncoders");
1654}
1655
1656bool FakeMotionControl::getEncoderRaw(int j, double *value)
1657{
1658 bool ret = true;
1659
1660 // To simulate a real controlboard, we assume that the joint
1661 // encoders is exactly the last set by setPosition(s) or positionMove
1662 *value = pos[j];
1663
1664 return ret;
1665}
1666
1668{
1669 bool ret = true;
1670 for(int j=0; j< _njoints; j++)
1671 {
1672 bool ok = getEncoderRaw(j, &encs[j]);
1673 ret = ret && ok;
1674
1675 }
1676 return ret;
1677}
1678
1680{
1681 // To avoid returning uninitialized memory, we set the encoder speed to 0
1682 *sp = 0.0;
1683 return true;
1684}
1685
1687{
1688 bool ret = true;
1689 for(int j=0; j< _njoints; j++)
1690 {
1691 ret &= getEncoderSpeedRaw(j, &spds[j]);
1692 }
1693 return ret;
1694}
1695
1697{
1698 // To avoid returning uninitialized memory, we set the encoder acc to 0
1699 *acc = 0.0;
1700
1701 return true;
1702}
1703
1705{
1706 bool ret = true;
1707 for(int j=0; j< _njoints; j++)
1708 {
1710 }
1711 return ret;
1712}
1713
1715
1717{
1718 bool ret = getEncodersRaw(encs);
1719 _mutex.lock();
1720 for (int i = 0; i < _njoints; i++) {
1721 stamps[i] = _encodersStamp[i] = _cycleTimestamp;
1722 }
1723 _mutex.unlock();
1724 return ret;
1725}
1726
1727bool FakeMotionControl::getEncoderTimedRaw(int j, double *encs, double *stamp)
1728{
1729 bool ret = getEncoderRaw(j, encs);
1730 _mutex.lock();
1731 *stamp = _encodersStamp[j] = _cycleTimestamp;
1732 _mutex.unlock();
1733
1734 return ret;
1735}
1736
1738
1740{
1741 *num=_njoints;
1742 return true;
1743}
1744
1745bool FakeMotionControl::setMotorEncoderRaw(int m, const double val)
1746{
1747 return NOT_YET_IMPLEMENTED("setMotorEncoder");
1748}
1749
1751{
1752 return NOT_YET_IMPLEMENTED("setMotorEncoders");
1753}
1754
1756{
1757 return NOT_YET_IMPLEMENTED("setMotorEncoderCountsPerRevolutionRaw");
1758}
1759
1761{
1762 return NOT_YET_IMPLEMENTED("getMotorEncoderCountsPerRevolutionRaw");
1763}
1764
1766{
1767 return NOT_YET_IMPLEMENTED("resetMotorEncoder");
1768}
1769
1771{
1772 return NOT_YET_IMPLEMENTED("reseMotortEncoders");
1773}
1774
1776{
1777 *value = pos[m]*10;
1778 return true;
1779}
1780
1782{
1783 bool ret = true;
1784 for(int j=0; j< _njoints; j++)
1785 {
1786 ret &= getMotorEncoderRaw(j, &encs[j]);
1787
1788 }
1789 return ret;
1790}
1791
1793{
1794 *sp = 0.0;
1795 return true;
1796}
1797
1799{
1800 bool ret = true;
1801 for(int j=0; j< _njoints; j++)
1802 {
1803 ret &= getMotorEncoderSpeedRaw(j, &spds[j]);
1804 }
1805 return ret;
1806}
1807
1809{
1810 *acc = 0.0;
1811 return true;
1812}
1813
1815{
1816 bool ret = true;
1817 for(int j=0; j< _njoints; j++)
1818 {
1820 }
1821 return ret;
1822}
1823
1825{
1826 bool ret = getMotorEncodersRaw(encs);
1827 _mutex.lock();
1828 for (int i = 0; i < _njoints; i++) {
1829 stamps[i] = _encodersStamp[i] = _cycleTimestamp;
1830 }
1831 _mutex.unlock();
1832
1833 return ret;
1834}
1835
1836bool FakeMotionControl::getMotorEncoderTimedRaw(int m, double *encs, double *stamp)
1837{
1838 bool ret = getMotorEncoderRaw(m, encs);
1839 _mutex.lock();
1840 *stamp = _encodersStamp[m] = _cycleTimestamp;
1841 _mutex.unlock();
1842
1843 return ret;
1844}
1846
1848
1850{
1851 return DEPRECATED("enableAmpRaw");
1852}
1853
1855{
1856 return DEPRECATED("disableAmpRaw");
1857}
1858
1859bool FakeMotionControl::getCurrentRaw(int j, double *value)
1860{
1861 //just for testing purposes, this is not a real implementation
1862 *value = current[j];
1863 return true;
1864}
1865
1867{
1868 //just for testing purposes, this is not a real implementation
1869 bool ret = true;
1870 for(int j=0; j< _njoints; j++)
1871 {
1872 ret &= getCurrentRaw(j, &vals[j]);
1873 }
1874 return ret;
1875}
1876
1878{
1879 maxCurrent[m] = val;
1880 return true;
1881}
1882
1884{
1885 *val = maxCurrent[m];
1886 return true;
1887}
1888
1890{
1891 (_enabledAmp[j ]) ? *st = 1 : *st = 0;
1892 return true;
1893}
1894
1896{
1897 bool ret = true;
1898 for(int j=0; j<_njoints; j++)
1899 {
1900 sts[j] = _enabledAmp[j];
1901 }
1902 return ret;
1903}
1904
1906{
1907 *val = peakCurrent[m];
1908 return true;
1909}
1910
1911bool FakeMotionControl::setPeakCurrentRaw(int m, const double val)
1912{
1913 peakCurrent[m] = val;
1914 return true;
1915}
1916
1918{
1919 *val = nominalCurrent[m];
1920 return true;
1921}
1922
1924{
1925 nominalCurrent[m] = val;
1926 return true;
1927}
1928
1929bool FakeMotionControl::getPWMRaw(int m, double *val)
1930{
1931 *val = pwm[m];
1932 return true;
1933}
1934
1936{
1937 *val = pwmLimit[m];
1938 return true;
1939}
1940
1941bool FakeMotionControl::setPWMLimitRaw(int m, const double val)
1942{
1943 pwmLimit[m] = val;
1944 return true;
1945}
1946
1948{
1949 *val = supplyVoltage[m];
1950 return true;
1951}
1952
1953
1954// Limit interface
1955bool FakeMotionControl::setLimitsRaw(int j, double min, double max)
1956{
1957 bool ret = true;
1958 return ret;
1959}
1960
1961bool FakeMotionControl::getLimitsRaw(int j, double *min, double *max)
1962{
1963 *min = _limitsMin[j];
1964 *max = _limitsMax[j];
1965 return true;
1966}
1967
1969{
1970 return NOT_YET_IMPLEMENTED("getGearboxRatioRaw");
1971}
1972
1973bool FakeMotionControl::setGearboxRatioRaw(int m, const double val)
1974{
1975 return NOT_YET_IMPLEMENTED("setGearboxRatioRaw");
1976}
1977
1979{
1980 return NOT_YET_IMPLEMENTED("getTorqueControlFilterType");
1981}
1982
1984{
1985 return NOT_YET_IMPLEMENTED("getRotorEncoderResolutionRaw");
1986}
1987
1989{
1990 return NOT_YET_IMPLEMENTED("getJointEncoderResolutionRaw");
1991}
1992
1994{
1995 return NOT_YET_IMPLEMENTED("getJointEncoderTypeRaw");
1996}
1997
1999{
2000 return NOT_YET_IMPLEMENTED("getRotorEncoderTypeRaw");
2001}
2002
2004{
2005 return NOT_YET_IMPLEMENTED("getKinematicMJRaw");
2006}
2007
2009{
2010 return NOT_YET_IMPLEMENTED("getHasTempSensorsRaw");
2011}
2012
2014{
2015 return NOT_YET_IMPLEMENTED("getHasHallSensorRaw");
2016}
2017
2019{
2020 return NOT_YET_IMPLEMENTED("getHasRotorEncoderRaw");
2021}
2022
2024{
2025 return NOT_YET_IMPLEMENTED("getHasRotorEncoderIndexRaw");
2026}
2027
2029{
2030 return NOT_YET_IMPLEMENTED("getMotorPolesRaw");
2031}
2032
2034{
2035 return NOT_YET_IMPLEMENTED("getRotorIndexOffsetRaw");
2036}
2037
2038bool FakeMotionControl::getAxisNameRaw(int axis, std::string& name)
2039{
2040 if (axis >= 0 && axis < _njoints)
2041 {
2042 name = _axisName[axis];
2043 return true;
2044 }
2045 else
2046 {
2047 name = "ERROR";
2048 return false;
2049 }
2050}
2051
2053{
2054 if (axis >= 0 && axis < _njoints)
2055 {
2056 type = _jointType[axis];
2057 return true;
2058 }
2059 else
2060 {
2061 return false;
2062 }
2063}
2064
2065// IControlLimits
2066bool FakeMotionControl::setVelLimitsRaw(int axis, double min, double max)
2067{
2068 return NOT_YET_IMPLEMENTED("setVelLimitsRaw");
2069}
2070
2071bool FakeMotionControl::getVelLimitsRaw(int axis, double *min, double *max)
2072{
2073 *min = 0.0;
2074 *max = _maxJntCmdVelocity[axis];
2075 return true;
2076}
2077
2078
2079// Torque control
2081{
2082 *t = _torques[j];
2083 return true;
2084}
2085
2087{
2088 for (int i = 0; i < _njoints; i++)
2089 {
2090 t[i]= _torques[i];
2091 }
2092 return true;
2093}
2094
2095bool FakeMotionControl::getTorqueRangeRaw(int j, double *min, double *max)
2096{
2097 *min = -100;
2098 *max = 100;
2099 return true;
2100}
2101
2102bool FakeMotionControl::getTorqueRangesRaw(double *min, double *max)
2103{
2104 bool ret = true;
2105 for (int j = 0; j < _njoints && ret; j++) {
2106 ret &= getTorqueRangeRaw(j, &min[j], &max[j]);
2107 }
2108 return ret;
2109}
2110
2112{
2113 bool ret = true;
2114 for (int j = 0; j < _njoints && ret; j++) {
2115 ret &= setRefTorqueRaw(j, t[j]);
2116 }
2117 return ret;
2118}
2119
2121{
2122 _mutex.lock();
2123 _ref_torques[j]=t;
2124
2125 if (t>1.0 || t< -1.0)
2126 {
2127 yCError(FAKEMOTIONCONTROL) << "Joint received a high torque command, and was put in hardware fault";
2128 _hwfault_code[j] = 1;
2129 _hwfault_message[j] = "test" + std::to_string(j) + " torque";
2130 _controlModes[j] = VOCAB_CM_HW_FAULT;
2131 }
2132 _mutex.unlock();
2133 return true;
2134}
2135
2136bool FakeMotionControl::setRefTorquesRaw(const int n_joint, const int *joints, const double *t)
2137{
2138 return NOT_YET_IMPLEMENTED("setRefTorquesRaw");
2139}
2140
2142{
2143 bool ret = true;
2144 for (int j = 0; j < _njoints && ret; j++) {
2145 ret &= getRefTorqueRaw(j, &_ref_torques[j]);
2146 }
2147 return true;
2148}
2149
2151{
2152 _mutex.lock();
2153 *t = _ref_torques[j];
2154 _mutex.unlock();
2155 return true;
2156}
2157
2158bool FakeMotionControl::getImpedanceRaw(int j, double *stiffness, double *damping)
2159{
2160 _mutex.lock();
2161 *stiffness = _stiffness[j];
2162 *damping = _damping[j];
2163 _mutex.unlock();
2164 return true;
2165}
2166
2167bool FakeMotionControl::setImpedanceRaw(int j, double stiffness, double damping)
2168{
2169 _mutex.lock();
2170 _stiffness[j] = stiffness;
2171 _damping[j] = damping;
2172 _mutex.unlock();
2173 return true;
2174}
2175
2177{
2178 _mutex.lock();
2179 _force_offset[j] = offset;
2180 _mutex.unlock();
2181 return true;
2182}
2183
2185{
2186 _mutex.lock();
2187 *offset = _force_offset[j];
2188 _mutex.unlock();
2189 return true;
2190}
2191
2192bool FakeMotionControl::getCurrentImpedanceLimitRaw(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp)
2193{
2194 *min_stiff=1.0;
2195 *max_stiff=10.0;
2196 *min_damp=2.0;
2197 *max_damp=20.0;
2198 return true;
2199}
2200
2202{
2203 params->bemf = _kbemf[j];
2204 params->bemf_scale = _kbemf_scale[j];
2205 params->ktau = _ktau[j];
2206 params->ktau_scale = _ktau_scale[j];
2207 params->viscousPos = _viscousPos[j];
2208 params->viscousNeg = _viscousNeg[j];
2209 params->coulombPos = _coulombPos[j];
2210 params->coulombNeg = _coulombNeg[j];
2211 params->velocityThres = _velocityThres[j];
2212 yCDebug(FAKEMOTIONCONTROL) << "getMotorTorqueParamsRaw" << params->bemf
2213 << params->bemf_scale
2214 << params->ktau
2215 << params->ktau_scale
2216 << params->viscousPos
2217 << params->viscousNeg
2218 << params->coulombPos
2219 << params->coulombNeg
2220 << params->velocityThres;
2221 return true;
2222}
2223
2225{
2226 _kbemf[j] = params.bemf;
2227 _ktau[j] = params.ktau;
2228 _kbemf_scale[j] = params.bemf_scale;
2229 _ktau_scale[j] = params.ktau_scale;
2230 _viscousPos[j] = params.viscousPos;
2231 _viscousNeg[j] = params.viscousNeg;
2232 _coulombPos[j] = params.coulombPos;
2233 _coulombNeg[j] = params.coulombNeg;
2234 _velocityThres[j] = params.velocityThres;
2235 yCDebug(FAKEMOTIONCONTROL) << "setMotorTorqueParamsRaw" << params.bemf
2236 << params.bemf_scale
2237 << params.ktau
2238 << params.ktau_scale
2239 << params.viscousPos
2240 << params.viscousNeg
2241 << params.coulombPos
2242 << params.coulombNeg
2243 << params.velocityThres;
2244 return true;
2245}
2246
2247// IVelocityControl interface
2248bool FakeMotionControl::velocityMoveRaw(const int n_joint, const int *joints, const double *spds)
2249{
2250 bool ret = true;
2251 for(int i=0; i<n_joint; i++)
2252 {
2253 ret &= velocityMoveRaw(joints[i], spds[i]);
2254 }
2255 return ret;
2256}
2257
2258// PositionDirect Interface
2260{
2261 _posDir_references[j] = ref;
2262 return true;
2263}
2264
2265bool FakeMotionControl::setPositionsRaw(const int n_joint, const int *joints, const double *refs)
2266{
2267 for(int i=0; i< n_joint; i++)
2268 {
2269 _posDir_references[joints[i]] = refs[i];
2270 }
2271 return true;
2272}
2273
2275{
2276 for(int i=0; i< _njoints; i++)
2277 {
2278 _posDir_references[i] = refs[i];
2279 }
2280 return true;
2281}
2282
2283
2285{
2286 if (verbose >= VERY_VERBOSE) {
2287 yCTrace(FAKEMOTIONCONTROL) << "j " << axis << " ref " << _posCtrl_references[axis];
2288 }
2289
2290 int mode = 0;
2292 if( (mode != VOCAB_CM_POSITION) &&
2293 (mode != VOCAB_CM_MIXED) &&
2295 {
2296 yCWarning(FAKEMOTIONCONTROL) << "getTargetPosition: Joint " << axis << " is not in POSITION mode, therefore the value returned by " <<
2297 "this call is for reference only and may not reflect the actual behaviour of the motor/firmware.";
2298 }
2299 *ref = _posCtrl_references[axis];
2300 return true;
2301}
2302
2304{
2305 bool ret = true;
2306 for (int i = 0; i < _njoints; i++) {
2307 ret &= getTargetPositionRaw(i, &refs[i]);
2308 }
2309 return ret;
2310}
2311
2312bool FakeMotionControl::getTargetPositionsRaw(int nj, const int * jnts, double *refs)
2313{
2314 bool ret = true;
2315 for (int i = 0; i<nj; i++)
2316 {
2317 ret &= getTargetPositionRaw(jnts[i], &refs[i]);
2318 }
2319 return ret;
2320}
2321
2323{
2324 *ref = _command_speeds[axis];
2325 return true;
2326}
2327
2329{
2330 bool ret = true;
2331 for (int i = 0; i<_njoints; i++)
2332 {
2333 ret &= getRefVelocityRaw(i, &refs[i]);
2334 }
2335 return ret;
2336}
2337
2338bool FakeMotionControl::getRefVelocitiesRaw(int nj, const int * jnts, double *refs)
2339{
2340 bool ret = true;
2341 for (int i = 0; i<nj; i++)
2342 {
2343 ret &= getRefVelocityRaw(jnts[i], &refs[i]);
2344 }
2345 return ret;
2346}
2347
2349{
2350 int mode = 0;
2352 if( (mode != VOCAB_CM_POSITION) &&
2353 (mode != VOCAB_CM_MIXED) &&
2356 {
2357 yCWarning(FAKEMOTIONCONTROL) << "getRefPosition: Joint " << axis << " is not in POSITION_DIRECT mode, therefore the value returned by \
2358 this call is for reference only and may not reflect the actual behaviour of the motor/firmware.";
2359 }
2360
2361 *ref = _posDir_references[axis];
2362
2363 return true;
2364}
2365
2367{
2368 bool ret = true;
2369 for (int i = 0; i<_njoints; i++)
2370 {
2371 ret &= getRefPositionRaw(i, &refs[i]);
2372 }
2373 return ret;
2374}
2375
2376bool FakeMotionControl::getRefPositionsRaw(int nj, const int * jnts, double *refs)
2377{
2378 bool ret = true;
2379 for (int i = 0; i<nj; i++)
2380 {
2381 ret &= getRefPositionRaw(jnts[i], &refs[i]);
2382 }
2383 return ret;
2384}
2385
2386
2387// InteractionMode
2389{
2390 if (verbose > VERY_VERY_VERBOSE) {
2391 yCTrace(FAKEMOTIONCONTROL) << "j: " << j;
2392 }
2393
2394 *_mode = (yarp::dev::InteractionModeEnum)_interactMode[j];
2395 return true;}
2396
2398{
2399 bool ret = true;
2400 for(int j=0; j< n_joints; j++)
2401 {
2403 }
2404 return ret;
2405
2406}
2407
2409{
2410 bool ret = true;
2411 for (int j = 0; j < _njoints; j++) {
2412 ret = ret && getInteractionModeRaw(j, &modes[j]);
2413 }
2414 return ret;
2415}
2416
2417// marco.accame: con alberto cardellino abbiamo parlato della correttezza di effettuare la verifica di quanto imposto (in setInteractionModeRaw() ed affini)
2418// andando a rileggere il valore nella scheda eth fino a che esso non sia quello atteso. si deve fare oppure no?
2419// con il interaction mode il can ora non lo fa. mentre lo fa per il control mode. perche' diverso?
2421{
2422 if (verbose >= VERY_VERBOSE) {
2423 yCTrace(FAKEMOTIONCONTROL) << "j: " << j << " interaction mode: " << yarp::os::Vocab32::decode(_mode);
2424 }
2425
2426 _interactMode[j] = _mode;
2427
2428 return true;
2429}
2430
2431
2433{
2434 bool ret = true;
2435 for(int i=0; i<n_joints; i++)
2436 {
2438 }
2439 return ret;
2440}
2441
2443{
2444 bool ret = true;
2445 for(int i=0; i<_njoints; i++)
2446 {
2448 }
2449 return ret;
2450
2451}
2452
2454{
2455 *num=_njoints;
2456 return true;
2457}
2458
2460{
2461 *val = 37.5+double(m);
2462 return true;
2463}
2464
2466{
2467 bool ret = true;
2468 for(int j=0; j< _njoints; j++)
2469 {
2470 ret &= getTemperatureRaw(j, &vals[j]);
2471 }
2472 return ret;
2473}
2474
2476{
2477 return NOT_YET_IMPLEMENTED("getTemperatureLimitRaw");
2478}
2479
2481{
2482 return NOT_YET_IMPLEMENTED("setTemperatureLimitRaw");
2483}
2484
2485//PWM interface
2487{
2488 refpwm[j] = v;
2489 pwm[j] = v;
2490 last_pwm_command[j]=yarp::os::Time::now();
2491 return true;
2492}
2493
2495{
2496 for (int i = 0; i < _njoints; i++)
2497 {
2498 setRefDutyCycleRaw(i,v[i]);
2499 }
2500 return true;
2501}
2502
2504{
2505 *v = refpwm[j];
2506 return true;
2507}
2508
2510{
2511 for (int i = 0; i < _njoints; i++)
2512 {
2513 v[i] = refpwm[i];
2514 }
2515 return true;
2516}
2517
2519{
2520 *v = pwm[j];
2521 return true;
2522}
2523
2525{
2526 for (int i = 0; i < _njoints; i++)
2527 {
2528 v[i] = pwm[i];
2529 }
2530 return true;
2531}
2532
2533// Current interface
2534/*bool FakeMotionControl::getCurrentRaw(int j, double *t)
2535{
2536 return NOT_YET_IMPLEMENTED("getCurrentRaw");
2537}
2538
2539bool FakeMotionControl::getCurrentsRaw(double *t)
2540{
2541 return NOT_YET_IMPLEMENTED("getCurrentsRaw");
2542}
2543*/
2544
2545bool FakeMotionControl::getCurrentRangeRaw(int j, double *min, double *max)
2546{
2547 //just for testing purposes, this is not a real implementation
2548 *min = -3.5;
2549 *max = +3.5;
2550 return true;
2551}
2552
2553bool FakeMotionControl::getCurrentRangesRaw(double *min, double *max)
2554{
2555 //just for testing purposes, this is not a real implementation
2556 for (int i = 0; i < _njoints; i++)
2557 {
2558 min[i] = -3.5;
2559 max[i] = +3.5;
2560 }
2561 return true;
2562}
2563
2565{
2566 for (int i = 0; i < _njoints; i++)
2567 {
2568 _ref_currents[i] = t[i];
2569 current[i] = t[i] / 2;
2570 }
2571 return true;
2572}
2573
2575{
2576 _ref_currents[j] = t;
2577 current[j] = t / 2;
2578 return true;
2579}
2580
2581bool FakeMotionControl::setRefCurrentsRaw(const int n_joint, const int *joints, const double *t)
2582{
2583 bool ret = true;
2584 for (int j = 0; j<n_joint; j++)
2585 {
2586 ret = ret &&setRefCurrentRaw(joints[j], t[j]);
2587 }
2588 return ret;
2589}
2590
2592{
2593 for (int i = 0; i < _njoints; i++)
2594 {
2595 t[i] = _ref_currents[i];
2596 }
2597 return true;
2598}
2599
2601{
2602 *t = _ref_currents[j];
2603 return true;
2604}
2605
2610
2612{
2613 return _njoints;
2614}
2615
2617{
2618 for (int i = 0; i < _njoints; i++)
2619 {
2620 measure[i] = _torques[i];
2621 }
2622 return true;
2623}
2624
2626{
2627 _torques[ch] = measure;
2628 return true;
2629}
2630
2631bool FakeMotionControl::getLastJointFaultRaw(int j, int& fault, std::string& message)
2632{
2633 _mutex.lock();
2634 fault = _hwfault_code[j];
2635 message = _hwfault_message[j];
2636 _mutex.unlock();
2637 return true;
2638}
2639
2641{
2642 braked = _braked[j];
2643 return ReturnValue_ok;
2644}
2645
2647{
2648 _braked[j] = active;
2649 return ReturnValue_ok;
2650}
2651
2653{
2654 _autobraked[j] = enabled;
2655 return ReturnValue_ok;
2656}
2657
2659{
2660 enabled = _autobraked[j];
2661 return ReturnValue_ok;
2662}
2663
2665{
2666 axes = _njoints;
2667 return ReturnValue_ok;
2668}
2669
2671{
2673 if (jnt < 0 || jnt >= _njoints) {
2674 yCError(FAKEMOTIONCONTROL) << "setDesiredVelocityRaw: joint index out of bounds";
2675 return ReturnValue::return_code::return_value_error_method_failed;
2676 }
2677 if (vel < -_maxJntCmdVelocity[jnt] || vel > _maxJntCmdVelocity[jnt]) {
2678 yCError(FAKEMOTIONCONTROL) << "setDesiredVelocityRaw: velocity out of bounds for joint" << jnt;
2679 return ReturnValue::return_code::return_value_error_method_failed;
2680 }
2681 _mutex.lock();
2682 _dir_vel_commands[jnt] = vel;
2683 _mutex.unlock();
2684 return ReturnValue_ok;
2685}
2686
2688{
2691 for (int i = 0; i < _njoints; i++) {
2692 ret &= setDesiredVelocityRaw(i, vels[i]);
2693 }
2694 return ret;
2695}
2696
2697ReturnValue FakeMotionControl::setDesiredVelocityRaw(const std::vector<int>& jnts, const std::vector<double>& vels)
2698{
2700 if (jnts.size() != vels.size()) {
2701 yCError(FAKEMOTIONCONTROL) << "setDesiredVelocityRaw: jnts and vels vectors must have the same size";
2702 return ReturnValue::return_code::return_value_error_method_failed;
2703 }
2705 for (int i = 0; i < _njoints; i++) {
2707 }
2708 return ret;
2709}
2710
2712{
2714 if (jnt < 0 || jnt >= _njoints) {
2715 yCError(FAKEMOTIONCONTROL) << "setDesiredVelocityRaw: joint index out of bounds";
2716 return ReturnValue::return_code::return_value_error_method_failed;
2717 }
2718 _mutex.lock();
2719 vel = _dir_vel_commands[jnt];
2720 _mutex.unlock();
2721 return ReturnValue_ok;
2722}
2723
2725{
2728 vels.resize(_njoints);
2729 for (int i = 0; i < _njoints; i++) {
2730 ret &= getDesiredVelocityRaw(i, vels[i]);
2731 }
2732 return ret;
2733}
2734
2735ReturnValue FakeMotionControl::getDesiredVelocityRaw(const std::vector<int>& jnts, std::vector<double>& vels)
2736{
2738 if (jnts.size() != vels.size()) {
2739 yCError(FAKEMOTIONCONTROL) << "getDesiredVelocityRaw: jnts and vels vectors must have the same size";
2740 return ReturnValue::return_code::return_value_error_method_failed;
2741 }
2743 vels.resize(_njoints);
2744 for (int i = 0; i < _njoints; i++) {
2746 }
2747 return ret;
2748}
2749
2750/*
2751bool FakeMotionControl::parseImpedanceGroup_NewFormat(Bottle& pidsGroup, ImpedanceParameters vals[])
2752{
2753 int j=0;
2754 Bottle xtmp;
2755
2756 if (!extractGroup(pidsGroup, xtmp, "stiffness", "stiffness parameter", _njoints)) {
2757 return false;
2758 }
2759 for (j=0; j<_njoints; j++) {
2760 vals[j].stiffness = xtmp.get(j+1).asFloat64();
2761 }
2762
2763 if (!extractGroup(pidsGroup, xtmp, "damping", "damping parameter", _njoints)) {
2764 return false;
2765 }
2766 for (j=0; j<_njoints; j++) {
2767 vals[j].damping = xtmp.get(j+1).asFloat64();
2768 }
2769
2770 return true;
2771}
2772*/
2773
2774/*
2775bool FakeMotionControl::parsePositionPidsGroup(Bottle& pidsGroup, Pid myPid[])
2776{
2777 int j=0;
2778 Bottle xtmp;
2779
2780 if (!extractGroup(pidsGroup, xtmp, "kp", "Pid kp parameter", _njoints)) {
2781 return false;
2782 }
2783 for (j=0; j<_njoints; j++) {
2784 myPid[j].kp = xtmp.get(j+1).asFloat64();
2785 }
2786
2787 if (!extractGroup(pidsGroup, xtmp, "kd", "Pid kd parameter", _njoints)) {
2788 return false;
2789 }
2790 for (j=0; j<_njoints; j++) {
2791 myPid[j].kd = xtmp.get(j+1).asFloat64();
2792 }
2793
2794 if (!extractGroup(pidsGroup, xtmp, "ki", "Pid kp parameter", _njoints)) {
2795 return false;
2796 }
2797 for (j=0; j<_njoints; j++) {
2798 myPid[j].ki = xtmp.get(j+1).asFloat64();
2799 }
2800
2801 if (!extractGroup(pidsGroup, xtmp, "maxInt", "Pid maxInt parameter", _njoints)) {
2802 return false;
2803 }
2804 for (j=0; j<_njoints; j++) {
2805 myPid[j].max_int = xtmp.get(j+1).asFloat64();
2806 }
2807
2808 if (!extractGroup(pidsGroup, xtmp, "maxPwm", "Pid maxPwm parameter", _njoints)) {
2809 return false;
2810 }
2811 for (j=0; j<_njoints; j++) {
2812 myPid[j].max_output = xtmp.get(j+1).asFloat64();
2813 }
2814
2815 if (!extractGroup(pidsGroup, xtmp, "shift", "Pid shift parameter", _njoints)) {
2816 return false;
2817 }
2818 for (j=0; j<_njoints; j++) {
2819 myPid[j].scale = xtmp.get(j+1).asFloat64();
2820 }
2821
2822 if (!extractGroup(pidsGroup, xtmp, "ko", "Pid ko parameter", _njoints)) {
2823 return false;
2824 }
2825 for (j=0; j<_njoints; j++) {
2826 myPid[j].offset = xtmp.get(j+1).asFloat64();
2827 }
2828
2829 if (!extractGroup(pidsGroup, xtmp, "stictionUp", "Pid stictionUp", _njoints)) {
2830 return false;
2831 }
2832 for (j=0; j<_njoints; j++) {
2833 myPid[j].stiction_up_val = xtmp.get(j+1).asFloat64();
2834 }
2835
2836 if (!extractGroup(pidsGroup, xtmp, "stictionDwn", "Pid stictionDwn", _njoints)) {
2837 return false;
2838 }
2839 for (j=0; j<_njoints; j++) {
2840 myPid[j].stiction_down_val = xtmp.get(j+1).asFloat64();
2841 }
2842
2843 if (!extractGroup(pidsGroup, xtmp, "kff", "Pid kff parameter", _njoints)) {
2844 return false;
2845 }
2846 for (j=0; j<_njoints; j++) {
2847 myPid[j].kff = xtmp.get(j+1).asFloat64();
2848 }
2849
2850 //conversion from metric to machine units (if applicable)
2851 if (_positionControlUnits==P_METRIC_UNITS)
2852 {
2853 for (j=0; j<_njoints; j++)
2854 {
2855 myPid[j].kp = myPid[j].kp / _angleToEncoder[j]; //[PWM/deg]
2856 myPid[j].ki = myPid[j].ki / _angleToEncoder[j]; //[PWM/deg]
2857 myPid[j].kd = myPid[j].kd / _angleToEncoder[j]; //[PWM/deg]
2858 }
2859 }
2860 else
2861 {
2862 //do nothing
2863 }
2864
2865 //optional PWM limit
2866 if(_pwmIsLimited)
2867 { // check for value in the file
2868 if (!extractGroup(pidsGroup, xtmp, "limPwm", "Limited PWD", _njoints))
2869 {
2870 yCError(FAKEMOTIONCONTROL) << "The PID parameter limPwm was requested but was not correctly set in the configuration file, please fill it.";
2871 return false;
2872 }
2873
2874 yCInfo(FAKEMOTIONCONTROL) << "Using LIMITED PWM!!";
2875 for (j = 0; j < _njoints; j++) {
2876 myPid[j].max_output = xtmp.get(j + 1).asFloat64();
2877 }
2878 }
2879
2880 return true;
2881}
2882*/
2883
2884/*
2885bool FakeMotionControl::parseTorquePidsGroup(Bottle& pidsGroup, Pid myPid[], double kbemf[], double ktau[], int filterType[], double viscousPos[], double viscousNeg[], double coulombPos[], double coulombNeg[], double velocityThres[])
2886{
2887 int j=0;
2888 Bottle xtmp;
2889 if (!extractGroup(pidsGroup, xtmp, "kp", "Pid kp parameter", _njoints)) {
2890 return false;
2891 }
2892 for (j=0; j<_njoints; j++) {
2893 myPid[j].kp = xtmp.get(j+1).asFloat64();
2894 }
2895
2896 if (!extractGroup(pidsGroup, xtmp, "kd", "Pid kd parameter", _njoints)) {
2897 return false;
2898 }
2899 for (j=0; j<_njoints; j++) {
2900 myPid[j].kd = xtmp.get(j+1).asFloat64();
2901 }
2902
2903 if (!extractGroup(pidsGroup, xtmp, "ki", "Pid kp parameter", _njoints)) {
2904 return false;
2905 }
2906 for (j=0; j<_njoints; j++) {
2907 myPid[j].ki = xtmp.get(j+1).asFloat64();
2908 }
2909
2910 if (!extractGroup(pidsGroup, xtmp, "maxInt", "Pid maxInt parameter", _njoints)) {
2911 return false;
2912 }
2913 for (j=0; j<_njoints; j++) {
2914 myPid[j].max_int = xtmp.get(j+1).asFloat64();
2915 }
2916
2917 if (!extractGroup(pidsGroup, xtmp, "maxPwm", "Pid maxPwm parameter", _njoints)) {
2918 return false;
2919 }
2920 for (j=0; j<_njoints; j++) {
2921 myPid[j].max_output = xtmp.get(j+1).asFloat64();
2922 }
2923
2924 if (!extractGroup(pidsGroup, xtmp, "shift", "Pid shift parameter", _njoints)) {
2925 return false;
2926 }
2927 for (j=0; j<_njoints; j++) {
2928 myPid[j].scale = xtmp.get(j+1).asFloat64();
2929 }
2930
2931 if (!extractGroup(pidsGroup, xtmp, "ko", "Pid ko parameter", _njoints)) {
2932 return false;
2933 }
2934 for (j=0; j<_njoints; j++) {
2935 myPid[j].offset = xtmp.get(j+1).asFloat64();
2936 }
2937
2938 if (!extractGroup(pidsGroup, xtmp, "stictionUp", "Pid stictionUp", _njoints)) {
2939 return false;
2940 }
2941 for (j=0; j<_njoints; j++) {
2942 myPid[j].stiction_up_val = xtmp.get(j+1).asFloat64();
2943 }
2944
2945 if (!extractGroup(pidsGroup, xtmp, "stictionDwn", "Pid stictionDwn", _njoints)) {
2946 return false;
2947 }
2948 for (j=0; j<_njoints; j++) {
2949 myPid[j].stiction_down_val = xtmp.get(j+1).asFloat64();
2950 }
2951
2952 if (!extractGroup(pidsGroup, xtmp, "kff", "Pid kff parameter", _njoints)) {
2953 return false;
2954 }
2955 for (j=0; j<_njoints; j++) {
2956 myPid[j].kff = xtmp.get(j+1).asFloat64();
2957 }
2958
2959 if (!extractGroup(pidsGroup, xtmp, "kbemf", "kbemf parameter", _njoints)) {
2960 return false;
2961 }
2962 for (j=0; j<_njoints; j++) {
2963 kbemf[j] = xtmp.get(j+1).asFloat64();
2964 }
2965
2966 if (!extractGroup(pidsGroup, xtmp, "ktau", "ktau parameter", _njoints)) {
2967 return false;
2968 }
2969 for (j=0; j<_njoints; j++) {
2970 ktau[j] = xtmp.get(j+1).asFloat64();
2971 }
2972
2973 if (!extractGroup(pidsGroup, xtmp, "filterType", "filterType param", _njoints)) {
2974 return false;
2975 }
2976 for (j=0; j<_njoints; j++) {
2977 filterType[j] = xtmp.get(j+1).asInt32();
2978 }
2979
2980 if (!extractGroup(pidsGroup, xtmp, "viscousPos", "viscous pos parameter", _njoints)) {
2981 return false;
2982 }
2983 for (j=0; j<_njoints; j++) {
2984 viscousPos[j] = xtmp.get(j+1).asFloat64();
2985 }
2986
2987 if (!extractGroup(pidsGroup, xtmp, "viscousNeg", "viscous neg parameter", _njoints)) {
2988 return false;
2989 }
2990 for (j=0; j<_njoints; j++) {
2991 viscousNeg[j] = xtmp.get(j+1).asFloat64();
2992 }
2993
2994 if (!extractGroup(pidsGroup, xtmp, "coulombPos", "coulomb pos parameter", _njoints)) {
2995 return false;
2996 }
2997 for (j=0; j<_njoints; j++) {
2998 coulombPos[j] = xtmp.get(j+1).asFloat64();
2999 }
3000
3001 if (!extractGroup(pidsGroup, xtmp, "coulombNeg", "coulomb neg parameter", _njoints)) {
3002 return false;
3003 }
3004 for (j=0; j<_njoints; j++) {
3005 coulombNeg[j] = xtmp.get(j+1).asFloat64();
3006 }
3007
3008 if (!extractGroup(pidsGroup, xtmp, "velocityThres", "velocity threshold parameter", _njoints)) {
3009 return false;
3010 }
3011 for (j=0; j<_njoints; j++) {
3012 velocityThres[j] = xtmp.get(j+1).asFloat64();
3013 }
3014
3015
3016 //conversion from metric to machine units (if applicable)
3017// for (j=0; j<_njoints; j++)
3018// {
3019// myPid[j].kp = myPid[j].kp / _torqueControlHelper->getNewtonsToSensor(j); //[PWM/Nm]
3020// myPid[j].ki = myPid[j].ki / _torqueControlHelper->getNewtonsToSensor(j); //[PWM/Nm]
3021// myPid[j].kd = myPid[j].kd / _torqueControlHelper->getNewtonsToSensor(j); //[PWM/Nm]
3022// myPid[j].stiction_up_val = myPid[j].stiction_up_val * _torqueControlHelper->getNewtonsToSensor(j); //[Nm]
3023// myPid[j].stiction_down_val = myPid[j].stiction_down_val * _torqueControlHelper->getNewtonsToSensor(j); //[Nm]
3024// }
3025
3026 //optional PWM limit
3027 if(_pwmIsLimited)
3028 { // check for value in the file
3029 if (!extractGroup(pidsGroup, xtmp, "limPwm", "Limited PWM", _njoints))
3030 {
3031 yCError(FAKEMOTIONCONTROL) << "The PID parameter limPwm was requested but was not correctly set in the configuration file, please fill it.";
3032 return false;
3033 }
3034
3035 yCInfo(FAKEMOTIONCONTROL) << "Using LIMITED PWM!!";
3036 for (j = 0; j < _njoints; j++) {
3037 myPid[j].max_output = xtmp.get(j + 1).asFloat64();
3038 }
3039 }
3040
3041 return true;
3042}
3043*/
3044
3045// eof
void checkAndDestroy(T *&p)
bool NOT_YET_IMPLEMENTED(const char *txt)
FeatureMode mode
#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_VELOCITY_DIRECT
constexpr yarp::conf::vocab32_t VOCAB_CM_IDLE
constexpr yarp::conf::vocab32_t VOCAB_CM_POSITION
constexpr yarp::conf::vocab32_t VOCAB_CM_CURRENT
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
#define ReturnValue_ok
Definition ReturnValue.h:80
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.
yarp::dev::ReturnValue setAutoBrakeEnabledRaw(int j, bool enabled) override
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.
yarp::dev::ReturnValue getDesiredVelocityRaw(const int jnt, double &vel) override
Get the last reference velocity set by setDesiredVelocity() for a single joint.
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)
yarp::dev::ReturnValue setManualBrakeActiveRaw(int j, bool active) override
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.
yarp::dev::ReturnValue isJointBrakedRaw(int j, bool &braked) const override
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
yarp::dev::ReturnValue setDesiredVelocityRaw(int jnt, double vel) override
Set the velocity of single joint.
yarp::dev::ReturnValue getAutoBrakeEnabledRaw(int j, bool &enabled) const 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 uninitialize()
Clean up internal data and memory.
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)
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 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:211
void zero()
Zero the elements of the vector.
Definition Vector.h:353
#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 Vocab32.cpp:33
The components from which ports and connections are built.
An interface to the operating system, including Port based communication.