YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
RPCMessagesParser.cpp
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium
4 * SPDX-License-Identifier: BSD-3-Clause
5 */
6
7#include "RPCMessagesParser.h"
8
9#include <yarp/os/LogStream.h>
10
12#include <iostream>
13
14using namespace yarp::os;
15using namespace yarp::dev;
16using namespace yarp::dev::impl;
17using namespace yarp::sig;
18
19
20inline void appendTimeStamp(Bottle& bot, Stamp& st)
21{
22 int count = st.getCount();
23 double time = st.getTime();
25 bot.addInt32(count);
26 bot.addFloat64(time);
27}
28
30 yarp::os::Bottle& response,
31 bool* rec,
32 bool* ok)
33{
34 if (cmd.get(0).asVocab32() != VOCAB_GET) {
35 *rec = false;
36 *ok = false;
37 return;
38 }
39
44
45 *rec = true;
46 *ok = true;
47}
48
50 yarp::os::Bottle& response,
51 bool* rec,
52 bool* ok)
53{
54 yCTrace(CONTROLBOARD, "Handling IImpedance message");
55 if (!rpc_IImpedance) {
56 yCError(CONTROLBOARD, "I do not have a valid interface");
57 *ok = false;
58 return;
59 }
60
61 int code = cmd.get(0).asVocab32();
62 *ok = false;
63 switch (code) {
64 case VOCAB_SET: {
65 yCTrace(CONTROLBOARD, "handleImpedanceMsg::VOCAB_SET command");
66 switch (cmd.get(2).asVocab32()) {
67 case VOCAB_IMP_PARAM: {
68 Bottle* b = cmd.get(4).asList();
69 if (b != nullptr) {
70 double stiff = b->get(0).asFloat64();
71 double damp = b->get(1).asFloat64();
73 *rec = true;
74 }
75 } break;
76 case VOCAB_IMP_OFFSET: {
77 Bottle* b = cmd.get(4).asList();
78 if (b != nullptr) {
79 double offs = b->get(0).asFloat64();
81 *rec = true;
82 }
83 } break;
84 }
85 } break;
86 case VOCAB_GET: {
87 double stiff = 0;
88 double damp = 0;
89 double offs = 0;
90 yCTrace(CONTROLBOARD, "handleImpedanceMsg::VOCAB_GET command");
91
92 response.addVocab32(VOCAB_IS);
93 response.add(cmd.get(1));
94 switch (cmd.get(2).asVocab32()) {
95 case VOCAB_IMP_PARAM: {
96 *ok = rpc_IImpedance->getImpedance(cmd.get(3).asInt32(), &stiff, &damp);
97 Bottle& b = response.addList();
100 *rec = true;
101 } break;
102 case VOCAB_IMP_OFFSET: {
104 Bottle& b = response.addList();
105 b.addFloat64(offs);
106 *rec = true;
107 } break;
108 case VOCAB_LIMITS: {
109 double min_stiff = 0;
110 double max_stiff = 0;
111 double min_damp = 0;
112 double max_damp = 0;
113 *ok = rpc_IImpedance->getCurrentImpedanceLimit(cmd.get(3).asInt32(), &min_stiff, &max_stiff, &min_damp, &max_damp);
114 Bottle& b = response.addList();
115 b.addFloat64(min_stiff);
116 b.addFloat64(max_stiff);
117 b.addFloat64(min_damp);
118 b.addFloat64(max_damp);
119 *rec = true;
120 } break;
121 }
122 }
124 appendTimeStamp(response, lastRpcStamp);
125 break; // case VOCAB_GET
126 default:
127 {
128 *rec = false;
129 } break;
130 }
131}
132
134 yarp::os::Bottle& response,
135 bool* rec,
136 bool* ok)
137{
138 //handle here messages about IControlMode interface
139 int code = cmd.get(0).asVocab32();
140 *ok = true;
141 *rec = true; //or false
142
143 switch (code)
144 {
145 case VOCAB_GET:
146 yCTrace(CONTROLBOARD, "GET command");
147
148 int method = cmd.get(2).asVocab32();
149
150 switch (method)
151 {
153 yCTrace(CONTROLBOARD, "getJointFault");
154 int axis = cmd.get(3).asInt32();
155 int faultcode=0;
156 std::string faultmessage;
157 if (rpc_IJointFault)
158 {
160 *rec = true;
161 }
162 response.addVocab32(VOCAB_IS);
163 response.addInt32(faultcode);
164 response.addString(faultmessage);
165
166 yCTrace(CONTROLBOARD, "Returning %d %s", faultcode, faultmessage.c_str());
167 *rec = true;
168 break;
169 }
170
171 break;
172 }
173}
174
176 yarp::os::Bottle& response,
177 bool* rec,
178 bool* ok)
179{
180 yCTrace(CONTROLBOARD, "Handling IControlMode message");
181 if (!(rpc_iCtrlMode)) {
182 yCError(CONTROLBOARD, "I do not have a valid iControlMode interface");
183 *ok = false;
184 return;
185 }
186
187 //handle here messages about IControlMode interface
188 int code = cmd.get(0).asVocab32();
189 *ok = true;
190 *rec = true; //or false
191
192 switch (code) {
193 case VOCAB_SET: {
194 yCTrace(CONTROLBOARD, "handleControlModeMsg::VOCAB_SET command");
195
196 int method = cmd.get(2).asVocab32();
197
198 switch (method) {
200 int axis = cmd.get(3).asInt32();
201 yCTrace(CONTROLBOARD) << "got VOCAB_CM_CONTROL_MODE";
202 if (rpc_iCtrlMode) {
204 } else {
205 yCError(CONTROLBOARD) << "Unable to handle setControlMode request! This should not happen!";
206 *rec = false;
207 }
208 } break;
209
211 int n_joints = cmd.get(3).asInt32();
212 Bottle& jList = *(cmd.get(4).asList());
213 Bottle& modeList = *(cmd.get(5).asList());
214
215 int* js = new int[n_joints];
216 int* modes = new int[n_joints];
217
218 for (int i = 0; i < n_joints; i++) {
219 js[i] = jList.get(i).asInt32();
220 }
221
222 for (int i = 0; i < n_joints; i++) {
223 modes[i] = modeList.get(i).asVocab32();
224 }
225 if (rpc_iCtrlMode) {
226 *ok = rpc_iCtrlMode->setControlModes(n_joints, js, modes);
227 } else {
228 *rec = false;
229 *ok = false;
230 }
231 delete[] js;
232 delete[] modes;
233 } break;
234
237 modeList = cmd.get(3).asList();
238
239 if (modeList->size() != controlledJoints) {
240 yCError(CONTROLBOARD, "received an invalid setControlMode message. Size of vector doesn´t match the number of controlled joints");
241 *ok = false;
242 break;
243 }
244 int* modes = new int[controlledJoints];
245 for (size_t i = 0; i < controlledJoints; i++) {
246 modes[i] = modeList->get(i).asVocab32();
247 }
248 if (rpc_iCtrlMode) {
250 } else {
251 *rec = false;
252 *ok = false;
253 }
254 delete[] modes;
255 } break;
256
257 default:
258 {
259 // if I´m here, someone is probably sending command using the old interface.
260 // try to be compatible as much as I can
261
262 yCError(CONTROLBOARD) << " Error, received a set control mode message using a legacy version, trying to be handle the message anyway "
263 << " but please update your client to be compatible with the IControlMode interface";
264
265 yCTrace(CONTROLBOARD) << " cmd.get(4).asVocab32() is " << Vocab32::decode(cmd.get(4).asVocab32());
266 int axis = cmd.get(3).asInt32();
267
268 switch (cmd.get(4).asVocab32()) {
270 if (rpc_iCtrlMode) {
272 }
273 break;
274
276 if (rpc_iCtrlMode) {
278 } else {
279 *rec = false;
280 *ok = false;
281 }
282 break;
283
284
286 if (rpc_iCtrlMode) {
288 }
289 break;
290
291 case VOCAB_CM_TORQUE:
292 if (rpc_iCtrlMode) {
294 }
295 break;
296
298 yCError(CONTROLBOARD) << "The 'impedancePosition' control mode is deprecated. \nUse setInteractionMode(axis, VOCAB_IM_COMPLIANT) + setControlMode(axis, VOCAB_CM_POSITION) instead";
299 break;
300
302 yCError(CONTROLBOARD) << "The 'impedanceVelocity' control mode is deprecated. \nUse setInteractionMode(axis, VOCAB_IM_COMPLIANT) + setControlMode(axis, VOCAB_CM_VELOCITY) instead";
303 break;
304
305 case VOCAB_CM_PWM:
306 if (rpc_iCtrlMode) {
308 } else {
309 *rec = false;
310 *ok = false;
311 }
312 break;
313
314 case VOCAB_CM_CURRENT:
315 if (rpc_iCtrlMode) {
317 } else {
318 *rec = false;
319 *ok = false;
320 }
321 break;
322
323 case VOCAB_CM_MIXED:
324 if (rpc_iCtrlMode) {
326 } else {
327 *rec = false;
328 *ok = false;
329 }
330 break;
331
333 if (rpc_iCtrlMode) {
335 } else {
336 *rec = false;
337 *ok = false;
338 }
339 break;
340
341 default:
342 yCError(CONTROLBOARD, "SET unknown controlMode : %s ", cmd.toString().c_str());
343 *ok = false;
344 *rec = false;
345 break;
346 }
347 } break; // close default case
348 }
349 } break; // close SET case
350
351 case VOCAB_GET: {
352 yCTrace(CONTROLBOARD, "GET command");
353
354 int method = cmd.get(2).asVocab32();
355
356 switch (method) {
357
359 yCTrace(CONTROLBOARD, "getControlModes");
360 int* p = new int[controlledJoints];
361 for (size_t i = 0; i < controlledJoints; ++i) {
362 p[i] = -1;
363 }
364 if (rpc_iCtrlMode) {
366 }
367
368 response.addVocab32(VOCAB_IS);
370
371 Bottle& b = response.addList();
372 for (size_t i = 0; i < controlledJoints; i++) {
373 b.addVocab32(p[i]);
374 }
375 delete[] p;
376
377 *rec = true;
378 } break;
379
381 yCTrace(CONTROLBOARD, "getControlMode");
382
383 int p = -1;
384 int axis = cmd.get(3).asInt32();
385 if (rpc_iCtrlMode) {
387 }
388
389 response.addVocab32(VOCAB_IS);
390 response.addInt32(axis);
391 response.addVocab32(p);
392
393 yCTrace(CONTROLBOARD, "Returning %d", p);
394 *rec = true;
395 } break;
396
398 yCTrace(CONTROLBOARD, "getControlMode group");
399
400 int n_joints = cmd.get(3).asInt32();
401 Bottle& lIn = *(cmd.get(4).asList());
402
403 int* js = new int[n_joints];
404 int* modes = new int[n_joints];
405 for (int i = 0; i < n_joints; i++) {
406 js[i] = lIn.get(i).asInt32();
407 modes[i] = -1;
408 }
409 if (rpc_iCtrlMode) {
410 *ok = rpc_iCtrlMode->getControlModes(n_joints, js, modes);
411 } else {
412 *rec = false;
413 *ok = false;
414 }
415
416 response.addVocab32(VOCAB_IS);
418 Bottle& b = response.addList();
419 for (int i = 0; i < n_joints; i++) {
420 b.addVocab32(modes[i]);
421 }
422
423 delete[] js;
424 delete[] modes;
425
426 *rec = true;
427 } break;
428
429 default:
430 yCError(CONTROLBOARD, "received a GET ICONTROLMODE command not understood");
431 break;
432 }
433 }
434
436 appendTimeStamp(response, lastRpcStamp);
437 break; // case VOCAB_GET
438
439 default:
440 {
441 *rec = false;
442 } break;
443 }
444}
445
446
448 yarp::os::Bottle& response,
449 bool* rec,
450 bool* ok)
451{
452 yCTrace(CONTROLBOARD, "Handling ITorqueControl message");
453
454 if (!rpc_ITorque) {
455 yCError(CONTROLBOARD, "Error, I do not have a valid ITorque interface");
456 *ok = false;
457 return;
458 }
459
460 int code = cmd.get(0).asVocab32();
461 switch (code) {
462 case VOCAB_SET: {
463 *rec = true;
464 yCTrace(CONTROLBOARD, "set command received");
465
466 switch (cmd.get(2).asVocab32()) {
467 case VOCAB_REF: {
468 *ok = rpc_ITorque->setRefTorque(cmd.get(3).asInt32(), cmd.get(4).asFloat64());
469 } break;
470
471 case VOCAB_MOTOR_PARAMS: {
473 int joint = cmd.get(3).asInt32();
474 Bottle* b = cmd.get(4).asList();
475
476 if (b == nullptr) {
477 break;
478 }
479
480 if (b->size() != 9) {
481 yCError(CONTROLBOARD, "received a SET VOCAB_MOTOR_PARAMS command not understood, size != 9");
482 break;
483 }
484
485 params.bemf = b->get(0).asFloat64();
486 params.bemf_scale = b->get(1).asFloat64();
487 params.ktau = b->get(2).asFloat64();
488 params.ktau_scale = b->get(3).asFloat64();
489 params.viscousPos = b->get(4).asFloat64();
490 params.viscousNeg = b->get(5).asFloat64();
491 params.coulombPos = b->get(6).asFloat64();
492 params.coulombNeg = b->get(7).asFloat64();
493 params.velocityThres = b->get(8).asFloat64();
494
495 *ok = rpc_ITorque->setMotorTorqueParams(joint, params);
496 } break;
497
498 case VOCAB_REFS: {
499 Bottle* b = cmd.get(3).asList();
500 if (b == nullptr) {
501 break;
502 }
503
504 const size_t njs = b->size();
505 if (njs == controlledJoints) {
506 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
507 for (size_t i = 0; i < njs; i++) {
508 p[i] = b->get(i).asFloat64();
509 }
511 delete[] p;
512 }
513 } break;
514
515 case VOCAB_TORQUE_MODE: {
516 if (rpc_iCtrlMode) {
517 int* modes = new int[controlledJoints];
518 for (size_t i = 0; i < controlledJoints; i++) {
520 }
522 delete[] modes;
523 } else {
524 *ok = false;
525 }
526 } break;
527 }
528 } break;
529
530 case VOCAB_GET: {
531 *rec = true;
532 yCTrace(CONTROLBOARD, "get command received");
533 double dtmp = 0.0;
534 double dtmp2 = 0.0;
535 response.addVocab32(VOCAB_IS);
536 response.add(cmd.get(1));
537
538 switch (cmd.get(2).asVocab32()) {
539
540 case VOCAB_TRQ: {
541 *ok = rpc_ITorque->getTorque(cmd.get(3).asInt32(), &dtmp);
542 response.addFloat64(dtmp);
543 } break;
544
545 case VOCAB_MOTOR_PARAMS: {
547 int joint = cmd.get(3).asInt32();
548
549 // get the data
550 *ok = rpc_ITorque->getMotorTorqueParams(joint, &params);
551
552 // convert it back to yarp message
553 Bottle& b = response.addList();
554
555 b.addFloat64(params.bemf);
556 b.addFloat64(params.bemf_scale);
557 b.addFloat64(params.ktau);
558 b.addFloat64(params.ktau_scale);
559 b.addFloat64(params.viscousPos);
560 b.addFloat64(params.viscousNeg);
561 b.addFloat64(params.coulombPos);
562 b.addFloat64(params.coulombNeg);
563 b.addFloat64(params.velocityThres);
564 } break;
565
566 case VOCAB_RANGE: {
567 *ok = rpc_ITorque->getTorqueRange(cmd.get(3).asInt32(), &dtmp, &dtmp2);
568 response.addFloat64(dtmp);
569 response.addFloat64(dtmp2);
570 } break;
571
572 case VOCAB_TRQS: {
573 auto* p = new double[controlledJoints];
574 *ok = rpc_ITorque->getTorques(p);
575 Bottle& b = response.addList();
576 for (size_t i = 0; i < controlledJoints; i++) {
577 b.addFloat64(p[i]);
578 }
579 delete[] p;
580 } break;
581
582 case VOCAB_RANGES: {
583 auto* p1 = new double[controlledJoints];
584 auto* p2 = new double[controlledJoints];
586 Bottle& b1 = response.addList();
587 for (size_t i = 0; i < controlledJoints; i++) {
588 b1.addFloat64(p1[i]);
589 }
590 Bottle& b2 = response.addList();
591 for (size_t i = 0; i < controlledJoints; i++) {
592 b2.addFloat64(p2[i]);
593 }
594 delete[] p1;
595 delete[] p2;
596 } break;
597
598 case VOCAB_REFERENCE: {
599 *ok = rpc_ITorque->getRefTorque(cmd.get(3).asInt32(), &dtmp);
600 response.addFloat64(dtmp);
601 } break;
602
603 case VOCAB_REFERENCES: {
604 auto* p = new double[controlledJoints];
606 Bottle& b = response.addList();
607 for (size_t i = 0; i < controlledJoints; i++) {
608 b.addFloat64(p[i]);
609 }
610 delete[] p;
611 } break;
612 }
613 }
615 appendTimeStamp(response, lastRpcStamp);
616 break; // case VOCAB_GET
617 }
618}
619
621 yarp::os::Bottle& response,
622 bool* rec,
623 bool* ok)
624{
625 yCTrace(CONTROLBOARD, "\nHandling IInteractionMode message");
626 if (!rpc_IInteract) {
627 yCError(CONTROLBOARD, "Error I do not have a valid IInteractionMode interface");
628 *ok = false;
629 return;
630 }
631
632 yCTrace(CONTROLBOARD) << "received command: " << cmd.toString();
633
634 int action = cmd.get(0).asVocab32();
635
636 switch (action) {
637 case VOCAB_SET: {
638 switch (cmd.get(2).asVocab32()) {
642
645 } break;
646
648 yCTrace(CONTROLBOARD) << "CBW.h set interactionMode GROUP";
649
650 auto n_joints = static_cast<size_t>(cmd.get(3).asInt32());
651 jointList = cmd.get(4).asList();
652 modeList = cmd.get(5).asList();
653 if ((jointList->size() != n_joints) || (modeList->size() != n_joints)) {
654 yCWarning(CONTROLBOARD, "Received an invalid setInteractionMode message. Size of vectors doesn´t match");
655 *ok = false;
656 break;
657 }
658 int* joints = new int[n_joints];
660 for (size_t i = 0; i < n_joints; i++) {
661 joints[i] = jointList->get(i).asInt32();
662 modes[i] = static_cast<yarp::dev::InteractionModeEnum>(modeList->get(i).asVocab32());
663 yCTrace(CONTROLBOARD) << "CBW.cpp received vocab " << yarp::os::Vocab32::decode(modes[i]);
664 }
666 delete[] joints;
667 delete[] modes;
668
669 } break;
670
672 yCTrace(CONTROLBOARD) << "CBW.c set interactionMode ALL";
673
674 modeList = cmd.get(3).asList();
675 if (modeList->size() != controlledJoints) {
676 yCWarning(CONTROLBOARD, "Received an invalid setInteractionMode message. Size of vector doesn´t match the number of controlled joints");
677 *ok = false;
678 break;
679 }
681 for (size_t i = 0; i < controlledJoints; i++) {
682 modes[i] = static_cast<yarp::dev::InteractionModeEnum>(modeList->get(i).asVocab32());
683 }
685 delete[] modes;
686 } break;
687
688 default:
689 {
690 yCWarning(CONTROLBOARD, "Error while Handling IInteractionMode message, SET command not understood %s", cmd.get(2).asString().c_str());
691 *ok = false;
692 } break;
693 }
694 *rec = true; //or false
695 } break;
696
697 case VOCAB_GET: {
699
700 switch (cmd.get(2).asVocab32()) {
703 *ok = rpc_IInteract->getInteractionMode(cmd.get(3).asInt32(), &mode);
704 response.addVocab32(mode);
705 yCTrace(CONTROLBOARD) << " resp is " << response.toString();
706 } break;
707
710
711 int n_joints = cmd.get(3).asInt32();
712 jointList = cmd.get(4).asList();
713 if (jointList->size() != static_cast<size_t>(n_joints)) {
714 yCError(CONTROLBOARD, "Received an invalid getInteractionMode message. Size of vectors doesn´t match");
715 *ok = false;
716 break;
717 }
718 int* joints = new int[n_joints];
720 for (int i = 0; i < n_joints; i++) {
721 joints[i] = jointList->get(i).asInt32();
722 }
724
725 Bottle& c = response.addList();
726 for (int i = 0; i < n_joints; i++) {
727 c.addVocab32(modes[i]);
728 }
729
730 yCTrace(CONTROLBOARD, "got response bottle: %s", response.toString().c_str());
731
732 delete[] joints;
733 delete[] modes;
734 } break;
735
739
741
742 Bottle& b = response.addList();
743 for (size_t i = 0; i < controlledJoints; i++) {
744 b.addVocab32(modes[i]);
745 }
746
747 yCTrace(CONTROLBOARD, "got response bottle: %s", response.toString().c_str());
748
749 delete[] modes;
750 } break;
751 }
753 appendTimeStamp(response, lastRpcStamp);
754 } break; // case VOCAB_GET
755
756 default:
757 yCError(CONTROLBOARD, "Error while Handling IInteractionMode message, command was not SET nor GET");
758 *ok = false;
759 break;
760 }
761}
762
764{
765 yCTrace(CONTROLBOARD, "Handling ICurrentControl message");
766
767 if (!rpc_ICurrent) {
768 yCError(CONTROLBOARD, "I do not have a valid ICurrentControl interface");
769 *ok = false;
770 return;
771 }
772
773 int code = cmd.get(0).asVocab32();
774 int action = cmd.get(2).asVocab32();
775
776 *ok = false;
777 *rec = true;
778 switch (code) {
779 case VOCAB_SET: {
780 switch (action) {
781 case VOCAB_CURRENT_REF: {
782 yCError(CONTROLBOARD, "VOCAB_CURRENT_REF methods is implemented as streaming");
783 *ok = false;
784 } break;
785
786 case VOCAB_CURRENT_REFS: {
787 yCError(CONTROLBOARD, "VOCAB_CURRENT_REFS methods is implemented as streaming");
788 *ok = false;
789 } break;
790
792 yCError(CONTROLBOARD, "VOCAB_CURRENT_REF_GROUP methods is implemented as streaming");
793 *ok = false;
794 } break;
795
796 default:
797 {
798 yCError(CONTROLBOARD) << "Unknown handleCurrentMsg message received";
799 *rec = false;
800 *ok = false;
801 } break;
802 }
803 } break;
804
805 case VOCAB_GET: {
806 *rec = true;
807 yCTrace(CONTROLBOARD, "get command received");
808 double dtmp = 0.0;
809 double dtmp2 = 0.0;
810 response.addVocab32(VOCAB_IS);
811 response.add(cmd.get(1));
812
813 switch (action) {
814 case VOCAB_CURRENT_REF: {
815 *ok = rpc_ICurrent->getRefCurrent(cmd.get(3).asInt32(), &dtmp);
816 response.addFloat64(dtmp);
817 } break;
818
819 case VOCAB_CURRENT_REFS: {
820 auto* p = new double[controlledJoints];
822 Bottle& b = response.addList();
823 for (size_t i = 0; i < controlledJoints; i++) {
824 b.addFloat64(p[i]);
825 }
826 delete[] p;
827 } break;
828
829 case VOCAB_CURRENT_RANGE: {
830
831 *ok = rpc_ICurrent->getCurrentRange(cmd.get(3).asInt32(), &dtmp, &dtmp2);
832 response.addFloat64(dtmp);
833 response.addFloat64(dtmp2);
834 } break;
835
837 auto* p1 = new double[controlledJoints];
838 auto* p2 = new double[controlledJoints];
840 Bottle& b1 = response.addList();
841 Bottle& b2 = response.addList();
842 for (size_t i = 0; i < controlledJoints; i++) {
843 b1.addFloat64(p1[i]);
844 }
845 for (size_t i = 0; i < controlledJoints; i++) {
846 b2.addFloat64(p2[i]);
847 }
848 delete[] p1;
849 delete[] p2;
850 } break;
851
852 default:
853 {
854 yCError(CONTROLBOARD) << "Unknown handleCurrentMsg message received";
855 *rec = false;
856 *ok = false;
857 } break;
858 }
859 } break;
860
861 default:
862 {
863 yCError(CONTROLBOARD) << "Unknown handleCurrentMsg message received";
864 *rec = false;
865 *ok = false;
866 } break;
867 }
868}
869
870void RPCMessagesParser::handlePidMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok)
871{
872 yCTrace(CONTROLBOARD, "Handling IPidControl message");
873
874 if (!rpc_IPid) {
875 yCError(CONTROLBOARD, "I do not have a valid IPidControl interface");
876 *ok = false;
877 return;
878 }
879
880 int code = cmd.get(0).asVocab32();
881 int action = cmd.get(2).asVocab32();
882 auto pidtype = static_cast<yarp::dev::PidControlTypeEnum>(cmd.get(3).asVocab32());
883
884 *ok = false;
885 *rec = true;
886 switch (code) {
887 case VOCAB_SET: {
888 *rec = true;
889 yCTrace(CONTROLBOARD, "set command received");
890
891 switch (action) {
892 case VOCAB_OFFSET: {
893 double v;
894 int j = cmd.get(4).asInt32();
895 v = cmd.get(5).asFloat64();
896 *ok = rpc_IPid->setPidOffset(pidtype, j, v);
897 } break;
898
899 case VOCAB_PID: {
900 Pid p;
901 int j = cmd.get(4).asInt32();
902 Bottle* b = cmd.get(5).asList();
903
904 if (b == nullptr) {
905 break;
906 }
907
908 p.kp = b->get(0).asFloat64();
909 p.kd = b->get(1).asFloat64();
910 p.ki = b->get(2).asFloat64();
911 p.max_int = b->get(3).asFloat64();
912 p.max_output = b->get(4).asFloat64();
913 p.offset = b->get(5).asFloat64();
914 p.scale = b->get(6).asFloat64();
915 p.stiction_up_val = b->get(7).asFloat64();
916 p.stiction_down_val = b->get(8).asFloat64();
917 p.kff = b->get(9).asFloat64();
918 *ok = rpc_IPid->setPid(pidtype, j, p);
919 } break;
920
921 case VOCAB_PIDS: {
922 Bottle* b = cmd.get(4).asList();
923
924 if (b == nullptr) {
925 break;
926 }
927
928 const size_t njs = b->size();
929 if (njs == controlledJoints) {
930 Pid* p = new Pid[njs];
931
932 bool allOK = true;
933
934 for (size_t i = 0; i < njs; i++) {
935 Bottle* c = b->get(i).asList();
936 if (c != nullptr) {
937 p[i].kp = c->get(0).asFloat64();
938 p[i].kd = c->get(1).asFloat64();
939 p[i].ki = c->get(2).asFloat64();
940 p[i].max_int = c->get(3).asFloat64();
941 p[i].max_output = c->get(4).asFloat64();
942 p[i].offset = c->get(5).asFloat64();
943 p[i].scale = c->get(6).asFloat64();
944 p[i].stiction_up_val = c->get(7).asFloat64();
945 p[i].stiction_down_val = c->get(8).asFloat64();
946 p[i].kff = c->get(9).asFloat64();
947 } else {
948 allOK = false;
949 }
950 }
951 if (allOK) {
952 *ok = rpc_IPid->setPids(pidtype, p);
953 } else {
954 *ok = false;
955 }
956
957 delete[] p;
958 }
959 } break;
960
961 case VOCAB_REF: {
962 *ok = rpc_IPid->setPidReference(pidtype, cmd.get(4).asInt32(), cmd.get(5).asFloat64());
963 } break;
964
965 case VOCAB_REFS: {
966 Bottle* b = cmd.get(4).asList();
967
968 if (b == nullptr) {
969 break;
970 }
971
972 const size_t njs = b->size();
973 if (njs == controlledJoints) {
974 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
975 for (size_t i = 0; i < njs; i++) {
976 p[i] = b->get(i).asFloat64();
977 }
979 delete[] p;
980 }
981 } break;
982
983 case VOCAB_LIM: {
984 *ok = rpc_IPid->setPidErrorLimit(pidtype, cmd.get(4).asInt32(), cmd.get(5).asFloat64());
985 } break;
986
987 case VOCAB_LIMS: {
988 Bottle* b = cmd.get(4).asList();
989
990 if (b == nullptr) {
991 break;
992 }
993
994 const size_t njs = b->size();
995 if (njs == controlledJoints) {
996 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
997 for (size_t i = 0; i < njs; i++) {
998 p[i] = b->get(i).asFloat64();
999 }
1001 delete[] p;
1002 }
1003 } break;
1004
1005 case VOCAB_RESET: {
1006 *ok = rpc_IPid->resetPid(pidtype, cmd.get(4).asInt32());
1007 } break;
1008
1009 case VOCAB_DISABLE: {
1010 *ok = rpc_IPid->disablePid(pidtype, cmd.get(4).asInt32());
1011 } break;
1012
1013 case VOCAB_ENABLE: {
1014 *ok = rpc_IPid->enablePid(pidtype, cmd.get(4).asInt32());
1015 } break;
1016 }
1017 } break;
1018
1019 case VOCAB_GET: {
1020 *rec = true;
1021 yCTrace(CONTROLBOARD, "get command received");
1022 double dtmp = 0.0;
1023 response.addVocab32(VOCAB_IS);
1024 response.add(cmd.get(1));
1025
1026 switch (action) {
1027 case VOCAB_LIMS: {
1028 auto* p = new double[controlledJoints];
1030 Bottle& b = response.addList();
1031 for (size_t i = 0; i < controlledJoints; i++) {
1032 b.addFloat64(p[i]);
1033 }
1034 delete[] p;
1035 } break;
1036
1037 case VOCAB_ENABLE: {
1038 bool booltmp = false;
1039 *ok = rpc_IPid->isPidEnabled(pidtype, cmd.get(4).asInt32(), &booltmp);
1040 response.addInt32(booltmp);
1041 } break;
1042
1043 case VOCAB_ERR: {
1044 *ok = rpc_IPid->getPidError(pidtype, cmd.get(4).asInt32(), &dtmp);
1045 response.addFloat64(dtmp);
1046 } break;
1047
1048 case VOCAB_ERRS: {
1049 auto* p = new double[controlledJoints];
1050 *ok = rpc_IPid->getPidErrors(pidtype, p);
1051 Bottle& b = response.addList();
1052 for (size_t i = 0; i < controlledJoints; i++) {
1053 b.addFloat64(p[i]);
1054 }
1055 delete[] p;
1056 } break;
1057
1058 case VOCAB_OUTPUT: {
1059 *ok = rpc_IPid->getPidOutput(pidtype, cmd.get(4).asInt32(), &dtmp);
1060 response.addFloat64(dtmp);
1061 } break;
1062
1063 case VOCAB_OUTPUTS: {
1064 auto* p = new double[controlledJoints];
1066 Bottle& b = response.addList();
1067 for (size_t i = 0; i < controlledJoints; i++) {
1068 b.addFloat64(p[i]);
1069 }
1070 delete[] p;
1071 } break;
1072
1073 case VOCAB_PID: {
1074 Pid p;
1075 *ok = rpc_IPid->getPid(pidtype, cmd.get(4).asInt32(), &p);
1076 Bottle& b = response.addList();
1077 b.addFloat64(p.kp);
1078 b.addFloat64(p.kd);
1079 b.addFloat64(p.ki);
1080 b.addFloat64(p.max_int);
1081 b.addFloat64(p.max_output);
1082 b.addFloat64(p.offset);
1083 b.addFloat64(p.scale);
1084 b.addFloat64(p.stiction_up_val);
1085 b.addFloat64(p.stiction_down_val);
1086 b.addFloat64(p.kff);
1087 } break;
1088
1089 case VOCAB_PIDS: {
1090 Pid* p = new Pid[controlledJoints];
1091 *ok = rpc_IPid->getPids(pidtype, p);
1092 Bottle& b = response.addList();
1093 for (size_t i = 0; i < controlledJoints; i++) {
1094 Bottle& c = b.addList();
1095 c.addFloat64(p[i].kp);
1096 c.addFloat64(p[i].kd);
1097 c.addFloat64(p[i].ki);
1098 c.addFloat64(p[i].max_int);
1099 c.addFloat64(p[i].max_output);
1100 c.addFloat64(p[i].offset);
1101 c.addFloat64(p[i].scale);
1102 c.addFloat64(p[i].stiction_up_val);
1103 c.addFloat64(p[i].stiction_down_val);
1104 c.addFloat64(p[i].kff);
1105 }
1106 delete[] p;
1107 } break;
1108
1109 case VOCAB_REFERENCE: {
1110 *ok = rpc_IPid->getPidReference(pidtype, cmd.get(4).asInt32(), &dtmp);
1111 response.addFloat64(dtmp);
1112 } break;
1113
1114 case VOCAB_REFERENCES: {
1115 auto* p = new double[controlledJoints];
1117 Bottle& b = response.addList();
1118 for (size_t i = 0; i < controlledJoints; i++) {
1119 b.addFloat64(p[i]);
1120 }
1121 delete[] p;
1122 } break;
1123
1124 case VOCAB_LIM: {
1125 *ok = rpc_IPid->getPidErrorLimit(pidtype, cmd.get(4).asInt32(), &dtmp);
1126 response.addFloat64(dtmp);
1127 } break;
1128 }
1129 } break;
1130
1131 default:
1132 {
1133 yCError(CONTROLBOARD) << "Unknown handlePWMMsg message received";
1134 *rec = false;
1135 *ok = false;
1136 } break;
1137 }
1138}
1139
1140void RPCMessagesParser::handlePWMMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok)
1141{
1142 yCTrace(CONTROLBOARD, "Handling IPWMControl message");
1143
1144 if (!rpc_IPWM) {
1145 yCError(CONTROLBOARD, "I do not have a valid IPWMControl interface");
1146 *ok = false;
1147 return;
1148 }
1149
1150 int code = cmd.get(0).asVocab32();
1151 int action = cmd.get(2).asVocab32();
1152
1153 *ok = false;
1154 *rec = true;
1155 switch (code) {
1156 case VOCAB_SET: {
1157 *rec = true;
1158 yCTrace(CONTROLBOARD, "set command received");
1159
1160 switch (action) {
1162 //handled as streaming!
1163 yCError(CONTROLBOARD) << "VOCAB_PWMCONTROL_REF_PWM handled as straming";
1164 *ok = false;
1165 } break;
1166
1167 default:
1168 {
1169 yCError(CONTROLBOARD) << "Unknown handlePWMMsg message received";
1170 *ok = false;
1171 } break;
1172 }
1173 } break;
1174
1175 case VOCAB_GET: {
1176 yCTrace(CONTROLBOARD, "get command received");
1177 *rec = true;
1178 double dtmp = 0.0;
1179 response.addVocab32(VOCAB_IS);
1180 response.add(cmd.get(1));
1181
1182 switch (action) {
1184 *ok = rpc_IPWM->getRefDutyCycle(cmd.get(3).asInt32(), &dtmp);
1185 response.addFloat64(dtmp);
1186 } break;
1187
1189 auto* p = new double[controlledJoints];
1190 *ok = rpc_IPWM->getRefDutyCycles(p);
1191 Bottle& b = response.addList();
1192 for (size_t i = 0; i < controlledJoints; i++) {
1193 b.addFloat64(p[i]);
1194 }
1195 delete[] p;
1196 } break;
1197
1199 *ok = rpc_IPWM->getDutyCycle(cmd.get(3).asInt32(), &dtmp);
1200 response.addFloat64(dtmp);
1201 } break;
1202
1204 auto* p = new double[controlledJoints];
1205 *ok = rpc_IPWM->getRefDutyCycles(p);
1206 Bottle& b = response.addList();
1207 for (size_t i = 0; i < controlledJoints; i++) {
1208 b.addFloat64(p[i]);
1209 }
1210 delete[] p;
1211 } break;
1212
1213 default:
1214 {
1215 yCError(CONTROLBOARD) << "Unknown handlePWMMsg message received";
1216 *ok = false;
1217 } break;
1218 }
1219 } break;
1220
1221 default:
1222 {
1223 yCError(CONTROLBOARD) << "Unknown handlePWMMsg message received";
1224 *rec = false;
1225 *ok = false;
1226 } break;
1227 }
1228}
1229
1231{
1232 yCTrace(CONTROLBOARD, "Handling IRemoteVariables message");
1233
1234 if (!rpc_IVar) {
1235 yCError(CONTROLBOARD, "I do not have a valid IRemoteVariables interface");
1236 *ok = false;
1237 return;
1238 }
1239
1240 int code = cmd.get(0).asVocab32();
1241 int action = cmd.get(2).asVocab32();
1242
1243 *ok = false;
1244 *rec = true;
1245 switch (code) {
1246 case VOCAB_SET: {
1247 switch (action) {
1248 case VOCAB_VARIABLE: {
1249 Bottle btail = cmd.tail().tail().tail().tail(); // remove the first four elements
1250 std::string s = btail.toString();
1251 *ok = rpc_IVar->setRemoteVariable(cmd.get(3).asString(), btail);
1252 } break;
1253
1254 default:
1255 {
1256 *rec = false;
1257 *ok = false;
1258 } break;
1259 }
1260 } break;
1261
1262 case VOCAB_GET: {
1263 yCTrace(CONTROLBOARD, "get command received");
1264
1265 response.clear();
1266 response.addVocab32(VOCAB_IS);
1267 response.add(cmd.get(1));
1268 Bottle btmp;
1269
1270 switch (action) {
1271 case VOCAB_VARIABLE: {
1272 *ok = rpc_IVar->getRemoteVariable(cmd.get(3).asString(), btmp);
1273 Bottle& b = response.addList();
1274 b = btmp;
1275 } break;
1276
1277 case VOCAB_LIST_VARIABLES: {
1279 Bottle& b = response.addList();
1280 b = btmp;
1281 } break;
1282 }
1283 }
1284 } //end get/set switch
1285}
1286
1288{
1289 yCTrace(CONTROLBOARD, "Handling IRemoteCalibrator message");
1290
1291 if (!rpc_IRemoteCalibrator) {
1292 yCError(CONTROLBOARD, "I do not have a valid IRemoteCalibrator interface");
1293 *ok = false;
1294 return;
1295 }
1296
1297 int code = cmd.get(0).asVocab32();
1298 int action = cmd.get(2).asVocab32();
1299
1300 *ok = false;
1301 *rec = true;
1302 switch (code) {
1303 case VOCAB_SET: {
1304 switch (action) {
1306 yCDebug(CONTROLBOARD) << "cmd is " << cmd.toString() << " joint is " << cmd.get(3).asInt32();
1307 yCTrace(CONTROLBOARD, "Calling calibrate joint with no parameter");
1309 } break;
1310
1312 yCTrace(CONTROLBOARD, "Calling calibrate whole part");
1314 } break;
1315
1317 yCTrace(CONTROLBOARD, "Calling calibrate joint with no parameter");
1319 } break;
1320
1322 yCDebug(CONTROLBOARD) << "Received homing whole part";
1323 yCTrace(CONTROLBOARD, "Calling calibrate whole part");
1325 } break;
1326
1328 yCTrace(CONTROLBOARD, "Calling calibrate joint with no parameter");
1330 } break;
1331
1332 case VOCAB_PARK_WHOLE_PART: {
1333 yCTrace(CONTROLBOARD, "Calling calibrate whole part");
1335 } break;
1336
1337 case VOCAB_QUIT_CALIBRATE: {
1338 yCTrace(CONTROLBOARD, "Calling quit calibrate");
1340 } break;
1341
1342 case VOCAB_QUIT_PARK: {
1343 yCTrace(CONTROLBOARD, "Calling quit park");
1345 } break;
1346
1347 default:
1348 {
1349 *rec = false;
1350 *ok = false;
1351 } break;
1352 }
1353 } break;
1354
1355 case VOCAB_GET: {
1356 response.clear();
1357 response.addVocab32(VOCAB_IS);
1358 response.add(cmd.get(1));
1359
1360 switch (action) {
1362 bool tmp;
1363 yCTrace(CONTROLBOARD, "Calling VOCAB_IS_CALIBRATOR_PRESENT");
1365 response.addInt32(tmp);
1366 } break;
1367 }
1368 }
1369 } //end get/set switch
1370}
1371
1372
1373// rpc callback
1375{
1376 bool ok = false;
1377 bool rec = false; // Tells if the command is recognized!
1378
1379 yCTrace(CONTROLBOARD, "command received: %s", cmd.toString().c_str());
1380
1381 int code = cmd.get(0).asVocab32();
1382
1383 if (cmd.size() < 2) {
1384 ok = false;
1385 } else {
1386 switch (cmd.get(1).asVocab32()) {
1387 case VOCAB_PID:
1388 handlePidMsg(cmd, response, &rec, &ok);
1389 break;
1390
1391 case VOCAB_TORQUE:
1392 handleTorqueMsg(cmd, response, &rec, &ok);
1393 break;
1394
1395 case VOCAB_IJOINTFAULT:
1396 handleJointFaultMsg(cmd, response, &rec, &ok);
1397 break;
1398
1399 case VOCAB_ICONTROLMODE:
1400 handleControlModeMsg(cmd, response, &rec, &ok);
1401 break;
1402
1403 case VOCAB_IMPEDANCE:
1404 handleImpedanceMsg(cmd, response, &rec, &ok);
1405 break;
1406
1408 handleInteractionModeMsg(cmd, response, &rec, &ok);
1409 break;
1410
1412 handleProtocolVersionRequest(cmd, response, &rec, &ok);
1413 break;
1414
1416 handleRemoteCalibratorMsg(cmd, response, &rec, &ok);
1417 break;
1418
1420 handleRemoteVariablesMsg(cmd, response, &rec, &ok);
1421 break;
1422
1424 handleCurrentMsg(cmd, response, &rec, &ok);
1425 break;
1426
1428 handlePWMMsg(cmd, response, &rec, &ok);
1429 break;
1430
1431 default:
1432 // fallback for old interfaces with no specific name
1433 switch (code) {
1434 case VOCAB_CALIBRATE_JOINT: {
1435 if (!rpc_Icalib) { ok = false; break; }
1436 rec = true;
1437 yCTrace(CONTROLBOARD, "Calling calibrate joint");
1438
1439 int j = cmd.get(1).asInt32();
1440 int ui = cmd.get(2).asInt32();
1441 double v1 = cmd.get(3).asFloat64();
1442 double v2 = cmd.get(4).asFloat64();
1443 double v3 = cmd.get(5).asFloat64();
1444 if (rpc_Icalib == nullptr) {
1445 yCError(CONTROLBOARD, "Sorry I don't have a IControlCalibration2 interface");
1446 } else {
1448 }
1449 } break;
1450
1452 if (!rpc_Icalib) { ok = false; break; }
1453 rec = true;
1454 yCTrace(CONTROLBOARD, "Calling calibrate joint");
1455
1456 int j = cmd.get(1).asInt32();
1457 CalibrationParameters params;
1458 params.type = cmd.get(2).asInt32();
1459 params.param1 = cmd.get(3).asFloat64();
1460 params.param2 = cmd.get(4).asFloat64();
1461 params.param3 = cmd.get(5).asFloat64();
1462 params.param4 = cmd.get(6).asFloat64();
1463 if (rpc_Icalib == nullptr) {
1464 yCError(CONTROLBOARD, "Sorry I don't have a IControlCalibration2 interface");
1465 } else {
1466 ok = rpc_Icalib->setCalibrationParameters(j, params);
1467 }
1468 } break;
1469
1470 case VOCAB_CALIBRATE: {
1471 if (!rpc_Icalib) { ok = false; break; }
1472 rec = true;
1473 yCTrace(CONTROLBOARD, "Calling calibrate");
1474 ok = rpc_Icalib->calibrateRobot();
1475 } break;
1476
1477 case VOCAB_CALIBRATE_DONE: {
1478 if (!rpc_Icalib) { ok = false; break; }
1479 rec = true;
1480 yCTrace(CONTROLBOARD, "Calling calibrate done");
1481 int j = cmd.get(1).asInt32();
1483 } break;
1484
1485 case VOCAB_PARK: {
1486 if (!rpc_Icalib) { ok = false; break; }
1487 rec = true;
1488 yCTrace(CONTROLBOARD, "Calling park function");
1489 int flag = cmd.get(1).asInt32();
1490 ok = rpc_Icalib->park(flag ? true : false);
1491 ok = true; //client would get stuck if returning false
1492 } break;
1493
1494 case VOCAB_SET: {
1495 rec = true;
1496 yCTrace(CONTROLBOARD, "set command received");
1497
1498 switch (cmd.get(1).asVocab32()) {
1499 case VOCAB_POSITION_MOVE: {
1500 if (!rpc_IPosCtrl) { ok = false; break; }
1501 ok = rpc_IPosCtrl->positionMove(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1502 } break;
1503
1504 // this operation is also available on "command" port
1505 case VOCAB_POSITION_MOVES: {
1506 if (!rpc_IPosCtrl) { ok = false; break; }
1507 Bottle* b = cmd.get(2).asList();
1508 if (b == nullptr) {
1509 break;
1510 }
1511 const size_t njs = b->size();
1512 if (njs != controlledJoints) {
1513 break;
1514 }
1516 for (size_t i = 0; i < njs; i++) {
1517 tmpVect[i] = b->get(i).asFloat64();
1518 }
1519
1520 if (rpc_IPosCtrl != nullptr) {
1522 }
1523 } break;
1524
1526 if (!rpc_IPosCtrl) { ok = false; break; }
1527 auto len = static_cast<size_t>(cmd.get(2).asInt32());
1528 Bottle* jlut = cmd.get(3).asList();
1529 Bottle* pos_val = cmd.get(4).asList();
1530
1531 if (rpc_IPosCtrl == nullptr) {
1532 break;
1533 }
1534
1535 if (jlut == nullptr || pos_val == nullptr) {
1536 break;
1537 }
1538 if (len != jlut->size() || len != pos_val->size()) {
1539 break;
1540 }
1541
1542 auto* j_tmp = new int[len];
1543 auto* pos_tmp = new double[len];
1544 for (size_t i = 0; i < len; i++) {
1545 j_tmp[i] = jlut->get(i).asInt32();
1546 pos_tmp[i] = pos_val->get(i).asFloat64();
1547 }
1548
1550
1551 delete[] j_tmp;
1552 delete[] pos_tmp;
1553 } break;
1554
1555 // this operation is also available on "command" port
1556 case VOCAB_VELOCITY_MOVES: {
1557 if (!rpc_IVelCtrl) { ok = false; break; }
1558 Bottle* b = cmd.get(2).asList();
1559 if (b == nullptr) {
1560 break;
1561 }
1562 const size_t njs = b->size();
1563 if (njs != controlledJoints) {
1564 break;
1565 }
1567 for (size_t i = 0; i < njs; i++) {
1568 tmpVect[i] = b->get(i).asFloat64();
1569 }
1570 if (rpc_IVelCtrl != nullptr) {
1572 }
1573
1574 } break;
1575
1576 case VOCAB_RELATIVE_MOVE: {
1577 if (!rpc_IPosCtrl) { ok = false; break; }
1578 ok = rpc_IPosCtrl->relativeMove(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1579 } break;
1580
1582 if (!rpc_IPosCtrl) { ok = false; break; }
1583 auto len = static_cast<size_t>(cmd.get(2).asInt32());
1584 Bottle* jBottle_p = cmd.get(3).asList();
1585 Bottle* posBottle_p = cmd.get(4).asList();
1586
1587 if (rpc_IPosCtrl == nullptr) {
1588 break;
1589 }
1590
1591 if (jBottle_p == nullptr || posBottle_p == nullptr) {
1592 break;
1593 }
1594 if (len != jBottle_p->size() || len != posBottle_p->size()) {
1595 break;
1596 }
1597
1598 int* j_tmp = new int[len];
1599 auto* pos_tmp = new double[len];
1600
1601 for (size_t i = 0; i < len; i++) {
1602 j_tmp[i] = jBottle_p->get(i).asInt32();
1603 }
1604
1605 for (size_t i = 0; i < len; i++) {
1606 pos_tmp[i] = posBottle_p->get(i).asFloat64();
1607 }
1608
1610
1611 delete[] j_tmp;
1612 delete[] pos_tmp;
1613 } break;
1614
1615 case VOCAB_RELATIVE_MOVES: {
1616 if (!rpc_IPosCtrl) { ok = false; break; }
1617 Bottle* b = cmd.get(2).asList();
1618
1619 if (b == nullptr) {
1620 break;
1621 }
1622
1623 const size_t njs = b->size();
1624 if (njs != controlledJoints) {
1625 break;
1626 }
1627 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
1628 for (size_t i = 0; i < njs; i++) {
1629 p[i] = b->get(i).asFloat64();
1630 }
1632 delete[] p;
1633 } break;
1634
1635 case VOCAB_REF_SPEED: {
1636 if (!rpc_IPosCtrl) { ok = false; break; }
1637 ok = rpc_IPosCtrl->setRefSpeed(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1638 } break;
1639
1640 case VOCAB_REF_SPEED_GROUP: {
1641 if (!rpc_IPosCtrl) { ok = false; break; }
1642 auto len = static_cast<size_t>(cmd.get(2).asInt32());
1643 Bottle* jBottle_p = cmd.get(3).asList();
1644 Bottle* velBottle_p = cmd.get(4).asList();
1645
1646 if (rpc_IPosCtrl == nullptr) {
1647 break;
1648 }
1649
1650 if (jBottle_p == nullptr || velBottle_p == nullptr) {
1651 break;
1652 }
1653 if (len != jBottle_p->size() || len != velBottle_p->size()) {
1654 break;
1655 }
1656
1657 int* j_tmp = new int[len];
1658 auto* spds_tmp = new double[len];
1659
1660 for (size_t i = 0; i < len; i++) {
1661 j_tmp[i] = jBottle_p->get(i).asInt32();
1662 }
1663
1664 for (size_t i = 0; i < len; i++) {
1665 spds_tmp[i] = velBottle_p->get(i).asFloat64();
1666 }
1667
1669 delete[] j_tmp;
1670 delete[] spds_tmp;
1671 } break;
1672
1673 case VOCAB_REF_SPEEDS: {
1674 if (!rpc_IPosCtrl) { ok = false; break; }
1675 Bottle* b = cmd.get(2).asList();
1676
1677 if (b == nullptr) {
1678 break;
1679 }
1680
1681 const size_t njs = b->size();
1682 if (njs != controlledJoints) {
1683 break;
1684 }
1685 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
1686 for (size_t i = 0; i < njs; i++) {
1687 p[i] = b->get(i).asFloat64();
1688 }
1690 delete[] p;
1691 } break;
1692
1694 if (!rpc_IPosCtrl) { ok = false; break; }
1695 ok = rpc_IPosCtrl->setRefAcceleration(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1696 } break;
1697
1699 if (!rpc_IPosCtrl) { ok = false; break; }
1700 auto len = static_cast<size_t>(cmd.get(2).asInt32());
1701 Bottle* jBottle_p = cmd.get(3).asList();
1702 Bottle* accBottle_p = cmd.get(4).asList();
1703
1704 if (rpc_IPosCtrl == nullptr) {
1705 break;
1706 }
1707
1708 if (jBottle_p == nullptr || accBottle_p == nullptr) {
1709 break;
1710 }
1711 if (len != jBottle_p->size() || len != accBottle_p->size()) {
1712 break;
1713 }
1714
1715 int* j_tmp = new int[len];
1716 auto* accs_tmp = new double[len];
1717
1718 for (size_t i = 0; i < len; i++) {
1719 j_tmp[i] = jBottle_p->get(i).asInt32();
1720 }
1721
1722 for (size_t i = 0; i < len; i++) {
1723 accs_tmp[i] = accBottle_p->get(i).asFloat64();
1724 }
1725
1727 delete[] j_tmp;
1728 delete[] accs_tmp;
1729 } break;
1730
1732 if (!rpc_IPosCtrl) { ok = false; break; }
1733 Bottle* b = cmd.get(2).asList();
1734
1735 if (b == nullptr) {
1736 break;
1737 }
1738
1739 const size_t njs = b->size();
1740 if (njs != controlledJoints) {
1741 break;
1742 }
1743 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
1744 for (size_t i = 0; i < njs; i++) {
1745 p[i] = b->get(i).asFloat64();
1746 }
1748 delete[] p;
1749 } break;
1750
1751 case VOCAB_STOP: {
1752 if (!rpc_IPosCtrl) { ok = false; break; }
1753 ok = rpc_IPosCtrl->stop(cmd.get(2).asInt32());
1754 } break;
1755
1756 case VOCAB_STOP_GROUP: {
1757 if (!rpc_IPosCtrl) { ok = false; break; }
1758 auto len = static_cast<size_t>(cmd.get(2).asInt32());
1759 Bottle* jBottle_p = cmd.get(3).asList();
1760
1761 if (rpc_IPosCtrl == nullptr) {
1762 break;
1763 }
1764
1765 if (jBottle_p == nullptr) {
1766 break;
1767 }
1768 if (len != jBottle_p->size()) {
1769 break;
1770 }
1771
1772 int* j_tmp = new int[len];
1773
1774 for (size_t i = 0; i < len; i++) {
1775 j_tmp[i] = jBottle_p->get(i).asInt32();
1776 }
1777
1778 ok = rpc_IPosCtrl->stop(len, j_tmp);
1779 delete[] j_tmp;
1780 } break;
1781
1782 case VOCAB_STOPS: {
1783 if (!rpc_IPosCtrl) { ok = false; break; }
1784 ok = rpc_IPosCtrl->stop();
1785 } break;
1786
1787 case VOCAB_E_RESET: {
1788 if (!rpc_IEncTimed) { ok = false; break; }
1789 ok = rpc_IEncTimed->resetEncoder(cmd.get(2).asInt32());
1790 } break;
1791
1792 case VOCAB_E_RESETS: {
1793 if (!rpc_IEncTimed) { ok = false; break; }
1795 } break;
1796
1797 case VOCAB_ENCODER: {
1798 if (!rpc_IEncTimed) { ok = false; break; }
1799 ok = rpc_IEncTimed->setEncoder(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1800 } break;
1801
1802 case VOCAB_ENCODERS: {
1803 if (!rpc_IEncTimed) { ok = false; break; }
1804 Bottle* b = cmd.get(2).asList();
1805
1806 if (b == nullptr) {
1807 break;
1808 }
1809
1810 const size_t njs = b->size();
1811 if (njs != controlledJoints) {
1812 break;
1813 }
1814 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
1815 for (size_t i = 0; i < njs; i++) {
1816 p[i] = b->get(i).asFloat64();
1817 }
1819 delete[] p;
1820 } break;
1821
1822 case VOCAB_MOTOR_CPR: {
1823 if (!rpc_IMotEnc) { ok = false; break; }
1825 } break;
1826
1827 case VOCAB_MOTOR_E_RESET: {
1828 if (!rpc_IMotEnc) { ok = false; break; }
1829 ok = rpc_IMotEnc->resetMotorEncoder(cmd.get(2).asInt32());
1830 } break;
1831
1832 case VOCAB_MOTOR_E_RESETS: {
1833 if (!rpc_IMotEnc) { ok = false; break; }
1835 } break;
1836
1837 case VOCAB_MOTOR_ENCODER: {
1838 if (!rpc_IMotEnc) { ok = false; break; }
1839 ok = rpc_IMotEnc->setMotorEncoder(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1840 } break;
1841
1842 case VOCAB_MOTOR_ENCODERS: {
1843 if (!rpc_IMotEnc) { ok = false; break; }
1844 Bottle* b = cmd.get(2).asList();
1845
1846 if (b == nullptr) {
1847 break;
1848 }
1849
1850 const size_t njs = b->size();
1851 if (njs != controlledJoints) {
1852 break;
1853 }
1854 auto* p = new double[njs]; // LATER: optimize to avoid allocation.
1855 for (size_t i = 0; i < njs; i++) {
1856 p[i] = b->get(i).asFloat64();
1857 }
1859 delete[] p;
1860 } break;
1861
1862 case VOCAB_AMP_ENABLE: {
1863 if (!rcp_IAmp) { ok = false; break; }
1864 ok = rcp_IAmp->enableAmp(cmd.get(2).asInt32());
1865 } break;
1866
1867 case VOCAB_AMP_DISABLE: {
1868 if (!rcp_IAmp) { ok = false; break; }
1869 ok = rcp_IAmp->disableAmp(cmd.get(2).asInt32());
1870 } break;
1871
1872 case VOCAB_AMP_MAXCURRENT: {
1873 if (!rcp_IAmp) { ok = false; break; }
1874 ok = rcp_IAmp->setMaxCurrent(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1875 } break;
1876
1878 if (!rcp_IAmp) { ok = false; break; }
1879 ok = rcp_IAmp->setPeakCurrent(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1880 } break;
1881
1883 if (!rcp_IAmp) { ok = false; break; }
1884 ok = rcp_IAmp->setNominalCurrent(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1885 } break;
1886
1887 case VOCAB_AMP_PWM_LIMIT: {
1888 if (!rcp_IAmp) { ok = false; break; }
1889 ok = rcp_IAmp->setPWMLimit(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1890 } break;
1891
1892 case VOCAB_LIMITS: {
1893 if (!rcp_Ilim) {ok= false; break;}
1894 ok = rcp_Ilim->setLimits(cmd.get(2).asInt32(), cmd.get(3).asFloat64(), cmd.get(4).asFloat64());
1895 } break;
1896
1897
1899 if (!rpc_IMotor) { ok = false; break; }
1900 ok = rpc_IMotor->setTemperatureLimit(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1901 } break;
1902
1903 case VOCAB_GEARBOX_RATIO: {
1904 if (!rpc_IMotor) { ok = false; break; }
1905 ok = rpc_IMotor->setGearboxRatio(cmd.get(2).asInt32(), cmd.get(3).asFloat64());
1906 } break;
1907
1908 case VOCAB_VEL_LIMITS: {
1909 if (!rcp_Ilim) { ok = false; break; }
1910 ok = rcp_Ilim->setVelLimits(cmd.get(2).asInt32(), cmd.get(3).asFloat64(), cmd.get(4).asFloat64());
1911 } break;
1912
1913 default:
1914 {
1915 yCError(CONTROLBOARD, "received an unknown command after a VOCAB_SET (%s)", cmd.toString().c_str());
1916 } break;
1917 } //switch(cmd.get(1).asVocab32()
1918 break;
1919 }
1920
1921 case VOCAB_GET: {
1922 rec = true;
1923 yCTrace(CONTROLBOARD, "get command received");
1924
1925 double dtmp = 0.0;
1926 Bottle btmp;
1927 response.addVocab32(VOCAB_IS);
1928 response.add(cmd.get(1));
1929
1930 switch (cmd.get(1).asVocab32()) {
1931
1933 if (!rpc_IMotor) { ok = false; break; }
1934 ok = rpc_IMotor->getTemperatureLimit(cmd.get(2).asInt32(), &dtmp);
1935 response.addFloat64(dtmp);
1936 } break;
1937
1938 case VOCAB_TEMPERATURE: {
1939 if (!rpc_IMotor) { ok = false; break; }
1940 ok = rpc_IMotor->getTemperature(cmd.get(2).asInt32(), &dtmp);
1941 response.addFloat64(dtmp);
1942 } break;
1943
1944 case VOCAB_GEARBOX_RATIO: {
1945 if (!rpc_IMotor) { ok = false; break; }
1946 ok = rpc_IMotor->getGearboxRatio(cmd.get(2).asInt32(), &dtmp);
1947 response.addFloat64(dtmp);
1948 } break;
1949
1950 case VOCAB_TEMPERATURES: {
1951 if (!rpc_IMotor) { ok = false; break; }
1952 auto* p = new double[controlledJoints];
1954 Bottle& b = response.addList();
1955 for (size_t i = 0; i < controlledJoints; i++) {
1956 b.addFloat64(p[i]);
1957 }
1958 delete[] p;
1959 } break;
1960
1961 case VOCAB_AMP_MAXCURRENT: {
1962 if (!rcp_IAmp) { ok = false; break; }
1963 ok = rcp_IAmp->getMaxCurrent(cmd.get(2).asInt32(), &dtmp);
1964 response.addFloat64(dtmp);
1965 } break;
1966
1967 case VOCAB_POSITION_MOVE: {
1968 if (!rpc_IPosCtrl) { ok = false; break; }
1969 yCTrace(CONTROLBOARD, "getTargetPosition");
1970 ok = rpc_IPosCtrl->getTargetPosition(cmd.get(2).asInt32(), &dtmp);
1971
1972 response.addFloat64(dtmp);
1973 rec = true;
1974 } break;
1975
1977 if (!rpc_IPosCtrl) { ok = false; break; }
1978 int len = cmd.get(2).asInt32();
1979 Bottle& in = *(cmd.get(3).asList());
1980 int* jointList = new int[len];
1981 auto* refs = new double[len];
1982
1983 for (int j = 0; j < len; j++) {
1984 jointList[j] = in.get(j).asInt32();
1985 }
1987
1988 Bottle& b = response.addList();
1989 for (int i = 0; i < len; i++) {
1990 b.addFloat64(refs[i]);
1991 }
1992
1993 delete[] jointList;
1994 delete[] refs;
1995 } break;
1996
1997 case VOCAB_POSITION_MOVES: {
1998 if (!rpc_IPosCtrl) { ok = false; break; }
1999 auto* refs = new double[controlledJoints];
2001 Bottle& b = response.addList();
2002 for (size_t i = 0; i < controlledJoints; i++) {
2003 b.addFloat64(refs[i]);
2004 }
2005 delete[] refs;
2006 } break;
2007
2008 case VOCAB_POSITION_DIRECT: {
2009 if (!rpc_IPosDirect) { ok = false; break; }
2010 yCTrace(CONTROLBOARD, "getRefPosition");
2011 ok = rpc_IPosDirect->getRefPosition(cmd.get(2).asInt32(), &dtmp);
2012
2013 response.addFloat64(dtmp);
2014 rec = true;
2015 } break;
2016
2018 if (!rpc_IPosDirect) { ok = false; break; }
2019 int len = cmd.get(2).asInt32();
2020 Bottle& in = *(cmd.get(3).asList());
2021 int* jointList = new int[len];
2022 auto* refs = new double[len];
2023
2024 for (int j = 0; j < len; j++) {
2025 jointList[j] = in.get(j).asInt32();
2026 }
2028
2029 Bottle& b = response.addList();
2030 for (int i = 0; i < len; i++) {
2031 b.addFloat64(refs[i]);
2032 }
2033
2034 delete[] jointList;
2035 delete[] refs;
2036 } break;
2037
2039 auto* refs = new double[controlledJoints];
2041 Bottle& b = response.addList();
2042 for (size_t i = 0; i < controlledJoints; i++) {
2043 b.addFloat64(refs[i]);
2044 }
2045 delete[] refs;
2046 } break;
2047
2048 case VOCAB_VELOCITY_MOVE: {
2049 if (!rpc_IVelCtrl) { ok = false; break; }
2050 yCTrace(CONTROLBOARD, "getVelocityMove - cmd: %s", cmd.toString().c_str());
2051 ok = rpc_IVelCtrl->getRefVelocity(cmd.get(2).asInt32(), &dtmp);
2052
2053 response.addFloat64(dtmp);
2054 rec = true;
2055 } break;
2056
2058 if (!rpc_IVelCtrl) { ok = false; break; }
2059 yCTrace(CONTROLBOARD, "getVelocityMove_group - cmd: %s", cmd.toString().c_str());
2060
2061 int len = cmd.get(2).asInt32();
2062 Bottle& in = *(cmd.get(3).asList());
2063 int* jointList = new int[len];
2064 auto* refs = new double[len];
2065
2066 for (int j = 0; j < len; j++) {
2067 jointList[j] = in.get(j).asInt32();
2068 }
2070
2071 Bottle& b = response.addList();
2072 for (int i = 0; i < len; i++) {
2073 b.addFloat64(refs[i]);
2074 }
2075
2076 delete[] jointList;
2077 delete[] refs;
2078 } break;
2079
2080 case VOCAB_VELOCITY_MOVES: {
2081 if (!rpc_IVelCtrl) { ok = false; break; }
2082 yCTrace(CONTROLBOARD, "getVelocityMoves - cmd: %s", cmd.toString().c_str());
2083
2084 auto* refs = new double[controlledJoints];
2086 Bottle& b = response.addList();
2087 for (size_t i = 0; i < controlledJoints; i++) {
2088 b.addFloat64(refs[i]);
2089 }
2090 delete[] refs;
2091 } break;
2092
2093 case VOCAB_MOTORS_NUMBER: {
2094 if (!rpc_IMotor) { ok = false; break; }
2095 int tmp;
2097 response.addInt32(tmp);
2098 } break;
2099
2100 case VOCAB_AXES: {
2101 int tmp = 0;
2102 if (rpc_IPosCtrl) { ok = rpc_IPosCtrl->getAxes(&tmp); if (ok) { response.addInt32(tmp); break;} }
2103 if (rpc_IVelCtrl) { ok = rpc_IVelCtrl->getAxes(&tmp); if (ok) { response.addInt32(tmp); break;} }
2104 if (rpc_ITorque) { ok = rpc_ITorque->getAxes(&tmp); if (ok) { response.addInt32(tmp); break;} }
2105 if (rpc_AxisInfo) { ok = rpc_AxisInfo->getAxes(&tmp); if (ok) { response.addInt32(tmp); break;} }
2106 ok = false;
2107 } break;
2108
2109 case VOCAB_MOTION_DONE: {
2110 if (!rpc_IPosCtrl) { ok = false; break; }
2111 bool x = false;
2112 ;
2113 ok = rpc_IPosCtrl->checkMotionDone(cmd.get(2).asInt32(), &x);
2114 response.addInt32(x);
2115 } break;
2116
2118 if (!rpc_IPosCtrl) { ok = false; break; }
2119 bool x = false;
2120 int len = cmd.get(2).asInt32();
2121 Bottle& in = *(cmd.get(3).asList());
2122 int* jointList = new int[len];
2123 for (int j = 0; j < len; j++) {
2124 jointList[j] = in.get(j).asInt32();
2125 }
2126 if (rpc_IPosCtrl != nullptr) {
2127 ok = rpc_IPosCtrl->checkMotionDone(len, jointList, &x);
2128 }
2129 response.addInt32(x);
2130
2131 delete[] jointList;
2132 } break;
2133
2134 case VOCAB_MOTION_DONES: {
2135 if (!rpc_IPosCtrl) { ok = false; break; }
2136 bool x = false;
2137 ok = rpc_IPosCtrl->checkMotionDone(&x);
2138 response.addInt32(x);
2139 } break;
2140
2141 case VOCAB_REF_SPEED: {
2142 if (!rpc_IPosCtrl) { ok = false; break; }
2143 ok = rpc_IPosCtrl->getRefSpeed(cmd.get(2).asInt32(), &dtmp);
2144 response.addFloat64(dtmp);
2145 } break;
2146
2147 case VOCAB_REF_SPEED_GROUP: {
2148 if (!rpc_IPosCtrl) { ok = false; break; }
2149 int len = cmd.get(2).asInt32();
2150 Bottle& in = *(cmd.get(3).asList());
2151 int* jointList = new int[len];
2152 auto* speeds = new double[len];
2153
2154 for (int j = 0; j < len; j++) {
2155 jointList[j] = in.get(j).asInt32();
2156 }
2157 ok = rpc_IPosCtrl->getRefSpeeds(len, jointList, speeds);
2158
2159 Bottle& b = response.addList();
2160 for (int i = 0; i < len; i++) {
2161 b.addFloat64(speeds[i]);
2162 }
2163
2164 delete[] jointList;
2165 delete[] speeds;
2166 } break;
2167
2168 case VOCAB_REF_SPEEDS: {
2169 if (!rpc_IPosCtrl) { ok = false; break; }
2170 auto* p = new double[controlledJoints];
2172 Bottle& b = response.addList();
2173 for (size_t i = 0; i < controlledJoints; i++) {
2174 b.addFloat64(p[i]);
2175 }
2176 delete[] p;
2177 } break;
2178
2180 if (!rpc_IPosCtrl) { ok = false; break; }
2182 response.addFloat64(dtmp);
2183 } break;
2184
2186 if (!rpc_IPosCtrl) { ok = false; break; }
2187 int len = cmd.get(2).asInt32();
2188 Bottle& in = *(cmd.get(3).asList());
2189 int* jointList = new int[len];
2190 auto* accs = new double[len];
2191
2192 for (int j = 0; j < len; j++) {
2193 jointList[j] = in.get(j).asInt32();
2194 }
2196
2197 Bottle& b = response.addList();
2198 for (int i = 0; i < len; i++) {
2199 b.addFloat64(accs[i]);
2200 }
2201
2202 delete[] jointList;
2203 delete[] accs;
2204 } break;
2205
2207 if (!rpc_IPosCtrl) { ok = false; break; }
2208 auto* p = new double[controlledJoints];
2210 Bottle& b = response.addList();
2211 for (size_t i = 0; i < controlledJoints; i++) {
2212 b.addFloat64(p[i]);
2213 }
2214 delete[] p;
2215 } break;
2216
2217 case VOCAB_ENCODER: {
2218 if (!rpc_IEncTimed) { ok = false; break; }
2219 ok = rpc_IEncTimed->getEncoder(cmd.get(2).asInt32(), &dtmp);
2220 response.addFloat64(dtmp);
2221 } break;
2222
2223 case VOCAB_ENCODERS: {
2224 if (!rpc_IEncTimed) { ok = false; break; }
2225 auto* p = new double[controlledJoints];
2227 Bottle& b = response.addList();
2228 for (size_t i = 0; i < controlledJoints; i++) {
2229 b.addFloat64(p[i]);
2230 }
2231 delete[] p;
2232 } break;
2233
2234 case VOCAB_ENCODER_SPEED: {
2235 if (!rpc_IEncTimed) { ok = false; break; }
2236 ok = rpc_IEncTimed->getEncoderSpeed(cmd.get(2).asInt32(), &dtmp);
2237 response.addFloat64(dtmp);
2238 } break;
2239
2240 case VOCAB_ENCODER_SPEEDS: {
2241 if (!rpc_IEncTimed) { ok = false; break; }
2242 auto* p = new double[controlledJoints];
2244 Bottle& b = response.addList();
2245 for (size_t i = 0; i < controlledJoints; i++) {
2246 b.addFloat64(p[i]);
2247 }
2248 delete[] p;
2249 } break;
2250
2252 if (!rpc_IEncTimed) { ok = false; break; }
2254 response.addFloat64(dtmp);
2255 } break;
2256
2258 if (!rpc_IEncTimed) { ok = false; break; }
2259 auto* p = new double[controlledJoints];
2261 Bottle& b = response.addList();
2262 for (size_t i = 0; i < controlledJoints; i++) {
2263 b.addFloat64(p[i]);
2264 }
2265 delete[] p;
2266 } break;
2267
2268 case VOCAB_MOTOR_CPR: {
2269 if (!rpc_IMotEnc) { ok = false; break; }
2271 response.addFloat64(dtmp);
2272 } break;
2273
2274 case VOCAB_MOTOR_ENCODER: {
2275 if (!rpc_IMotEnc) { ok = false; break; }
2276 ok = rpc_IMotEnc->getMotorEncoder(cmd.get(2).asInt32(), &dtmp);
2277 response.addFloat64(dtmp);
2278 } break;
2279
2280 case VOCAB_MOTOR_ENCODERS: {
2281 if (!rpc_IMotEnc) { ok = false; break; }
2282 auto* p = new double[controlledJoints];
2284 Bottle& b = response.addList();
2285 for (size_t i = 0; i < controlledJoints; i++) {
2286 b.addFloat64(p[i]);
2287 }
2288 delete[] p;
2289 } break;
2290
2292 if (!rpc_IMotEnc) { ok = false; break; }
2294 response.addFloat64(dtmp);
2295 } break;
2296
2298 if (!rpc_IMotEnc) { ok = false; break; }
2299 auto* p = new double[controlledJoints];
2301 Bottle& b = response.addList();
2302 for (size_t i = 0; i < controlledJoints; i++) {
2303 b.addFloat64(p[i]);
2304 }
2305 delete[] p;
2306 } break;
2307
2309 if (!rpc_IMotEnc) { ok = false; break; }
2311 response.addFloat64(dtmp);
2312 } break;
2313
2315 auto* p = new double[controlledJoints];
2316 if (!rpc_IMotEnc) { ok = false; break; }
2318 Bottle& b = response.addList();
2319 for (size_t i = 0; i < controlledJoints; i++) {
2320 b.addFloat64(p[i]);
2321 }
2322 delete[] p;
2323 } break;
2324
2326 int num = 0;
2327 if (!rpc_IMotEnc) { ok = false; break; }
2329 response.addInt32(num);
2330 } break;
2331
2332 case VOCAB_AMP_CURRENT: {
2333 if (!rcp_IAmp) { ok = false; break; }
2334 ok = rcp_IAmp->getCurrent(cmd.get(2).asInt32(), &dtmp);
2335 response.addFloat64(dtmp);
2336 } break;
2337
2338 case VOCAB_AMP_CURRENTS: {
2339 if (!rcp_IAmp) { ok = false; break; }
2340 auto* p = new double[controlledJoints];
2341 ok = rcp_IAmp->getCurrents(p);
2342 Bottle& b = response.addList();
2343 for (size_t i = 0; i < controlledJoints; i++) {
2344 b.addFloat64(p[i]);
2345 }
2346 delete[] p;
2347 } break;
2348
2349 case VOCAB_AMP_STATUS: {
2350 if (!rcp_IAmp) { ok = false; break; }
2351 int* p = new int[controlledJoints];
2352 ok = rcp_IAmp->getAmpStatus(p);
2353 Bottle& b = response.addList();
2354 for (size_t i = 0; i < controlledJoints; i++) {
2355 b.addInt32(p[i]);
2356 }
2357 delete[] p;
2358 } break;
2359
2361 int j = cmd.get(2).asInt32();
2362 int itmp;
2363 if (!rcp_IAmp) { ok = false; break; }
2364 ok = rcp_IAmp->getAmpStatus(j, &itmp);
2365 response.addInt32(itmp);
2366 } break;
2367
2369 int m = cmd.get(2).asInt32();
2370 if (!rcp_IAmp) { ok = false; break; }
2372 response.addFloat64(dtmp);
2373 } break;
2374
2376 int m = cmd.get(2).asInt32();
2377 if (!rcp_IAmp) { ok = false; break; }
2378 ok = rcp_IAmp->getPeakCurrent(m, &dtmp);
2379 response.addFloat64(dtmp);
2380 } break;
2381
2382 case VOCAB_AMP_PWM: {
2383 int m = cmd.get(2).asInt32();
2384 if (!rcp_IAmp) { ok = false; break; }
2385 ok = rcp_IAmp->getPWM(m, &dtmp);
2386 yCTrace(CONTROLBOARD) << "RPC parser::getPWM: j" << m << " val " << dtmp;
2387 response.addFloat64(dtmp);
2388 } break;
2389
2390 case VOCAB_AMP_PWM_LIMIT: {
2391 int m = cmd.get(2).asInt32();
2392 if (!rcp_IAmp) { ok = false; break; }
2393 ok = rcp_IAmp->getPWMLimit(m, &dtmp);
2394 response.addFloat64(dtmp);
2395 } break;
2396
2398 int m = cmd.get(2).asInt32();
2399 if (!rcp_IAmp) { ok = false; break; }
2401 response.addFloat64(dtmp);
2402 } break;
2403
2404 case VOCAB_LIMITS: {
2405 double min = 0.0;
2406 double max = 0.0;
2407 if (!rcp_Ilim) { ok = false; break; }
2408 ok = rcp_Ilim->getLimits(cmd.get(2).asInt32(), &min, &max);
2409 response.addFloat64(min);
2410 response.addFloat64(max);
2411 } break;
2412
2413 case VOCAB_VEL_LIMITS: {
2414 double min = 0.0;
2415 double max = 0.0;
2416 if (!rcp_Ilim) { ok = false; break; }
2417 ok = rcp_Ilim->getVelLimits(cmd.get(2).asInt32(), &min, &max);
2418 response.addFloat64(min);
2419 response.addFloat64(max);
2420 } break;
2421
2422 case VOCAB_INFO_NAME: {
2423 std::string name = "undocumented";
2424 if (!rpc_AxisInfo) { ok = false; break; }
2425 ok = rpc_AxisInfo->getAxisName(cmd.get(2).asInt32(), name);
2426 response.addString(name.c_str());
2427 } break;
2428
2429 case VOCAB_INFO_TYPE: {
2431 if (!rpc_AxisInfo) { ok = false; break; }
2432 ok = rpc_AxisInfo->getJointType(cmd.get(2).asInt32(), type);
2433 response.addInt32(type);
2434 } break;
2435
2436 default:
2437 {
2438 yCError(CONTROLBOARD, "received an unknown request after a VOCAB_GET: %s", yarp::os::Vocab32::decode(cmd.get(1).asVocab32()).c_str());
2439 } break;
2440 } //switch cmd.get(1).asVocab32())
2441
2443 appendTimeStamp(response, lastRpcStamp);
2444 } // case VOCAB_GET
2445 default:
2446 break;
2447 } //switch code
2448
2449 if (!rec) {
2450 ok = DeviceResponder::respond(cmd, response);
2451 }
2452 }
2453
2454 if (!ok) {
2455 // failed thus send only a VOCAB back.
2456 response.clear();
2457 response.addVocab32(VOCAB_FAILED);
2458 } else {
2459 response.addVocab32(VOCAB_OK);
2460 }
2461 }
2462 std::string ss = response.toString();
2463
2464 return ok;
2465}
2466
2468{
2469 bool ok = false;
2470 int tmp_axes = 0;
2471 if (rpc_IPosCtrl) { rpc_IPosCtrl->getAxes(&tmp_axes); ok = true; }
2472 else if (rpc_IVelCtrl) { rpc_IVelCtrl->getAxes(&tmp_axes); ok = true; }
2473 else if (rpc_ITorque) { rpc_ITorque->getAxes(&tmp_axes); ok = true; }
2474 else if (rpc_AxisInfo) { rpc_AxisInfo->getAxes(&tmp_axes); ok = true; }
2475 if (ok) { controlledJoints = static_cast<size_t>(tmp_axes); }
2476 else { yCError(CONTROLBOARD, "Unable to get number of joints"); return false; }
2477
2479 addUsage("[get] [axes]", "get the number of axes");
2480 addUsage("[get] [name] $iAxisNumber", "get a human-readable name for an axis, if available");
2481 addUsage("[set] [pos] $iAxisNumber $fPosition", "command the position of an axis");
2482 addUsage("[set] [rel] $iAxisNumber $fPosition", "command the relative position of an axis");
2483 addUsage("[set] [vmo] $iAxisNumber $fVelocity", "command the velocity of an axis");
2484 addUsage("[get] [enc] $iAxisNumber", "get the encoder value for an axis");
2485
2486 std::string args;
2487 for (size_t i = 0; i < controlledJoints; i++) {
2488 if (i > 0) {
2489 args += " ";
2490 }
2491 // removed dependency from yarp internals
2492 //args = args + "$f" + yarp::yarp::conf::numeric::to_string(i);
2493 }
2494 addUsage((std::string("[set] [poss] (") + args + ")").c_str(),
2495 "command the position of all axes");
2496 addUsage((std::string("[set] [rels] (") + args + ")").c_str(),
2497 "command the relative position of all axes");
2498 addUsage((std::string("[set] [vmos] (") + args + ")").c_str(),
2499 "command the velocity of all axes");
2500
2501 addUsage("[set] [aen] $iAxisNumber", "enable (amplifier for) the given axis");
2502 addUsage("[set] [adi] $iAxisNumber", "disable (amplifier for) the given axis");
2503 addUsage("[get] [acu] $iAxisNumber", "get current for the given axis");
2504 addUsage("[get] [acus]", "get current for all axes");
2505
2506 return ok;
2507}
2508
2510{
2511 x->view(rpc_IPid);
2512 x->view(rpc_IPosCtrl);
2513 x->view(rpc_IPosDirect);
2514 x->view(rpc_IVelCtrl);
2515 x->view(rpc_IEncTimed);
2516 x->view(rpc_IMotEnc);
2517 x->view(rpc_IMotor);
2518 x->view(rpc_IVar);
2519 x->view(rcp_IAmp);
2520 x->view(rcp_Ilim);
2521 x->view(rpc_AxisInfo);
2523 x->view(rpc_Icalib);
2524 x->view(rpc_IImpedance);
2525 x->view(rpc_ITorque);
2526 x->view(rpc_iCtrlMode);
2527 x->view(rpc_IInteract);
2528 x->view(rpc_ICurrent);
2529 x->view(rpc_IPWM);
2531 controlledJoints = 0;
2532}
2533
2535{
2536 rpc_IPid = nullptr;
2537 rpc_IPosCtrl = nullptr;
2538 rpc_IPosDirect = nullptr;
2539 rpc_IVelCtrl = nullptr;
2540 rpc_IEncTimed = nullptr;
2541 rpc_IMotEnc = nullptr;
2542 rpc_IMotor = nullptr;
2543 rpc_IVar = nullptr;
2544 rcp_IAmp = nullptr;
2545 rcp_Ilim = nullptr;
2546 rpc_AxisInfo = nullptr;
2547 rpc_IRemoteCalibrator = nullptr;
2548 rpc_Icalib = nullptr;
2549 rpc_IImpedance = nullptr;
2550 rpc_ITorque = nullptr;
2551 rpc_iCtrlMode = nullptr;
2552 rpc_IInteract = nullptr;
2553 rpc_ICurrent = nullptr;
2554 rpc_IPWM = nullptr;
2555 rpc_IJointFault = nullptr;
2556 controlledJoints = 0;
2557}
constexpr yarp::conf::vocab32_t VOCAB_PARK_SINGLE_JOINT
constexpr yarp::conf::vocab32_t VOCAB_REMOTE_CALIBRATOR_INTERFACE
constexpr yarp::conf::vocab32_t VOCAB_HOMING_WHOLE_PART
constexpr yarp::conf::vocab32_t VOCAB_PARK_WHOLE_PART
constexpr yarp::conf::vocab32_t VOCAB_QUIT_PARK
constexpr yarp::conf::vocab32_t VOCAB_IS_CALIBRATOR_PRESENT
constexpr yarp::conf::vocab32_t VOCAB_CALIBRATE_SINGLE_JOINT
constexpr yarp::conf::vocab32_t VOCAB_HOMING_SINGLE_JOINT
constexpr yarp::conf::vocab32_t VOCAB_CALIBRATE_WHOLE_PART
constexpr yarp::conf::vocab32_t VOCAB_QUIT_CALIBRATE
const yarp::os::LogComponent & CONTROLBOARD()
constexpr yarp::conf::vocab32_t VOCAB_TIMESTAMP
constexpr yarp::conf::vocab32_t VOCAB_VELOCITY_MOVE
constexpr yarp::conf::vocab32_t VOCAB_REF_SPEED
constexpr yarp::conf::vocab32_t VOCAB_STOPS
constexpr yarp::conf::vocab32_t VOCAB_MOTION_DONE
constexpr yarp::conf::vocab32_t VOCAB_STOP
constexpr yarp::conf::vocab32_t VOCAB_REF_ACCELERATIONS
constexpr yarp::conf::vocab32_t VOCAB_MOTION_DONES
constexpr yarp::conf::vocab32_t VOCAB_PROTOCOL_VERSION
constexpr yarp::conf::vocab32_t VOCAB_POSITION_MOVE
constexpr yarp::conf::vocab32_t VOCAB_REF_ACCELERATION
constexpr yarp::conf::vocab32_t VOCAB_VELOCITY_MOVES
constexpr yarp::conf::vocab32_t VOCAB_RELATIVE_MOVE
constexpr yarp::conf::vocab32_t VOCAB_REF_SPEEDS
constexpr yarp::conf::vocab32_t VOCAB_RELATIVE_MOVES
constexpr yarp::conf::vocab32_t VOCAB_POSITION_MOVES
constexpr yarp::conf::vocab32_t VOCAB_LIM
constexpr yarp::conf::vocab32_t VOCAB_OUTPUTS
constexpr yarp::conf::vocab32_t VOCAB_ENABLE
constexpr yarp::conf::vocab32_t VOCAB_DISABLE
constexpr yarp::conf::vocab32_t VOCAB_OK
constexpr yarp::conf::vocab32_t VOCAB_REF
constexpr yarp::conf::vocab32_t VOCAB_IS
constexpr yarp::conf::vocab32_t VOCAB_ERRS
constexpr yarp::conf::vocab32_t VOCAB_GET
constexpr yarp::conf::vocab32_t VOCAB_OUTPUT
constexpr yarp::conf::vocab32_t VOCAB_REFERENCE
constexpr yarp::conf::vocab32_t VOCAB_FAILED
constexpr yarp::conf::vocab32_t VOCAB_ERR
constexpr yarp::conf::vocab32_t VOCAB_REFS
constexpr yarp::conf::vocab32_t VOCAB_REFERENCES
constexpr yarp::conf::vocab32_t VOCAB_RESET
constexpr yarp::conf::vocab32_t VOCAB_AXES
constexpr yarp::conf::vocab32_t VOCAB_SET
constexpr yarp::conf::vocab32_t VOCAB_OFFSET
constexpr yarp::conf::vocab32_t VOCAB_LIMS
constexpr yarp::conf::vocab32_t VOCAB_AMP_DISABLE
constexpr yarp::conf::vocab32_t VOCAB_AMP_PEAK_CURRENT
constexpr yarp::conf::vocab32_t VOCAB_AMP_ENABLE
constexpr yarp::conf::vocab32_t VOCAB_AMP_VOLTAGE_SUPPLY
constexpr yarp::conf::vocab32_t VOCAB_AMP_CURRENT
constexpr yarp::conf::vocab32_t VOCAB_AMP_MAXCURRENT
constexpr yarp::conf::vocab32_t VOCAB_AMP_STATUS_SINGLE
constexpr yarp::conf::vocab32_t VOCAB_AMP_STATUS
constexpr yarp::conf::vocab32_t VOCAB_AMP_NOMINAL_CURRENT
constexpr yarp::conf::vocab32_t VOCAB_AMP_PWM
constexpr yarp::conf::vocab32_t VOCAB_AMP_CURRENTS
constexpr yarp::conf::vocab32_t VOCAB_AMP_PWM_LIMIT
constexpr yarp::conf::vocab32_t VOCAB_INFO_TYPE
Definition IAxisInfo.h:104
constexpr yarp::conf::vocab32_t VOCAB_INFO_NAME
Definition IAxisInfo.h:103
constexpr yarp::conf::vocab32_t VOCAB_CALIBRATE_JOINT_PARAMS
constexpr yarp::conf::vocab32_t VOCAB_CALIBRATE_DONE
constexpr yarp::conf::vocab32_t VOCAB_CALIBRATE_JOINT
constexpr yarp::conf::vocab32_t VOCAB_CALIBRATE
constexpr yarp::conf::vocab32_t VOCAB_PARK
constexpr yarp::conf::vocab32_t VOCAB_LIMITS
constexpr yarp::conf::vocab32_t VOCAB_VEL_LIMITS
constexpr yarp::conf::vocab32_t VOCAB_CM_CONTROL_MODE_GROUP
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_IMPEDANCE_VEL
constexpr yarp::conf::vocab32_t VOCAB_CM_POSITION
constexpr yarp::conf::vocab32_t VOCAB_CM_CONTROL_MODES
constexpr yarp::conf::vocab32_t VOCAB_CM_CURRENT
constexpr yarp::conf::vocab32_t VOCAB_CM_IMPEDANCE_POS
constexpr yarp::conf::vocab32_t VOCAB_CM_CONTROL_MODE
constexpr yarp::conf::vocab32_t VOCAB_CM_POSITION_DIRECT
constexpr yarp::conf::vocab32_t VOCAB_ICONTROLMODE
constexpr yarp::conf::vocab32_t VOCAB_CM_VELOCITY
constexpr yarp::conf::vocab32_t VOCAB_CM_FORCE_IDLE
constexpr yarp::conf::vocab32_t VOCAB_CURRENT_REF_GROUP
constexpr yarp::conf::vocab32_t VOCAB_CURRENT_REFS
constexpr yarp::conf::vocab32_t VOCAB_CURRENT_RANGE
constexpr yarp::conf::vocab32_t VOCAB_CURRENTCONTROL_INTERFACE
constexpr yarp::conf::vocab32_t VOCAB_CURRENT_REF
constexpr yarp::conf::vocab32_t VOCAB_CURRENT_RANGES
constexpr yarp::conf::vocab32_t VOCAB_E_RESET
Definition IEncoders.h:204
constexpr yarp::conf::vocab32_t VOCAB_ENCODER_ACCELERATIONS
Definition IEncoders.h:213
constexpr yarp::conf::vocab32_t VOCAB_ENCODER
Definition IEncoders.h:206
constexpr yarp::conf::vocab32_t VOCAB_ENCODER_SPEEDS
Definition IEncoders.h:211
constexpr yarp::conf::vocab32_t VOCAB_E_RESETS
Definition IEncoders.h:205
constexpr yarp::conf::vocab32_t VOCAB_ENCODER_SPEED
Definition IEncoders.h:210
constexpr yarp::conf::vocab32_t VOCAB_ENCODER_ACCELERATION
Definition IEncoders.h:212
constexpr yarp::conf::vocab32_t VOCAB_ENCODERS
Definition IEncoders.h:207
constexpr yarp::conf::vocab32_t VOCAB_IMPEDANCE
constexpr yarp::conf::vocab32_t VOCAB_INTERACTION_MODES
constexpr yarp::conf::vocab32_t VOCAB_INTERACTION_MODE_GROUP
constexpr yarp::conf::vocab32_t VOCAB_INTERACTION_MODE
constexpr yarp::conf::vocab32_t VOCAB_INTERFACE_INTERACTION_MODE
constexpr yarp::conf::vocab32_t VOCAB_JF_GET_JOINTFAULT
Definition IJointFault.h:42
constexpr yarp::conf::vocab32_t VOCAB_IJOINTFAULT
Definition IJointFault.h:41
constexpr yarp::conf::vocab32_t VOCAB_MOTOR_ENCODER_SPEED
constexpr yarp::conf::vocab32_t VOCAB_MOTOR_ENCODER_ACCELERATIONS
constexpr yarp::conf::vocab32_t VOCAB_MOTOR_ENCODER_ACCELERATION
constexpr yarp::conf::vocab32_t VOCAB_MOTOR_ENCODER
constexpr yarp::conf::vocab32_t VOCAB_MOTOR_ENCODER_SPEEDS
constexpr yarp::conf::vocab32_t VOCAB_MOTOR_ENCODER_NUMBER
constexpr yarp::conf::vocab32_t VOCAB_MOTOR_E_RESETS
constexpr yarp::conf::vocab32_t VOCAB_MOTOR_E_RESET
constexpr yarp::conf::vocab32_t VOCAB_MOTOR_ENCODERS
constexpr yarp::conf::vocab32_t VOCAB_MOTOR_CPR
constexpr yarp::conf::vocab32_t VOCAB_TEMPERATURES
Definition IMotor.h:162
constexpr yarp::conf::vocab32_t VOCAB_TEMPERATURE_LIMIT
Definition IMotor.h:163
constexpr yarp::conf::vocab32_t VOCAB_TEMPERATURE
Definition IMotor.h:160
constexpr yarp::conf::vocab32_t VOCAB_GEARBOX_RATIO
Definition IMotor.h:161
constexpr yarp::conf::vocab32_t VOCAB_MOTORS_NUMBER
Definition IMotor.h:159
constexpr yarp::conf::vocab32_t VOCAB_PWMCONTROL_INTERFACE
constexpr yarp::conf::vocab32_t VOCAB_PWMCONTROL_PWM_OUTPUTS
constexpr yarp::conf::vocab32_t VOCAB_PWMCONTROL_REF_PWMS
constexpr yarp::conf::vocab32_t VOCAB_PWMCONTROL_REF_PWM
constexpr yarp::conf::vocab32_t VOCAB_PWMCONTROL_PWM_OUTPUT
constexpr yarp::conf::vocab32_t VOCAB_PIDS
constexpr yarp::conf::vocab32_t VOCAB_PID
constexpr yarp::conf::vocab32_t VOCAB_REF_ACCELERATION_GROUP
constexpr yarp::conf::vocab32_t VOCAB_STOP_GROUP
constexpr yarp::conf::vocab32_t VOCAB_RELATIVE_MOVE_GROUP
constexpr yarp::conf::vocab32_t VOCAB_POSITION_MOVE_GROUP
constexpr yarp::conf::vocab32_t VOCAB_MOTION_DONE_GROUP
constexpr yarp::conf::vocab32_t VOCAB_REF_SPEED_GROUP
constexpr yarp::conf::vocab32_t VOCAB_POSITION_DIRECTS
constexpr yarp::conf::vocab32_t VOCAB_POSITION_DIRECT
constexpr yarp::conf::vocab32_t VOCAB_POSITION_DIRECT_GROUP
constexpr yarp::conf::vocab32_t VOCAB_LIST_VARIABLES
constexpr yarp::conf::vocab32_t VOCAB_VARIABLE
constexpr yarp::conf::vocab32_t VOCAB_REMOTE_VARIABILE_INTERFACE
constexpr yarp::conf::vocab32_t VOCAB_TORQUE
constexpr yarp::conf::vocab32_t VOCAB_TRQ
constexpr yarp::conf::vocab32_t VOCAB_TRQS
constexpr yarp::conf::vocab32_t VOCAB_RANGE
constexpr yarp::conf::vocab32_t VOCAB_IMP_OFFSET
constexpr yarp::conf::vocab32_t VOCAB_MOTOR_PARAMS
constexpr yarp::conf::vocab32_t VOCAB_IMP_PARAM
constexpr yarp::conf::vocab32_t VOCAB_RANGES
constexpr yarp::conf::vocab32_t VOCAB_TORQUE_MODE
constexpr yarp::conf::vocab32_t VOCAB_VELOCITY_MOVE_GROUP
void appendTimeStamp(Bottle &bot, Stamp &st)
constexpr int PROTOCOL_VERSION_TWEAK
constexpr int PROTOCOL_VERSION_MINOR
constexpr int PROTOCOL_VERSION_MAJOR
void handleRemoteCalibratorMsg(const yarp::os::Bottle &cmd, yarp::os::Bottle &response, bool *rec, bool *ok)
yarp::dev::IControlCalibration * rpc_Icalib
yarp::dev::IEncodersTimed * rpc_IEncTimed
yarp::dev::IControlMode * rpc_iCtrlMode
yarp::dev::IRemoteCalibrator * rpc_IRemoteCalibrator
yarp::dev::IAxisInfo * rpc_AxisInfo
yarp::dev::ITorqueControl * rpc_ITorque
yarp::dev::IPidControl * rpc_IPid
void handleProtocolVersionRequest(const yarp::os::Bottle &cmd, yarp::os::Bottle &response, bool *rec, bool *ok)
void handlePWMMsg(const yarp::os::Bottle &cmd, yarp::os::Bottle &response, bool *rec, bool *ok)
yarp::dev::IRemoteVariables * rpc_IVar
yarp::dev::IImpedanceControl * rpc_IImpedance
void handleCurrentMsg(const yarp::os::Bottle &cmd, yarp::os::Bottle &response, bool *rec, bool *ok)
void handleInteractionModeMsg(const yarp::os::Bottle &cmd, yarp::os::Bottle &response, bool *rec, bool *ok)
void handleControlModeMsg(const yarp::os::Bottle &cmd, yarp::os::Bottle &response, bool *rec, bool *ok)
void init(yarp::dev::DeviceDriver *x)
Initialization.
yarp::dev::IPositionDirect * rpc_IPosDirect
yarp::dev::ICurrentControl * rpc_ICurrent
void handleTorqueMsg(const yarp::os::Bottle &cmd, yarp::os::Bottle &response, bool *rec, bool *ok)
yarp::dev::IMotorEncoders * rpc_IMotEnc
yarp::dev::IInteractionMode * rpc_IInteract
void handleJointFaultMsg(const yarp::os::Bottle &cmd, yarp::os::Bottle &response, bool *rec, bool *ok)
void handlePidMsg(const yarp::os::Bottle &cmd, yarp::os::Bottle &response, bool *rec, bool *ok)
yarp::dev::IJointFault * rpc_IJointFault
virtual bool initialize()
Initialize the internal data.
yarp::dev::IPositionControl * rpc_IPosCtrl
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
yarp::sig::Vector tmpVect
yarp::dev::IVelocityControl * rpc_IVelCtrl
yarp::dev::IPWMControl * rpc_IPWM
yarp::dev::IAmplifierControl * rcp_IAmp
yarp::dev::IMotor * rpc_IMotor
yarp::dev::IControlLimits * rcp_Ilim
yarp::os::Stamp lastRpcStamp
void handleImpedanceMsg(const yarp::os::Bottle &cmd, yarp::os::Bottle &response, bool *rec, bool *ok)
void handleRemoteVariablesMsg(const yarp::os::Bottle &cmd, yarp::os::Bottle &response, bool *rec, bool *ok)
Interface implemented by all device drivers.
bool view(T *&x)
Get an interface to the device driver.
virtual bool respond(const yarp::os::Bottle &command, yarp::os::Bottle &reply)
Respond to a message.
void addUsage(const char *txt, const char *explain=nullptr)
Add information about a message that the respond() method understands.
void makeUsage()
Regenerate usage information.
virtual bool getPWMLimit(int j, double *val)
virtual bool enableAmp(int j)=0
Enable the amplifier on a specific joint.
virtual bool setNominalCurrent(int m, const double val)
virtual bool getCurrents(double *vals)=0
virtual bool disableAmp(int j)=0
Disable the amplifier on a specific joint.
virtual bool getPWM(int j, double *val)
virtual bool getAmpStatus(int *st)=0
virtual bool setPWMLimit(int j, const double val)
virtual bool getMaxCurrent(int j, double *v)=0
Returns the maximum electric current allowed for a given motor.
virtual bool getNominalCurrent(int m, double *val)
virtual bool getCurrent(int j, double *val)=0
virtual bool getPowerSupplyVoltage(int j, double *val)
virtual bool setMaxCurrent(int j, double v)=0
virtual bool setPeakCurrent(int m, const double val)
virtual bool getPeakCurrent(int m, double *val)
virtual bool getAxisName(int axis, std::string &name)=0
virtual bool getAxes(int *ax)=0
Get the number of controlled axes.
virtual bool getJointType(int axis, yarp::dev::JointTypeEnum &type)
Definition IAxisInfo.h:63
virtual bool setCalibrationParameters(int axis, const CalibrationParameters &params)
Start calibration, this method is very often platform specific.
virtual bool calibrateRobot()
Calibrate robot by using an external calibrator.
virtual bool calibrationDone(int j)=0
Check if the calibration is terminated, on a particular joint.
virtual bool calibrateAxisWithParams(int axis, unsigned int type, double p1, double p2, double p3)=0
Start calibration, this method is very often platform specific.
virtual bool getVelLimits(int axis, double *min, double *max)=0
Get the software speed limits for a particular axis.
virtual bool getLimits(int axis, double *min, double *max)=0
Get the software limits for a particular axis.
virtual bool setLimits(int axis, double min, double max)=0
Set the software limits for a particular axis, the behavior of the control card when these limits are...
virtual bool setVelLimits(int axis, double min, double max)=0
Set the software speed limits for a particular axis, the behavior of the control card when these limi...
virtual bool setControlMode(const int j, const int mode)=0
Set the current control mode.
virtual bool setControlModes(const int n_joint, const int *joints, int *modes)=0
Set the current control mode for a subset of axes.
virtual bool getControlModes(int *modes)=0
Get the current control mode (multiple joints).
virtual bool getControlMode(int j, int *mode)=0
Get the current control mode.
virtual bool getRefCurrents(double *currs)=0
Get the reference value of the currents for all motors.
virtual bool getCurrentRange(int m, double *min, double *max)=0
Get the full scale of the current measurement for a given motor (e.g.
virtual bool getRefCurrent(int m, double *curr)=0
Get the reference value of the current for a single motor.
virtual bool getCurrentRanges(double *min, double *max)=0
Get the full scale of the current measurements for all motors motor (e.g.
virtual bool getEncoderSpeed(int j, double *sp)=0
Read the istantaneous speed of an axis.
virtual bool getEncoderAccelerations(double *accs)=0
Read the instantaneous acceleration of all axes.
virtual bool setEncoder(int j, double val)=0
Set the value of the encoder for a given joint.
virtual bool getEncoder(int j, double *v)=0
Read the value of an encoder.
virtual bool resetEncoder(int j)=0
Reset encoder, single joint.
virtual bool setEncoders(const double *vals)=0
Set the value of all encoders.
virtual bool getEncoders(double *encs)=0
Read the position of all axes.
virtual bool getEncoderSpeeds(double *spds)=0
Read the instantaneous speed of all axes.
virtual bool getEncoderAcceleration(int j, double *spds)=0
Read the instantaneous acceleration of an axis.
virtual bool resetEncoders()=0
Reset encoders.
virtual bool setImpedance(int j, double stiffness, double damping)=0
Set current impedance gains (stiffness,damping) for a specific joint.
virtual bool getImpedanceOffset(int j, double *offset)=0
Get current force Offset for a specific joint.
virtual bool setImpedanceOffset(int j, double offset)=0
Set current force Offset for a specific joint.
virtual bool getImpedance(int j, double *stiffness, double *damping)=0
Get current impedance gains (stiffness,damping,offset) for a specific joint.
virtual bool getCurrentImpedanceLimit(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp)=0
Get the current impedandance limits for a specific joint.
virtual bool getInteractionMode(int axis, yarp::dev::InteractionModeEnum *mode)=0
Get the current interaction mode of the robot, values can be stiff or compliant.
virtual bool getInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes)=0
Get the current interaction mode of the robot for a set of joints, values can be stiff or compliant.
virtual bool setInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes)=0
Set the interaction mode of the robot for a set of joints, values can be stiff or compliant.
virtual bool setInteractionMode(int axis, yarp::dev::InteractionModeEnum mode)=0
Set the interaction mode of the robot, values can be stiff or compliant.
virtual bool getLastJointFault(int j, int &fault, std::string &message)=0
virtual bool getMotorEncoderCountsPerRevolution(int m, double *cpr)=0
Gets number of counts per revolution for motor encoder m.
virtual bool setMotorEncoderCountsPerRevolution(int m, const double cpr)=0
Sets number of counts per revolution for motor encoder m.
virtual bool resetMotorEncoder(int m)=0
Reset motor encoder, single motor.
virtual bool getMotorEncoderSpeed(int m, double *sp)=0
Read the istantaneous speed of a motor encoder.
virtual bool getMotorEncoderSpeeds(double *spds)=0
Read the instantaneous speed of all motor encoders.
virtual bool getMotorEncoderAcceleration(int m, double *acc)=0
Read the instantaneous acceleration of a motor encoder.
virtual bool getMotorEncoderAccelerations(double *accs)=0
Read the instantaneous acceleration of all motor encoders.
virtual bool getNumberOfMotorEncoders(int *num)=0
Get the number of available motor encoders.
virtual bool setMotorEncoders(const double *vals)=0
Set the value of all motor encoders.
virtual bool getMotorEncoders(double *encs)=0
Read the position of all motor encoders.
virtual bool resetMotorEncoders()=0
Reset motor encoders.
virtual bool setMotorEncoder(int m, const double val)=0
Set the value of the motor encoder for a given motor.
virtual bool getMotorEncoder(int m, double *v)=0
Read the value of a motor encoder.
virtual bool getTemperature(int m, double *val)=0
Get temperature of a motor.
virtual bool getTemperatures(double *vals)=0
Get temperature of all the motors.
virtual bool getNumberOfMotors(int *num)=0
Get the number of available motors.
virtual bool getTemperatureLimit(int m, double *temp)=0
Retreives the current temperature limit for a specific motor.
virtual bool getGearboxRatio(int m, double *val)
Get the gearbox ratio for a specific motor.
Definition IMotor.h:147
virtual bool setTemperatureLimit(int m, const double temp)=0
Set the temperature limit for a specific motor.
virtual bool setGearboxRatio(int m, const double val)
Set the gearbox ratio for a specific motor.
Definition IMotor.h:155
virtual bool getDutyCycle(int m, double *val)=0
Gets the current dutycycle of the output of the amplifier (i.e.
virtual bool getRefDutyCycles(double *refs)=0
Gets the last reference sent using the setRefDutyCycles function.
virtual bool getRefDutyCycle(int m, double *ref)=0
Gets the last reference sent using the setRefDutyCycle function.
virtual bool setPid(const PidControlTypeEnum &pidtype, int j, const Pid &pid)=0
Set new pid value for a joint axis.
virtual bool getPidReference(const PidControlTypeEnum &pidtype, int j, double *ref)=0
Get the current reference of the pid controller for a specific joint.
virtual bool getPidOutput(const PidControlTypeEnum &pidtype, int j, double *out)=0
Get the output of the controller (e.g.
virtual bool getPidReferences(const PidControlTypeEnum &pidtype, double *refs)=0
Get the current reference of all pid controllers.
virtual bool resetPid(const PidControlTypeEnum &pidtype, int j)=0
Reset the controller of a given joint, usually sets the current status of the joint as the reference ...
virtual bool setPidOffset(const PidControlTypeEnum &pidtype, int j, double v)=0
Set offset value for a given controller.
virtual bool getPidErrorLimits(const PidControlTypeEnum &pidtype, double *limits)=0
Get the error limit for all controllers.
virtual bool getPidError(const PidControlTypeEnum &pidtype, int j, double *err)=0
Get the current error for a joint.
virtual bool getPidErrorLimit(const PidControlTypeEnum &pidtype, int j, double *limit)=0
Get the error limit for the controller on a specific joint.
virtual bool setPidErrorLimit(const PidControlTypeEnum &pidtype, int j, double limit)=0
Set the error limit for the controller on a specifi joint.
virtual bool disablePid(const PidControlTypeEnum &pidtype, int j)=0
Disable the pid computation for a joint.
virtual bool setPidErrorLimits(const PidControlTypeEnum &pidtype, const double *limits)=0
Get the error limit for the controller on all joints.
virtual bool getPidOutputs(const PidControlTypeEnum &pidtype, double *outs)=0
Get the output of the controllers (e.g.
virtual bool setPidReference(const PidControlTypeEnum &pidtype, int j, double ref)=0
Set the controller reference for a given axis.
virtual bool setPidReferences(const PidControlTypeEnum &pidtype, const double *refs)=0
Set the controller reference, multiple axes.
virtual bool getPidErrors(const PidControlTypeEnum &pidtype, double *errs)=0
Get the error of all joints.
virtual bool setPids(const PidControlTypeEnum &pidtype, const Pid *pids)=0
Set new pid value on multiple axes.
virtual bool enablePid(const PidControlTypeEnum &pidtype, int j)=0
Enable the pid computation for a joint.
virtual bool isPidEnabled(const PidControlTypeEnum &pidtype, int j, bool *enabled)=0
Get the current status (enabled/disabled) of the pid.
virtual bool getPids(const PidControlTypeEnum &pidtype, Pid *pids)=0
Get current pid value for a specific joint.
virtual bool getPid(const PidControlTypeEnum &pidtype, int j, Pid *pid)=0
Get current pid value for a specific joint.
virtual bool getRefAcceleration(int j, double *acc)=0
Get reference acceleration for a joint.
virtual bool getAxes(int *ax)=0
Get the number of controlled axes.
virtual bool setRefSpeed(int j, double sp)=0
Set reference speed for a joint, this is the speed used during the interpolation of the trajectory.
virtual bool setRefAcceleration(int j, double acc)=0
Set reference acceleration for a joint.
virtual bool relativeMove(int j, double delta)=0
Set relative position.
virtual bool getTargetPosition(const int joint, double *ref)
Get the last position reference for the specified axis.
virtual bool setRefSpeeds(const double *spds)=0
Set reference speed on all joints.
virtual bool checkMotionDone(int j, bool *flag)=0
Check if the current trajectory is terminated.
virtual bool getRefSpeeds(double *spds)=0
Get reference speed of all joints.
virtual bool stop(int j)=0
Stop motion, single joint.
virtual bool setRefAccelerations(const double *accs)=0
Set reference acceleration on all joints.
virtual bool getRefAccelerations(double *accs)=0
Get reference acceleration of all joints.
virtual bool getRefSpeed(int j, double *ref)=0
Get reference speed for a joint.
virtual bool positionMove(int j, double ref)=0
Set new reference point for a single axis.
virtual bool getTargetPositions(double *refs)
Get the last position reference for all axes.
virtual bool getRefPositions(double *refs)
Get the last position reference for all axes.
virtual bool getRefPosition(const int joint, double *ref)
Get the last position reference for the specified axis.
virtual bool parkWholePart()=0
parkWholePart: start the parking procedure for the whole part
virtual bool homingSingleJoint(int j)=0
homingSingleJoint: call the homing procedure for a single joint
virtual bool isCalibratorDevicePresent(bool *isCalib)
isCalibratorDevicePresent: check if a calibrator device has been set
virtual bool homingWholePart()=0
homingWholePart: call the homing procedure for a the whole part/device
virtual bool quitPark()=0
quitPark: interrupt the park procedure
virtual bool parkSingleJoint(int j, bool _wait=true)=0
parkSingleJoint(): start the parking procedure for the single joint
virtual bool calibrateSingleJoint(int j)=0
calibrateSingleJoint: call the calibration procedure for the single joint
virtual bool calibrateWholePart()=0
calibrateWholePart: call the procedure for calibrating the whole device
virtual bool quitCalibrate()=0
quitCalibrate: interrupt the calibration procedure
virtual bool setRemoteVariable(std::string key, const yarp::os::Bottle &val)=0
virtual bool getRemoteVariable(std::string key, yarp::os::Bottle &val)=0
virtual bool getRemoteVariablesList(yarp::os::Bottle *listOfKeys)=0
virtual bool setRefTorque(int j, double t)=0
Set the reference value of the torque for a given joint.
virtual bool setRefTorques(const double *t)=0
Set the reference value of the torque for all joints.
virtual bool getRefTorques(double *t)=0
Get the reference value of the torque for all joints.
virtual bool setMotorTorqueParams(int j, const yarp::dev::MotorTorqueParameters params)
Set a subset of motor parameters (bemf, ktau etc) useful for torque control.
virtual bool getMotorTorqueParams(int j, yarp::dev::MotorTorqueParameters *params)
Get a subset of motor parameters (bemf, ktau etc) useful for torque control.
virtual bool getTorques(double *t)=0
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
virtual bool getAxes(int *ax)=0
Get the number of controlled axes.
virtual bool getTorqueRange(int j, double *min, double *max)=0
Get the full scale of the torque sensor of a given joint.
virtual bool getTorqueRanges(double *min, double *max)=0
Get the full scale of the torque sensors of all joints.
virtual bool getRefTorque(int j, double *t)=0
Get the reference value of the torque for a given joint.
virtual bool getTorque(int j, double *t)=0
Get the value of the torque on a given joint (this is the feedback if you have a torque sensor).
virtual bool getRefVelocity(const int joint, double *vel)
Get the last reference speed set by velocityMove for single joint.
virtual bool getAxes(int *axes)=0
Get the number of controlled axes.
virtual bool velocityMove(int j, double sp)=0
Start motion at a given speed, single joint.
virtual bool getRefVelocities(double *vels)
Get the last reference speed set by velocityMove for all joints.
Contains the parameters for a PID.
A simple collection of objects that can be described and transmitted in a portable way.
Definition Bottle.h:64
void add(const Value &value)
Add a Value to the bottle, at the end of the list.
Definition Bottle.cpp:309
void addVocab32(yarp::conf::vocab32_t x)
Places a vocabulary item in the bottle, at the end of the list.
Definition Bottle.cpp:164
Bottle & addList()
Places an empty nested list in the bottle, at the end of the list.
Definition Bottle.cpp:182
size_type size() const
Gets the number of elements in the bottle.
Definition Bottle.cpp:251
void addFloat64(yarp::conf::float64_t x)
Places a 64-bit floating point number in the bottle, at the end of the list.
Definition Bottle.cpp:158
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition Bottle.cpp:246
Bottle tail() const
Get all but the first element of a bottle.
Definition Bottle.cpp:361
void clear()
Empties the bottle of any objects it contains.
Definition Bottle.cpp:121
void addInt32(std::int32_t x)
Places a 32-bit integer in the bottle, at the end of the list.
Definition Bottle.cpp:140
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition Bottle.cpp:170
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Definition Bottle.cpp:211
A mini-server for performing network communication in the background.
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition Stamp.cpp:124
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition Value.cpp:222
virtual yarp::conf::vocab32_t asVocab32() const
Get vocabulary identifier as an integer.
Definition Value.cpp:228
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition Value.cpp:204
virtual Bottle * asList() const
Get list value.
Definition Value.cpp:240
virtual std::string asString() const
Get string value.
Definition Value.cpp:234
void resize(size_t size) override
Resize the vector.
Definition Vector.h:221
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define yCDebug(component,...)
For streams capable of holding different kinds of content, check what they actually have.
Definition jointData.cpp:13
PidControlTypeEnum
Definition PidEnums.h:15
std::string decode(NetInt32 code)
Convert a vocabulary identifier into a string.
Definition Vocab.cpp:33
An interface to the operating system, including Port based communication.